From cc8df40e135de62493708ccac7c43545f70e8f53 Mon Sep 17 00:00:00 2001 From: YI-BOYANG <46438966+YI-BOYANG@users.noreply.github.com> Date: Mon, 21 Nov 2022 14:38:30 +0800 Subject: [PATCH 001/130] Add GEPRC new target "GEPRC_F722_AIO" --- src/main/target/GEPRC_F722_AIO/CMakeLists.txt | 1 + src/main/target/GEPRC_F722_AIO/target.c | 40 +++++ src/main/target/GEPRC_F722_AIO/target.h | 167 ++++++++++++++++++ 3 files changed, 208 insertions(+) create mode 100644 src/main/target/GEPRC_F722_AIO/CMakeLists.txt create mode 100644 src/main/target/GEPRC_F722_AIO/target.c create mode 100644 src/main/target/GEPRC_F722_AIO/target.h diff --git a/src/main/target/GEPRC_F722_AIO/CMakeLists.txt b/src/main/target/GEPRC_F722_AIO/CMakeLists.txt new file mode 100644 index 0000000000..51e664a263 --- /dev/null +++ b/src/main/target/GEPRC_F722_AIO/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f722xe(GEPRC_F722_AIO) diff --git a/src/main/target/GEPRC_F722_AIO/target.c b/src/main/target/GEPRC_F722_AIO/target.c new file mode 100644 index 0000000000..e067971fd2 --- /dev/null +++ b/src/main/target/GEPRC_F722_AIO/target.c @@ -0,0 +1,40 @@ +/* +* This file is part of Cleanflight. +* +* Cleanflight is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* Cleanflight is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with Cleanflight. If not, see . +*/ + +#include + +#include "platform.h" + +#include "drivers/bus.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" +#include "drivers/sensor.h" + + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0), + + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), + DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), + DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), + + DEF_TIM(TIM2, CH2, PA1, TIM_USE_LED, 0, 0), +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/GEPRC_F722_AIO/target.h b/src/main/target/GEPRC_F722_AIO/target.h new file mode 100644 index 0000000000..33020da40b --- /dev/null +++ b/src/main/target/GEPRC_F722_AIO/target.h @@ -0,0 +1,167 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "GEPR" + +#define USBD_PRODUCT_STRING "GEPRC_F722_AIO" + +#define LED0 PC4 + +#define BEEPER PC15 +#define BEEPER_INVERTED + +// *************** Gyro & ACC ********************** + +#define USE_SPI +#define USE_SPI_DEVICE_1 + +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + + +#define USE_IMU_MPU6000 +#define IMU_MPU6000_ALIGN CW90_DEG +#define MPU6000_CS_PIN PA15 +#define MPU6000_SPI_BUS BUS_SPI1 +#define MPU6000_EXTI_PIN PA8 + +#define USE_IMU_BMI270 +#define IMU_BMI270_ALIGN CW90_DEG +#define BMI270_CS_PIN PA15 +#define BMI270_SPI_BUS BUS_SPI1 +#define BMI270_EXTI_PIN PA8 + +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW90_DEG +#define ICM42605_CS_PIN PA15 +#define ICM42605_SPI_BUS BUS_SPI1 +#define ICM42605_EXTI_PIN PA8 + +#define USE_EXTI +#define USE_MPU_DATA_READY_SIGNAL + +// *************** I2C/Baro/Mag ********************* +#define USE_I2C +#define USE_I2C_DEVICE_2 +#define I2C2_SCL PB10 +#define I2C2_SDA PB11 + +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C2 +#define USE_BARO_BMP280 +#define USE_BARO_DPS310 +#define USE_BARO_MS5611 + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C2 +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_IST8310 +#define USE_MAG_IST8308 +#define USE_MAG_MAG3110 +#define USE_MAG_LIS3MDL + +#define TEMPERATURE_I2C_BUS BUS_I2C2 + +#define PITOT_I2C_BUS BUS_I2C2 + +#define USE_RANGEFINDER +#define RANGEFINDER_I2C_BUS BUS_I2C2 +#define BNO055_I2C_BUS BUS_I2C2 + +// *************** FLASH ************************** +#define M25P16_CS_PIN PB9 +#define M25P16_SPI_BUS BUS_SPI3 +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PB3 +#define SPI3_MISO_PIN PB4 +#define SPI3_MOSI_PIN PB5 + +// *************** OSD ***************************** +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN PB12 + +// *************** UART ***************************** +#define USE_VCP + +#define USE_UART1 +#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 + +#define USE_UART2 +#define UART2_RX_PIN PA3 +#define UART2_TX_PIN PA2 + +#define USE_UART4 +#define UART4_RX_PIN PC11 +#define UART4_TX_PIN PC10 + +#define USE_UART5 +#define UART5_RX_PIN PD2 +#define UART5_TX_PIN PC12 + +#define SERIAL_PORT_COUNT 5 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS +#define SERIALRX_UART SERIAL_PORT_USART2 + +// *************** ADC ***************************** +#define USE_ADC +#define ADC_INSTANCE ADC1 +#define ADC1_DMA_STREAM DMA2_Stream0 +#define ADC_CHANNEL_1_PIN PC2 +#define ADC_CHANNEL_2_PIN PC1 + +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 + + +#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_TELEMETRY | FEATURE_VBAT | FEATURE_OSD | FEATURE_BLACKBOX) + + + +// *************** LEDSTRIP ************************ +#define USE_LED_STRIP +#define WS2811_PIN PA1 + + + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) + +#define MAX_PWM_OUTPUT_PORTS 8 + +#define USE_DSHOT +#define USE_ESC_SENSOR From 7e564b3e76282ba36d1fce37d390d280d8e5aa57 Mon Sep 17 00:00:00 2001 From: YI-BOYANG <46438966+YI-BOYANG@users.noreply.github.com> Date: Mon, 21 Nov 2022 14:57:41 +0800 Subject: [PATCH 002/130] Corrected the project name . --- src/main/target/GEPRC_F722_AIO/target.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/GEPRC_F722_AIO/target.c b/src/main/target/GEPRC_F722_AIO/target.c index e067971fd2..6699298db6 100644 --- a/src/main/target/GEPRC_F722_AIO/target.c +++ b/src/main/target/GEPRC_F722_AIO/target.c @@ -1,5 +1,5 @@ /* -* This file is part of Cleanflight. +* This file is part of INAV Project. * * Cleanflight is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by From 66c2a8fbb5dbab99b71eae1ba8ce04e2e2ce31d4 Mon Sep 17 00:00:00 2001 From: YI-BOYANG <46438966+YI-BOYANG@users.noreply.github.com> Date: Mon, 21 Nov 2022 14:58:17 +0800 Subject: [PATCH 003/130] Corrected the project name . --- src/main/target/GEPRC_F722_AIO/target.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/GEPRC_F722_AIO/target.h b/src/main/target/GEPRC_F722_AIO/target.h index 33020da40b..ba933c3dc8 100644 --- a/src/main/target/GEPRC_F722_AIO/target.h +++ b/src/main/target/GEPRC_F722_AIO/target.h @@ -1,5 +1,5 @@ /* - * This file is part of Cleanflight. + * This file is part of INAV Project. * * Cleanflight is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by From 81c0101e4b2296202e00d6dd814732a75398e177 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sun, 15 Jan 2023 14:36:22 +0100 Subject: [PATCH 004/130] Add bf "hd" compatibility. Same as BF43COMPAT, but with a HD canvas, in case DJI implements support for BF4.4 but not INAV. --- docs/Settings.md | 2 +- src/main/drivers/osd.h | 3 ++- src/main/fc/settings.yaml | 2 +- src/main/io/displayport_msp_bf_compat.h | 2 +- src/main/io/displayport_msp_osd.c | 15 +++++++++------ 5 files changed, 14 insertions(+), 10 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index b64d641124..57668d2ec1 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -4714,7 +4714,7 @@ IMPERIAL, METRIC, UK ### osd_video_system -Video system used. Possible values are `AUTO`, `PAL`, `NTSC`, `HDZERO`, 'DJIWTF', 'AVATAR' and `BF43COMPAT` +Video system used. Possible values are `AUTO`, `PAL`, `NTSC`, `HDZERO`, `DJIWTF`, `AVATAR`, `BF43COMPAT` and `BFHDCOMPAT` | Default | Min | Max | | --- | --- | --- | diff --git a/src/main/drivers/osd.h b/src/main/drivers/osd.h index 298866b4e8..e9ae4d5ef3 100644 --- a/src/main/drivers/osd.h +++ b/src/main/drivers/osd.h @@ -49,7 +49,8 @@ typedef enum { VIDEO_SYSTEM_HDZERO, VIDEO_SYSTEM_DJIWTF, VIDEO_SYSTEM_AVATAR, - VIDEO_SYSTEM_BFCOMPAT + VIDEO_SYSTEM_BFCOMPAT, + VIDEO_SYSTEM_BFCOMPAT_HD } videoSystem_e; typedef enum { diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 1156a2b0c3..3ce9a6faac 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -72,7 +72,7 @@ tables: values: ["BATTERY", "CELL"] enum: osd_stats_min_voltage_unit_e - name: osd_video_system - values: ["AUTO", "PAL", "NTSC", "HDZERO", "DJIWTF", "AVATAR", "BF43COMPAT"] + values: ["AUTO", "PAL", "NTSC", "HDZERO", "DJIWTF", "AVATAR", "BF43COMPAT", "BFHDCOMPAT"] enum: videoSystem_e - name: osd_telemetry values: ["OFF", "ON","TEST"] diff --git a/src/main/io/displayport_msp_bf_compat.h b/src/main/io/displayport_msp_bf_compat.h index 4eb96399fa..bc6a66550c 100644 --- a/src/main/io/displayport_msp_bf_compat.h +++ b/src/main/io/displayport_msp_bf_compat.h @@ -27,7 +27,7 @@ #ifndef DISABLE_MSP_BF_COMPAT #include "osd.h" uint8_t getBfCharacter(uint8_t ch, uint8_t page); -#define isBfCompatibleVideoSystem(osdConfigPtr) (osdConfigPtr->video_system == VIDEO_SYSTEM_BFCOMPAT) +#define isBfCompatibleVideoSystem(osdConfigPtr) (osdConfigPtr->video_system == VIDEO_SYSTEM_BFCOMPAT || osdConfigPtr->video_system == VIDEO_SYSTEM_BFCOMPAT_HD) #else #define getBfCharacter(x, page) (x) #define isBfCompatibleVideoSystem(osdConfigPtr) (false) diff --git a/src/main/io/displayport_msp_osd.c b/src/main/io/displayport_msp_osd.c index 9dd51461d1..662ab89dbb 100644 --- a/src/main/io/displayport_msp_osd.c +++ b/src/main/io/displayport_msp_osd.c @@ -60,7 +60,8 @@ typedef enum { // defines are from hdzero code SD_3016, HD_5018, HD_3016, // Special HDZERO mode that just sends the centre 30x16 of the 50x18 canvas to the VRX - HD_6022 // added to support DJI wtfos 60x22 grid + HD_6022, // added to support DJI wtfos 60x22 grid + HD_5320 // added to support Avatar and BetaflightHD } resolutionType_e; #define DRAW_FREQ_DENOM 4 // 60Hz @@ -289,16 +290,15 @@ static int drawScreen(displayPort_t *displayPort) // 250Hz uint8_t len = 4; do { bitArrayClr(dirty, pos); - subcmd[len++] = (osdVideoSystem == VIDEO_SYSTEM_BFCOMPAT) ? getBfCharacter(screen[pos++], page): screen[pos++]; + subcmd[len++] = isBfCompatibleVideoSystem(osdConfig()) ? getBfCharacter(screen[pos++], page): screen[pos++]; if (bitArrayGet(dirty, pos)) { next = pos; } } while (next == pos && next < endOfLine && bitArrayGet(fontPage, next) == page && bitArrayGet(blinkChar, next) == blink); - if (osdVideoSystem != VIDEO_SYSTEM_BFCOMPAT) { + if (!isBfCompatibleVideoSystem(osdConfig())) { attributes |= (page << DISPLAYPORT_MSP_ATTR_FONTPAGE); - //attributes = page; } if (blink) { @@ -464,8 +464,9 @@ displayPort_t* mspOsdDisplayPortInit(const videoSystem_e videoSystem) screenRows = DJI_ROWS; screenCols = DJI_COLS; break; + case VIDEO_SYSTEM_BFCOMPAT_HD: case VIDEO_SYSTEM_AVATAR: - currentOsdMode = HD_5018; + currentOsdMode = HD_5320; screenRows = AVATAR_ROWS; screenCols = AVATAR_COLS; break; @@ -478,7 +479,9 @@ displayPort_t* mspOsdDisplayPortInit(const videoSystem_e videoSystem) displayInit(&mspOsdDisplayPort, &mspOsdVTable); if (osdVideoSystem == VIDEO_SYSTEM_BFCOMPAT) { - mspOsdDisplayPort.displayPortType = "MSP DisplayPort: DJI Compatability mode"; + mspOsdDisplayPort.displayPortType = "MSP DisplayPort: BetaFlight Compatability mode"; + } else if (osdVideoSystem == VIDEO_SYSTEM_BFCOMPAT_HD) { + mspOsdDisplayPort.displayPortType = "MSP DisplayPort: BetaFlight Compatability mode (HD)"; } else { mspOsdDisplayPort.displayPortType = "MSP DisplayPort"; } From 2b283dc83f965ffa3781d8a3f6494619b9bd57c2 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sun, 15 Jan 2023 14:44:46 +0100 Subject: [PATCH 005/130] update docs --- docs/Settings.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/Settings.md b/docs/Settings.md index 57668d2ec1..b64d641124 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -4714,7 +4714,7 @@ IMPERIAL, METRIC, UK ### osd_video_system -Video system used. Possible values are `AUTO`, `PAL`, `NTSC`, `HDZERO`, `DJIWTF`, `AVATAR`, `BF43COMPAT` and `BFHDCOMPAT` +Video system used. Possible values are `AUTO`, `PAL`, `NTSC`, `HDZERO`, 'DJIWTF', 'AVATAR' and `BF43COMPAT` | Default | Min | Max | | --- | --- | --- | From 5db8b8b2f40e93eb242853a75138147f26bab887 Mon Sep 17 00:00:00 2001 From: Scavanger Date: Tue, 24 Jan 2023 09:39:11 -0300 Subject: [PATCH 006/130] SITL --- CMakeLists.txt | 25 +- cmake/host-checks.cmake | 10 + cmake/host.cmake | 39 + cmake/main.cmake | 16 +- cmake/settings.cmake | 5 +- cmake/sitl.cmake | 143 ++ docs/SITL/RealFlight.md | 20 + docs/SITL/SITL.md | 112 + docs/SITL/X-Plane.md | 22 + docs/SITL/assets/INAV-SIM-OSD.png | Bin 0 -> 353983 bytes docs/SITL/assets/SITL-Fake-Sensors.png | Bin 0 -> 12872 bytes docs/SITL/assets/SITL-SBUS-FT232.png | Bin 0 -> 12444 bytes docs/SITL/assets/SITL-UART-TCP-Connecion.png | Bin 0 -> 2900 bytes src/main/CMakeLists.txt | 5 + src/main/blackbox/blackbox.c | 2 + src/main/build/atomic.h | 2 +- src/main/cms/cms.c | 6 +- src/main/common/bitarray.c | 2 +- src/main/common/printf.c | 5 +- src/main/config/config_eeprom.c | 6 + src/main/config/config_streamer_file.c | 105 + src/main/drivers/accgyro/accgyro.c | 3 + src/main/drivers/accgyro/accgyro_fake.c | 61 +- src/main/drivers/accgyro/accgyro_mpu6500.c | 0 src/main/drivers/accgyro/accgyro_mpu6500.h | 0 src/main/drivers/accgyro/accgyro_mpu9250.c | 0 src/main/drivers/accgyro/accgyro_mpu9250.h | 0 src/main/drivers/adc.c | 17 +- src/main/drivers/barometer/barometer_fake.c | 8 +- src/main/drivers/bus.c | 37 +- src/main/drivers/bus.h | 0 src/main/drivers/bus_busdev_i2c.c | 0 src/main/drivers/bus_busdev_spi.c | 0 src/main/drivers/compass/compass_ak8963.c | 0 src/main/drivers/compass/compass_ak8963.h | 0 src/main/drivers/compass/compass_mag3110.c | 0 src/main/drivers/compass/compass_mag3110.h | 0 src/main/drivers/compass/compass_mpu9250.c | 0 src/main/drivers/compass/compass_mpu9250.h | 0 src/main/drivers/compass/compass_qmc5883l.c | 0 src/main/drivers/compass/compass_qmc5883l.h | 0 src/main/drivers/display.c | 2 +- src/main/drivers/exti.c | 6 +- src/main/drivers/io.c | 8 + src/main/drivers/io.h | 2 +- src/main/drivers/io_def_generated.h | 4 +- src/main/drivers/logging_codes.h | 0 src/main/drivers/opflow/opflow.h | 0 src/main/drivers/opflow/opflow_fake.c | 0 src/main/drivers/opflow/opflow_fake.h | 0 src/main/drivers/opflow/opflow_virtual.c | 0 src/main/drivers/opflow/opflow_virtual.h | 0 src/main/drivers/pitotmeter/pitotmeter_fake.c | 33 +- src/main/drivers/pitotmeter/pitotmeter_fake.h | 6 + src/main/drivers/pwm_mapping.c | 4 + src/main/drivers/pwm_output.c | 4 + .../drivers/rangefinder/rangefinder_vl53l0x.c | 0 .../drivers/rangefinder/rangefinder_vl53l0x.h | 0 src/main/drivers/serial_tcp.c | 307 +++ src/main/drivers/serial_tcp.h | 51 + src/main/drivers/sound_beeper.c | 2 +- src/main/drivers/stack_check.c | 4 + src/main/drivers/stack_check.h | 0 src/main/drivers/timer.c | 0 src/main/drivers/timer.h | 7 + src/main/drivers/timer_def.h | 1 + src/main/drivers/usb_msc.c | 4 + src/main/fc/cli.c | 11 +- src/main/fc/config.c | 4 + src/main/fc/fc_core.c | 13 +- src/main/fc/fc_init.c | 13 +- src/main/fc/fc_msp.c | 25 +- src/main/fc/fc_tasks.c | 2 +- src/main/fc/runtime_config.h | 3 +- src/main/fc/settings.yaml | 6 +- src/main/fc/settings_generated.c | 1697 +++++++++++++ src/main/fc/settings_generated.h | 2209 +++++++++++++++++ src/main/flight/imu.c | 20 +- src/main/flight/imu.h | 4 + src/main/flight/kalman.c | 9 + src/main/flight/mixer.c | 5 + src/main/flight/servos.c | 6 +- src/main/io/gps.c | 83 +- src/main/io/gps.h | 17 + src/main/io/gps_fake.c | 98 + src/main/io/gps_private.h | 6 + src/main/io/osd.c | 8 +- src/main/io/osd_dji_hd.c | 4 +- src/main/io/serial.c | 11 + src/main/io/vtx.c | 3 + src/main/main.c | 6 + .../navigation/navigation_pos_estimator.c | 2 +- src/main/programming/logic_condition.c | 7 +- src/main/rx/fport.c | 2 +- src/main/sensors/acceleration.c | 18 +- src/main/sensors/barometer.c | 4 +- src/main/sensors/barometer.h | 4 + src/main/sensors/battery.c | 27 +- src/main/sensors/battery_config_structs.h | 6 +- src/main/sensors/battery_sensor_fake.c | 58 + src/main/sensors/battery_sensor_fake.h | 30 + src/main/sensors/compass.c | 2 +- src/main/sensors/diagnostics.c | 2 +- src/main/sensors/gyro.c | 6 +- src/main/sensors/pitotmeter.c | 23 +- src/main/target/SITL/CMakeLists.txt | 1 + src/main/target/SITL/config.c | 28 + src/main/target/SITL/sim/realFlight.c | 421 ++++ src/main/target/SITL/sim/realFlight.h | 29 + src/main/target/SITL/sim/simHelper.c | 47 + src/main/target/SITL/sim/simHelper.h | 33 + src/main/target/SITL/sim/simple_soap_client.c | 162 ++ src/main/target/SITL/sim/simple_soap_client.h | 46 + src/main/target/SITL/sim/xplane.c | 403 +++ src/main/target/SITL/sim/xplane.h | 29 + src/main/target/SITL/target.c | 345 +++ src/main/target/SITL/target.h | 188 ++ src/main/target/common.h | 6 + src/main/target/common_post.h | 4 +- src/main/target/link/sitl.ld | 21 + src/utils/compiler.rb | 8 +- src/utils/settings.rb | 12 +- 122 files changed, 7142 insertions(+), 191 deletions(-) create mode 100644 cmake/host-checks.cmake create mode 100644 cmake/host.cmake create mode 100644 cmake/sitl.cmake create mode 100644 docs/SITL/RealFlight.md create mode 100644 docs/SITL/SITL.md create mode 100644 docs/SITL/X-Plane.md create mode 100644 docs/SITL/assets/INAV-SIM-OSD.png create mode 100644 docs/SITL/assets/SITL-Fake-Sensors.png create mode 100644 docs/SITL/assets/SITL-SBUS-FT232.png create mode 100644 docs/SITL/assets/SITL-UART-TCP-Connecion.png create mode 100644 src/main/config/config_streamer_file.c mode change 100755 => 100644 src/main/drivers/accgyro/accgyro_mpu6500.c mode change 100755 => 100644 src/main/drivers/accgyro/accgyro_mpu6500.h mode change 100755 => 100644 src/main/drivers/accgyro/accgyro_mpu9250.c mode change 100755 => 100644 src/main/drivers/accgyro/accgyro_mpu9250.h mode change 100755 => 100644 src/main/drivers/bus.c mode change 100755 => 100644 src/main/drivers/bus.h mode change 100755 => 100644 src/main/drivers/bus_busdev_i2c.c mode change 100755 => 100644 src/main/drivers/bus_busdev_spi.c mode change 100755 => 100644 src/main/drivers/compass/compass_ak8963.c mode change 100755 => 100644 src/main/drivers/compass/compass_ak8963.h mode change 100755 => 100644 src/main/drivers/compass/compass_mag3110.c mode change 100755 => 100644 src/main/drivers/compass/compass_mag3110.h mode change 100755 => 100644 src/main/drivers/compass/compass_mpu9250.c mode change 100755 => 100644 src/main/drivers/compass/compass_mpu9250.h mode change 100755 => 100644 src/main/drivers/compass/compass_qmc5883l.c mode change 100755 => 100644 src/main/drivers/compass/compass_qmc5883l.h mode change 100755 => 100644 src/main/drivers/logging_codes.h mode change 100755 => 100644 src/main/drivers/opflow/opflow.h mode change 100755 => 100644 src/main/drivers/opflow/opflow_fake.c mode change 100755 => 100644 src/main/drivers/opflow/opflow_fake.h mode change 100755 => 100644 src/main/drivers/opflow/opflow_virtual.c mode change 100755 => 100644 src/main/drivers/opflow/opflow_virtual.h mode change 100755 => 100644 src/main/drivers/rangefinder/rangefinder_vl53l0x.c mode change 100755 => 100644 src/main/drivers/rangefinder/rangefinder_vl53l0x.h create mode 100644 src/main/drivers/serial_tcp.c create mode 100644 src/main/drivers/serial_tcp.h mode change 100755 => 100644 src/main/drivers/stack_check.h mode change 100755 => 100644 src/main/drivers/timer.c create mode 100644 src/main/fc/settings_generated.c create mode 100644 src/main/fc/settings_generated.h create mode 100644 src/main/io/gps_fake.c create mode 100644 src/main/sensors/battery_sensor_fake.c create mode 100644 src/main/sensors/battery_sensor_fake.h create mode 100644 src/main/target/SITL/CMakeLists.txt create mode 100644 src/main/target/SITL/config.c create mode 100644 src/main/target/SITL/sim/realFlight.c create mode 100644 src/main/target/SITL/sim/realFlight.h create mode 100644 src/main/target/SITL/sim/simHelper.c create mode 100644 src/main/target/SITL/sim/simHelper.h create mode 100644 src/main/target/SITL/sim/simple_soap_client.c create mode 100644 src/main/target/SITL/sim/simple_soap_client.h create mode 100644 src/main/target/SITL/sim/xplane.c create mode 100644 src/main/target/SITL/sim/xplane.h create mode 100644 src/main/target/SITL/target.c create mode 100644 src/main/target/SITL/target.h create mode 100644 src/main/target/link/sitl.ld diff --git a/CMakeLists.txt b/CMakeLists.txt index 04623c6774..6e6a6462f9 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -10,8 +10,15 @@ set(SVD_DIR "${CMAKE_CURRENT_SOURCE_DIR}/dev/svd") set(DOWNLOADS_DIR "${MAIN_DIR}/downloads") set(TOOLS_DIR "${MAIN_DIR}/tools") -set(TOOLCHAIN_OPTIONS none arm-none-eabi) -set(TOOLCHAIN "arm-none-eabi" CACHE STRING "Toolchain to use. Available: ${TOOLCHAIN_OPTIONS}") +option(SITL "SITL build for host system" OFF) + +set(TOOLCHAIN_OPTIONS none arm-none-eabi host) +if (SITL) + set(TOOLCHAIN "host" CACHE STRING "Toolchain to use. Available: ${TOOLCHAIN_OPTIONS}") +else() + set(TOOLCHAIN "arm-none-eabi" CACHE STRING "Toolchain to use. Available: ${TOOLCHAIN_OPTIONS}") +endif() + set_property(CACHE TOOLCHAIN PROPERTY STRINGS ${TOOLCHAIN_OPTIONS}) if("" STREQUAL TOOLCHAIN) set(TOOLCHAIN none) @@ -33,7 +40,11 @@ include(settings) if(TOOLCHAIN STREQUAL none) add_subdirectory(src/test) else() - set(CMAKE_TOOLCHAIN_FILE "${CMAKE_CURRENT_SOURCE_DIR}/cmake/${TOOLCHAIN}.cmake") + if (SITL) + include("${CMAKE_CURRENT_SOURCE_DIR}/cmake/${TOOLCHAIN}.cmake") + else() + set(CMAKE_TOOLCHAIN_FILE "${CMAKE_CURRENT_SOURCE_DIR}/cmake/${TOOLCHAIN}.cmake") + endif() include("${CMAKE_CURRENT_SOURCE_DIR}/cmake/${TOOLCHAIN}-checks.cmake") endif() @@ -68,9 +79,13 @@ set(COMMON_COMPILE_DEFINITIONS FC_VERSION_PATCH_LEVEL=${CMAKE_PROJECT_VERSION_PATCH} ) -include(openocd) -include(svd) +if (NOT SITL) + include(openocd) + include(svd) +endif() + include(stm32) +include(sitl) add_subdirectory(src) diff --git a/cmake/host-checks.cmake b/cmake/host-checks.cmake new file mode 100644 index 0000000000..9e08e1b61a --- /dev/null +++ b/cmake/host-checks.cmake @@ -0,0 +1,10 @@ +set(gcc_host_req_ver 10) + +execute_process(COMMAND ${CMAKE_C_COMPILER} -dumpversion + OUTPUT_STRIP_TRAILING_WHITESPACE + OUTPUT_VARIABLE version) + + message("-- found GCC ${version}") +if (NOT gcc_host_req_ver STREQUAL version) + message(FATAL_ERROR "-- expecting GCC version ${gcc_host_req_ver}, but got version ${version} instead") +endif() diff --git a/cmake/host.cmake b/cmake/host.cmake new file mode 100644 index 0000000000..1ed8c7432b --- /dev/null +++ b/cmake/host.cmake @@ -0,0 +1,39 @@ + +if(NOT CMAKE_CONFIGURATION_TYPES) + set(CMAKE_CONFIGURATION_TYPES Debug Release RelWithDebInfo) +endif() +if(CMAKE_BUILD_TYPE STREQUAL "") + set(CMAKE_BUILD_TYPE RelWithDebInfo) +endif() + +if(WIN32) + set(TOOL_EXECUTABLE_SUFFIX ".exe") +endif() + +set(CMAKE_ASM_COMPILER "gcc${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "asm compiler") +set(CMAKE_C_COMPILER "gcc${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "c compiler") +set(CMAKE_CXX_COMPILER "g++${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "c++ compiler") +set(CMAKE_OBJCOPY "objcopy${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "objcopy tool") +set(CMAKE_OBJDUMP "objdump${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "objdump tool") +set(CMAKE_SIZE "size${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "size tool") +set(CMAKE_DEBUGGER "gdb${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "debugger") +set(CMAKE_CPPFILT "c++filt${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "c++filt") + +set(CMAKE_BUILD_TYPE ${CMAKE_BUILD_TYPE} CACHE STRING "Build Type" FORCE) +set_property(CACHE CMAKE_BUILD_TYPE PROPERTY STRINGS ${CMAKE_CONFIGURATION_TYPES}) + +set(debug_options "-Og -O0 -g") +set(release_options "-Os -DNDEBUG") +set(relwithdebinfo_options "-ggdb3 ${release_options}") + +set(CMAKE_C_FLAGS_DEBUG ${debug_options} CACHE INTERNAL "c compiler flags debug") +set(CMAKE_CXX_FLAGS_DEBUG ${debug_options} CACHE INTERNAL "c++ compiler flags debug") +set(CMAKE_ASM_FLAGS_DEBUG ${debug_options} CACHE INTERNAL "asm compiler flags debug") + +set(CMAKE_C_FLAGS_RELEASE ${release_options} CACHE INTERNAL "c compiler flags release") +set(CMAKE_CXX_FLAGS_RELEASE ${release_options} CACHE INTERNAL "cxx compiler flags release") +set(CMAKE_ASM_FLAGS_RELEASE ${release_options} CACHE INTERNAL "asm compiler flags release") + +set(CMAKE_C_FLAGS_RELWITHDEBINFO ${relwithdebinfo_options} CACHE INTERNAL "c compiler flags release") +set(CMAKE_CXX_FLAGS_RELWITHDEBINFO ${relwithdebinfo_options} CACHE INTERNAL "cxx compiler flags release") +set(CMAKE_ASM_FLAGS_RELWITHDEBINFO ${relwithdebinfo_options} CACHE INTERNAL "asm compiler flags release") diff --git a/cmake/main.cmake b/cmake/main.cmake index 0367e797bd..fa6186fc3c 100644 --- a/cmake/main.cmake +++ b/cmake/main.cmake @@ -23,6 +23,16 @@ macro(main_sources var) # list-var src-1...src-n list(TRANSFORM ${var} PREPEND "${MAIN_SRC_DIR}/") endmacro() +function(exclude var excludes) + set(filtered "") + foreach(item ${${var}}) + if (NOT ${item} IN_LIST excludes) + list(APPEND filtered ${item}) + endif() + endforeach() + set(${var} ${filtered} PARENT_SCOPE) +endfunction() + function(exclude_basenames var excludes) set(filtered "") foreach(item ${${var}}) @@ -73,8 +83,10 @@ function(setup_firmware_target exe name) get_property(targets GLOBAL PROPERTY VALID_TARGETS) list(APPEND targets ${name}) set_property(GLOBAL PROPERTY VALID_TARGETS "${targets}") - setup_openocd(${exe} ${name}) - setup_svd(${exe} ${name}) + if(NOT SITL) + setup_openocd(${exe} ${name}) + setup_svd(${exe} ${name}) + endif() cmake_parse_arguments(args "SKIP_RELEASES" "" "" ${ARGN}) if(args_SKIP_RELEASES) diff --git a/cmake/settings.cmake b/cmake/settings.cmake index 065f3a87db..fc35c2e016 100644 --- a/cmake/settings.cmake +++ b/cmake/settings.cmake @@ -29,12 +29,15 @@ function(enable_settings exe name) ${ARGN} ) + if(host STREQUAL TOOLCHAIN) + set(USE_HOST_GCC "-g") + endif() set(output ${dir}/${SETTINGS_GENERATED_H} ${dir}/${SETTINGS_GENERATED_C}) add_custom_command( OUTPUT ${output} COMMAND ${CMAKE_COMMAND} -E env CFLAGS="${cflags}" TARGET=${name} PATH="$ENV{PATH}" SETTINGS_CXX=${args_SETTINGS_CXX} - ${RUBY_EXECUTABLE} ${SETTINGS_GENERATOR} ${MAIN_DIR} ${SETTINGS_FILE} -o "${dir}" + ${RUBY_EXECUTABLE} ${SETTINGS_GENERATOR} ${MAIN_DIR} ${SETTINGS_FILE} ${USE_HOST_GCC} -o "${dir}" DEPENDS ${SETTINGS_GENERATOR} ${SETTINGS_FILE} ) set(${args_OUTPUTS} ${output} PARENT_SCOPE) diff --git a/cmake/sitl.cmake b/cmake/sitl.cmake new file mode 100644 index 0000000000..ba7448623c --- /dev/null +++ b/cmake/sitl.cmake @@ -0,0 +1,143 @@ + +main_sources(SITL_COMMON_SRC_EXCLUDES + build/atomic.h + drivers/system.c + drivers/time.c + drivers/timer.c + drivers/rcc.c + drivers/persistent.c + drivers/accgyro/accgyro_mpu.c + drivers/display_ug2864hsweg01.c + io/displayport_oled.c +) + +main_sources(SITL_SRC + config/config_streamer_file.c + drivers/serial_tcp.c + drivers/serial_tcp.h + target/SITL/sim/realFlight.c + target/SITL/sim/realFlight.h + target/SITL/sim/simHelper.c + target/SITL/sim/simHelper.h + target/SITL/sim/simple_soap_client.c + target/SITL/sim/simple_soap_client.h + target/SITL/sim/xplane.c + target/SITL/sim/xplane.h +) + +set(SITL_LINK_OPTIONS + -lrt + -Wl,-L${STM32_LINKER_DIR} + -Wl,--cref + -static-libgcc # Required for windows build under cygwin +) + +set(SITL_LINK_LIBRARIS + -lpthread + -lm + -lc +) + +set(SITL_COMPILE_OPTIONS + -Wno-format #Fixme: Compile for 32bit, but settings.rb has to be adjusted + -Wno-return-local-addr + -fsingle-precision-constant + -funsigned-char +) + +set(SITL_DEFINITIONS + SITL_BUILD +) + +function(generate_map_file target) + if(CMAKE_VERSION VERSION_LESS 3.15) + set(map "$.map") + else() + set(map "$/$.map") + endif() + target_link_options(${target} PRIVATE "-Wl,-gc-sections,-Map,${map}") +endfunction() + +function (target_sitl name) + + if(NOT host STREQUAL TOOLCHAIN) + return() + endif() + + exclude(COMMON_SRC "${SITL_COMMON_SRC_EXCLUDES}") + + set(target_sources) + list(APPEND target_sources ${SITL_SRC}) + file(GLOB target_c_sources "${CMAKE_CURRENT_SOURCE_DIR}/*.c") + file(GLOB target_h_sources "${CMAKE_CURRENT_SOURCE_DIR}/*.h") + list(APPEND target_sources ${target_c_sources} ${target_h_sources}) + + set(target_definitions ${COMMON_COMPILE_DEFINITIONS}) + + set(hse_mhz ${STM32_DEFAULT_HSE_MHZ}) + math(EXPR hse_value "${hse_mhz} * 1000000") + list(APPEND target_definitions "HSE_VALUE=${hse_value}") + + string(TOLOWER ${PROJECT_NAME} lowercase_project_name) + set(binary_name ${lowercase_project_name}_${FIRMWARE_VERSION}_${name}) + if(DEFINED BUILD_SUFFIX AND NOT "" STREQUAL "${BUILD_SUFFIX}") + set(binary_name "${binary_name}_${BUILD_SUFFIX}") + endif() + + list(APPEND target_definitions ${SITL_DEFINITIONS}) + set(exe_target ${name}.elf) + add_executable(${exe_target}) + target_sources(${exe_target} PRIVATE ${target_sources} ${COMMON_SRC}) + target_include_directories(${exe_target} PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}) + target_compile_definitions(${exe_target} PRIVATE ${target_definitions}) + + + if(WARNINGS_AS_ERRORS) + target_compile_options(${exe_target} PRIVATE -Werror) + endif() + + target_compile_options(${exe_target} PRIVATE ${SITL_COMPILE_OPTIONS}) + + target_link_libraries(${exe_target} PRIVATE ${SITL_LINK_LIBRARIS}) + target_link_options(${exe_target} PRIVATE ${SITL_LINK_OPTIONS}) + + generate_map_file(${exe_target}) + + set(script_path ${MAIN_SRC_DIR}/target/link/sitl.ld) + if(NOT EXISTS ${script_path}) + message(FATAL_ERROR "linker script ${script_path} doesn't exist") + endif() + set_target_properties(${exe_target} PROPERTIES LINK_DEPENDS ${script_path}) + target_link_options(${exe_target} PRIVATE -T${script_path}) + + if(${WIN32} OR ${CYGWIN}) + set(exe_filename ${CMAKE_BINARY_DIR}/${binary_name}.exe) + else() + set(exe_filename ${CMAKE_BINARY_DIR}/${binary_name}) + endif() + + add_custom_target(${name} ALL + cmake -E env PATH="$ENV{PATH}" + ${CMAKE_OBJCOPY} $ ${exe_filename} + BYPRODUCTS ${hex} + ) + + setup_firmware_target(${exe_target} ${name} ${ARGN}) + #clean_ + set(generator_cmd "") + if (CMAKE_GENERATOR STREQUAL "Unix Makefiles") + set(generator_cmd "make") + elseif(CMAKE_GENERATOR STREQUAL "Ninja") + set(generator_cmd "ninja") + endif() + if (NOT generator_cmd STREQUAL "") + set(clean_target "clean_${name}") + add_custom_target(${clean_target} + WORKING_DIRECTORY ${CMAKE_BINARY_DIR} + COMMAND ${generator_cmd} clean + COMMENT "Removing intermediate files for ${name}") + set_property(TARGET ${clean_target} PROPERTY + EXCLUDE_FROM_ALL 1 + EXCLUDE_FROM_DEFAULT_BUILD 1) + endif() +endfunction() \ No newline at end of file diff --git a/docs/SITL/RealFlight.md b/docs/SITL/RealFlight.md new file mode 100644 index 0000000000..eecb0b0d7d --- /dev/null +++ b/docs/SITL/RealFlight.md @@ -0,0 +1,20 @@ +# RealFlight + +Supported are RealFlight 9.5S and RealFlight Evolution, NOT RealFlight-X. + +RealFlight is very well suited to simulate the model flight specific aspects. Autolaunch and the mixers can be set in INAV. +However, since the sceneries do not correspond to a real environment, the GPS data must be "faked". The position is always shown somewhere in southern Nevada ;). +GPS data and flight modes work fine though, only for missions with waypoints it is of course not ideal. + +## General settings +Under Settings / Physics / Quality Switch on "RealFlight Link enabled". +As a command line option for SITL, the port does not need to be specified, the port is fixed. +For better results, set the difficulty level to "Realistic". + +## Prepare the models +All mixer and servo influencing settings should be deactivated. +In the model editor under "Electronis" all mixers should be deleted and the servos should be connected directly to the virtual receiver output. +In the "Radio" tab also deactivate Expo and low rates: "Activadd when: Never". +Configure the model in the same way as a real model would be set up in INAV including Mixer, Expo, etc. depending on the selected model in RealFlight. + +Then adjust the channelmap (see command line option) accordingly. \ No newline at end of file diff --git a/docs/SITL/SITL.md b/docs/SITL/SITL.md new file mode 100644 index 0000000000..ebc4696614 --- /dev/null +++ b/docs/SITL/SITL.md @@ -0,0 +1,112 @@ +# SITL + +![INAV-SIM-OSD](/assetes/INAV-SIM-OSD.png) + +## ATTENTION! +SITL is currently still under development, its use is still a bit cumbersome. + +SITL (Software in the loop) allows to run INAV completely in software on the PC without using a flight controller and simulate complete FPV flights. +For this, INAV is compiled with a normal PC compiler. + +The sensors are replaced by data provided by a simulator. +Currently supported are +- RealFlight https://www.realflight.com/ +- X-Plane https://www.x-plane.com/ + +INAV SITL communicates for sensor data and control directly with the corresponding simulator, see the documentation of the individual simulators and the command line options. + +## Command line +The following SITL specific command line options are available: + +If SITL is started without command line options, only the Configurator can be used. + +```--help``` Displays help for the command line options. + +```--sim=[sim]``` Select the simulator. xp = X-Plane, rf = RealFlight. Example: ```--sim=xp``` + +```--simip=[ip]``` IP address of the simulator, if you specify a simulator with "--sim" and omit this option localhost (127.0.0.1) will be used. Example: ```--simip=172.65.21.15``` + +```--simport=[port]``` Port number of the simulator, not necessary for all simulators. Example: ```--simport=4900``` + +```--useimu``` Use IMU sensor data from the simulator instead of using attitude data directly from the simulator. Not recommended, use only for debugging. + +```--chanmap=[chanmap]``` The channelmap to map the motor and servo outputs from INAV to the virtual receiver channel or control surfaces around simulator. +Syntax: (M(otor)|S(ervo)-),..., all numbers must have two digits. + +Example: +To assign motor1 to virtual receiver channel 1, servo 1 to channel 2, and servo2 to channel 3: +```--chanmap:M01-01,S01-02,S02-03``` +Please also read the documentation of the individual simulators. + +## Sensors +The following sensors are emulated: +- IMU (Gyro, Accelerometer) +- GPS +- Pitot +- barometer +- Battery (current and voltage), depending on simulator + +![SITL-Fake-Sensors](/assets/SITL-Fake-Sensors.png) + +Magnetometer (compass) is not yet supported, therefore no support for copters. + +Select "FAKE" as type for all mentioned, so that they receive the data from the simulator. + +## Serial ports +UARTs are replaced by TCP starting with port 5760 ascending. UART 1 port 5760, UART2 6761, ... +By default, UART1 and UART2 are available as MSP connections. +To connect the Configurator to SITL: Select TCP and connect to ```127.0.0.1:5760``` (if SITL is running on the same machine). + +The assignment and status of user UART/TCP connections is displayed on the console. + +![STL-Output](/assets/SITL-UART-TCP-Connecion.png) + +All other interfaces (I2C, SPI, etc.) are not emulated. + +## Remote control +At the moment only direct input via UART/TCP is supported. +Connect a serial receiver (e.g. SBUS) to the PC via a UART/USB adapter. Configure the receiver in the Configurator as usual. +The connection can then be established with a programme that forwards the serial data unaltered to TCP, e.g. with the Python script tcp_serial_redirect.py (https://github.com/Scavanger/TCP-Serial-Redirect) +If necessary, please download the required runtime environment from https://www.python.org/. +Please use the linked version, which has a smaller buffer, otherwise the control response is relatively slow. + +### Example SBUS: +For this you need a FT232 module. With FT-Prog (https://ftdichip.com/utilities/) the signals can be inverted: Devices->Scan and Parse, then Hardware Specific -> Invert RS232 Signals -> Invert RXD. + +![SITL-SBUS-FT232](/assets/SITL-SBUS-FT232.png) + +For SBUS, the command line arguments of the python script are: +```python tcp_serial_redirect.py --parity E --stopbits 2 -c 127.0.0.1:[INAV-UART-PORT] COMXX 100000``` + +Note: Telemetry via return channel through the receiver is not supported by SITL. + +## OSD +For the OSD the program INAV-Sim-OSD is available: https://github.com/Scavanger/INAV-SIM-OSD. +For this, activate MSP-Displayport on a UART/TCP port and connect to the corresponding port. + +Note: INAV-Sim-OSD only works if the simulator is in window mode. + +## Running SITL +It is recommended to start the tools in the following order: +1. Simulator, aircraft should be ready for take-off +2. INAV-SITL +3. OSD +4. serial redirect for RC input + +## Compile +GCC 10 is required, GCC 11 gives an error message (bug in GCC?!?). + +### Linux: +Almost like normal, ruby, cmake and make are also required. +With cmake, the option "-DSITL=ON" must be specified. + +``` +mkdir build_SITL +cd build_SITL +cmake -DSITL=ON .. +make +``` + +### Windows: +Compile under cygwin, then as in Linux. +Copy cygwin1.dll into the directory, or include cygwin's /bin/ directory in the environment variable PATH. diff --git a/docs/SITL/X-Plane.md b/docs/SITL/X-Plane.md new file mode 100644 index 0000000000..a4c85ab086 --- /dev/null +++ b/docs/SITL/X-Plane.md @@ -0,0 +1,22 @@ +# X-Plane + +Tested on X-Plane 11, 12 should(!) work but not tested. + +X-Plane is not a model flight simulator, but is based on real world data and is therefore suitable +GPS missions with waypoints. + +## General settings +In Settings / Network select "Accept incoming connections". +The port can be found under "UDP PORTS", "Port we receive on". If no connection is established, the port can be changed. +You may want to incease the "Flight model per frame" value under "General" + +## Channelmap: +The assignment of the "virtual receiver" is fixed: +1 - Throttle +2 - Roll +3 - Pitch +4 - Yaw + +The internal mixer (e.g. for wings only) cannot be deactivated without further ado, therefore always select "Aircraft with tail" in INAV. +For the standard Aircraft preset the channelmap is: +```--chanmap=M01-01,S01-03,S03-02,S04-04``` diff --git a/docs/SITL/assets/INAV-SIM-OSD.png b/docs/SITL/assets/INAV-SIM-OSD.png new file mode 100644 index 0000000000000000000000000000000000000000..59b936c676539047166e586117db935506f94cdd GIT binary patch literal 353983 zcmV)vK$X9VP)TWWSxw5gF;XGL|K%4TR)hlyo&cW2Ym z(X+Cvc!hC{wccWOcVc>nWNJm2hhk}TXl7|;w$A5vd38NWMs9mbgr?DlhwOd6;Iub3q%6Exq3N5{{#vqLmiWA9ZVG!JTwkb6yayJac7Bhm?HQ@A;va z6X4s?U~6}r#@sPEJ?-k;t=8%ZvdiY(0t3zGj;+eTzpOkvG@qq;p`fA8=lAF5=fc6k zf`5Fi&gUp}M7`ecrN-yA*6+R6@5HPUf3YFXew)Ve%p7%FDe#HT*J0_JEV+g5)<;8l|Z>@rDS+-?^ z_u$>@_UG9wzS-=Z)nr>ww>5Q}xK}=Wu~_`RK-;RfTA^L575M~js|4Rb|6So`1wLUr zvTp3g^nR_7Z!H|(G!MBsIc+m%rr#c8w}%Jt7QTIfmm6>qw#k=Cw(V|*tqw19et~aj ztAnpJ+dQ}}lWfoMja;6`&(HAPIBYu=FQ@2V@~r@#$Oyh)0qsu)-}oQ;e4B@bZ}7Ho;2YY^ zRaW>81MheYe~1Nd@dAPT3SDj{HxtcU6nH<;kKmFCz3=AajRLre-1CTSxx^oIC_bIi zxA9WEKoB2K$t4E85rV6L9tqzTeg?m8e@+Sxe)moE5%Y13-REHd&cK}=)r-LIo($hB z1lKDD*=A4uB*FP18GKv2!#CsMk>BC);O&?Mx-ov6*+O^|z*6}~BI-;g(Qncz!0 z@SfaJ_C3kUz3=9Lf8Pn%jo$QI5WOSV_msUoi|GA4eFpC#a8Kj8H^FY{EslK?3T81v z_PYJ4NH~IUNejTRtO4&HgYEM;`fXD7eGUF0@LmbzyGO`3hwl}9pBBBXP#Cvz*dk64 zMg}v3cxRVV!l^f6-;wB@h0Nm(9cIquECpz$sq~4Hy zFSX=*N-xjqB^13+L&1B@p?e(9zA<`Rz0IHez zjljFNlGu086nJ=g@MiF>oOs{^wDN-Q1nAv7D0+(+Y=+S9MI!We^wgW`CbKNU31{B; z9pc|tgn55StDD?m_WcCO_v9%Xc;C(MWbIqU?l2I?$gNdP#LM$ixPUi|+!(v3(W*%% z_D!C_oPnd~a=UG)&-J!#2%oo=D-GL-*a5z3Cju0sjahe)d~@_3FD2RyKXBBZ#(+0_6LEVSFP;b&@_g>N-LBga zpXgPu3wC*J`ng*a@CjYn1u)9EJGujpV3tvYUnKz9s^@y1?|ZKJy(6#{9Ec822;l7^ zIX>ClqaOp^!0W2t0X$Oh1521(b-Ut*{;%js1O0clj}gAfuZ+=fj=@c?nTX`u3fD~p z0mUTro5|lRLc$dQU-h!;-px?3-4V3YptorrdfC!haqew8I`oc3a74Wwt#CpwyDVB_ z(HqJp=p9CHEqLF=SxzAPe#$C(Bgy+t(Y+PsjoEh?c!w=mO1g=_zQ>e$GYp?bu2@Ro zJw826&%W`c<8DTynp?$yj*-%Dj7A%X$X46)8sJk7)&|@$8u=W~s%~dAYIq(6!Hsln zD0;j8s8TMMhZS(|RuZr;p~Fjll5+z@`vy9`zj2ERPY;{^5Zt0t@?7cB8!q_oU_T#u z@U@Y+ZM+UY33Tv(=P@hbl6KN-2HAIVV5RtsloA5m@BMh9LfwjsI zv!Dpx^APQXB6sM5r2ybDn#njB^VYC$%*Z@{J2)A7Mb5}Oh05S$Fz5r`Y8md?;H2z( z48A*VWdODcypnKrw*rnHxrT*Muu(n%H?78^cVjp>L0iR(=f?m-E9CHDB5d^BJ~_TT z>L%geMYpuYH$Xp|^iccY=WB?V-tmU;e~A5q|3UN{*UAI%BNdMvyb1kA2;S3Z-_ejQ zdQiX@jDB+hzCeqZD{<}8`a_fsb3UH>TJ_gu4JS&v$=)QaAc<}H{78TICG48h|B@8saE zXWwnF2ykxe7unjD?RjMcV+}xy4S-!IgPO;l{9X;g;$Y)3sb$^gAPlkYl4%Hv2=&?tSZ^8b9+HMD&1H(qOk_`|8dZ-DzC*yZhQb#E9hFl!)Fay@X=25_RBJ_sL`v~A$!D$J|Q&I0Q z!^vZ2*<19R++eHsmz&>2;+?{6@EfidQb_*AN=i%|PZ&^NJLbkkoNeOuffU8%STmZ)aj=1*% z;`fR#SR&B`xlVdJqqmiVVK5KtPqK4w&c0`lyE1R;^(Nr0 zXWx-dZ|oL)$}p)zeBKbTqx~lJ5b`aoSVpPd&+>{TfbVf&$#NRGW~s98qyVmG-@cZ8 zgPl+iF}#w%z9BpVD!K(%4htP=AHZ|N0_3v+uB*h!8vu^MVdaJkHg6p-ly^LU_Jh*e zMckf!>j-HEy&!Pi^=J@a)7lN4g32}U9lTLV5l_|u_HB5s54H-@atgj*@Pu>OKj906 z?*zV)xr75ML+~bjucP4PilF|@JcQW$y`bthqTmAQP6Oa^y7h}#y=7!S0`6^c+{T<+ z;p2H5-J%hMZ@|8VpUEhCo_l$Q zsJ$!M8NUbiZQHgKd&2c-iGPRF@8J9;dPlVF6?1)K_X#22{AR(swNg)1zC3#K7Z=AM zeTy~|4CNfavkNDZ?PRAZOXfOZGnP<0Ndey2=?&TUQ)baSsCfr;6TRpyfcHG%ln$~A zO5n{Q{4{(%KE;?$BIij6`>sIE8vv}tzU^wa50zesTYV}?ST>^Eh~pw6F0OQjtP}d^ zu&&-_9e^6cL!930z%@gp<;3{%ydsfs=y@WR-{T*l0bdCiRn<^f(aQNqR|1bpI=uZo zuy2OmRzM8tNis@0nWM?cH(9cztCuUHc!$7uP{YV&X)^1e4)>#&N3l7KeG>sClk6R$ zddJc46wDiO?<;viUIFmv5qV0yC#kSo&%Eo}F&)Id)5#{H&s!SO5oUA}i{3(1)i^bP zN3d^SW#4_ob3GTa?~X^VEkcR7vW7RoW)-rM_ZD+*+udvvXeWTfZz2A#eSqI?ymo?t z653f1lnzGSIQVX$2iOsAnS|e;Y)e7cx0Zd2@GUDj-wpe=^&lp)Z#r6;9KM-=vcjQN z)P7B!d34W@E)hKn`G3!`$z`qce{jrLr=J6Ad-64 zb+LM4sOm`-+4W+ziZ)W3howsSZMiav#c!+X5fHY}cN&b`7`Be35Vu3tJp0{P_{J3b zWKb^oigu#YzJ*oXiXy~+AMD!>gE6LhGxSd50XN0zoE4G4Nyv%La3U$#0R*)U2jBP; z^H_8fDtoissvL4onBio$yVo0!S%S-ijp=*|vhT<#OFANt9fMEV{3aiX-y}F>IcK9f z$-RQhX{c^89xtDR^EuO~U@Bp?a-351=Iq-_s(n{({Vjy`OQwBW#3MNHJ(bgXXyMQE zkmek(o!AIoPq0&O(D%GJ_(rD(`28?^pLLD6`#+K3JKlO?xV0hmi7V%mQ1-pnh$r6% z`?f4Q9LHqYq!;iBMv5mZ>L6V44}^Sc?j#gWt(V`V94wveeJr{O)4okp2s<%%;@*#< z-kk&U#=3VPS&)HuoYVV`v+qfk8Os>ao608j2(Ms}euwKO!f>UuS{Y{*l!TMiTfyR) zRk7Olx{EM#&Dl4x1y;JTS}&SLFlGypCLaAfXe2P=qBR4PPUXm{gUNl_IN6d)%)QKQN6!RGyoo(3rhez z54%Zy&cmoAyU9GG=&cg(r6QOJUqqWtc0g_l-vRs%)4nS%#^@Sl-xk$Q`US6moZ$^d zNU`Ch?;@%m>pLN;@yW11D#801#*AGu_H86(-=4z0yGb%wTz7;ALBUT@O`&~%kL)`b zTqVYva3czV^5|JfdQH!i*|*6tyq9t!=cVC0T0}9AWX%%E+$N*lrWjIX?x>qQ?(Frx z!4vWiN~-sj0^V`L2?Ot^jB`4C%u?(0o)f!CJ!U{&Lh-OzLE<*iv+o4polW!>17qnw z@*ECj->!#2lTKY))bF<)z8#{8l?o0@LEaO%7FjObLhYmw2VHm)A5c`+?T)tbQ$AMJ z>u1rv3tT)&k^yLVZefHJ6xmq*hts}81{g*37L}78S&|HMfU_|lo@*i|#mbg%F|H(h zB*)t07DB#{1G-hIJ1}gSK{r8{+0K;=QncU$;@&6~ma5)~*!SHNX=R|m{gge^n`N6w z@I9}G+D(?p>?Q*7rdB~|NN1Wfm@1Rtt*~#g@-RyK?t4|QR)%2BohP0z&5Cca$PE`Y zk?1{W_}gSk1%lUpw`h3qc3V{}uU4yuhUY@(Nuh$K`DN#cp&U=0Cq;701ja$)=5`Ae zX$C%t_Wk`iPb`Ig6FREFZ{{a4bs^n7@wy)KePh;bu2@f+c3tpTwj%}aK+ZSSP0Sq) zC!*#(+l6{F;aiLrOeLK>VYeU&^q!=5dJCD}A9YhY^-!-MWZv_ot_p3+#^Z_Igc0xY z@;Nx9lM1|d7f-||Zlv~&d?a{*5ozCu)JjPocsvK41F#OUP&A$>CJ+gLY-uyH-_za>Mb{+@kH;b%)awW6->y!=@U5I z_YD9Mo1vNZjkJ?Ne{=>mq%xpoJ6zg>oZRJdBHsyt*RAhXT|ame&nxx&a^x(5W4D7H zhcaSz+)=;ZknkH#4-FdKj*I616AaD6Q-Ig0R=c%-CT8Ce+P8bz?YdpB`khE9s{Gwk za7)Yma7s$wTO&~$%Ey+lP8lS%=>CW6*i0<&O)DcG{9HK4#7&`n>zpUs(x%a9Yzp4@Lcl{u;)%L# zYS=f+e_gTFN~)gpbh?Q;jebnT+dNj`#L=Y1?xdSMW_O&3h7%g>ee>mu2;PZjEU|9F z(0kV+OWlBcm|1YSWTMGDq1|N4!cC+eooQ5)PNr0<#O&LW*mv10GBYsKzEKu9XWs_O zR0Z&C*oNWZn5wQpfSQ;|kS?uQTQm?}MY8c=SbBw6ftnlF-O`WBF zNJju~NiYfUZZ*j7m~<1$zK@Q2OYA${#EyPQeij|;{gB*nLb3$~uXkebrr{=8>?X|U zP2GYY!@#>9C3?q9>8SJZ&&qt|G}7svw!|_Ed=t2Cd$kjheOqLOQb?d8+IJNZ?1m?R z?2vm;NDeq=!Ex|yWArC{eO(N?1SNsQ5|1Cqd9g4MC9v9PcgX7o{CXgM9kJTwdE)8~ zV%WD%`zBk({Z7=As7&u35l}(`PAGQc@k+dgX@+v|BU-Xl3XhL<(K4&-9hM85xy|y6 zZ1={}H|u0bF=NTyf?2`^sccM8YuK##`F%&{wA} zyWl4)Z-OhbZlk>2stnun{=TK#nQPeJ1%7Mco5#q87`MfY?-j|ZGU+wVkW4}ADDm4o zLiBdTgxHh-KFic*naXg&gcH^xpAfupdHf{1)4NWs-eNFpJ&9QmdrkDCI{FEDvSz7_ z=|mg7cZ@bkx^#*8b`?ff!@z2`(}0z|1te?ZU~2$?@Ia3wTcg7|u3z(g!oHy`#lt&_ zwrxdRI39bW3fM}uK-_l+etQ{>;iD{&;{#l}ijG%82w~S{9~|G`xQPU4@Z*g7`UeC~ z1^)lzYdR&0`2R+EH1L0kY_9ixpto*vUi6=Y49&BESoY2gZ_?S%JWl4dOY0a_Zyr=- zIy-}RT$g3iF-scj{pD(MCFv%~hU9sR{8Oer9i>etjae{}(_5+_M!AAP>`vNYnWJ!` zXWz(B;-SE5VW$CuTn&WhMhAReG!S*>2ioFS1enp0@Me+lZIP@y)Etl68iKG0?^&s8 zk360{T-6Ckj!)>ou9ExLd;=Kn?Nv1=fsXDQqyHDY6_1*H$I|a4Q}V${cSZwdsVK1%t{7TCj{0y$Nz_ z=HpfJ9jABaOuRK?J6tWH&t#j9V+zl0{zMnzjszktiX`&&p%>~EuU0$Nsy541yEE+g zP(cJ8Z@k#?-~VPs1fL{L8f1>al}Sq(BG9{egyh>iKH0?Nb2{ek!pS3H-#Jk482FK%SS#Gw@cK_vtv^ZIVBDi|{QFFaD`5d=apRQ}D(-oKbXD*tXIFI1^Ot*X?lD z!9XBMYWxm!njE8IqKZbxhu+eHrMY`4!>)c4Io110n+zMrzFDl`B=d~ror2wgI-Q6% zo%uXLqPHNNjDg|wz&nn36D*HRg`J1;?lH|1 zL@Sn3GSxJCOh=z>@&e>rH#9FO;Fgwrs}OFBItss?0>N3(TfURmZ9njB%OQUm@tczG zm`(=kNLMb8YfvZSie-rEy}NEA#CoG#Scu&>6D|9WuCf%Vca~^D)~FM#(+M#Orj7Jo zk`CfPZG5ENM9nsN5%7*+-;p}FhJUNjt*lCBx>)hUny=eS(eGwb5nO)+9=F6i{QH6L zqnweaO*-bzjXFXw)sESMe8}(ZgR zNw7Zt^dN4N6zn?$wrxwaiG<;}w7&TQm)Gq@jDxmXkPr#oS@iK&(K{{m&cMBAk<>do zc;8UboA>Exq?4N@`6d~x-T~FSt}%MkJzCjhzSPRzLZY`6ZZc-cR8p=cV4#~#FI4an-1RO1KxHH7_1#2Wt*wrX`1kCMX{UN21CX! z@&AeTniue!n7Iz>M7*iZE6KL78TRK<#Z$e({Z%96 z_-bG|y~74&1J_wb@Ob(SY%^%~26qPb2R1lD>%tLW%{862l{INID5=;Q zpGv+2oV2sO+6;Fdx3ptYoGh{RJ&4~4eJWw-4KTN@xuOctQun}MWP%Ym)~{{Q#rKRr z5S!~(HQd`S0<3Rx`b-hn?znD8#qTD{@u`8k_Y4*8;SXTv?G|+M>XCnp8`Mc@_5SiO z(Uzelq23cLcuz8R$k&w)`9QkKJVG{!BHwD2j=p|azhJ4XSdLHk0^@}pfZGmVxQxG@ zmG{DCVA%5&#WPq2^{r_NK8ILSQml3AVlMrX4qk1qHq!04I$p`^*y^!E9IHO4sJAhz z-lzuPH2~jWzYq7T_}TUv4OivZhUfRo+rgmR_ln9bz&Ag0jTZoKGly(J+C)6d#p;dh zCRcK{U>fR8Wbcf@f^ik{TG5-Z?>TuV0k=L@P%g2QWbZie9-r=ufEV&(-a6-akbKKC zLH3JXUe`9$sU^~SLL`2NULV)@8!dc$ql(`Ne)G0lf*I+-%%~Rofvn3h7L$?!P z=9M!*nS-YRzcPaNqmXZa)cw9nvF)NqLf{7tm1)Btz^huhTD?uj*}X?Teo7~0wjjKS zl?-Xno4ULwcXt{4bnYm6hZw!2f9n~E)2K2L=;%Sfa5OY|`8Lp;e!zXP_E z7hvMT(xw$%)OI}V*XCl-ORrDb(hDd%uplhraC|Pe2D~{xPv$u>ywXrenCDB8ZfWRg zU>&B*Z#=shfbT)21h!3pv3LAo3BYkvUAF}L&j8B~;4XmszE@Sr_t^>j2K^y8byzA} zhY!@sN%f}aoeTBerOPtFyCHi2mI=H`h5Q{u@zhT5$V~5fRJzGrSI3~1>Bx!RqRE7j z@6#C7dp|3dIceXqv-Dx)o5QxMtK=(+TTDDw`G9+1wDM1H#+uR_EGa{fUtKw1mEhJ$pS3?46|=bg>OLn1CV}l zQdxIh-wz-)`T=r)Z^y~eZ$bo<*^VogO!b!iCO2t%Fk++7xKjItOo~_l$R4!_Q=MQ$v5F5l9eljTe=XMhzY3xmCm8T zCh8!_zIE`OnthiGmjJzk_oQLp&~AeEyM~T^_bV##+NZ1 zKsw2necQU|!mxxZJKTS`2UUC@9u;bJj|J7p5{tY*JWUAA%hcCI!*>SuJ#6UM_n=hU zY>Hmh(y(s?(~{z2T16kS?`FWYtz+Nd90PUrkq1r>fu+vu?AuXty>pzhB+HevU4#=U z--M#KI2fORded-|Nmi%#UAWyOJkmR?1ubI6axAY{hU+G3zR7-7la~-r5@Ng^r@GjR zIpqb>+)`O-j*~zMRO}cIoGq-&vIT8B(|@4-67U^;P$>KMQnK%p!FDhR+?A=YZ`8>E zAsg-=c?sFK?fJ0(bTAybo@z?5v$JnUqnqSWM9d5)JAk*4ZvsCjGnQ8Y@J&pPyW3>QhkFm`(`7SDYb7CJj}wV0s*}5 zR`X!r47-`jgcj!R*lT>W^Ef|gUk~~~=W2o24fNbpty{*uP6aHy58pkXU=MCQp z{ycJYo_MYX@HzVy=Ho@}I|2KKlln!^8pt>d3kLfl~CaybxswR9%DI?I#F@;nYkzv~kqV6TTB1l$-Wl_T5e=5T7Ej zZ!z73`@YR2?7NNPPQ32u1biFC_?>}$6Kgk*78HHn=8oXKyIYW1PJ+}sRT-L?3!7=k zGD`H0nz4*drjn@l^HkAGA|-E0G&$VX+8_J2qZTm}l5bmG+#MTzusmlrKfAW4$=n?GO4{@G^vTq&zChS{wn55LcJ8o$N z?%XXw_%1egW8bU;4OhsU;*k8VZo$WxY{7&>mPqi%E%LaBI2HRQCGvN7nPx1NCY@jf zF&4eUI*7Gy!D&di$#ncIXTgq1E>+x+&iIhneGv9-NAhet#fjkMW`2^EM_B5>O-L+^ z>h6~3mTc+&#FmJ)w9gj7JB`aS#t3A~_nkZawsv9PNIcOE+5Z)aCuUIl?(3#58T+=B zh*#u1NyxszDWE(U_DfLw-dX!*c+JRmCa?EwHVa|j8Jmb@tM`LcM4Y7z?Fo6kpVD@r zks-_QHk~;Q_SUUf#&i%%_#NodnMSML@`U9f)+}4(^7-@-;)xw0f=82Y{mQ2;g^C}F zjf>)QC`_t&s&~D|M)2A}_)YcV$BsXb9t-=ny+&!Rjk3~e-vc4@q^W1$L71-Tk^=SY zdr0r!-^qC*b}%SzL37twZx$^$%hl?QF*#|U4v!YhG9Vw5=pCY&NGq1}#71v96gDcD zN*5}4IOYxUyKulK>}~^`!I67A0x$Q+$<@~bI;~khuVia?t9xxd9>-YQt%Umb!RU7= z`>qyz*S5l(Ckp!(5(j1Y4q@MLHPS1%I@Hx^--cJKlm~-tx$g(g1nJnfBeCy{Zb7YC zaJDme6SE2NdQYy1aFU`74f{>fSLraLH}66VZPS_SMelhk&3ify!R`p~KD2DoBG3)C z)50+juk_^GjskpJ1xxL~_zTkSP#1e5@@>a4>HdoI=Yx{t@EVndj4kfpT6rE)(%sbjv$*T+KIVqzR9jV#F%y? z)%ynbS3<9M`bvfj=_Ykbz3GspcD<6c>D2Yidzo~^68Z#DDy&>SJdLeEV?LAdfp|B@ zZurILf^~G8odf+=39GGPnJ;J~kHlU(!u@V*mj|LIRTKO-*;)Qi_f5aU*tZoj14^7H zrV90*3oo#3hfl{_&2aV&`M0)YLGSy9WjmfG@r1JPX2KCmDci&}bI3R0r8-f%cfwF_ z`bO*~SLqrV$dKg|i8pylZT0?G4-Kc9hqdWY_C1f%O+@Mqk$Nd-!cwbXL|8a%QU8 zCSmM5Y|~C%!lp}f=fN$5?^{}_GxRcI*mXZUo%6q9l~vR|@R?oGFi!eg8GczMHV`lA8u; zxJiEO8^E+z&^c9-ux~7rh~i0>SXd|ADws(&k(oE?vb>>HmT5x0NxaGAF72WvHJgwT z%lgN8JrD{@G!uP~WsK-8Wx_sBd6SMXr8AAsggqGfCg6>M8)J8?b)@V&D*#36$)U1= zT=|n98@IwAO(KCLj(*!#=4ApaI$h=YQV=2zYn@%2HZ$4$2Db`yq)FG+fH&VVyV%Af^7^3Cf?R`f7W;HgV*|Ypvt%iPH<7$CcEfkyJ^M~VEA4Q0Y3uDC z@O7Hi1@lSu zX41)Qw-$Lkr2|8~Z?xbY>-3&v9FP}#EVT{t^N2o%xdy_gVRjRVc~7Ha1&<=on=9U@ z2*6t+`~JS+J30AIitX`N#Vv&Hhk}2X1 zJX&xU(VJ`D@WX@+S*idYn=FWRlS%dwOP$+p$ep?#)ZO5z3wsKXVq2lGx+s=o69~F4xWWkj1t<}CEd~X6vivU&A zvTq}deHSWyFEjg=QoYUHmn>)bq9pjZz<9nYu?~9JR+Z}3+?VsOcqQ& zY+2VQ3)bZoOMMgCG9=j~T=N!E1*dYXU}PP`>4B3?1l0s%cZ)!GE1rEf|0uBj^7MO; z=$aS(J_gk0kFV&D+-l;(O{-HFc^xYV-yQ#~pwlo6cT`IQ-+Pox zh~vO}d?@6`k%9!g$xqcqyZQZMxSe%ZX7a7maqNBmeBbw0h4t+zjyF8lYpZ{* zO$e{9RwJ>CV1F|Oe0K_7RdX7ExhJ~QL$m7X!&BrE`E0?kkz+cKyM}s`fD_utFwp^c zf@Hx-#z^luH+ly}?^K$%Hqjf`Sc>Q!-asrVCx--YLcGD{Gn7xLQILUmBKB=1Y`Xeh z>9_S#^xJ+>fXzz3kNcNYt+rDfZdyiFPNl+st1y;CJJb&L8>vRx!2{Bwv27UI{Z`2F zLP`~@)!DtuQckGKUPOFDVqtl}NgD8G$%0RJcNv>3??T#iNTy&tEZjt6I0?z~eqN51 z8nlF6ItQWOEzxU&**7-|GVuQ6EM4Y@>oEWv>rt`yhL*PVr{Bkl!&xCih~3f~B~5qvlE z0B=0)-qdmXrnvEi^(GmxB=Ak}+dLldX3aY0&OO9}@V&#DrC>Mt!mQqtFDZ&Fd8T)! zIUV9P`S1V!Z@yv)zM4y#Nj+h>$yD-rbK))AO{NjyCW>@&kp4<#yb`P3En&H`B^U-7 ze6wc*e#ZPcIr#1}h5ZLpzMIWvnm>hR%Hw11M{{3Ib>n}qrg{9jNw!TN>bm%9-9zX@@M4Y;t$q?p?54!LR4%SMw;*JDh!snm3Px>xh6U@HPi>}wcAhP#$)pe_1 zF;s_y!cx&YgnNscw=kqLj-=g3FkdN*SAPEdS@oK<0*Xl_e7|lv%Pz;c?iUB8X0K~ypf!#)=fS&^Z%2pMx_A>aKjs}Hnj}%ZsojKHy&+IvrN|W|E0qwypC(!2O}N?Q zy7=bZn|1XXg7-zcczgfOH7@2<^saLxUt-!l*VAssyyY?mNj4#?mT~iyhv;G;w3`?O z*?48E6@l78_tWGe!TY!oqs^|_Wi=UAMf3BPPmEUK}IY&coR0Q#0rX+Wl-$a z$tHm{%fkfH;0N|^hxe{5p`Uem~&zpI| zH zcT+;|UJrpcxbzT$_e}L~BWyj9d;Ic(Z=Ncm7flkNch&V8eXxx@SBf!ddv2`+ z_LpjI(dGxce!=b7J8ItCEVwiGe%vV+R>QoxSx~J(i|>%nlx~8V_Z_bwuFo$z0Ikoq zjncN^cHBz2)-V6h4dpL)wKJ`HhuF z1*6WilXI_DA^Xq3{^?SiDmabHgbmgYA4W70X5(9;%R3lu5(?id@Zxx7QV2JjdO{V0 zIyo#}y>7>{athZi!CwLda021r44-9bG1Ly;v}BME)w`ugzpP+txD5=_@L9j%afDXU z?bH2(62WWRtCh?B@-|httODJRN`RuG*yBt;g%l;4m`MV$Q{i|_(e(i0_^f$9@6wWF6{_59;>^C-Y+so&% ztedCwN@HxM&AU;=dS=y`Nj=-M5umYii;&t0Q8=PI90XT1GU9mK? z;CAGMd>(caO1w!dENLRXNrc}|yu~tAyda&hRGQGBIgr42qf{=e-=35%OXW?a^6mqK z?|I!Qpx@YV2v561zgj2oZ4@eKe+BL@`<;vNl8snO%zGMTHaVQnL^64!?G!Inwjy#( zBH?=lz#Abr=HI+wu=Fx?gPm|>hnUGigCP~11awis9KBcaZ4_Hpnw(NNT ztSbPtE4Ph`>q8(P0YKkejHl-w{DqVXRRgJ8{lfVa!S}U)hQ4eV=r`6cw4X^LtkQ!v z)#@f%(R;7>-J-nvl(KK#Y9ffkAvj-4G#__UWwD{8HnOn6|qqm6J zX~VtsPVZT6qBr8+O!Q73PKC3)S-i>9E*0`phvmiQ{>OKt?dWW~84YXwx3$U;IZvj` zaodN#v627#S0BD`s`za#)eL=M{0g3l*m3iP!JDUuM0j3AX9@g+z}Owf zz0vx&DJtaAw`iK7@SXqkV-;#7;1#%mwQklYYO4l9K>xp zj#$c&gVXzQ$9NMWdZQNN8=C2zB3bZ>m<4gLV1{&)dRQOB9Q(cj{T}(Hx3x{!)q}ddX{_dkm%le4n1<-&mo2?bqN5x7MhS1=&Pm;E6I}_pO<5$(yt9m{6)X z_!gKqdOl@bq_UDPUA=A^?0(7rsEFT4_$Z}m(m#xN9*q}I=#jCn<4ld08$|d@c{eS!L;Z5~oIiF&dT`71zTCRZbjplQ%eWY^v z1s{2d%C%~JtWWfgW8V7)@s=oglUx(Zz6Fn9YW1YRbW6ycdiZr~CUZfA0qhmO4>+|G z{R`25V`e^y|673I-9w8fOg*8vpO}90+r7kwHIqTVF+wJ98NQ+Y%p#j zEMl+tedzN*7@A?l=&0-s4-*v+u3i|)idl{71(v7#HV-{$Nx5`nBVF#sx|eT(-T@R)TNH zzQ@bwb2iR1VC;J=dQAeti2~l^!_HSy?K_y^-O38zoGO_FyAghyDfI4F_&#PyhLYso z$`lOTs&vABjS^!IlI9*{+C4S~3GNX_6FTBxB%}If9Q$sjvY0F!^loJ~ZNsqPJFvBl zwoP%}gmAbB;J00L8JkTDGuDknsUg}h@>+SVuSo6+%Mx)(3zrKL!R2PQ30l%?rxdQbrymSdK zb)!%N`~MH#|F&iYwF?K(kwqKUO@CW0i}`^H+q|^g@fmMc(5!6=Exa>CjV16YSa1u4PP^D$7jD;nq2P6j1xUaF{k~}X9{i2n zHqdYEoD5e!*V|AfuhrJjc>)cE5_ZSL3hrI@mU`n+sEL|svJ3O3@ZB?;;>%s~)Qh!$ zy=veGpwV&vg(0tmOh~;~rjq=sPDDn^+!(MR*ESbSaRXn1uS^+?n`%Z$*z#o>>g|Bj zgo(i0u|2<3@?5V}sq{;Q(g@=*K*Pms_VA#AZ_~1&o5bxxLqmg(Q)1&_-!&{Gj=%Lg zRtD9CV0JDg#E-KaL~qW#QHT5&R%CgTY{?SqCX;j{I)M>ODv{JR;EmC{UUlDn`0(z2 z4L-cPzkCDUyKmmzyXU9NDd5>(+l}fE-nxX1-lR)s{0xA7RQ;jY#q&Go&%(N8T(HR@ zcsK2hM`n}Ht)R(!H}cKdH-ApCx2!IdSM+{q_eg4|36_p~(r;8lzv;0I^cmipBnHJq zBf4}}01Ds47H%r%e=enH|Ax|!<^Y;cI#F>8^f++_Jh%=AtJ-XxbQv*=BQlNja= z6TLhC_T!Hqe*Ey}9eDrl%?I@U#}5#`m-T-b?eni!=S3f>TEz>}Aiumu`>#7bvhw?1 z$Ip73w~l#_4`4Nsn=7U1${m55mZebP0b@TxzB1wqc>l=)DFo? zqdI&_NBoprLk!+ThUsCyiL_EeNOezu?_9>>9Zd6AIICn>uB^M=%hI;AE)V@GCEpJc z`KF&4-rDs%K-ZD~yHMqh6z~dsyXoR9Najfz?k%iYn!9=hXOFYkAov-`BNu!7CR10`h-* z1{}GB^!vKAF8IZwSHS-7DhfOaHG0cU3%HD8;K5xpt2|$~QLN3I->O9}gP-96r zUakoHw!KDq(+4cNTiXuZTf)B0g)@`j+W|MgpLYDpu+-R;P>S7#FHj=M`=mT-RFI7! z&B~>wLMI36okyg%TBidCEfa$`9*|EhdIx4KHGUHryb1gMaQ`14{_Pzg;cqSh`@X-V z@NM}0VQI8EgTJ3a!@I`8g5zb|FAe*n#t3Cco_Xh|p(B=>9<;qTpq-wI&6O>wh9MX3 z&3xZY{$%68%|9j?rAr7guNa=v2-r+s<7-7=HwNY=H|&Y1Es}4Zo4|kH!wUAKD=C6q2;;qUH0K=>ZljT-lTgI7gMR2~oDTl9VR-A4Uc zH=}b<<}Iiu5T{RDasZ-0UB9AWZmNl59PCM{_)SwpZxOe50`ONfegWE@%!M!f7I`>{ z=spPw-_4#h1YnZ*STtdYdmJ2OLeZ>nt|SAYnLsiD0Jvha_e4|IA7~Z*@=3XTQh~{? zx0h?gzD*2^2)=1i0y3dEh<(#1{kFtQ(Vz;0LaPw0_r)vX6TL-~_wJeAv)Fi($E2FK z+@_Nz6qY!>pR!=L!n#$>d(I$Sgzt{~#gm=_;Z5quZ3?e`cg;iz;P)$< zzXW!Nz&Ab{(2f?h_iOk!R@u0nug}kPxboVs_3{3OTe}XTx4y*kFr)FOEDpAnt^h3+d{f5LL%Ff5 zo}i+LGtJE&o24^%Sk;ul=@p@KM(?PbC3EukOl3B*$xq*iaU*t&=H!3>#+xt&lorL0 zrtr6vY<+TtG!Fp4D{Y{k1HpLIUw1ESl~R8=99C+5wC0GR@f(s)W{$wc;rEB-!+y>8 zr9ydT2(Q(WHxoNfaL6(T&3l%SdCQ{r%@<+D@+u8@KS?W=nMLm~&3hie@8xp(-X*?0rtII*4rNZy?|egZ(PtwSiruQ=RVti6_qM@kn(tp-E=fw zS*~oo0C?lFG;>8Q1^9DGOX0e>v=(LVOu=8_`z45Xr28a60G0L&lVUPL?-fGt+3(-J z{r>HDq@nbfT0;I-R*n*4nGC>J$lSdO9glG!sM{US^^7VT+JR#`lzjul{ze$Mu#V|8 zq3zrAI)<%2469uQR{&JE(mjtiEv9CHQXzX>hV`I6WwNQ~Y%QgD*m>3tU(D@Zi& zx(eOPC3rt?dv2i!ewT#;IEQw?2M>Pr!^P=x`V4K~old9P{<=JU79s_gU)u)R|NI;h zDtM4+6O;xEP2R9~xb-=AoDSE%SJFjz_VfauHG9Hq;@$B3RSeG?yXDt5R)qQ;LC_=6 z9M4>?R+xwX{_y+5*KgkzGpeYF>yQgBil_5-F&%c6y=j~Ga>f*c&zPfI=ub{&lcIcpfwCC}dDJQu9>=f-keU_CI1-!?H zkWH}3`;?Bx3w*ovVqi|#w}{{LnIoY03I}G0qGoS53H)^}Gk^4M#@tQZDK{*ngyrBg z@zl-=$td5xK0y8r@f)UAi8?h*uwtnusSt9dMouBOAWEr1fVmPeT^6Jl2)-WyYJYn~ z)cXOTqHGb-HNvNgg(Vg88NyAnRmdmxoA6{oAr>}ag}h|+PD#D7)BB^oPG_#wya9Y8 z`n?pk=~VavO;;k|Ms!>4upCSF5-ou5cgeCP83iTw-Fk5nUSRew1-$Wk5i$8X$Zufs zQ1INW;IC+%3veev?*M+wY1{gML6yI+7Ci^AT+T3d&+rnaM8C6=Z^}FBfcP^s$PTZTOn>--wri~0YDJtaeXd_zk z1xq%hBO$k%30v1{-b+Nkm%(j1o&p>nFX;s#x!jvkdr+CxRJPtULcENN`R}G^3y!AJ>nI#^MUX9yE22yh^gdF#+96zFyaIb z?;yp5U^n~&QMD5%D{^z=H-%*=r@(i#!(C6F9jtxNWS|s0BJ#K-VEMB}8sg33XtQiD z8R^YLZ;ahnlQbii%;-JI)F2-wdJ~s-P&W~fTO{05!oR0vHXhCBJU`3WJ&kQa+rMnm zIwj+kpQ%w0)x@`6#N!ahu5O`&4(K9}ZK1hE$VNqLhe4yR{ebWW@n|CA@yc244ZZ z7u=U3cu-6srHFV`dIF()h3}jJ+)V7MkG-u)hAewxP-sPRt#_ z+oU=LUCJcr?aU$s4}!|UEy%vXeIaJPNUnKP>tasSd$#+4yg^mr%$k07yq6tNBei`!$w5ilU90lIv z1C7RG)ubf^nY5ITFACpy4BEkZ_exMq$W+}z-5k|}67U&fLf31?1I{b^j)QMj37Lod zP0j>zq0UOI$%zXFq$n-U@UXuYhm5+f(&tgB6FOurW<{kAii3`0%FC7%oe9HM1!{EL z1sS$s6neIpC9<9HyUdMvbJ2UYBl9K$@?VJPEimr{=sn?)-jn<^?>YnYpyo}WdoC?j zj>j0h$0X1D8HSq()O(sn^WJ-^An(voWRv|sH#H6dj@`rF5(%wm0pwo6U?FNk(QZ97 zy}1&nH_cc4-dQ~{d6Qkluw`;3M#Ar&qMMjzc%Q?2gxZ2hjkS2j%D7N zlBwo*Vt;(VDmd3@-gByX%fbo7?2C)~ax7ku0N zVBArC-cBCbRNN*w%UsBCLwPq;zR_ak)fag}CqCUI^?W=_^bYk3l5mr{cENHU6urmw z^J=Gk^*j~vd&)*Er=nT#G)y;M6QyqTn>y{zpo6T8<-J=y1EvqC22QsEsGWSM* zBhJngJIZx}xc9;lXf-hf&X@^=1#ZhzG=v|o1ng$=$pVesGa1Ga?`fwAfdk0EGk*1X>bI(NL?W`O<17C3d)mtp!bKOCi&8W$C0iWbT z7@dd^5QglwVHma@HFdHh6yh3kJJsQ~ecbS!L41mi0hi;qX)K}H3?{sarapHex!LuxGN0nJ;NZn6xlS`xEKyYQD^fBql0KYT^Ny=2qzLTNl2j}Kz^ z^5Xg**VkX`&j%>5gf{Qf&s;V6eAul3nYM#p`EsL)Fp!~`PnZW~v7$z?Mbm0miyhaK8Xe2HuOVP=J>v z8hM6vxNrjr*Yu8Va@wI$8jCkVLXtGy!(I-F0{E z8Fr5^aUzyx7u_}3cpN9hgtq7Uqf)7~ab1`_L=mX!g8RT**R68;UB!0+-@5A#N2aRR z#e3luMG1|ou3LlOq2Yl$qUi0hyMZ@w4e_4VwX;&`tmBG%(FPtX`2h}w-brqk`8(+W zRH+2~n-{n@MY0U$ zK)oOHN;jd@dm`FR60vX5E11P@@)4=tA9Z$F1yR_1B;ObzQys z+HluiyH1NMk-_`QZNoJ`b{OmH@ZPg7H9D3#czlLL4o!F!h3ZX)a54`03rGnTBAA(dBfk|~<1 z9$`0`hm2UxgXvVv=6w#~`=?)j{q?8951sXGp-?a`_+_l+0|mPybvWyR4O2NF4}g`?O}R>(fKShPFc zzrBCoEe*D{?!D)B&XIiu>nc6N9iji};kwG^KP=Cqg-0jl4NTg{AY!}nUcX;s$M z{iAn^8&m5^Gb}AOH2Or(s->!qRle}OijDOX=F_R_F{5TbCacUAlIPnI(VI7sQOBGB|q?2;Q@_{tS2j+7k(fjU+0{7D-ZHc8&r4uY;(01u8LsF?I zc0-rR~)usT#ZwD1a9T<;F!-3pBp7P#q{TezTN0u-V1#`%mu?k`BH5PxswUliy*p=;6ju z4&SC}tkM5}xjaB{*`XD=B76@hz~v2PK+`yPi^+pR&M9+bhiC^PuBJKkF@ zeA}IM1s{&Tfr!(#M=*bw7kuxyA{iEUf*Or6YFjZ&m8KrPb?iG|{7z!DcG#qhDN=Bv zoGe5^9Os!pO6^EZI1Z)J*iuD^_d>+hZ@dwcTUksNW+Hyr8NR96JKKzgRt`6r2YPfg^YPT>J=b729<8h!>svs+fBN;Ozg(_;WB6Yeet|W|1C(xH zPBpAmm%@UGRTBsQ8!ffB9Rt+9L|giX-xnw|F;U(JU+)#VxS_UYi2@9#s1O-Y@k_zQ;sy z1H!kkp8^@K2_KgF@S2*-Npr`Aa9kdF>q2AXd7P6s;GzHC@58@~EfY`LUI*OIcI2WK z)Uq$C=v9}zQ22X3@V&dABylxyCioV<6tBsr?H~@+g{etN{|0|+Gs>35DR`!3FC4M) zoxv~V-WaM`0wKXuhsiAh$>u|wWW|Ds71yot1%q?1e}>K&F$ zg_(E!e0-33qsw*Gy#?I+r`yY0|Lo$wJ`XpyRV;rm#}|GBP;bn>jU~_WuK$2uDGxUV z*B>kTs=%1&{{%mW$UmYUO=%_H1`CpTmtmPc0mHujx@?6TxMq5z5n#f`}g;k zwSNxR-S_W*`SdrhP2!83wpZJp42D|?zHJZcDHYfA5b5m$nk}&JxBlhYUAtY+VAzD% zce#f53*6X-=iz^DF5NELZ}a`N0lb0RsiIab?k;h=aDnymwlAq67@|vS&nrNt-SFBX zkN+q50S0-AC+Qo9iG`9Td|7(`cB(s0G8!+=@VxA5B@glD7)sPvkMRm}&3hiky!m|mvi^^TyS}}}+`BR=++!msr=m++Z~*f*PxKZh@o z2P3zAeGQG@`>A2TygN7>e;ncoBHWOyteAVyS#j`2@J+8F;Qj5};v0Mtwb$=Ixt9R5 zyEOpc?x*|9dqBT!{A_Q#;J<&+@Co}SbJkU_g0$^+)7xy3_)Vt$2z+;4*Q*MCaLT^B z$R}=_GW*^(F7bZR1qi;uwsr}9+@9#yZdxX|;M2#@?J#c%6mzz|XJe^{i{Idc0=~mw z1Al-}_RW_I6{~d)-8opzwp4~K-u3R^MUEBR`^J19ro+c<7S!m+c=CdqM;0t{3UTpo zCvH=wVC8^)4=UjJh9}y-JMbHnYtUIf@?F_T0ysPRu7fkmvB8cFdWqJt@mgpFyn0~k zmhcDY`hzg`9p%loUVtPw1H3*@_-^hWz$MOW3PbJ=Q?BJ1OkqTacu5`}zRiT`dQ8mu zLM4^Ig%iOn28_)-H1GIC?_@@Awq^-9clsL3Ct4t%F<0r0n#@9w2{eahP7>*wd!MfiLa*f)UhAD}B?=-1%0-iJ<=7x$U~@W#BmC8{T_;{b0w zw!X25we7>)!uwms@R8I()H{tlF|k>U>Sy;M-}8-JIwS0p?h!1rH~Ylgu$ z7sc1;<-lc4t9`$Sh_Uz0JoHB8WDLF?ofxPbxg`G&<5u`SIJMt&8JYdh$ zja%36^bz;&-u`9%!`D;VAOC!MdQogp?VC2~)H_J|L{IKPc~mf#FDZGGM8VIWMszUE?Yl^7 z7PRkP1q7GvMkkpfRVCGZ1i+4r9cxK}T0JaL2^6U6|cPGKtS`;kmgVhw!ZpphJe>v%S2 zCK$eDoA^R0bjTaLA9qYQVS(Q8vn#1gCs`fCgsoVn*SzOpPQehP_fp7&Rf%_yc|&jD zvVKvoUsP}Xex-k18F}5y|NqyY)<0Z4vt*NJ4Byy!Lbi+I|I5w7C)Z*Rl*Z)=QA+g|PMwv6rLa4E7);kbqeF7Y+85zs_R zjCe2b?uq|gVc+-%aPj%4()HSZ9QaOE_`V1I#N-_e3+fz^`-p}7DpW^|wQoYc`5-*} z`Vr4oKEPLpWRX&YZ)MbHw`~?ygf zL}1^EnD_Mg!l)VTjeqM_{%dH|3b&Vk`Ss_Y|7G2{V)OA3zM1w-l1=a~@C3#~8biPI z{6bz6Dbu9IE=QwzlM{=?zGrB`hhX$fWZyHUfuqm9Euehz@C}M5m)%c-_6`2QK}xgf z6#?pS}j9AEG_B>yMZp-0HZ#@4AIe<%AeRNT_TT@2^z` zc*U_vQ5}ARO09sLErXFOnol}Vj~8b&O)Q?g^#u0aWd6g!=(gL%>>GL+zi;?9wfzgx z*t+6bz}UAGK=ewPa}Fu%sVl7W9TMslc(Ln zO%%<0t`9d^1`%B6HW8Y1mYX*p-dw(WSE%&;jo$Q z?h=Y8xA(uizkL76EjCduRY_2(u-9aT;Txju$ZK03GE^7nqGr=>+qP+1*nSPidB}Vq z+|R~qD$FNt**5YEV$B??AEw|u@jY@yNo3!6Ad|ZWks1!w9Vn+5EuvS`zgKV{jq)* zI$=4l2jje1e|(tNWXgy)q};4Y=XBY*|Bw62cOTvq)|cI`+bFIf_x|bEpa1oLU6U4u z=ZhLzm8uEsdx@4Vhu-M4U4YyyNBEX=O@u_j))B2$a?ym0f3_s{JrlHV@ogcmZBk5s zSXJHkaP9Ja*C*QdC#apQR)l?v=vTB6Ca|#`15M2%m`3Q*?jZlR-6;$y`^Mqm9nXXN zF|0#vgT#Y(u&ujFjNDb6`(dHm!>Fn%n!*>yaBOdb^%OBautS`T2L1*kg3>l(-+K7o z(Z8`LvMoNYtS%E2M2UbJ%P2`ylTOi&Hz(2PNA?uYYfXnDjrr~Dio(I7D-UVE{ym0{!|Kxhj z*~(coi-l4jZ55QndIqCm;d38L6hq(jkPHoIxM^3bZL3-IY6aKxJQw<~q4rIHr{mRp zw7-KrBSciOs&v0k;2!(On^hEO*a!DdWtyfOVKVeQ%M^1>5ZhnlHOehXRe{bK@&llV zl*)+fFaN0ymizk&@twJ0oZO``szxFoea%tmlP!{+QWmcj7 zNpL*hUq&1l5=*P-56k_H-#J6@x`7%A_K$lFWF@Sjwa#IoLrHU!m{Q2~L74j1)9=c}uJ(>3Fw3V&p|uB~2pE1l5zI@J%fLMBj$7+bgN6s3g?eff=i@(msE+tuWXS_fyuUMSG-MSyZAHV}sNpfTD#+ocIjFq}~0{UtGY z^F;4S`X0;Za1*WOJ*R2j;i-a>+e9d_JYAlzFFyeMzP#)fuK~Q*dxm@a)2~0>!UhI7 zG+(S$h84W(RH-yrFT=S9CC%+wZG@hzg?8>y-pcZ1>zG6nyjqE7h*~5Ku|Ow`Ljhd& zf;+ON(yIde{&WwCZpnTB-gS)?zKa#Avos73!#Awk!LPqbir)Z96R^jjQyZ2W#Wof; z@NTGYkf*SPFqiB{hHVq7Bqq-9ru+NUCyuP$L-q}}P$(e-I)r?eMG+g)?2dT65M78f zQVg#+z(0UxT4^iP4)h-edOdFx++&>dijT?7`WB zdkDb>*lYLxeb;|m>B3l&Hd)u4;U+={`@Dy473R>w_W2cT$>H(cMY{=?FiW0M(N{HTxfjBJFl`eLQy}`mlXdqrnpGSyZky!DMcZJxmv>b^^xATH!J5J1*0fm@2 zVpg|Exvze^02e^Be?uq^KAAxLhUk6q^b`W$l3OtKqGd>jCDy!Wk2{8&&_wTtFB-Q= z41kkF@AOkTbFn{OTVkmby;&8SK2>n}%%Z6v`IP)UATPn?mqwnM`Aa`Zv&RS zATi__CJT!2?Nj(ZZ5P-T+fkwYyt`(CL#aL=qts1#cZ(}0h<%gC4&M~^jcZI~`Glm# z3PbgxD`nA!NvxNC;j-&hZNX=VUx!z{vwpt;$@BtTAWXDfuU`hVdGPiOqA@t4RPs9j zMQeEX|EX-&MVmc`0e{E)x0QxVhk2UN+fwKc(SA5fZ?KRN=v}E*w&(_%HJ{G`G#knB zz8ZtVj~{N<9b0jCTj1g0A0QsQ#ihMw`gKZ**-fErvMD)M!Wq74#j7i3V)qCE*A)Wr z)j^|L*m$_X7yzUPIkG`^`>4U#6!6>i z{|ffkT$qHy010*v`!&43C@32iG>W_A3aKI9hH`w@GsJ~UEOWbVZ3B)kz^E+o3KJR0 z*WI<4p_SThlEUO?V(eB(b~FAvSg8kf5V>~Zn#)!%#k;xK9fj}Q_TZnu<@3^>C9QK5JCB8ygFL?#<h0ol4fc^l`3H&wH?sZ6sFbMz{rx*e}0nj#-&YKcx4NpXrWDe{|UqA48* zHz=jaI#H0;$=Ji=FpGDD`t6vGQcyV)fb@}Q-dI0@y!+w_UY>q?f^rJP@(E?%j}Kfs zk%CSZJDW}N@Okt4cnIFVg}F`QnRl8{!H_DQc^r82Y?B1o&CMnvc+;Wy=jC;~TC5r8 z_2*MOsPp_RNFmQx|2RLt?)T2G&(F`LU~ho?9p5kh(7syk9BguWDjM;QYqT=p5~PAR zMsBhdoP{GL4I(96*ufCl30#D+o*AFA7a~+3e#88HVHgOFbwaub0Fe_xy7p$-5Xzfs z@CMwCju(VriyRKFfS-w)2e|>f!c>vEX{qRKnN4~}!RvTm0u!Pma5j9pJiw@P+^lQ_ zc;%#X`8lGoP(|DrA|1}YL+~3%ZqG#Kjf1+GfsiwAz_=lFV+6lI;0-=N?HfX@XaNuC zCE493i3W8N)iK;K%gIEXk52~P#A-6h&>v5D_eY)RO~6~9ZKB#ura|}?CM+3tPet^G z{QCkx^Y!wXW>n!VL3R9c2_E4x2b1^dXE~Irbv*hv*Sfh$kV__ndTZcYV9$;;rV|8k zcKmE14cJQ=SSyF;gj2iW0#%|2!yw7S?gaX4F*GC{y&`^NPz%s(Q;*Og$BP<@;u;ii zc$F#PNzp}`kw@*r=MgJYYXDl9uu13kc0}mrp9tLz3l%m|X%2@|$?g3chHXT^A$CJ0 z1-S{CQCzg0EYd{{hRx_a&UTI!WU4nx^cIJ7lDSQAfjpH>vQ+7$&GXi&CZSG2VXZO% z-iUxN>&s_~*m~T~Ig*OvH&sneKkE|(kHaM>iYA13GXSUTd&b$e=r(bb@b4h^#!H-R zga@TBf1@;9u(3!nv@|#+p_3RUZmcv?uMFd|)xrvC`NcqN=F?ZHKgHyw6bDZe2TkUt zU`vbObw$IblT=CJu_nrRr72wDsMI^yog*w`USSW)1%YnHz8~cI%M6i&aWgu*R_Wjh zOFm+m#%*#(?Ivl4$=VXU2&wC!~^X9o!OCD_^3nwyoGqycW#<}xCZbrO6Ge?KS zyjw?t-L%kN)Vn3*Ch$$F1O+f&D9e=sWUC0yRFelD6U6sw!c)kp0Cuy{{^@>)vG47HlD-ycwg9!jDn;?C!m@fN0?yH;mwySsbxlh?*(Bu3rW7#KsN($ zg{|Y~(6(pi;SK{-^j(C%pupm#1gsFf;o>EB3vvLT2-N#g4LsS&DM%w>clUX7=KX~%S>7ad zo6vBRyY%5EQL%#a(E4~nyCo2xYM8e~y){dg9K2}-+MWPh$~8G{eHOv{NMsW##J8x! zn;RS@k|pp;MTG8X}62cz*d2$td4u!8uMm{zDzo^euOHT9YpplEp^2 z@`zZiC1@-XSGU9uQo%ddYGFM80PKk~zGhzlXeTpV@vfRh9BfB%6qzNkLdpobV^Zi|kV-VX zlU}C=xyoV*`%>iIc=i%pCIq~no+iHu@ck$jUG6eo$uT>xJa5r$BDPq@Q12%kZh|m- zk}8=>DUa7`-gBMXBqGmStwEcL$UTh&@8o8aT-z&U;(b)pIn-(*Xg!p7hr#zueVMx8 z72OhsYlrD)I`GDARkO!$0&sIN1zC=f&)h`s;OgWmv;4gia9RpU*CM(li!hk9TSwCM zyC?AkA)vgL$v$$#c0x38sd;!I$Rwr~y&a`gJ{(&g9xf)oVFx&J5CSF+-X!*|@b<+n z%sZ|HEnSHve23O6QGdKr#c&fZn@qB_SmJaOO^fB6I!+R}O+@r&X2G#6n@n}0w@keE zjom!gzO0_15xmV(7?mBlWzig3(ptvz9eTjH5B3x zX!tL%CU&$N)1qmfiD~{>0Nh!KY6tg@IAX<_6I#KebP%(ucLLl5#AV*C8H-#<*!oD< zE#VLkf^n>&TruAXnT(w67Ai=Y_YSg&Z1ldtfP1`Ox5?*Vd*!h-=*Xj$qGl5Gcx&Ms)|V)&m$HC@ z*D5iJ3*BktFZ&zAZ-(BAO;9>1a8nE3ApJJc$bJZZJ0vzK8(;i*8)W|Ekoqs0y z4^GE3uL$vtkRoBCsW_qLL$NiU951kMR*1F;b(|~|J>wfJNSol?K_Yx#aM#J>>~WR` zzGt&p))utK#AXvTp(8ixBnEG4@_xEYp6D&xy!9oPAq$p4w~1yteo0z%_fyKF zXf><|?~+E&C6@(Ex})%o+FVSWg`$zVQD*=YSy1Jrom8xVL-1`|gS%)y8nYMo%JY{h zPQUVW&EO65nh@k=f=b*umZ{s^aO~fq0mO2t258>!Pv%uu)g*b2{fVha?3(lw)to{USzxU41&ld|->Q85O&tdc*K+9@- z@fcVGmCKG{Jx^EI);LNQJcFB6kME{sJE-IVUbXfcqfx_mJzLUPnlN<|Y+hT$Rc|oIyFT9U@%<@JVKAON; zFpok@yo%rOh{p#RzQqOybqgE$Nf!u96z`oi?+21?Lc18QCP4s??my>*pcq?(ROren4E04n_NXBzyli+Cz@CI8U@HZEH;smgp ze2p#NJ($k=xA*VggAbkaAOl}WYn`@N>sR=;@!B&qE4>o0fSn4&F$`;uX`jMiTf((H zY-@XdA0N+A7aZ>Q(c!Si!4}ZlCB+ZrlFMP*s=8f^-@OA);1ApflW8W*<5NiT%2Q9i(UYz1x$i&y^2_^Ap8$q`dXMn?+rw<8S`6va zNP+JPfNx|YbPN%`OK#giAsglj++wrE^`ryXPTF)#R)21|xcP1%z_(po3)RC7m&z&@ zfqJxmfGUiG@V)hm7QZ8RRQ|v0z58!k*_tg1vew?B1?tL4+6fOGU|GS+q0m0k25xby zf7sh9A@Ku_s&&(?xB|^O2=GPLF(k6wNvd@J^*g`sn~!g zCsp)jA)WO%8?kIAg>-IG^*k`I8RMSyP+5s>?8Z!<8`+n8|2d7gj!*3(L2h%*?Hwnn$3GI`@DIvNg=fm_VBzLJ7B3%&}yZ6dxg_pwzb(J15zD1EnScAA|M~s*0>J^k#pV0&1q;vrm-Rz<=lY3! z4bThVI#@|pIkE5iw`9xKrm~YU2qZ7>zX$4Fd;Y1S#1kOj0$V@a7cKaHjvC2_e(iNF zhcsM@-_Jex3t#rf0+!#Sx}LY#_gnOdGut2x(+fiW{tv~zA4@i2mrp8SDNiIAIa{wOs88-ZGn$5{}PUDoD?yn*>5K zDAV?C{Pu0X@%BI8e*Znd`1faLjW2KCjz6iX6aFJ-i{XT!A9CZ9l{AhaeE(Yf>ihR! z1o*0ht=H%yd6m2OeZO&bhBk4`hTIN79r?xop4hj<-O6*6zF*~PCv+BCl)$cFef%e~ zxV*RF`-8Z9*sUKh{2qu00%w0L_I=V?-Qn*+@&6zR~#Xo7?RG=b!oW{vnF&_ z-{QPdQEwTs?8sKZfc1H&nN3LZ-reRMU5`&btTb(~v8{skf#qz@*W*(QVUKDQR7|&f z^;EnjIu>uRn*nzQ2%k9>6C&Pohj?NvS4(3rxub7wd5S63a6!fw&->rszxvQW`|=;4 z9RG(v@0aiU-{;N)>g)V8807PV{9y2o0XV*VhY|-EOteFVP!-+X?;B@`-+=5y(_g*< z!}hPQzMj=oH_D&9oS@~ezPu&)KCh?~N(IgmzTXZMe9IHd=Vt)$@84SRjeqfnqK)6L zB~$++9bG;$_tr<3$)THN1i96RTL`+0uxERu!Ekr^cP2&Sndk6GS?U>pJNM|~CcgiCmZqC2;U;g=*mml;6cx>ZKUZD48vH7oj|H~IV zs2rbfHayTQu)6gNxwy5Zocq3Cem%>}(v@>$&H5b;FoYuj<`6;lGzodSm)uw4 zMsH{2KEWu+^6?K_K{KMac;3inlU>kzuNkx^AJfsANklejW}2{coL7G4oq~zzZI&1g zE_~}=6EX^3S-mEYZSppWcs&(g*x6}Pa1(F%w{Ong4F-c;?1NDRZnO2eRJeVoxXR+L z_7=T$>;hKnFZl%)=%4q$zQ;>3mxm_(js9ys;W;9}A~%G$F z*M_rBdI0{s5By!wWeMMd*8~oleOJQlyA{K}YiA$y-}`4PcKJtu@94(a<9!)&Y)9`9 z$C{p2G4Sm;Xtc3C!o4MlPrRq)QgM^LRg)<7HW{7H^^VjVG;c~;2Kz7RL$QqVcZCo{mHt5v%CK|*#2pSe^MshA*k|LwQ)cg>H3K|aU7Guh9B z_3bJs_cHR+CGh_7aMFB|vj@}vLjhsN8p=hPvj6FR@%kN*p{zcm3Lpc(MjM*sCv z2Ygq`*szA<1D%<`1 z$v|n}uL-`DCN9~xhU9$z{;T-fzrF_qe|a{xT2g+$@Eut;du+Y?B&%X_idt=i;TrQoD&ue|p8+&J8Um{`- zsB!#t|0^6h=FY}v_kR_4^|eo@ns^s4U%h|-3O@Y9`vwGk#1pY>LDGqR|57C9NkuzS z6#LeY{HJ`s?};bU-W!&B^81Bv)2{u<+Dv+wdyt5rOw+7>BMW^&Mk(m>(J79Txs>e#??|C zGhE3|E2-Cn3nh=z5p`^p}y+}CI_=YsdFJ^zR&iUz(lU`uB=T<>h;`6IUw;;JCx zJRKo{aq#TzTd)lN8@LDm{`T#E{{5}Y?Q{lxUp7$XYMnLR9sbago(--+kYeQDxw<`n z{_fqUcNnh$`b?z!9Ufi2Ivan&cL00?O1~c8zx=aRo^qCl;;YI4*}8yf0li=xoDduf z_=aBtf4w)xK~`?^{P~~$^t=yoorr?5~ zK|b&Q=ihZ~=kE~P`FrndAm904wX?ThzP$bNA78w4-J%b2Isz-W2JaZXe_iux&{v45 zNr9LHB4wY@IQa73TWR=)pY4;H?w?}iDHSjpex*av=i|O$>;KS;)_h)D0@%Rk;0w-tB@5HB{ zuWm86^ULIn-tn^0C)aTPZ1Uk1KEZvxgyz{3iunL)|Kfk~&c2e-n^c6?H4Ix8-%@D) zr4G|S@892_^}R8PC%@*#tV#AQD(ioK{~zDKeUb!R;WevneR=?HMDJB5Sk3fNEF9^O z_LdpI+ht_gqthgi(HyyeMtb+9YXU80!gA+U!6p;EN%D4U-i{$1hvsdtTNCg3%%yp! ztmqseqJtw0g{yFt_oHSj<*6wVZ>D!YOz>7}cj2b_Zg3vKZUx`^XGVX6;_&N+9?6Ej zcX1U~uye%Y*JHb~>hDll#SLIc4ag38O=JD>VrKfIdU_wOeku(-AV z?%lY5-yi(%d=5YQYrlbddA~+wD9=5pMgdS{o{h1JP~bX#{L8Or{$HhRO&CW; zl$XA|pR?L)rH>R}zW>_qkBig|tDPtLGceA){4+`HXWsKCsgP7c$AVAui~N)b-kEUS zwH|DvtXunz-;Gb0j!yt?%VvU1TQTt9GGV{+GIdA?-GVz!SgKONpJS^{+-8$x)x_=; zv|0rd`(S5BidO>f#vKNO*pFUFWzH(QU9%M5-LnNYa#Z;nAayP8f^X$4VRjQ39+uNn z%cw&Du)Do!2PlItqlK}Nv(AqA3_bqc>D*Euw*XfDJK-JZ;lI3m`Rgy_-^(v*_wPUW z-Z|xV#Jk|-uV2q(ZvNzXz6SLuV=@lD&A*lmk3{Z2|N8P5`ZWNRSb!jcWwZNfXz3f3 zoL^t!%|PyTc}o7vE2GUYvE_*=CKiN0vavhi%XE7E_Pyvb*N|vp`%auNzBERaoh9#U zh2DZ+qtJ~fl(NbjgYf~u_YQ5|O7h-K^KP1EDxTA6CRdw~t~vIE9%Ym&z^v25;AyqAFOxFgw)^K=lMZC{*q(!#7+JSt6kGOm8 zz3l;ji;J9V;8KhHBz+Ewe!?O(YrosD54|-b3xEDaaNT#S@z-BL0>7)7JkKx1FEu^a zLZF3Y8)G{aU4>FqL7!j!v%IXf6SsfSw?hNgYYpElF64jF{S%BlbH9V@tAZ1YB0IH z4$$FE4wF!gcQ&_)9MaiE^EPf1E2NWQNGH-tthlmW}xF?QpxhWauta&ZqPI*b`6V{NQ%6h~PKgADwk}1p2Q(jX||O8^1HkH{MJB zEZ3M6Tdl9TGXdI*JJ`_l2I5!7`S|R9(kj9`YOhrST5jA{UPFKQ85}HX5-I@s-p7x} z>MICuVnY&)V8ZQw-`XCAO*CKp#eU;UpGPjm-F%VVZyxvFh2}j7}J5{`CC$;JMq`{U>~S%tOgrwF!J%;mG~TaPi6$1@9Bx3%j`E0^LsMm-Z|} z0!_9=?bR~0y|8jC-m%~4pUFtl%wi+u<{r{lCq@AS-gqkIMy;9B-t| z0pEO`D0mZdmegCm&-#!~=)!JC2*$rAkY}Ibe#G0IPFyTsTUOwU(XN$cbT|3dbU9n- z7P6!*)mMuj?u?c^t^5r^Hw{x5%6-d5BDLZB$p(q&zvVVkPL<~Lw$3!AAfo6q;|uZV z%`uuKbav28uA@)a(rbdeI{=qpz{{vY>^n%FuteEpzdG-q$!_9auxz^8yb}VJ){IVw zct3ubw*hahRfII}?&AvHYH#?Vhm``n3x%8Zd1mlt;t6Wp1mJ+N#usQKDcrtp2NHv$ zNJ}i+yzFrJ-T+`j4v0uNX)v82dOvq}Z1+&=H61mWe8+zHZ`o@ExlanaZ&w=4!y_%r zl?8W|rLXdY0yTD$UIOhB)IIe`uoJ|icStH( z?V8Ndlv_ZwJsRJU#2d~l74bF~g7S6>^A429J9DKV+pug}^gFE)R;Mft{hqTY$BvG@ zq~pxS&ko-P+cmu=g@Vy49{ae`gmaL3e~Sih=@9(*TUO1aCSTOxg=F6nzL9>nLC#Z> zxOD*84wPds1ki}tK}X(Ahgi0j(?K#P(R_`VEzdvK?Z8sW7tDyV)W0+E9lBuj&OJe1 z(bJf>IH72ia0cJYRY+*4JW543dG|s(1SNJ8fM158o1~NEfThIlozE*1 zs!igCbhh!^@sV&mPgo`dERWbqMXJdaUtxH}N?1Le!eQd3k z6W~qw9Z28}HX6`7bVHkP8(xcVJ`g?vTVF9JlScCxNrGWVMO5 zj6180tAbrw(w+D=fN#LXrcDUh4&=KW>^l{}(=zdw@TB^_7W}>df6~Z1PrNfB#m7R=#ESERm8@6nM-R!{a&`e-= zVK5l%0^7AbuDR#oMJ>0cZ!F-*ihqM^u&sc&Esfsm^^^?X@?~2ed3KcB5abnk(I=I3 z_Slx6Ng_D@R*(c-{*I8yZwNUlD0mMYrJl%zd-JH8vF}^Wzb%azv16&wJIqs`D*cwq zvFnSBk?t!`=|6`*T8Kn;-0AsBI2maJDl&ovekaODf$(QzRB*TOy-%Tup2|^U3vd;j z-7=dKm_v1z5 zjoy7_cX)RnK)dI1H0Qjw1M4Q>ChY{p6NAZQH<92StU<5d$ak{u7A=FUjS?=&H+`sh zG5}6LaO%)gLN^lbHZpSh^Z>~f-h~w1%`XNm)2yg|<&Giwg1Jx(0k;qNSdU$ZeLvBN zxqMVmiGjsi7YkR52v6kU!-=V3iE!-*d{eG!<*JUgxOYIJ8=bDxw`-#Iz5m=WG*6+- zO*JO6f(i~QuL-6*mbfjiwvz#Ts^=JX>7`;DmeUyUZaQQW#=37D*uCYwRG;Uegk?gv z$-%K(`llK3HsJlpTk+OmWk&FxB@}q$^ZAa73B3U5#>$Xdjxf2Y*fCOWt#rV}e5-8f zV|~Z3=%K(+-8`4 zSGWvbk;7ct@NmmePXf%7^lWe>whWTD=G^irX5{VutlRW1Dn}Jz1YbK^xx;VJKz-W< zv9`fIz?+PMqYk5hI`J|}c(r`WuaZ|^-GKaJaBXvQ2?#u^3Zx|PZ>Z;N~< zETA1BrPBr6MgX_^1iO!QWXZPTU2F0C8cp!2-5%_ub<6Y0n$*1k!gE|hW9kTDbklL6 zkD0FR8v^su^t)gqpU^wfmaaqce=mrA%d<;j?uwYB+=8FCG1fv!#_yDfYH}bP1#Zcv zb{l@=j+Is+8!>>Ps9P`!W^3vBf(u`|-Pt$4}!V@1}b@URT1p zGdesSZ)5j7egy3}oq}D{oK7iGbycgM7K}aZCOolo|0ZD-mOn5<-ufo7uIdsymue4|G4p3n6u+goQ`rN&UG!UncRTc;5O@VZqSjV2vu|fKUc>jL z9v4>3`;v#?<1T6VEyI=TUE=XZ@wS-vjom5e7}C+$eUsQJI48HsJSiN1)H3g`_L^X$ zpatHK;x)1K?rxzF@_6shyTK{=LsrG4W{KW41>f`mBVym{W`@f;beR%XEBtQS$D0zW zxrDOT=97*zk7KurEWrY;+}KqF+G{O^^<@#J>&-O{;GlvSGvRWn0fN~0GLrZ+aX=^o ze`?^Z&@h}~eEKOJ3yGtJu$A~rRQ&FsMb$=a@iayBmQzr&r6;p?;>gBdvgw=+9aI|8 z=)S1KprjM0-$T3SKZf}qi3(Dso;&Jg6Q%N_VAkQsCm1+#~`x*-fSqQGDxq zW3A3O73tO}9Vj41Q_7lwds}}*N3v~wBe__R&f9&4(i0v!E325YJ4bfj2J|O_-}>Co zmt$<~!%lp6>PDa5iCV5{y zCh@if?{J6rKB5WJOy=9>Z-dNgca2LYl6Du17X;o!y~UdZ--xzT{WIbc!q=LFE1cds zP@8e_HFL5U7A3_L!?)M=D>9^@Sw&_w@kf>n2<;83EcDae)+X_#6uWPEisus<2rWf? z$?#kJMBk|_{ZlD;Qra=T{-hl;Pt>6vt*2UPODFwbVfsk|e6#CIr)?0w2gC!!=~NSl zknbcNzLRRHhyFON)T%bIC2yzC+l-*OG;eo0 zexB~~o*k)A5LA;w*yP=PbisR<4(~MR2F>JrkTsi=HwTv5;w`ZH;-V;F8=?FCMRAl1 zxXVPFxnlsFVYgc|;qO?hC$6244cy2ulZM24$#mhk1CnE3yRYQlZu%v++jG-b0JECOv4H0TX~A#!K-yFyPw{zvAeKszss16mz-OjPAa#cfbM4+ zyNlw_`wQUVlY9iVW zt`qj_^D7j^rF?=`M5CnOgo72KzfDY!Seq}Eq&)gj{U)Xiwo-ZWsC{DBlH1f9VSFiv zZ&tBtcf>Rp+R^FIulniQ`bCZp!35kc0tbFa&N1U`-g-ah8jaqUYHHXVRN|w)fLOl< zaH8LIH9_)5r}ugn0GB53*nFj<%3C`HBf?3-fTb0&jQ5%x7Q2<+&5+Y#!QICYyt@&> zJHwHs`UM!ny9=}C59i5q!v?O|S*7s{=7DElT*#{ewl5I6^OF|BxBcVMOd{TC9+fQz z_B99awPf~S{6^29j{C^tOIabST#4qhBnxk1J&H6NE~qm_x(g#^ND8$9U~ctfK*bVS zO>K%cdptH^@<{yC2X6V>j)&uyp~Xq3@NNB?typCz;R(x)JlvkH=@FW_P+NmjKMBEk zVw*P(>Y(C%Y2rEBVM4mK25;m1lh>w!Lq8!@-z#5fnY?eLu{(J?-Z%wsQU)xyj`PZ- z4YVUHpn={EIN7zQD<9*y(g@yHyLEWaBz(uXOy&Z+fp-tG+XV9xx(U%yGLeEeVRsQ( z_hd2=x0H)HB~b)z38dj8%Lw-lBRi4gC@l}4aVpW0jv;k73jEb;H3YFSvPqNMew#$T zu~TJ@@QrL;7t@C6^{rA+m`5;tOh!4tiq7pkh1$NS&$#Vw7XIjFnE|{jq1(c7c?)pq z7_qI6J_2)sLPM+@m-=nJnGlUf=B+xsNj0(jforCdtk=f)$8JtAoUEriY2JE9XUd&| zX>HyJ-Z$IW4K(gHv1W8KoLC+Zz)@31=r-*8>d`WmMlX?lRGA&#X}QX62jp(?G{~BW z*Hwbj9|(Z`z9^;ci;FknYO$4XwFL2&@6PE7oy|u1_?qiboN}EQ=V^j8sczp!%_x?6 z1y3)DeK(mRE=`4js*+VLEQXn{rDopLzW~+|Ct+yHp<dst0L9{Tveqb8;X&B^RBe$&}9g}Q$}=y4Y z=X0_;*=${QRK+)ZE62#;X%e_O$CRN=j^J&pf>vwZAf_*4D>Z4*K9qY<4fwl zf~<%oqL}_zi<9%tY-aTMy%;_oOOfa7yAnzjMUXiLx+{@kv@m#g==(3&1dNGq)J6j- z9gFMePH_zT28&6gnhGr5*GlwugyN^5o)EzX8g4V{`@!bZV( z$@|8cue8SFw~-}=B#ZZPYE7&&O8eFEch4-*q?_&%OoHx0vpth)cPj5Tgj;oZOUb18 z{sI{{Aa;vDJD*1kA4%+fLl(l3xR}(X46&2K7;M(&!RnMVVlH~D^?_xqi7*V_vJb^l z!%53thg%DIJfA1)Ro0#~dlj!I?L0hXZU)q>O_z%C>D?;C)>!lpv<|awL%1XCJ0*(~ zeP6{TnlQu3#x-Oqh44sSf~|BX99HU9DogmLekx1#o~n3dpny6E`MxEpPopkx3ERQ9 z>J)Su1!I`^e7g-Jx9NjTSkXDIQ}7C9?{3s5_=uv(PJ;I=*4|y%wwpf;2H+8l!R`S! zcI)O>-To>y6HrTPc>wR?L}NE_@sX0d#rsBt-T7KIr*{|HfgO`kMnYRX;YplyQH2^& zqU@WyR>;rY4rwa-*TdS3N$Ae2c1KN00DN;gzLC3_OC82s>Ew=Khqs~KniIJVe0%Z_ z^bU0hhS+z-UXM805xyDwmZoqTgjeKSV)rHj)Qe425Q+M{V=PX;StGO?N{QvgI(j5&E)gSrt`cqBzYrpN5FfgWs_OlZhT||?ZENMf^q3R z)^MfGyRFU2?#}jZ)n+oAwSPO$r_k_KF9zs2krx5oB$@zn zmjS!02;VFjV~~2f=Duy0-DI7it1y!8u>o2hQ0h8x{+mL6RqA&}n;|%M50WFHqnbtK zsVGJ9mUf@jZD>Ehp2NJA0Dk)q>K&roVfJlxjwf*MWm-X%lE|0gGs{iKiQUc%!|XWh zz7EH9C}W9^6S)=78mJVLHeekXzO9AuZ{hMbMnUZpY-V(M-?-A1*hv*T93PX7KiY92^5U(*h)yZt@&>UR zPAl`oy46K)T?Xrr^vs)1GT<~5Qnv06D?{BwfqH~*oxEK0%2|D{62I4`jCK>K%99RL zSlB=hpJ=$P=kB~wj81D2*!5TA6V;5=6J zc3ZsRLt@x3ad(o7rJI2=tDN8;&% zX!o;=ixKf|!MbZUe6MZvUPs_I@uboK?Ut$C&gK;Ucj$r5O|Z6#39YYat(A7OgRGGn zSB-}90J+Y(N$LmTq447L+Eb}OerNaCJ4ngtnA-@Vwx-E7iqrVLn0%#KONM^qD5 zZIX!HhiBf@1zS+=YM!p_J_W%$8}WAdy9IPNKdO_;L8efp4pY{oXi}3Uf&(U!6d@oF zA2llGK{2^_Q-rW3ux=Dg^5tr^8i8;7j501?nXYvkqhO?2cHInnPIMt*TN%Q+=FY`% z^Xo-5q39(aDY2+lD_T2VsA3a&W*JKFR4A9plyEiJ3PKk~qcn9kpZQjjz z@V;>zSZ<}+B+>`#0`EC*rHU85XGii0O39n3?<1ALcDt_eoHX_w-y(?M-EN-evuP$Z zULmLl&&VSms_>@#V|vec`c!+aze-QrFi?( zAKFXEyzVypc3^d)aH0q6(w*KmcyI7QQapOw3CaX>_vJzg+zP%mj$dC&>V173bl|x1 zI=Z7Hsdr!!I)Mi8m@e;NmnLrl?;91c{MoIV#P-2D519YpC$(phUnzgfHUJoxw>OBDb)>YorF*q6_@8*mfaC__t zB3=ggUPtKjHlb25iFR-K_Kt3xVwEQj@{O>)QS6&`FgH3juk;hc+qXQviJx!ixth>y zD*O($peWT_^_bpP)TFVphdb!Ea;E%Y)e^(3jm&)#!R?b&?9Q6fi4+TNQcowt9upUE z%keW~F1b_`oZSGrw*l{V*g~@A0UgP?r|$VmJsBVDHpS4qvC6!gc1Fi3d2iM8O-iL8 zle`s(yN)Xle_+{-O5WYaTF{Y#cVs-LyQjSyVwE2U8L+!%aye>SxW<+$%>_6(#&pyc zL-EZ8ZR(5wyrsuPUxx6a>{nZ(vSQy1gT*6*kXu`aCmA|#LzUlK1K=U8WW8QH<2tpInY1<+!}anpAM?=}dPe0tybPDvLnOr8!=B*8a8oV`z3xFotaDUToIoH{|PX=U1ZR&~H^}B>JE}CiyQZT# z>hKZ|BJ;)3Ks;fha-gvrz#Fi;I4Ywb)biDpVRaJ$SL_4lydJMJ21SjX=B(l9h+pp~X4uUqDP}4FA*$CV1PP+rQtyQAF zttwLRFUL`}JH&3&367ICtL5DSeGhl~Y*PU^KsQd_$biZxt*Y?6=I^;K(9OPG4JPL8 zJ(1g-X0q-1Wd`mYMQw|Jhb0pmy#ra?a~T*i4tA64fI3d-y_VqwiFd%Udo8)PBHwGv zD5wPQ_0Gh58W+)NIx{-)je_BPrR5ZyCznzkd_w0+swPbG?jGGL$VV$p4{Wy6%Ge6n zkH2Lk-nG0XooL>ThmwQQXaIYa61s~;yhCb)ZH@96upA+D*UF<2=_X~;O$fw2L~p?G z90zKxp3E&F1Xwu%xYSkL9NYl6lFsezHAfBYS~gQ{+6>7-{oYXL%7zuj@<DDEp4;B{uWEeF*!u z4=d?kJ`ufBcH(X5zjV=WTFvPMM*fD7CGqYc0PQ^SBtNi^AweY=QMI}W>{0yee0J8wMQ#vQ0^ zCPjqx0f{6<1>W?QZ1c`bqlt8OmuqDO-HLPrf+Kt*|IWGF6Kq`GqO773-G$%guv0?0 z1+*HyjVD~fv0U5<*f}Pyso|!Y)KJ#ijlxHe+bUGgr;tr9NEM)LRGF2I%`X>hF|DJ$ zg|hy{0`N-2sq(vvy|Z)I2>Y&>w%j;l$?bmZdllVcP;(3k@SO(T;ZMD^V(}_cNfodt zdn5Cf6g=o$8?SflIQ%qFmTw!sRc>c*m-o*MyfgH{ZsW`*gx$JQP!_@_OWsFG#%r%h zfi-DA+FX3ZB$zrj?9{uJPjKFBr$aZdGGS#VW+J|LK`Zeiw3&?5`J`$X98r@=8B8Sx zvd0AEWjeJ)$wWN+WfV|y1r5v*00$awH1ERPM(J1;JnCCvV-9)>lWF2o^;kFc2rU7) zbdt~rk4(n9P3i0QIy`QS1xFp}DmOM1wkU9?{l=^Y{F7XJ|775cmw5c1QtxVqBFw&z zaf!MFRahq$y_58A1L5(VCem`Up)x^a-V(dv*m9w!EH7nh$FU7hdbb|4RPJv1F3q@u z{mQ)Em4XiN-kNZH+=@;_HHno?!giA*cunjLh9hU=HFjThGjHe2sEaB_@CK7N5$_Dx zT{Bieh26TZdqg4$Sxf-D^IGmE?9Qt^e65-X)Gm`yLU>)Rli&?#?w8Axve$#y4rkUD z7K?8f_1`xyL{J)D&t0DsKE1RI;M`a^U9&(AFBZh=aX6Sn0N#);E|ZyNJd>MPSdo@i zVNgStF?)T838$hPYolDQ>MCx{IOnGb^RE1E4ku&TcjQ>|B#WQ>A(DyOnpd)S418zf z-SNzwDE2~QHYwin4O(RABoS{ZoCK<7kg$8L9Vbfb-W9u(Dg}3Oc_*nRGrobAWE4E) zd1b*FjXyR8?_Rly_s+XHa~{w+&!Tp-9DL2f?m_WA0{4hS5&_;2sFZJAFz7DVYSnVy zI-;bv>6lU)zI}n-K4~kypNmyO0M_+o9ztma#4gyk_AbK<_4W|GGL0BJNwCJ@AC;ZN zb4SU>+o3(>Xq;c`EVPL%UE}LuakrG{Ez3yZp6|>o`rU%JfCJ%HlCRk_ezH~I6$_~= z3GDkgyt@)oOgQ`ANAqU2RI#2xYrxV3EHBlpjwaogK^*lCbk35!2uK4riuZ%eCO6Gy z$S4@?gmvWNqx+R4o6KyR_dIF6^1xmb3Rf1omQV2L2yQ9f87C`~4Bm4odFL~gck7u- z=I<834NZa0|=V7gZ3=^S~rJSro41AhCcdP^K1R;y#boQrHL7#3a7 z^m|*FM>w{=Rxl@>q1eDua-vjwku#& zfp-jIXM%1Q0l!qQ(Cm#C!g$HV1TKSs8NH`^c4t?Aw>85MKg8fH^Nw+ON4+Mqd6;;o z7MmQ>;!T_JOz}QG_qJ_<85&@<;2kqpiNt%`{B4jGyldPbsKb=+-(TRm!ic)M^BTK} zbpvt>=q}gFecY_rt7Qjr6RN{WIL6$_ z<*ki^@0Bs1Sn#8Go0pAlz&{yncDL4Dpi2d#LkqqdqC^xT#U9th4>y*<gL_+s^x?4Ctl&;h-vPs@qicLOeB;Lm4Jv*$` zvjW~}+^1H=~baea>I11HAmi9c4)k&z2I`39SK6&&6 zeMR<4RpQyVb57x;a#ZrITVW$ocB*D#%`YTDH**e3#?3>Pi)*8rbb?HmDQDu6eNUyZ zk`=)v^$zXE?^_Fzoh@0J=n*8rd)EFfOQbS%L8vCB z8^sZP4SlZ{@^i}4Ehv$@hOn)kC02u~tztUjjiJ;|P&~n-%u~8)jHyeWyAg;D&$e1( z%iy*ijxO9jY5>f!u_bR;sbGAu$u(& zdv?(CO3LSi;JSNU(L{^hhIhw<_bf&4Cc!)1-)#;md4(W(0cmYmV)upWp_20p=nmA3 zyR6ZBr0MrihI0V4iE<0R?fZUpI28qBAbT4= z)U?JOtc|uduOS5f+>ts6;4Xx40>i0apBzk=p#%|+2 zA@Ri629G>OUtuVGQi);TA#i4L$q|n%o#XM!HnLh~yF?by7K>dJZ-~ZYwaFr&Ih{^s z>~@sF2Gn`7f0ehc6x>(xb}gWNj(SZVg?O8EWr%5aj~veli6-n9%P#%h8oKdJp>saS zP$Ou$O!5|Xzn3m=#O{&i-6N@(*o<3W8$rUdJgSa|Dwsnw+>;RYnD!`#|c z8z`7HqVl#-;5QbmHe8$jC-?_HrgSnJ_RC7SFMuAJHnXd#n#MDpHhmv@G2{4BfVeb7GG zu1;5W?MA923*N@!U0~75-Fdgh?%8a+Z4VL{H^Xb)Vxq7ck0BLy6Ytiv8*GCRhzHGt zY6KN{%hv+C#j9bhRULZL>|LGs#R-{BhIJ`=Gx)9#fqk+i2itwnb>Iieo!u4}z z3ZFaKx9PMB+rgQ1GG%sds{x$e+Nf1xGfPbMRzW8SOD?8rR+I05^b%}Uk*vL=H;q?r z?yc#!b^D2_bYkUB-*&0YV%ARf?Lg*}&{^flv9P-mW!9WxVmxbx z^32Q4htl|Lnj+kcX`_Uq;MkVU**)MV5pttyBHt^6JA!)O#lrV(IJI-j)#l2H(ZMU< z!1!m_wq3yOVBZm0D|igttndy?|Hc(h;9^{!%TNRzA3pj3Ew)blLp<=q^%S4ya0uX*97FIY*2QA z3j|j6u{5Z|d3u`sVW?ZB4=@x~!ID*olovu8zQ-erT}UR8kiq^jcZidt8- zM{sDQZ^6ok2<>CPSe$tMzUSrG;U5NuLxMFwf0WFe`oGEijc)M7@iYs)rzYKQ@S7R8 zqeL9+CmXCGR6A;6aiz`3Haqv^7{2K&Itcz|R88TvLT~wY7U+ty?@9*Wh|1GwysxCQ zZyTILTFMS1W=Di>1Kx*%Zb!Oup>Uh0D|Z6#sZ_j!X|PW+z8N-~M0Vq&E^mk8t$l*T zx#yvHWsKE?$=wHL-GJPYBJZoCmYRh6sJa;nsZxz5Dd8NIr&QYu{IHT?x5Dg^mQ&E+ zJu2t(t)igaZ=Ss=wg9#fxksb2_z0X|KyQg4-PKxaqQTp*diJF!74Pb}SoB_9wETwW z^&7dh<6`ZmZMXIWrY=O8hv#)118S~CdiU(ky6He~C3J7p4w_N88ESL1r(lm($mM5m zI>Cmc_hwZmZC zSEEGh^dz&hGZzIJf^AyQ@c37_or7H`jPVmTk@zHor>RNnC zqY3<*ejKD31Z#PlGy8V_g(ogI$;lHFOqkhwrRoKD!S7wMo143>Ts%Fu4RW`$ z99K@KX1j7Xw@KoNPSZ8RASLgJRWMR)!ok}(y&na;b-J?P5W2g^#qMw_zPqd7t)P3G zT1TZiOnA1^yca^110vldZJQP<*cl$dK_$>`1n-eNrW{qP;{7dgKXO8+?s>lC+O1aE zSJwf-%`qi9z{lcKC*Ig^H9+>R*X!jfvF~X}H=eGW4glwIdVPqQxIG_7zRk>;iQF_< z2YA>DPPP$@@i0}TX(rUvZw2@;B-)VzS!N~N(6YHjzZdq|rIUKw`SX)-pfSwDv$1bm z3OTXLNjL#Nc{H6nJ95)u!g946_g?G)-3q`jO$V%7D`{u5nglzq#;g=`A z_tQ@epy%~^&JA+SX@p0cSkGK~!nY}N^l|WwPCy${)n0?CqB1q!P28ea@=7~oOKGo7 zUkV59W-NZo5GH5eEP9!?4t5fz*P2YHvv2buC!t>h?quX+q4jRaElu94p-O}I>f1rL zZSU3yPX0iZ&WXBB+S&3sveje{#Tzv5M3Z+j4!dvCqw(^@lDWL&vHNf~@2;6Y;~wv$ zuf<=PwfOYiGpECw>D^oLsHT1M!yu)+yT)3)mBqUz!TUXp=Kyk#26#w$0r|=zl?p;a z=Z(4)p^~arZsp6+Fj)4e_?4nLSZ3lIj2=c5Z-L{(`k1DP(Rd=r`cI0J=M3pq#Csav zM6l6Yg7-X?e8=nFYexBT;v2+iGnZpCYJ*yOV-A;fxYWvl-g?17)9+LO zkHBma`;MP)Kd~L!5%PWV)CKrg{qYU~i}%|tM35Vn2UY9d8#C^ZpR&|WemTX!`K;8nrM z>&0TZE?$j$y`I+)935T@{yofv&35PxnTF0Fn=u>n@jxx#n1*m$ohh#M4ki_FZ?vsM zi{#U_$y)~Iw6g8S?}%5t$qq@i+c3}tC?VsC9y4CCdB^bFqa!18qW2IY?E8eHy5%T| zXdx#Rx7XwmfqMt3d$n3xw0reUH4_HjWH;d*-W|SxW-Z9Kvsz7pV8>*92E{w+xYBJm z`E2*WZtdmDG`Got0NfOLUs*-o$4*v;1@CSK;vHKgDE`4`fZeYKNljF0exX)lCT|Je zi2C?J6p|NQ91bfnWeM1=)$(9^H?I`rXO-97CU}|EY$9iL_6X=0$s0tIpJlu<9lW>BQYv;@X{jbQ zddKXa8I$+Hz*`l0clmVX5qY<}N-&LiJAEb+yJxe%%~K@rJS(B9nNC>cHYsXjp!9X4 zVgk0n;)p3G7Ye+^WdbC7tO)mH@>QEjs$4J`s+*N;(i;Q9Ls&;J@6&p9=!;9a>h=0P zZ`c!f?&YGk6AQmxi#j%Z6IoxITn*bjbO4g zhnCrJd$||uRs!I5ZGm9sBe_lMA$ad&ASZAl~Ixt1Or| zNGCmD>Mr)J0GKbMZIjuzSrJ}a=a$S7LVZzYReo)nr>K1@VBl*^gKa`_f!#P;EXj0R znE}nrrJ>_EnbyVwQ3m2|8ZegdeRoHX{MDQfQ&TE@Hf;y&PCe>;+L!FmZP<5sjo~n7 zmCWZ&ZWGi@fP7zHS^%CwHIaMqQyRA1Js6L~dum!uZqiOGsn+Bs&f=}J@g`n5PhK8A zwA^jCnqViDD)TyvdbrxBZIIK3w0$u<_bC9GSfZcJ28?Y)L3)3>F@y)gz6ssU7s3>_V64=d$>_yFK| zzA1aa<^H_*EA4_ptMOY)G9=n`0=7{sc=z4Ps-ITqeY-1m$J6gH|9+xizS<4CCHr3P zW-`eR-JEt`8rrR~8yR?@srN3j2^~{TchipJdyJex3Fi`{RY zJ$nO{C&0RK;;fD%3)MOTd3EAfxkh3s-3_4B4ZUnR@jV}q8}gMN4(wFxbq_4xUSFVh z-#Z=lsPm*P9Vb)xqoXr&`phEReCg7k@4o zx6w)xHMC%ATqf(i6mKVVC)b+9oLB02r8Jv_ zR&)|g-m^o3w{A5#c9C}|6rUwn>71-&v>P;&zkNJUF7ejKl;&lPy@nNdydYRh>=uZP zZ$5iwvF;*bHw{yw!vvI*v0&c*1*q3_av4!g5X*aBAB=)nSmn3Mr(O?CDRm9_tqFj4 z3ymjeJ;?wtlGHr~CSGWNZb>TOKk%{boeY=c!k!7zT$BNIAdr%7_3;NeZ) za(4LmMcyHUca|=}sMCZO35rKH^I3D&{^2|&7|)PeM|HIAM4e>5r{Ob9RT6g7B!fn8 zjOWxSAc^IHqZse<*SF>FApzSl?imO1nGI&2usoXCj|J`newDvd;Wh(RZ;P~z=A`q^?C=|J5Zo%6K5ziLudAhir zSuRn9=t?hH?c@!72=BIfysu?6K43-OOzh5-iw}&)WW7(3x16v1*)f0SRJ^x0ab>V} zx)Sp_;bN0QjM?OXx(QWgcdwMyM0aYdS4RQw?v75Ac)eR*Z8kripQlJBOd`o!+ru@} z7Ms5Sd&$LxkxX!jSTb+$cf$q)M&ZX}RvB2WSN$;^Uw#!ZK5TfF+}+UEPyJrMQHPLD z)hk!aU<(`$tH87C^^*J)|J3*E;({;gUc*QBy^#dQ?vhFiRmS3X(+DRz$u7ya+zVbS z!$}Cf)lR(9#_9G=Tf;OQU`q5>3uqk)+=1DVJ0f?>mzVS`^=^RdYX;tz8TD>8!9d}h_4L7gg3Sy*K{&Du zmBC8rc8%zm;mQDxKykl$oKx@!nm0<`=A`nNP7|HW>FzQXA0v2Ek6^pqp5OfNZjdrI zY$g~OoY(SvQm2LmRDj(VMJbtR@CNQp$CM~{S5Y%j>d4ryN^f@^PcE&w1p&_u^am1t z3rrTDh9p}ca}RDoT0ZQT;DbxOeoqi@jofv=T&@pun-2aEXb!F@xGWpoZX=94gz9z~ zp;1+gYOzrOzQLo*K&2lyA@ts$%A)re^vXQ3bQoShzP+&lUtOnr>)<@SrN|(lcj5$- zn3*&Oct;aFx0a~#hXHP8FR_B~I~lw8SGy(qmH|teth}~@l@@?!!|v(MF2O8C-cFyO z+OFKDDBkEaF+Rb0%yy;a6g;5fttIa+lf1iE#}mA-qHR>WB`ewJS@QUpK!kkDJa&j&kseOSsN!Vx!?CqQ=NpzSr;Mmq&# zNII(C@}X_VVE2Ypnl-(>Fc97$Jl9q~4Z}#SH;V~;*|(|_ltr+YG2nffp$QhCTeh04cXxRwY2KuoG+p~= zBzoUO6mP-5KSxDx>)5j3mQD^B&!K!ySn@ue;?0aE-7e$Z*`t-Ap?Cq^=~MAKlvAr2 zr+1ARP4I>m(QeR8E);fa&HF-OcOFxfq?(L90`mG;fHB78t5uiF#8e7`U^1?b>p-?k z2(}K4LA>7Z0KVz6A(l(WfB{=jV|$e`rLc~7NYz`OPfF}2 zhQC$^j-6n^j3<~W z;;?_OCCkF|H2mt2k_i{OrM-J`9jI25Ah7c}8Rz3={p;=%3>NdAvd#ERs>#;1T`6S~ zi+Rr!^PVRJ;}4#UFHrkafl1!SR81nHNk-lsuXo=-e|IW&n;P$$4(G5_N(tUA*+W%C znoU)LE%Xgyf%ixS;>jC0rY@6V^(!E`!0(~-c=IHDPl5JO^X{P*Q@q{~u-gahhGtw~rVP#%}@Zx$qAhDi{JTrO7&i%h5AT2Y^$i5}bPk(|Eu56v&dQ zfQ~XZ3rjv(&=_%hZTSPG(WE19h~v^~q&xyju9M1?jmz7JV&XW=ysbQ42w&}XVgDks zJaE6uKFF=*?rT=$9bl^op|_ok&j{YiX|jjK+tq543A|YuY>L+eBbH&_9S`0I^_m!& zq-&p69^K)s28ZK$x4TGC>)o^S!TE3bl#6l(hVWa{aWkd^@-||(qTM*ZfJvQ;3nrR) z#Jk5hor7nW<8d9jV9|qOcTf%OtDuRuCVsy^tb4r@Kz6kV)^6~XV7hWB;2Yji>X(N7 zhVT20Ua5q>?|#V}=4|d|vJ|qmwYo?LzF;q0cF`$HasxrM+8r zz$%0HrGtHE=%bqMJix#w&Y&RM!rycT=5Uq1(Oc9(gN1 zZhoP=o6W@32+nTWgM2D>n<^@miq|mCx~X8_?1C^`LpLm)QO5}~@3KCs^rc?nSHDuD zAXRyjEP|(x)ew3cC%0er{fi=4151K!hPbU#WX*@~tJ65PWZF?2O7z^ogf}|4tHk zs|WirAZ2x(tkMoGLxz&u-^JnN9^h@W@4a&HyMuRxdTX=EB~fmCp$*=b&T5kk(`S3O znoOH2pJTxLCM6mlQwHm9@+RqoPgurxQXROGO4bQ-#(kvYO1I#>YoUogtek!PErZ~# zXW~u9(p;bDrYan;q(nRbI1~vAsy%`k;^Lb(u+vb^*C?7Z#tC7JNz!m-ordBOr9n1v zuSH=t8-F^B@#OrN3@n+TCCK_+* zs7xiSEEJ?VD&*ZT6c0_Xh~3ZL6j3rEouociJMcAu+4Xw0EZeDuA;R6W3H|NF_eHO3HrSACf)LM{eHpzN-)Gexpa&?Tt%~Mx&HtDg(lqvW_uLdZP|B ztsTs!>PX>5v8D!A{?U;g7Mcu57al`ez5vg-sNRq#&IyIuZnxtl{4??K98Wla~DW7@}A*lsEQ) zPuI(!reHP)+XWkNwbbkNhP~lw{X6e;>>=&;dZk9G-*d5VP0q~E=0*j30t4Su`h(AF z(7UH>L%{&}Mgeyqqw;M%nc#>(G8jj(MPWX{ec*^pE=+w=ND-*4B*ew@)&EntHsjkY z0B^zd0o4+hx%<*85rhLu@(4seAn}-tAnjbe6#;^6r^At+Xd};;klH z@tze9shV^jp~l-$M^(shSQ(>tV~rrJ4W}DTnBSzv1n{DfPFki(P^;bOECB#-5%Yd? z0W+1Lm;hxS%V;Gqaq-rWolH&)W&={w74QW1hgAs2mwK)L`^^~0HrNM!A7&T?g!_oz zb)ebhR@tAFDWlUX(LrUseu{Tm@=7JJqA>QItQapk=13nDa1z0x;Yussq26#_Yyu=& z8WJVPv5jf(eP;Js!JZ%kP3Xz@m|o7=pbVT-pLyKkf`Fc!Qc$CXwyRjlTHFwulnQgy>^ zRNbQr-i53U-p)c3db9b%$MXz_m1cgS#>=UoJrIiofm`S0PCS8kOPT`F)IE|_-bGp7 zjc~2E%&OAdO>XXxzobzjyamJ-DD0J6{^?KNPmQmCDYpD_eOQK5N)Wrt0=FB2e1oYQ z9fN|A!&NFi5zqHtsWB9kTX1f1r;Soc0D2;PJ9TipY&4RinldHfJ9G)qIw-paWwTH_ zP~9hsO(*S#o~XJ23H>I+x_8<*?e)gKH!QcR!(q8x?P1=sUWd>nyetm|F4N&;eF&g0{xm@72GOKZ z0_?_@rADux%kaY=kFOGz18wD&vy}42VBNO#Z_HIj39C&97=b+fVkHg!ZK5M!fyvb@}PcKlL$$T53 z-vXth$CbLsI|aOF2c8{fUX!kE6YL&YG|_r@9D+ytyN%v0-m~ot(mjHCRvc)=?IIHH zqLRa*i3)~u-pDG!7We~4N;fIXhz?=5?lRHbdtCLQzuQ_l8@h&caB-n7KD5{GRWFJ| z1ng5^ui= z;ZeSoALYfXS{_#_MH_DK<+4A7`fgBA>H@jpQy{3*?|FSdY_ES$Lbtfy5U>u1miHund%0M+GxZm4aESYX z?rb=IgK)hG=ynjhBM`hY%-J7+bZ(5;X4H0vqSQ3t(vgI%7dR+ zh7T)~WAU@Nsd)LXxcwm;>$Z1t@+foXaa~wthJAk8~m#aRgewU{}kB*tz$y2F6&sHT%Z7Gg{429fG03%G9Gu zoEQ$KftnhAfJuI8)EWp0N`!9k2bOEKGOfdp!1djdr<9Pb z#3F8Vn?OLmTpd=u_)E_#LEus`bN^Y9?B1Ay_sL!&u=})(UX!}t^6QNrO;`f)ZhY4O z)(z0zClm+hZuIUwe5--6`F_3LQ1HE~#By-EN_1tXsZ&oM1Fd-kntDeqBoAQU%cyk1 z*B72Je6PO6g(uwk9_8v`D))Yz+tnSYShrHU14Xpr8v*yR< z$Me*KN@EW+PYS+yOnyYzeen#Tn>cs51_zb+gv7fHS$Hr6QVypoC(njsN?CH58)Xp+ z!&kjNTVw|rQ*9Ad>uuiyBIj3r*oIu*zKud}G0}MP z{kZtOA}9JcfbEr?BGrz-P2@53%v$_)k!ypM2N8BXUU@@}VQ zGFP>X&5wHPJr%n1d@HBOVmm6CGXms(gATzF^-k4lRSDjs@(2=^<-C-;$5j3*V>nfe zz^kU$;dtnobPjG$4l&-|CrBTn`2?RahXW%E9&DgNwz7(y-L0~?I)q9SIMk#gNGZq00PO|@bVxtBzrRP^E&(S$J*}J6B|kQ^oDUT@`{u=TQSmzwzB}pz_Lfy0d3lF^ z5=U`=#{!8tP&WU)OUu3eaOmFif62A0$3#z6UgKG%Qo9v~?*ZPLdULgVj~4GK%U1FV zLDOj>(fcO4lw)0;$pcFQZ>5^dWs&!s7n>ZPc$>-it0OnThKP4Jg?Y!ERl>{m5AA0A zJfH2N{ecAJEoJW>5%w1a(az)A8JfFCl5FQ|KEQXr3_KjLy9Vvso}4(V;!Gtp2M)b4 zmX%b)JthL5PjOuValP*qpFyiDY26;gbU@#xgUVCL;Q(|`1ayN{5PM-uy+)nlI1P0| zdEfZ%pI+R9)D4zFWZnG+N-20}4FTT$em}R%gZ$-6o2;#7qg{T^DgVx^TX(<=(|SVJ zEUa?#Y{!kO-EwlTSu4n7fQYna_i1+U1g#c;sfmubP3&=L-ElTsvW@F5N_Mz zt)1P?Pz#lX-uBZ>A~&MlTCsVxtp}8<{ToG zI8|B9TqUUcV2iri1m8l_iQb8)FuXu+shJ4KuGPvTNW{}tB^^@wRR0RIXJx0>-9XTV zAq7%UhOo0R^3mcA_1!3x0Cb^lV34?3va@9~ez*{u?l_(}k`S*>mQmNMAcfxRY$t7D&5D(t?p1@9R49b+@W0`FP- zT^lo%gLL!`%`dP)of@Jx)^m>xc8@^dhI2{@-hy^d{91legA~qK#o=M9vg*?cLp^#r z3FzI!*FCS^z-B2V+(XQ_qtuNRRQ{xlMJAw>oPuBiz21ER?sZsQ0J#K)bI@4QKPfg1LiHg(u?|c-<9NzFYfzZBO;zS7-~pVmTI#N71`PMbw`fuXlKI?pT4nZ zJlzRfi#HUM#d*wIteNXuMr$hH9I(Uw?PYin$NtBEAZ$OJbBCPWNW2#)c1yWLySw)} zsWjP~y*Rh!@SeJ`+to&8jw^YNax0D9if_w64%`4Y%|2Vpm9yESR8n=->M+%s9QU-+ zEqL#miihWq5Y0Kyd{}9Qa>!g#l+cYc!$k~Fg4j(4LEMCw*gYzbXo*3N#7m}K#W1{2 zta}&<;|OjImTv^_daE_57F+aDJqTa|f|qb>SlmHtBA#2VR(aU#m+Iwu562fEN-0P_ z^6gUpzDLe(@O?v@cmG~Ifx}xc>;?@L_j@nIrIahZXfzuA(pPX6=CYt!1irQSy^NV8 zi|wKUD~fb_KUDfA0o~rvS+cKcr6d*Zmcd)Ti6*jF;a^q{pyj#e?0d=WKM(f>?)~o{ zVcqnCF>iF3$R-m-yY~X`5bNH@Bsf*|-H8tGn+W?3`Ak0JNhLtIqTK}ED4C#^vgJ;b zv_8Q@)_5z`gdbEM!)emZEO^KJyP?YD-47DDi>bLvD^_V}co8w27IP51(H}S(wE(-t zQyDFSc`Sk*A#{60y^(Z#ICoYZ%2ZASy|J)(H{f*E_?NQqk#vQSl>N7 z1#bypw?Bm01t8mq-kxCVXbYDvZuFS+>2iM$F9rI8@GXG8B+wgl6d>NE(vRYgK=IP4 zKdJh;)jry-ogp79UlPSfolUTx){SSP+=o8xbKvOJP^wc6Yf=rQER); zL$UgsL-(~-y7fpUk?+e5C357*u*=$=@uV_PyE(z$;2qMtBi#EYrbRG(Vo8x4rg(ow z&k15T0C!k3nH}BZ%{rhg)#Uhxl_`SvEWSxlU^i6=4zlp>JRe@jE3-*0uL`K%gK8qH zUq|?>fCLk=nMmv|`(uj0d#XW@?B4ZZI0(;Myb-=3Q#m4Sr3$h)G`#kD7>@7bY-JrM zqOd3<{D;>TPLo`1~!hzFRH zNv@Q$*9~?$akCYa(7r=kRh)zaJ)JmZd{_0vaR=5{vRvA^(dEjO@JXl}`BomktR37+ z+~(|ixr)l$tH;7^m#>@UDW%;+N+xkx%Ix61R>nXL;SVXKnkEu&%jJ!)|5r%!M%84l z7KZT(_`CtcKP#hPoZfvLr-^3XS69~RFctkB3%d)cf_IGGP5-9T_PhK}J`;UnNn$sa zbIUWzK@qVVb{D{NLLF36F(KMrY?Wn`2|lA>GMRX-Vl}qFq)sKUw7D?s!NDcGDJVA} zHl@p<5uZ|MPg4+*{na>M1v zo}k}#@l}f73@_?Am#uF1Gc_9)aBN{?mKu`a7)nvH!}n&Vz>i-3(qF5i9OdEFP~RwV z6K3DxBiV03z8BvFxoxf6I81br$+ZquUdHtZX3)E}QSd>$+vF-!up7%vH2apkn}PRd z@(0c}c1y+k^XKS(&hahY*aCG0gYktf>+wFud8NCKDqiq*55?oZTl+jC?`FG{wVD=D zD3nu_y|0MS7jjfsAvanDfp-7pO>rW7UKQ!C`hbg`@72Obl-45r5ZVQY6wT=YkoQ0W z5x`zYzU>1sKJ7Pp;s(EjLCQYXyn6M9s_JeGArD`=?}5mTf=R!D@f?8fQ~wmtJy9#^ zl_Z3hast8cf9#ijgy_#{{j^?cMCTeZVA*o%B90bBbQpM3)u6K-MQ-W@D#NqEJVz4u zRuTMk=(Z%4m3`c|dhClcakDhFfGdvTt49_~5(>NZG(0-Hjm6~pq2Rq{n#rCBuA-H0 zt4Wx5qfPLJ4lDmx)M}!zn;orTvJ!L?4%^Nm?~v*}JCJAsMw5bN@9sX5Xp-zRaW3b~ z=IxK2EV;^>QpEX44jZW~>eB8!_L+=iG)Jc@iFOy^Ow!a)f#_Wv`Bkr2X%^PtUrWSZaAKlMiMBaLavS?i9l_y2jR(y z@3&fhy)S+x2&isNPQ|C@;2F?6*FQT0<>klHk0s#W|C;Lw68^6*AfK80Hl{XUlSK(F1@Nw+nHIk5jF`RdIY~U=v4SFvY z-;#D;aS_)7J3L?m$0Pjglub;Hch?G69vZ^CyT{@kdN=JZKs2Y8tpYaBSI*4vf@0kl7Xz{hLI*5F z;%ijgElnnZb^pcp<<79|5v=;qVN!=9%c@#|w>wShRVXXLS}B3CL&{S2upAJU7|n&P(vnosbJQvWOm z=$-r5A9JOgzLXk2{nV(}bEdz4e^iRd0i0jUm13M*&@5aMZ<>$aScu*ZY@>IOiEtav zzp+m;bumg94Oda=;&A#%I2UUD{)m2UPl9nfI5#tPUu)J)p&Xs2ynYyXlSMF4?XUYV zZ%(^2Ho@NLCRkTG=kt7K^KJ>=cAZK5`q`mX6WwZ}rIO<~yp7w$61;aAtQ4=B?e@p> zL1w+%ELYa7kWTTL!0iz{6(L)R9k5tJ1=$>mSB{DTx{DJiGw~=BU#)}kT`c>fs;5pb zZM|CtEK$?;PETP`7@n$-mIMY49uXK zOH}uiIj#h>`Ajh#1aB^!%wxPJ2UAQq@s_P7SI3*Kw3C%-f_Kbt&TQLm|8RbuxkZpm zCIsLzOo{!0Bb=%%5_Y3%QqEUp1=VO&Y*qa?Egu^Lt78J@>ez3!ibasSwdsW8cin@D z1^6HjEQCF;SVsIE*UNQ**d^rO{azh7HE1Ob@N|1n%H5|xCRw@B$qmR2-jf`5n}E9z z%S!;!U!3*(0{R6YBQJ-$%;nAiwf|e`Uwgf?GvMn2zJC-i&(0b@)lX0Tdi_+3C)p5; z2mcK4*`I5}w^^7M&oqGaU{c)P)PMml~EaM_g~%=sWK4slB$YTR;$(8xK*P} zB`c$n5laZXSL>5v@nVGafgqLmb-&#ATYgU-T6*da;4U0!f?=dog3fOo&GBI4tkkd9 zOZB0I<_3l+hiCu?u6^o*N!+W0hY1*~?fzL`d{N_u ze~$+7+`fv51|lbbg~l-%Xv>96TAY^vPS8%^ZMJprDFD4CVqaNGP27TdBI+IcYS;Yov5h&@`REO~wE z=Y|_-QW%Whf|m~)IK9v>LGg*#uLAid8N3AU@P6;bJ;*J&9H2B_1m5S)`uBo%H!%HE z_91ZT)ypk`=zVeX*Lv=u5&Y{{z_4>F-r+O3aY!e`#6$aMH<5vOSsSRpyCCoz-zunBe40=2(1JJd z?gEJ>mdE?>4)3nz@ZPPBYHpuZX36C!qe-#G{3dj3vH0xS|9A$(dvrmIIT+6Ywk(G# zi+ZyzweI`ChS7)J>kVlQ9`q9NPD)Gm zFgs6V8vq@6wV>A|nv_ULX$;Zq4Sgr|I<%Z1+M_2NzG_sw?|TB6OQ-cZJ=cE%hq(Cb zTO-)S?4RBHt;rbFaQG}wd|vLMW{PBwMdS#xtqFI)vD}C$5z`@UXtv`wGM7mn75zm- zNjH~I_G#EoWZ&ODYjZfQBr0?pcgdwy9SH4#fyz^MSdEDrz_Z)C&E(m1AFqi^@Fv+L zgx%pK2Gt3xWN&L7ekPf>#2|$2!sjRhKYB3U*aSoSIo%_qb4(wV6uh(R-7;0#YXq>u3$L~9tS1n5SL25c4|*eF4(cO8QCje4s}YB`Lk z!G?SZs=<3euuqHi`gf)K9H4g}tGtIV;FBA`wOgas=+qbYdq4Idg5>wl#`k9k-w!tq zrh4Q;9zcPx%88;R6Qtc?DV%u@rHaxCdBztZ^iIuk+F#7l4)-LRMl9!un|+56dUXhG zdvsAbA)sy+60feIvjGE>{@7|`%E&~OltOPn1nADS@|n~H(@ssZ(JCrW)r;fmtv8Q zDWS<^jB&~`oK;rGb&6T`@KjQEzAEC~>s5V{PO7ac%;taxaMQhkB~ykOmp2AEa+R--s+70WRCAaJ_{joKi8rOM@|=>I1o85Wz#A7SM;f||7kH%w$W2Y%Aa&QtAXt_0 z999216uJ68sbWXqV0$NV$^;2l364V>l(#ox}_`4ed(%;^n!dF!- z7AMfC0w(eLeFL=>zm;?I&DC-lk#oagK~`Y8vQFaM(*ai6QtlW_=H1qd#&ozD1RDn8 z&ggt6E9162C~j3{Y46u0vG1kx_G1Vn-;!>}&Qdb5TVb~f-Aee@ZDZ7VF=Ujy=yt5aY z$gY9Htdn&%M>6hWQPS@k%`LQKI_KH5_ZZAUwym$B{0*dgtRgvMG?#eFDp;@9S@o+~ zI)hCdvJUpDvK|)IZLfz`lwldSh2d(+BVUP!9VTcUffPI*QZ`DZdb#X>M|N)9wFFhX zHx$1IzD>>-V^9whsJR6jvUN4lqZdg_c=G^W(mNEYcR@C_1sO8XkhEshG*Nd37v9w z$e|*|a7UqGGJHE=4!>F_%rC=fOgH;}Jf?k6PJ7pgQ+mY7IeH*YbyjAh?hI|Kt> zBN#kL?*^j@D&9Xk(VMXQ=El+IeZ!jt@ujH~EHL3jDFL>C@>s)_1-UxR{oUO|YbIA= zlVEqZLKEyW`C*W?$OKO-(JDB|*Z9gMg7h;q1{P(HpsaiyL33aW=5atFA=L!WAqDIT zBp-o$+hd~}2NoKAgzrfUv+y9A^oWClRDumA0;$CZ2n2pH zd@(H5Cw{A5B0o10^FG+T0lfu^zsK`QLC;VB8D=W)#peL)h7Rx2i__D8h9}=Im;3#* zx8h^|`%k%2>7QOqPV40cO+t7RP|Qo>9>p(&$;Edsiom`#D6f*(_tG(r8@5z9lRGiZ zQ=LuQvZ4gaBQ6g)$&2C)%wq^Yas6@`JN6TSZ}a%UbjvzPwjt?9hV8=vcc{KZi`|Ib zo6A6tEyRpd?#{eX;x-4B>pgjQQxorGqe(LkySH+V;eT=bo@1G}w09HZR-imDSVr$c z^hsj(!Il{KVticrW9c7bNvG}!I_QrKn0ozmUu)w=}y)h;xQ3)B=;gqs2w<)28s#lk# z-zAW>QQsCH(V*$~5>8w~60(&0vD6s*r-YV8C>8wYhMYYs zmrq}m@Du;}zfXSp>8BUs7QgiN?5yAV7s0fDdhvfjS9saW0eydaCjOFMsh`W0#^MeI zVQ>9QPCxj!aC~L$bMZHqE?Y(B#T*{f!ThBTTdwhjK&I)*9KLQlaoV;AM*iZMFC_uJ zSFT44tL3+D9(gpn9b+wV)R!n*w>hKiI8G%)0KS9Tjm&$>YXsL1DKxQtCe37%psku% z7hP~7nWBPh&AzQ#lSdn_w45e~kLPqlf_IAE9Vd4~EI#XKj`WrAjd)VMYb|heKSSaz zV0!>B^N_j`PXeoJV`(m-EIjR<3GAMf^F_hBedrR@vf>#la_}g@xJFbJe-K{ z4a-%~wf!=TEVMA6<9R553-*raEk3LvO@e^Rn4T1z_(zbwQTQesxPWe0)hUdTJ1YjJ7qwb#moke=vvyULDyEwMY_kK?}UwPNhdTXCv|Xt&$GsI%|o zTYz&Q{6FuBGzTX7gst9xF~*XDh8xYhQd10gzhV0KmwBgvHA*!nr>eM{q3~i{cIiHUBr2h z-QL&ZKD4pyT~|gfwZH(6JqG^da?iW$(k;~ zDu8M{sVu~l8g?`FZe(bKhqHt~6XPwTF!-9YcF50<-U z7Axn^DsLC??h3o7sdp)vl;Ax!d|y^UOS3k?=>?rl=25*e1v(E#ykFH8E00z#R?atg zV=4aKnqgFxX40rKV9P5T4Bmv@=TN+HJrQnz_NXwI1Yq5~2tO)Vw~tV&Ad_@+76nYY zgNUIUZfTv`#Jr964UcyURU1BP0##@zsh=r>-99Vc8tK|}2FN5Fdv1)*_r#S53q)c! z(`^FSoGsw&23Pb|3TuckmTx6Q)D`$b!%yN088asLa1b1WP`eUM^jW5dYABlBEFXpt zQF?i3A?PIO)BU8|4>__*dGv-))(WCInH@5_#(1Bq971dkt~wYi+(tK9a9qvJiv7zJ zrvESxy{FM|hI_xB->mjue=fOH=AKo$3*ueG23F-}lfi)>Rt;b0-KE-n@#e$V;-~%H z--g;n@QC#a5sb{F7XZdKY6vr8$F02^?eU}-UlZOJl- zWFb2)@=8qI8BiR+&3boa_S4b2fNOjLaV}$UbK3~ou2gWAq%y_OF*iwqh?I(56G&wd z!n*)|NuT4y6@IrH?RAxH`${EY2$@_6m#fbRjC;iwo^H`2Jj8p4O6JlHL)SwsLmVS* zkUn^roLa6yZtT`;YYp_C8_xPc?UaSlWK6uvB&(UDh$oys^{o3&#;20kOMm?z7EL+- zHryo3aCdH3bB{hu3+dx$0z#QPM;ozZuv z9Q?`~I|jQ;)?Gq4W|hXw4b_AT;zzbj33Um)big*L#&VX5W4Z7>p z+YoQIbfas5cy|_<$XDq{+KI}I9HQGgu!B2i;7eYqBtVA!FR8);5kulvxNzTRD5l>f2lWB8G47);RM zL@L$RgGa$KVw(M&$uz+SUah=`-dzkUpZ#_J-Sg)sjrASgozfXtIZn(qoE^yb^c!`( z#OU2jv`0nD8QcFLm0)a1H|ny&67UQegt>O)OTh+eqT!s{jaw6}#v?_L;F|y(0t=l7 z^k6sQ5hWIH5}rrqv6rS^YO{$uVc2$a0`SCR7a+!)GI2GcVI^U`ohzLUMR%_o(a&%R zYE_Qa`;?32hl;@8^NQx2P!Y>^RjUOE7lyS<=-VD^BwpBWwZOU|kGF|+!@HZ1WcLm;8S65e8p9s9)Toh3zAA#D_IfB!9CM%65Z>MLKb9gse&_KOS&PkEt zU0cq%UP8SuA80@4p{AAf;7B@up9wW?`PoDv@K-2!cty z+xP=Zxf}X6<2Qs7-il|%#19O1(|0<{e1`zMR((cbO}7zn^ITFI&0A;41>rAAn%# zW=$b>{Zj7B@0TV*mbmLecP#{Ev8G*bNSm^p{P6lgx%TVL!uCSGT~O}HjBfMARq5zH zD_tdvRgw=uZb&0<#=+fh3gP4<`YNXzD;MeAb7=Q%4YF_N@or9rElL@H-ES{v+RwHg z+G-ba(z{SfsFuci`B)=q&fR&y?1yf|4Cx{FW~;}CQ@rD9?bokIgTgQ}w4Jfkf2 z6P{Ai6_TfuIXx0Q;lse#|^mfYTMu|NXF#N%@WccRgaEzk92hPw@whqfI-ccC9?t>B4c zd)*H|{4n*+oE(uFh_BkZEUDU?Hw9`JD)_wcL1N)&ukp!TmTbt^e$A<0>VatY>x~~b z%L#Y=n;Vw6`MaxecFCe{oDVKrm}p$61$R&62!4=cGAGdF*;;z{Z4JC{=Rr3&o|$CW zw=8#GPjpsZuc%GI5}Bg@9vaQ-i}ksB_*7n z8r#Wf))`MK%TGm+2{<^XnV>B`V7S&Wc1y#$p_BmR@1m5DJ5E7|rM&CvwCd0)2)Fiy z*{zhm@AEt}&?q=ls5#>}?$`uSA>qXMx?v_^9Cz&$mO_NOYF}}zVCFcHFa0PEW1`AF zhg?Bqw-Wqq53YSl?XoZw~xJJI0#uaA->I|+-D1;@Q7=>xF3l3 zP~{v>h)X5N&g0&5SJ7AE)fzx%DvA%v<#>R0IlSC|Q(^Z_`4N~@TozAL4cnffp9;pl1vtaQ7tzKmc;u< z7P~K@c2DZv*DHfyFE=iDKPd5DPw-w`zwqqmHFaj&FP?PK|a4C2|Ma z_)J*p#)nL^&E)ia*C|z#6f;V?BjIQnONEdsAiON7xir|#74PLcG3-D{nJN=U<=QX= zdR2c;%yw?Kpxty^>bZ(=m8*IPw>1O2Ye!B-aPIn%j_v4Fa2W#(DR!)+t#W4&6YZwQ zE6G7sgw4JnUeDPlSwOKM}!+$Rohs*>_$wvrAz4T@m5b;U~N9J!Z1u?+gcBU z?t|Ye9DK$=0vX(>A!bTh%a5&z4XLBRV*AE2ROIi2LjNDz-;+&O% zfj3o5_rZk9Js-U99sD|u?Y{bWy}L%dFII^ri^8a&c>nKd$)wJ_4eMsB$&}rDS(xAh z3f@N#LcHtPy;|^|HF)!1>+SyY^{~69c(Z5{0lH6l4`-~G`whR-sk=-Hb2mr70=rp8 zVF=d**8a$Mz`5^~)R<;!XQ1grB)JHln-@}!4IE{saGVs9iA?zmBIVg$SGi^B8SV?F z?Z&waxf!-XuBS{;_HKGAk>jcfqJ`qp8#)kDMQl11Dj#N1HWZFXv8S(5IE>LJWR)b? z9Z0QWC5%Xp%}L=YEpj(k5uFGu$l*N;-a+X-X+81UJfrmB76g8aEb1Oc#JuU*pe_;D z*O9dbm!8);w#=lmNH3oPaK4}o?TmnhYteYDN#Ct1h)}3JBXu2T|bV5*`VLoXCy?Ho^2zD&Yg<68$ORyf?dLG$S*c4&;;a?9@0wDa|We) z7`2-M?h&2&SvJI@bK>20p6HQQ0g_dK|572egucw_qUhI8F!LNd?luA6k!X2HHffpl z94W!MiHIL|yFwA?rhnuvC%;6Qw${-AYAZ1duzT^1(@*}xVw7SGKbwSigr1!J0qT+l^Qpq~*u2XV^Z>j+@3x9|-&HL~ycO!?&PDUuCm&$ZCpi{xnY=Us8E0Mv1+U_4ie>~`-I zfcg%(hBg>C>gHWOmq1Gadef5y*s;vrJnvbq*$dJsfTIB-LdAv_vzN?l924?tEtbE)3FCblk~#x5b+ zzZ~0Mw0<+!R8rI`R5Ewz=dQ++wdj&n;C*k!glYEG#q-4Z0*8~Fe1zmZUaPDXR#qQo z?cL9A7pK6^Y{gG@5SLw+Z%gd1ZC5T4ye~JccpsJ1N+X}VD!$mH!F!GFoJD%~*5$Jo zYe^<2gTZ-0xSd+_+1PZlN6;R0YWD7OpR!Q9%iM0eq~4ukmom^`v@*C;FrWm*0=z&j ztPHf7QbKk%Q6^HB`Pv9FA<(t`J7hyCf@J8~%Edh;FTlGxjdKkZ1rJn;p8&Wjm6haC zBsl9el}St(pNt~9C!8r^E{UttLlJ7y9nvYpV>zDA2f1sjq}cR<-#k$gQsS;~yNWf5fZmS>b!&Hp+dcp|=vF z%52ZkIvNELI5&sB5?57snuT$oE7m6qgP?(Ld=fq;k9u(EDgY`y=u|77RVp_Bfqc7( zv{i&KZZ0tnd<-Yy#fB9dU6Z~vl{$#0ij|N3cwzk6s^|8sT(M~zF)1!bp;(q3$4SWG zO_Z5_ff1c7ay878+!n`iKg@@{95VPY>ptxgcsH|C=Tw|J+41qVV3{V%bdrZ5EQbO8 zUQ)S3PY7>~t;;EWd%cB~d##dx6acS5m4BEDm3>{bOZ?)ny#%}G7`bmI^0~|Sl1eKv z!%Cx;+^hlKbMbqB;?u0$U9UL<2Y+|M|3RJ{eDq5Ey?buo@a@vA_=Fdy!ueB1HL*=^4kvn>#8*>A35$0YAeVa-I8eJezyxYas+7%klOO<5 zt=1_`go)%>SSf5J?z&Hh+#rmsKp9DtDxgbVCTMPugyLK%Nl)izu}%0)cT8IX%Qmj` z=sA4fH#;?uP}sBW(!I^q1manwTSB51Ck*qv=Shh)T9txg$4NhxShzu0c#bKi+smyS zF(%FKqksNquH13m$T>BRL0C^R!tO9sE?x-G{RX?cfBfo?Q4>SbrSQF4_*k-USmNqh zCx;KD-=F%9zb?i-Y2-euXLG+UdMK;q_tFx0b5_qSSq9)2WeWEcy*Ajqh<0CGjKilc zih<>ui%;(}nY$CeUUSZLq)ElRO`yr!Nq6@z*`BjiaP9iEa%=zm1jmc5O$y#Cq6BBl z7mO4B*#L(?c)#0|MrRG)Js6yyI2A$fOi*vYct*_IIqfu}S(8b?{=mX%!i$w!2P~7o zyls#C(TE7QudzU>Mye`cVAr21VKBfA#k)XlsT~>fw$AWQsOBBe+Kx?*AmU&N#S^6u zPctXNQzR}SxEi)~ocWwXs8Toe`j$o9x(CBI!8Cl}5KDl<36z{udiHI>lTlw__$cU; z=SjaEMV>1~+eg&`LS@mogDGZiCyF0#C1UVccmH{Buj^z<0$qeoDndN<+nFFb?-GEc zU>@y1IwI`;;)^f7@3y;9cW=*HcPzP-eZOA0!?Q-7_^*WyZy2*z((PJ8V8OS?8G*0I zjX3q)_nR5GT?F36@z>`kCykTm@1`Gy%!(6Se=#j}SGljnBITP;VD7$;&*XMlbIyFd zyTtCoXY%&PdTq}2lGVx$TTQC^oUNm}Igl0aeVy~6e%{)UN${vx%->qGIj11r&yXT` zvX;-pIT?4wccza9_fj(F9ve)G3FW9{-bKf-*{vKAc8`c12O~%tqfGO9q@5aFC1LZ4 zN(l^$T<=t|+6^~gQBrvqDMH&67Cx9u5YWxwow&TqlPH`1;95IT5~`s>GPvu;N<_Z# ziu3+uZem>p{2#(i`lfXlZI*Th8z1tnR91{gAy)gu`nmK0tCNJ~ZXYW=!0tRz_(Cyy zTS+duSu@Wen4F%eS50#{j3%dXfgsTjhmsnEHgX!Gope{p8xp_0Q~1E_Psy7i1Y4b zl!Wg?D;YgMs59)>xE||VqmzUBMoz`b-(1wqfp0#6$z+Z6?!~lw0r8&3?rWAz-cIW! z3#OGDPVqJlJ)Tw`P4&gYc;cvC%!0qtch5eV^JHo{=V)t5g!jC?$}QMT%22?yu)9+h z40mSm+h^$R)JS*1x<|!IJR42QfT@wKgTQg3QE=)+fxJViR6)6UB`2oaQ)RYmY>3vJ z56g|ju1x@FYek=JqTji#bY`cq&FyA@@mN79NnjC45*ZB!P89M=j%G7ToSqWdjg%c* zT*u&=RBj;%N?nwead!ifue9&RKH+O(1x9MmxHkvZ?@X76bQ6QzHu{Sb*in=fqMM=D zbir&8o??OoKhaXv(IdExf{=&~j+SZW{>`^B&*|4h24K%xyKIe|ujHD($$~Iy+L3DH| zyL-y@9|zK`R3>_$bqwCi>o_i&%kG?vzXmXe%tO{xgqz@w9 z%0!f)b)G>OKNDcCBN@h7b@;l5-5}1c=OyEV9^Ctb^)f_bLsKBSTZ!N7e7)1(`T93e zMl2ucvI*fk-y=yzjx&hpHHE?|J$C`oOA(>0PYThM&9HPI&bkSIJ?83P2D4}M?Rw>V z-BMzVfkp01LAn{Wp>yBVM3L7gc9>_5bM9pH|Ge-&zIoaC`D%uJk5!d-oiO|2Pyay2 zpT1YgNp;KXMyS8%>;K{VJL}}?O(le1TzyQ*+1w1l*&x9+X?IQUp4(bkC7P7O%A!hV ztd=ZWi{E65cd=PnxVsmuR_@;wUY_S$8`+A#N1zGI-TMbf5$r7SbvGIgA@=}AlPW8A zTrxbyZu24N)JS(Q8kG~vu|tscl9Abqj|jdA*CQv=_SC`iN=;}U_}GIqyjyD&>BK3= zlmLabZ`=AblO{UQRj2$!(&s2CoyG~1Z6e^()pn@x$}=ZG=6bTkQc@tS8{kd&jMhmt z0ZO4X!XVP{1i8(POrf3I&-}Dor?qINY z=tTeX>#uiqc0MNvZxPFf^Tkba)LdfVnb?lg#p-3Z?WH2q85cYVVSN%(Jr|1a>l^%A zfbpfEy+GftOx$D2U9G&At`cMCKA7^1@Q1%P!rVDOccKUg{{9;}!p0I?;K51g7?1`| z=k|A{%zYAOKb6;iktffqYWPop+{>d()}B;O>fKXOg4Yvk@#SLt^<{mta$#xZ!%QnV z)8uF_?=I>0{t3G>KE>#A61ywGd;U`VwBCJvx%JEhQFWG1De-FUoa4ER;FB4_n-IGJ z@b;&RD(UEyHSwlo*hHBO%nA;-4hN9~8C=O4a-(5k6q|)g+gMD%hhr?oLlu#}1UlOa zBsEA9p+_c+3VSw0xAz2*=hRIFL=s-Af&9V&-buoM9CNp%>joJ?vPl>miec^{5mpI| zH*+k^1TpjH2wvI z-Gtwt!_xhv6(%FpuF>fL&kaXmmI1oEnU1Z#6cT|cZQ)OgCu?n3){*)3+93aWdL`&@ zWK?;xY#_N(-=1)j+?HI3@9(6}t!u%=qVCL#Lo1B2>P|ljw!fi3g%3fu@3#+e&hT2YCEDOwMpqH$zgkE!t(`tG zZ{Ek*5yJCW4hlmhlxPl{S#vmK>BVCEp@$_*0c!uT@VyGP|JJ9H>$B~-`u5q)WMs)z zUE!`=fr}j5XUv)Jb~DBF`~3Xwn{SerVBbqNZ%!-+v|GKm&i@3O9lSIB3eS^>zW?ej zWODwKvR_=h85icf`Ls5ZMgHzmGkJCoz5BYBB>1+vT-Os#Y8?zq8izMFt*lbK>y^Wc z!UVZke(O_6-jjhQYXx|hXSn^<#S2WliFTi#S2?h=(9LQIk1Ojtl{RSisH}%anu)<= zm;{3$lEKK)qacH1!pN?Q5R=r@4v*|Ci%to*BciRqKSRC=jAew7Z5BfWcG_VrAyS=n z{S+-_i7io{;If+poElR}SicEbQz*cRCK zo&Eo?w0(7w?9#Vc*cpZ2Jzxn=rwnhiX1EsQqfvX>zn)pvmRsKRw$&S&iL}A>Aj2c$WY^i`<I;erAahPz%aT}wNeAfRTq zw@r^tZP-X+%aU39X){Y=4<;3&(5j0<;mnUt>0NVTie<%EyFr&dlDkE_B|h`FTRw^y z=-xvQ*22&Oc+-2k*%WvQpt^!y8MInnKe0mOBxWLV&_@IcZ(FrJ$ui^QzmE@?M$RGE zQ|$Zfrk=!IBn2MSm6ECn=cZ)blR<&A(cG_zd=q+WsNd%q&^!Jn%)eW<_uhd<@>4#d zhn^EmJ4WQbxN77K>!TOXnVz2~Cm(6f zNbFHMo?L>YX5&d_%9F^LC2y`eqi>~#u^Ny~=KyEd0Y)c9k&c8j5IV~Ui!@@0p=HYO zEin#^S@2HbE1@qeDe}bTDxH+|2p&APAur>pTvuSxT`D5WP)od)*Agw95)#-A`*5Pz zt~+c#Z8nFN^!vTOhrp}Q)!3>b_73;A&U_)QzU#Gl-bn9Yil)srPF5-Z@wA!*9NcfA{j=;_ze{dhZ+fR`&Cg_vZynvmemF zw@99!giuj-0pFj3bWb-`&Oz>_n>mZhhU)>|)mr6c%_F!xj;cntFE=`@tVW1q;{6a& zf-4ieX9Vx9%eOC9hnbu>>=2|kr!jVTPat>UFEJ2aug&2D(Nm+KKQ!Hy2$x9gfO ze1YZn$S1T;P-V&HK$ZG!V#QfTh|2|&!b7Jeo*4#`c3XI^@=}?4u5D+wF#wA0@4L;W z%3mf)G}v|fZm)0khZ03O(ca_7d)=pd1JCtR2;Z1v`kCi`-Xo;n{%qT8ZF}48Zj=ps zNpWJ!(Vo_RvV(4UM(;4phr;SV+2M^Lc^ANjGt#4%iLjOWZ}^@c{kICc&&FLhQ%;ge zGfA!YhD+X!z!s}q4AcJ*y{8wB z6Yy=s69)rtuI>Fg7-}DzFY^p3AG14VlDfrlA0_NQqnZ6to>k6QD zf=JvmqOTfj$Ct_?yfVlocrJKJ&D=( z(Y5D0NoLF>MMB`Xz0<@@m7~e4n|YDks{z~`KQ~4v&rdqxzlY!a+c&=>0v_7mE$+p+ z;8`b7`zJ?dyMHQ05**LX_2)V}hcjgj_Wkape*ATw+FfM`F2e3-OXcom#W}NqCZ;NW zVotd%jcS8A-c@PM+U8IKwc6&~nX@$MIYJg4i4c@z7#EZuEB?GkhocsG6eL2wd2d9t(fHD4^t8|HrZ z_z%55c)fyPXBrOiJA&_izt!!w+?}2Xza*qi+8OIDo(Hwvwtbx|kD;4RDc0XNWZ$d> z*>xHFY?6JC>2{rJSA~;=(0`dKzqz?GZ2M+HELj`8XDorQ5B}Up!sHusBy*&bi*aD! zn~RI@5?$H8OZdk1e@)a+wd+^2?-!li>g7Frptn4D@og=*``Z<*3#HtByF~7OTNURl z7EQ|LoQWL4v4vvJW#iaAws;o?kXM`L-bXcu_bQX%OpxF|J$tsYtMY_Bg6HQ>V^EYX z%sql4&7^bMDLN_(47b^7QaZcwA>#P%$kBoBLg&sR;@)yJrrm~yO9JnaR3^QfD=L!! zB%C0boh7kBZaW>x(FhYrrSH&YV@H{d%ABO<76)9^any>7QU+H>dxJx$C%#Ofm`J`$ zVq+(ia2-|edWfAILf3f24iYU@h}1zyFfKfRDt!5p@SHe$Kizdg+iSUqm?8o_Yy!Hw zOI!VR0?$S1z7Q%3A)5Cx#lcXTO$TNV8b615C$G4VmE2dAmh z(w7`K1ty-RN^-nO3?7e>Va_>HZc5Aj`e zyHCyjr9@4Rj(Be2@3fxmJR$B+cY!T%`)RWY`}f^YA#na;kl{kbO^B|LUQDtd3M$H)n-VQn2lVtD6r1?5FrS-RF4;)9*&1{{9QP zes_1B(dBJN(X)I}Tz>jqb#4pLUZ-aG*|Ic~`J>9~GQWE~t2CNPxfVYun=F`BmOJs6 z8=Y2eZA}#Y0jC3@2$0JhRt#gLHA%>RoQ8D=7RS`9M#xqQpCS9@xBXE zd!&O7)?R#ADEurs)pWyHH^DkQ6ZOQFnIG9wr;@pNp4=TqbR(n?pf?v#BF==rk5Rh- z=(gE>?ZzIY>jXRSbO+f@A%G{Au@0(8#aN95#I~?1>81VH)eic|glM@$q!4j30jq_{ITgVx0DS4OfAu^GzlneM zJA&}v{f^)pTY%OLGph;pY(UXD6a<#XG7sqd&zer6VG9eeDr+G zz84qftZ)dH>D{;U0!=1X;!DlsdTLU+B1!Oa(~>tU-XH8VIl8~WdzyH!Y4G0KKR8*V z?hJ-h(C(931nd;=Hi%tCQ3Vs|-7(-@N!dEE(=>?aTHV2pyW<4(R*N!0h<5;y#5S__ zodUN;x+{9dctmLycwBf09bfVMGDf_KBm%8eTgS%IO&r~_!YFEc(rDXAbz>Ra;?4yC zHOO&`c($KmpGQVM@H{m`PYYF-KAj${Fk$Bo3G{nob2j`_{BGqK`g~KLMcX4_5(s);hImPQwva^ zJW0Icya&a*=j{Qrv!=+P@OYf_o%aw^%b|l7g#IuL=xmZ%7M&F$>H1>Z`ny5vxg>iY z&91ZW$~iJNZ5xM41==-fyC}W6sRoQUXCDCI_dFn-y!>7KO~=mlxnpH_@9(V9yNj|- zrvz{l(9J9G2PkUz^NW+@j!5?RR;MgF+sE}U=z8@9mgz?at72cD@#m>IkPeXV4q0tzdyKR2Yf}qB_f!|p)VnrME@K~+nET>u&6%k6wW$~%4xJLmY zQ!&R$;SJwOE^IgHfqBfqQ?P3j2X=jpS_I`LmQJw^ZzYV;dK9O=&xx){h-LN`-7OPC zmmre9ZToF{j2aGi`b?3z{>+ksNv|uDmoGyb5wVeTI5;1iJ0povruUCs!fqkDhuv<} z_Du+(Y_~kw+IiykU7hy(E^8;=uywpmunnxo$EG+w))|&Bg%MgT53|bSc9)(D$tDU3 z0G`*wF>D^YMdWw*GECeNT#{0`Azo4lx92s5_4feTtL5y8Xp*{hq-5S@>^9dX6ou~f zY?8uEV#+3qe)qEvW8e2Wo+k+}%Et)m&hlvYE>rJM_KPO?>iudQ8+dh+ytfiN5840i zSe3+0*Ta}(2<*9d-1C+U*;`yQs}E>+YFE z%~?R09iR$cJ9;!>GNG4!S|GTj$S+}o2=Lx4QOYEdnQ(J#*dV$)&Mh$T*i8k}L_~yw z8>ErgK6l)pgp$JvmF^CCO`h*fL>bNvrS~Lpa!nXakeTOQ5nCSD4NDWgP2f!onC>Ck zQQH|fXw-@J1W;5AqeJ9QAt4UeIw0bL-rJtFv-4zUX9p21QVG9%c-SSxF3_9a>3kJ6 zg>HABw%f<}0T%eRE0i5|_cHoT6qh2q$DR_0+0&=TCNS0t--k#(%;~psdp-KKkcfir zWb0QcSNNOybnRjW^u4TAh@pn9sEIoi{lV9Brz(0U?v%38P z(#h}sY zxLs$VvbIyXQ0-m<-EWtrnY=9rmE(o@x7f@vx=CFvxn2=yvQgEf;N9aEhF3=)<`aA? z_4i+V!EgBBns1@C{lez%U^U7&ZP2Hu^zTW|uoI}P1o=XOcEZ4)GDmp;KF zGcXwVc5oU&J_%%0w{|0`8-{PXp4;6OHfR9Si5pAlOBahYQe*^(Xr;8c4xTPtffIu# zdt6RNhZZmawpwY+L!~@ghGP-kviUAT$u$>sVoLx4Yo<*^UMGNw3daHlB#~9{=`_ zzy0mw!>5Gd8JF-x+0(Wa_C>qdeu~w2x*Hx7COLt5&r^KKz3$%Lqu)PmHjn9-dr8QR zxn|GZ>0vI4#!dWo_~KUv-}go8RTO(p*x%V?iR9~=qFs^gazzpwk`T4W7LqaDHuyaU zh3^aAA8`cDvMyX6kp2Swd#d2b}t9-4bLh|-uVKf$&AELUncOq#>Ywcz(?Nycft_uI!2r)h%~ds_G1 zJtyktNzXgZt=K|DAh6qUR5BVV-vR%2_6Cq?GU*Zm?^yjF@#oLIh=~4B_=kIgLsOoH zVtVlOzGZC_DL45iUf=2;x4qExHw=gQ@$nEM`S1DdnEovxmUrm20MHtWPSKxc(A)Zj zEg>HP)^ig_&L%1LeD*zAB3b9!XUwT9nq4T{RUvR`-M*<07(WESuRa#J3;6DY*wyJc zjXNY~-eu?Kd2&)IC3ADSiGBYxM(;+YaPJ4|tMYp1edpkIzF0C59(Y?X7@kABSGi0| z=w4JbJjZ7;S$DRc;Jwjd17FIK$RY<} zCPb^6tTo~s>S(!E{(@#8~ZXu^8>QF)U0VbON`Zbr~c zPfY9_L`f%F(fJ`k7cnt#Oery@eB$o>2GWM>NeJcwO3jdvJL*0L36Bt<<%zb5t&&*$ zk;m|WM~gPX@OS_ zD}%lJr?1Y{`%Y~>d1C3^FW3)03_I@@Xx$5p-Sf8L4WchryDQATT@c^>vJkjLU(c%!n`Fi)(*0XmnRv1l8?g0mQ z*V^RggZB*U22z_aDvTZj8I(=K2=68iZr^1o!DA|IUAatRTLxUJ!<}c{u5Cw>>lWf9 z;lfJ6BTEgI9b;>rlciE(B1$@U*dy)b z9-Rn?gZo+5B*^BLVsF^|{nH`5C|*jBN?WN%KlqMo-Fb^9w7|rP7bE1=i|Kbpd2vL5 zEkx9gxJV~*qEml|AX|Dn?vA@n^ty++<&aJvP|lwo9(E5;3BdpO+sA|MY4k8kfX8@_I-12%k>Hs`)tkz zO4=(I?CBo`B?|6$bA$15MuUzgU?f$a2YGz}qJmVmvE4uS7$0$ah`L?Ycsop z1F`RUsc=*2sf=(P`$6iFMU;K-P-H}r=^mL-((nIY~YkygwCizbO=L2623O(ixo`e0O37{f+PT*T{2)?VIl0Ihk^H z?>}z@<@L`d?IjDf?zw9@x6c-2nT#ERw@X3h*PFF9?8C6d6?#rzW3*NJ9@f!^i zoHlr`f!){Fmv5iFJz2R{*#5SWlx0CFU-J)>17=^g~yLQ7ub;T0Q#c*&tt zaj(~RBf4jddP*HdUCkzwOg;YUvFQ3yB(a_Ew{0u&+~#md(5*1m#JsW9(jv>;K28@o z8r~mu_YS+hf`cUMcAsXh+s$JMXNt%ex-(yL8S!ACjT-Il$fmcw-P&#+vdI0k+jjeX z?`gZsV=442jI^VnF!|Z3<8zuxv)OJ6OBwX;8MOp(%>z|>ZQ;2+2;W}MpmnbhPI!We zJAY)0<0mK9lN~klIQA_2o^%_q5#JgkI%B8f#K`rs_GzX9c^5@(e>)Rik^rb} z(IyPegy3y;mAte>w=JS>*KcP8-Wrr#LHBmD08&k_(A!%r zEapfQ$hYC`wp^7*##Yd{(@v0&G`uQKBhn+$YKb&=?C(YqPW zd$0^z;rrrC&lm1A`<{U7&7k&pWI0Qp&+f^-ZFo%a2rG5 z6dHdJcz6*zzLmVFkNHLKql#x-2&$cwRy=f{(hzrC<4n2!MkTI6ziLDQ_u5Nbo z98_ETsBIUhu;fj6j5O`UU>@N);cWzZog?TKZ$sk9zVFJ@Y=maa$R~hAR-rx8N@?`W zqHbeiq@^aYL(T2zblu_q^j{ zWp*vwK3x@MdB)7!9%Y(-AKAb+1mTY#(+NXz$hQfrdT%kQ24u6uO>RW-vu(8w>r(P-S)b!j*JU`Z|WJ_z-v?KUL)KK5c!?} zz5&i{k^&8K8|q!Txi3CFf?v$$bsO*=zunG@4qS-bw@YdFGP!%ICVm~C$%7@DY`(Sf z9tQ78y&HeE|Lfh!Nn?#flfm>({7m!09B-gqswRGr>WGJxMivQz*xU%Cprb3bn?tl^ zsz(W;VpDF6#~vlelh`gtzH*dz&J#*Ef%67-KpjVc?sj!HwzO}p^6xLpO5zT_RxR^)-2mXwY%MR_b`h5 zLrHXA5Z%8Ux_M4do~R6+ILOCBN|x&noCwib_K5y~1IKz97VwIb$Z?bNy|+Q%i96fi z`TRFX@QMK`T-q5t-UW6ehE{HiRs_T)RpW>R$YA{L^dRw>2+PuCWtQO>_XB$Fn&K1*m`hP*#T!E zd42Fc`{eTWRb3#ts*(b$tKO9SyF~6cpAfZYT5_J1eG3)ko}}H^245EjnJibk7lc?7~eg^ zxhvv5;^iD-(^;T9QNth0+C;7$AMve@Ha(TRJp)5G5I&Y*+6bFs^EH;>v0h16+9QOG zz=fi)4UgO^JM*1AM@C(h1E^!dK1HA{VJCqZ(9M$^VI~%)orJeih00C6+={)HOhWj& z@wi>7VEiycOJ8iaT#vpK8JZ}a!^6EthvIM`G9lYAVrPTh^WEJ+OL#*)R7v(Iv0}orPnNdLheAg&Q%s&%e#!AGR<8hf_`dJKzRwn!K<2tW=1SIQGhBOueb@XT z6Nc)wCy9LJ0O`Lx^goh`=gI_<6}z)r`%UN3hDUT!@=`vNqRqbhFX z0aIYt_IDf2z7O0XI*=$t|^uO`J4!Q$I_6Xy63mNu0+CA*6JCkmE!tBIU8h!VXN}3A%w@ zB>H8i0%@(5!UPd|3g=C6Y!&je2{T7waysza1imtEa0a{XvFU{E-q^I{JGfq%gMtt1*Qd{; z))Q9ioBOlxvEnfmG*W$0WJXo0b|GXR)V$eKe!q%ppG`Ej&rTLU0=zeg+|%s)q7+L? z#{Fhf;62?6U*E}@y9>X6lDvN(zJG6>?9VlsRGj;EY2n#K_ri=v@Oq65*v+XXg~Pir z@=a(aM-L&IEUT=X#%{c9IrzDrTrxk@1XaVQC$+}2Mq_@ONqtIbzK{mQ(=yf4h$yB8#hAJVd4ep9S!5HLo3~(CnaTjc`_PFo|0p)wZ$6jPx zPds_(OZw@EBJqiI{}0jjVeg|;is#8J%b}WBiJ{?1?)HieoLH+%nKp;Q~pMD@Z{(eU+(p7_mnFN}>Quf~n>8#f6SPLr*b2Jg!m?B06&?0IL^tdiqQPEH#Q zr%_*rFOYm{pK{XNjY|r_n_xI)V(n*G*MXB8a6W?CJ+2xa@tx!;!Cqjy(k{dYMrE1G zRKrkh3l+=maF|6fo}xWG~o7K@NLcXSA+VVV(NCdS?Fb~9d;2chK_ zcu#sZQC;XYNW_*|*AxC{hg#lAI6Nfk7)JDaO4-`!!%7`v`2~^;;rfUpYx#E+Xs%be zh(v3<{eSN55qjS-_ijgRdRCZ622ilS`s3raf!toK2)gNJLG;@P`~K2JmN<|%OblC2 z+$Wx`cnPOieuumb5yUeP9kO=99(LA7cc%@kN~3q-4_qvFml=XZ4AmUgU0bPK1>T#@qbeg! zihajdo1Ru4VQ*)(!Fwjqiky|$#2+pj^+H^q;4mK-IOrL@g+C}REVpY*dujsL|NAMjP_)bvho`f%z zowk0nvx9Y=ILy74N8o+9x3?$F?}o@$9A2Jx+rQcQywz?KdZ($NU!T~!()vzG4m%k} z|M=(;_S~%8mF;#Wd`^!A18@6EifuDPwV;2~o1H#+(yQpRk+?mUNSKYo7x*QIQ*q39 zZ+x{GSQ^xZ{lqE*P%LZGfqnA{*!S5~)A~d<)HMI*uPX6+svNT7*{q0Ev8#l_EX~ksDGW^)tP4D}iT;9=@uIpBzW`N<-zlnVt0dgb6D~o z*K8~vRO*`IZ9eOuT8PI+yQy1<0t_TaRb5W8$isIaVylFVaxD^ObF4FTAM#Mgt@cEUQBR5wQyO3AozV=z({ITG@S=cU@a4yD%z|s+TH4f{T)?qq|( z`6i7=nhY^`Jayev&}~HEM@bL~ zpRFR&*S1dXG6XpdIR+dnngm;}@G$%IqycZG{LflS^(~L+FGx2ki(Rf+h_Z-yJvhIJ zgq=xTLF~G3S<>xW{hhCOcAg+UM0E#;lA9zg^v%;rB6h$28aG>3_&M?We!m}vTzgOV z!HGdU>h3-2o&vL@GPs1!71fvY4`r#_Vh8%jhJXS&q?}KNJrpxQ3+WYONQf}_$4JlY zUc&p`LrohJPFx22Ua@^y#DItQVBfV3#_?8T<;R}reXJ+=)gxA??buT?c4g%&5~6Nu zy}rwLAwLy>Zx*=0wrf(!RpBow%WyU-a?cMAtUgS=%~ee1B~U$kwvW=C^%RpycQnv6Rz3DIdZ2x&<(Q5oj6>2gV z4CWdH8`GLeMYzX`iR07TNb7)wYg{7(KZtgn434^DRVQYtgc$WHfi@v=pv+EAUDWT=}Vaog~;;E6{;V{mKB@!VYCp_ z7ht3)S=dHnJlm~(879`SoAz8!W_#VN`}pte7$&q2loNyJ6o$?(Fdq zQ|sn3DUUdCf!!{z!vlZ6v@FknvInJv&Iez9$$r5xKX;4!A~%c2oVX`qtBjTKJ!|3< znR~C#rj+XOj?4t9p5ojEv3`A4d9bTdHzQ#s`_scq)eiTCm(sts%2mEisA z=mCb6^{sgP?ENg~|Gd?Ur9P8_b_2XGUz{wqnw*UHb0%1KV{QK316qWU9hln~R>qPW<4=V#e5)+dCTl8% zpPQa(*nQOfJyBoPJ=NI!alOb_sUi}eAZ?`Ahxyw=B@Usf6>Z|D_6WQ{5H>l%lCUE|MZwMv86Q_6OA4V$kSvu_S=rWe#} zX;25#P7&i4DYj`2u4Y8+jRN>X97Q}}wSQCYPF@un$(s!`?kUo3F7tfd3yN~es~3e( z@#S`<*gfqs!A5+2tMYP*&*VXB;wJ=eh$dsLn_-hHCZVddGq)6Z4}ny}a8 z`f~r>a>d((csq@`th+NOg{n&LCej@Rj^h)2LvzrbAPdp}!gb)EMnR-&{qR_ubR1&O ziS0zTK7~&(i$<=?(@G-QQu_qZh@!Fyvs0A>8Wt0eQ%kV=E=AVNp5E!ZIQE3EA<0OW zhlp6Ow_+g)(J%;fIW5}*muIHy5ouO;nb;QF+n==vbhEwP@11@R(CiUk@4Gr0?23Mm zo9GC>o9&@O*QHDM5Lq0CeGW_!7Nin-kN)`87yo(+D+|)BdVTDuL;5gFGj1;*7Fg{= z=Z2NMDOf7+(FZ`k7Ot^t19CmHnA0mZ;$0I-CAsMgAZ)S)fygG;q}MA^oJ}hXm(<@8#C>c$bMID-vOeC5srH;4*ZRG2b9t41I zLHMf(v9*G0&<2SOGA%M?XMwnr^hmeWN^>_SI7jgf7Hy!B$3n+C^;!axNuv9nmCzjt zz7^dS8}^u2vgDkh2@TS+D+s&=5p5#U{lV@zLI6WI@{vFVxy2(K_Ie=QLzS5=8hW0L zo(64jn|_mp6EXBy zFh|z1%2FHDS0#@<~{-^swg~ zYH8JZ^;CjLwXj&9G0v_y&iJs;Ca84<%7vg((=2YLOAMA(ihVSIUp*w-o{k4Bzj#w+ z1&)m+536*qu3D%iP~9#=?zd~3Os;EfXFt|9;wQ}}TT7dUw;sYHSj16nKGNi9EO>9# z4c;%5y1OF|nxDK~w3`FHoBq6)|FpjtyPc`F%EpY*WQK6lRoZD}_!`-*woyg`m;(uP zi9Gw7z1_i`j>avOsSHL6W5$eAO#*$FWvr?Ih|}1Y33zvmbXaUbX2iK2djw8R?{Nzi zl8KwkA>FKa(r%$mx_~NTw6sHY13Kln= z?*8#{VZ(`iQ?Fp3(?GK!@P07duCwj>{>@e0!@cqG$Z-%-ArsNPwcf*dW86mXF1>had+3YIPkR}_xnl`gu97UVH-`tIhP1S z;-I%MgbjNrVEf29-5W@o1gBBUN^C4&A|M4}RJh)Cb_WAL#q&bAfnXvsl<(vrBR6&` zrB0HUq0+@FWwGYYX9ZQbP25sB!AXN7w!Gphi<4nJb92ZdN>R)J?>BmN0P7)_6_@+- zDP97!q%~(VX3l_dEQU-o?8?!1Q-kZ9!Xr{=*z+ca8wK!(JSus6>;)|IrrwlN$t-HW zc`(*}QQyd!n;bah>t4#cmyzz;O65$3;N|t@+=cknO~aR)@2oU^!;=}_n+`OYm*D*) z{}nH1^zPDVg1;+)_s`3_b4uA{Vp!QI<4k6#cc2?tH?)(C_;Z?JE8c8ZrZ$#q z7|H7)f^lgU6cUT}s>iU@O?xGJDKhLeNvTJ}}9t=Ns7pb?qCo6a@VS&8mP9^SboZFRU8>s7fCS9;(-|Pphw&cf$$@Ydx z-Mk8@GErPF#r#(I*4YG+HgDqz+2^25Gx$Bty=AlUUw-elZMN3X4b}yGqD$RQev?o?7r%WcSm>A8r765y_Y&B=| zHSrUA_e2WpCKoHmdiUZ4@9Ix6h28uYzP$XWizVxo1m4ccg7EIiZHDgDNZ$x=BIqWFOcjTQNUYru{dT#w($_Er##l@A zU6rPUg+qm=N14LvEtr8O>JI8jqV2#-m5)svBHgj&I)w74j$fET=v77LhGFaylkaKzv3RoB;uP9M zBFfdJ?+Kw@wny5@NJWt(0*(Tl-VlvE@Tl}Xv;hbB@bOJ1qqZEx7%*fXU2ZN z_n`}pZg%R;=KFh4Zm(yA6cYeT%>R9_n0d!w&-BztB-n1uUVvx@A64zuBzR{cJYAW8pras2bruk8V{Vxdiw+R1XOC(t@ky)-@CN(VL zLxLbDJ;~TjxGg?Gvzg?*oj5*Kex&0p8xr&l1rcv{Dv^F>u5F7Q5wSC zO(&Do)LKecxxm^m(F12N5L$10Eg?PC66lm~ce}3Tik^Z&PwGTzdO)sZOYzcWqy^&t z5&~#shbTovoHy-xkJH6@B6FNf!wlj=;;}GL_2dw(u)~)0`fi^mhJCySkVCDkJT?_( zkVSldyM@EEN(6@W(+Uaez0xRB%p!R}>AB_BB!A?rSdZN&Ov>Q_f6wvXbOXKM@QRxG zVxUQ%J)|f`2-_O_tH%){V;)<$`fjG`9_M=SHVxiqQ;iD00B9FxlBv?Ni;4Y77P=os z;a-&&I4yL~hwfqleu>3o^_+5{+FkYK%*fqamrKBVYwJOXx2Xr7(Yuc}xL7&SHaw4g zUryF9l+gW_J>J**Kc6fI?}n*qm|3l?>D_+WmQ$?5M?9&FGKsHZ-!CcosSYF}y(f}P zVyF$acH`XT*jE{+KE|z%hRZu0bR*Lv%z?0}Jvh`Z=fhfwMnSvEZTpUX$Z009N{@R1 zw+TzLIMrRheTvK|x-m>7bPO9hud9$Af}bnx%o*&SJI>x9@;q0XoWGQiRK$dhQsiM0 z0lMkc0IcG?ERXUv7t5I#KK2r&WSmRq@bI+h5f^ur7N|JN!9LGYcoC_t1IzzA_ z`tD-o5@tQNji9Z~vx;FNF!xwA#c@lxhAz7%%mmVOtH%PjVb1R@>{zlnkQH*{3?$h0 zj>WJ{gzcI1D%1VoxyQp}&*Yu3a)KxFM4L{L?W`>XA^F6Bv4{|vmXjAE_X7j?FG{y- z2_?0uWTl}PT%Vxc8#b0KAl-|E?z!ER<&<){$>er5bk7mHOSyYuF=yGRa>^oj`5^x8 znHbmyNbp{}DZcP`^B5pf6j*gxR)X%5aY;}Oo+Fq7E2Sp<7;B@N+z}< z&g-Le$Blb^H%&O_Po^o+*lrfMeW_ci723dWZO4R~Y0Ha&@iKDGcL($f4jw=5dRE+G z@=ZYagaF%$y-0+vrG$dK(JHeIUCc7+PFST!j$lA!KRP`;?MCgkP%6^hZr06)?$A3v zCR!}o?WV{TZ&7+Cx|M6*c{7q=*l%ysQDk!)vTPj_K_{Z^7S8U_8u~1edsY#1;ubuRzd!ifcMoe3fNQb z?W>EKspM6C)&1%LW|9kJ?!~-&slTLx^xNAdEoVz|Os1lxX2JWi7G-k1G`o8$y!!$4 z?lREi)#jnQmPS=$+()a+7Ycv3ahfb!(5a*P6z!e_Z+jfzZ5J6-e$g?k8N)|BdvyFj zD_twDG`w5INl}WXW#U5fc4cOdWU7XCHW(@5)>$kx949ubB1F(rtV4=C^uf!0yRX1+|0+~_cpDdD_qr7gFQ zLU#`xJZ*`mBizg~`L(MN(#`OVE(M#Xl30!Jz4zLF_ptle>FT?oqE`i{QAP|p>K-17 z)^OMoVkn4rqgY1~B}dXY*HMOF_FAoN><4YTW$;MID?i39(knWKEzhEpfM*rnZZpSx zZ}m#hF4ghS;5Xs4TZk;IkVD%(26-2Z-fp?4!)nWW9~MUNbi`U&^GATcAb|fGAiHt_ zj@{cAS5s`eSh{)h5UV$A+h-TNJO3NT^YO!>^@q}yK8zk{*V{%p0BRZY0N9lnIhdIyUYwMi*wAUh;W-{ zmm|XTNCy+RZA{zjBTQ}AwS!dI1kZjZZ8)7_Jt1P7?x} zWBqcNWy9tOB6iZ*n~oM{ zimp)_6c#f9-Y6s%{qRd|Qo6BtY2~41BY8IW^5f&4*NmcQsPzy&a5svj-#qT_?d^4& zLL9>!Zh9549mJ`I#M_N_0;24dF@Pb`T|>9+9~T<95lN7!#Q`NA8&1Y!M>d38y)rD2 z!>C+vY!=ab)%gI0#2&PIuy>D@aXiJB|NipJVvUDSNJPp#>sJ8YzXrITM(x^FQ||2& zu&l@=54xHb(u;0jQCa1iye_dP4nTy@aHgg^ziE6@Va`fsU z61>NOCPznGM+?Dwa~+bm9X6;wp}}QImbK7q;mBg-&?tMZpT9#W)2m}R*O)0gurbg>b8h7 zExKLA@S*Xn4}YH`0-p+#=#<%s>qG?d8c9{MrPRpSTeR;ueuSSK9I{_UrY(g9%$Dap z@l-o2U=@j~ZnK>kw55+NX(jaQ;ZOw$rnf&3pdO11Me#Csm1iZnN8sKIRr9!+(Q^)w z0*Fn{96iViv9r+8LrdAv!^3Q^?d^Cbg~XgTq-b}Mc~yWj8@*dX8u7ZYaEF#_mU7C- zSd&r(=>Gq?d)uEjvV3cF)0)zBIJIMAZSSFE$lg>vs+dk@?0Y*^ZlEWV$ znC2!kg~;Js#250#YUhmZzkYw~w|Cj)7r^wHkn}NW0tO68)T@@)UN5pzQKVzjTu`OP z1BJacz&sywx@jIh>hvCR`ab99#PYu?`~L9FfVZ#OUIFcTm+J@LG4*k!SnA`GA5pTp zT~Y3(k(~SOB{k%}hjnkKbrVFNOyB);fBy1ry7TLbzk9X4``H6sR9`qx!$_gM$(aq8GM7KcqI@%%07+)!M7D&eRn8Zt!CR2V9KFG z&%$Eo80M6THEG)G?>2$cv6j{5SivWcO-Vm|)K|{XM_<_>eANRUTQg`VAvA_9P)?I6 z0XHn?#8Z+f(fgm{}xpc|qGrB~X~@>#b#6Hmy#zb&4;;Iaogkg$7aa#s!AM;nZRcNR}=>FQqV?7nXt{^}O>9E;mOZG5$4?q1^G&mQL8U)UqK9ISjA zgZKOQZypj&)_C{a-;KY&o135hesZ73dy{6eI=rwm_X?uynw=*od@VWp-Z>3XBZw(= zkZ?Z0tRGkA^j?-vCOn%nv9R&wSr(Oadr>w@3s;BDGg+P*_(Jl)#-rdY?rS6z4bkgJ z8yy*0nyIz1wu)^jB0~}<7hu?gu&1X%V%xiDiN#@~()80z3@3=r2)O}Rja|ZBV#Y>_ z7F`l#bGO-YQTQQ|R<0%)X25QdpC@^^cic;1=7SPWSUR0fC#pG_WavB@7DBZfjln>D zH=tW%S2O6EaTB9!YOF2m8VUV2o!BaX(`>hQcbg8ot8#7-fBNH9-arT(9Kw-B%elC# z0W@bn@v4W{xA_T!@_xapZcxk=#x$}0qgm{pIk$JhUs32riT-k}ojtLed@1(*Ei&v{ z+J>PTsJzU+FBc!LLG{P^(d5S`gzQzZaIcfqpF+x0pPyBvwOv2a{Vv* z|8a4%XD^>!ZPZL2BHdrU(Zn59RrSRs}Pj|<2fZS`~ zjknincM9bsDpAv2hEXSqqY$kmFmq=?8HOpW-T-wIuNVaR=u+Z8GB3GWT-NN=82Y3O!C^+%g>%l|l;|XEHV+jO zb|Un+a82lQO{ZfCEr)~M!EW=r!{)9=Q8*KCHVKZ$1jju1kYl!Ig2ol1&Wf-byxfcz z@fzqq^d(Hh{T+$)tHYHCg>@752!g4%iaGTL-5${6xvd?idv}rQ5hY!C=$S*?`sWLL zr$6V6`-JT!qChT)Pml6%1@CW9%)X-oZ~@hq^=05CDSOqv{qgci!Fvh1m)9uQV0#;- zdy7QQooe^>0=O5koZEjLobe5VJ7@9B+vQ-+gJmX9U=XbFZdWAu=KU8hG+EZW?>3rj z;@t}*e|7oNbL*2;YYD#_df?t!=G_NN!JLTK&2|X6Q$p#8Sa)<5bkYNON`g*#W;myV zBTKo6!e;>OJa^;64!%vs@NL};WH7-YWSjL5G^uA`kKQBYYb|wk8{mG?Jk)9O7GPOjurZqf#(ZH<2kk2^nq=~9Q%?xE#nPx)_Q-`_G~FP%v)v+ue{Qn^Sf zcz?p!%~rH~d64q$_R#&HUUIXZ$k|-|x{|0Qs<`ycZl7&=Qn}vVef7ol?q~C0<(tKZ z&YLf55`6RQp2^Bh9kAE8uRi^R+uu)iPMA#Jb6i>5TySr%({5llR&UZy`tIE+*3pTB z0@BZTWwONNLKugs>F^@_oOdH1LzqqMoJh4rn+YMWi6?ZIo=gy99G88m%k;R^M7;AU zQan<}=_zm$vkqwh*9k0vxj}zOs>gYbCMsg9G6VSrk+9H7}$;<<1F3iRdS6yJ^E*vh{>SM;;BWQ(o{5PHfWkE2c& z#pzBNX&kx2H{C)5i5@83@4x7mR`H~bYNEqC(m9LHMP&#vde=17q6n4%7S9HJRI*?j zNTju#*Ojnt0tYvw4sRCpXOju^@qrq6W!!5j!lotClti%|8Tb1R0R6G&-MU>uRzL3+ zEaJ%D%)Wmgw-qNzy@up+>4fsbV(n%%=l=0)0r!%%WOGUP&4bW=^N`ei?>^-niwo7( zS^c)URQc?I-GwJIn$)s6U;MCgH5C8m4vXNk^`Uqcyni}l1~$96z^~+N-PFCn?%F*3 zPG>a}zf(E9qo_Qcqxoq`?;{^?f*29V4$$1BZ#F(OONU5P{za&W2|!%_Qu@{DPCFKzSLq8X1>p>$(BZs3OZ3hy3K1mC-UZ-FzE zT}+#4S(*Ei?u?#V&{uQ!lrwQ-{89j0MHQO&GiTbWMR_;NCg%z0KmH(vlg9ZH&`rdE zn0Fh>cT~7uSy2@d7QCm~WTl56;+)BR>k+>1-w|T_N|MVpC&?n~UKId-*icRK_4#%! zLU|`{-+e^64RkL_-FF{Tu1r+=fnnD`b?Y)EzS!jIVZr3-2G44RCeNO&0QMI>t97#&SA69nENp>sIu?e*iHwINt81e3s6 z#N?B#(4$-he#x{MYkq>)Y?eN>2z4g!ud2@3gaBl_O^|_ooY4@g$ z%0&m&_0`I4a}8CUc0bKg<(s+Q&4-osXwH{Bt6YHh9J}A#PrR?I5?JT&eif8|f{Ew9 z=;i?lAs+fYyZCF$uoj<z#MaqGLyq1A7(?5a@3N(OH`U& zMd&>gL!>Y{&?)kKI6Q0#OgF^lG#rJgEzvS!TC(6~sd6;x_mBH!qwJ69mRjMK5pXie zRy&lOaDy!I>eJGU)mZ5?e7Cp1w>K)|w2eLymbN8glgTc9!kC$Nvx#lC7k}yhh2Z;V zRGiG0$e8%@DnexvNfJL;R$2RI1x`do#nubqL>@e&_Xfe+6L0hn+`Kvorl#iQndS#eP7^dz9n>1U>&*LL5s1g_6qGxPxlJ(U zfR5?FPmP^n7pUYmL3;l)an_iVIT^4RpPci$WB}bHo1*p=)qfGvm3e^G;NZpH@qVuy zrNqREG`|bOxYz5aahh5_X@fJcfW)0dAubPw<&%NV^sd16Okh+N8#7F%&`vP4230-; zO!v~Ve0S<DwA5_7?}jfs(m1auK#_*~$^Vht`FjiS))@EFj&SC%<3 zX5y>O-L|{IL*1P=C-h>BZnhM#yHWl;ozCboA|3Pgp+_a=aT`v=CxtBLi)Nt9h#WQD zUa+qLOa@JbzQL;N8z15{>#_DaVsG&OeOxU8{P5LbyY4I57@$15Su35o`R|=kE~M_8 z+xr(6ZZ}m>v0_q-cgoQlIyoaJd>m!o51#l|4)9^)8O zaMz#^Ss{i*cr#ZT6&sspR?8?1^HhB8)!}#WjF_gX4x(p@BQJ6w-5bp4+i%fRAAtNStGSjjnn{ z%Z+0GE)|l>JW^xUt2vv?%X$sq#}74eu_65~U$oOw$Zab+aHa}ss zyPrMHQ2cwZcfYSDE4TD_JCESCFYvzk^QXDL`{a%q!Gontd}mqgK8WY1m2t?S_$)Yc zqh?vv8Q9?ku#^aR1oC}m&tRzI6ub<|KHVkbc!C85;4cP$+5IgoVRnpV_K7q$O{3C8 zVW`7MW~q)tOdNzJ>i1Gu1GR}^>;_}!5KU}`NkG_5Ao-mPaGW_%QEyktY{*0L{qOr4 zPXf|u5`?FzwL+%K(03$oV1$$)5I|)eYfGTMVvc7Kd0+Kk}%TJS0$?K@9JGw3s@a03Ll|y?SA3I-$8d#tqXJZl95~U<$@15&yy}E-wO@!?w14pd?m&F zYH`lj8ztR}argY3*msv5Ec64y5c5q-B%6(Y^98c?QmKuTl6A=b_|0+dqYdVg2W^2z zi=ytEt!VdcO)dN1BQSz+CE`0gw%FC3KK6_|#dG>A(g!5LiJ?uEmXZUP<}co-w?9$?B5 zTfsRpIT-K;8@8pURk zW+2{z{!8dK^GWBlg zDG$YGZrV{cr9*F>BAiprwqwh|#<{@hrzWh!y1`VJ1EmLp?+(>q4Eheicqn63Jc;3M zi@zF2fPdKCZMyLU#hS94w_#0!nXy8=QTo$MS3aU$!IXn&{xN3*`1$73l+F^a#&mh| z9DKem%wjf-k4W*rK*C$}1mQ)Z+YP;oYd{xrxF|eY6Ra0*9CN^(-wEKm%YP2X<-3Xa z#yIu@us_a|k*mhP54HNg#erm9*8Wg;Y=8XPQprZbeR;G5-Rs3A_apcHMco@la(=sD zQtuC3?x4C)?Y?@F8mi?I*rn|S2i8bo zhED^UH_UiMsY4^_@k98;JL%{+;|5qx;Ky;a7xqs}m#S1yTSSs)iLk=ryG@b=T~;xI zIxJ)pVGmP!Q_|-Wj+OmWx-j&@J~k^$R>}FsB5#i0D^{FJ3||s>_eXojCc*ZCz$86C zd}#>=iI$!xW8HVgLh$b9ch8Gy4*iAU+cbgl&8DyA=GhwU$hJ?-lttl(aB#<(cB2hLB)s3} zU8ePHY7sM0{ZaHlIp+(@Gv}|989(BnP~w|7hg@*%%N6#$Y#~|V(;t=wZa#cF7Vd2b z_eQDY{tV^Tm4S8SzFEj6_ml4ReM;POr^DoGX-;?ZQ00@vb1J>Ng48GI5q!UCePMgO z`p-I{j7*j*3C*B2@~2M(~~ohU?+NgSSKFq&|=Ytry&}i=O$JLtCbK`u!fVS>AO){?nhas2>(q=-!ad! z_!ucmmc5Z$XPiUyk;r&Cwt+n(UTg@)ht`UqEJOO9#ZVSQeVX?6_V+`7wy7~kS%#ay)?PWA{6H z8Zd16Mp^9bG@0^NM~Ouh!*NX3^W93L7Dd_^3nzg9;fZA<5HG5V5)f~pn`7Q0=CZ0; zw-R7%Qz<#GVqyAzkpPR!cB<*p#5nJJuL>k}qCWjG5Sr&xO9b%QIZmvbk3@a@6@TXz zYvRQ$!StH^y6}DJLpC3lqU&{Y$TIt`6Y~%28^B*3uD31cetQ@1zPB!LOXOY*E!?kl zU)Oxyx3x5-59nM~?!cue<+@~28)&S9_tn#3_p_%QJ#$jJ!|%JX`)b|bJ=eSWZ_pV{ zYLdxnGH3O;vVK^30HS>m9YkRmmMFxIF_{y1zRkqDrhDV9iF0;KdIK4jz-_@#@PSFd zXOw}=ITzv@vIE^OJI5&+PB4JbNTU*ly*LRZk3AB&25D+_>iSHkxeNL*d}Hs1d9=;X zK*EXnX30>cc!1N;WI(fNINIOeJ1%?SagQD&Ez2|vM?d`1BQDzS_e+B|G#h8cstL2E zd6M&}M3(NSz;2LkUD}~)e1H5sZtX_D=PV|>_*3lKF;Vp*hk<2rLMYk2Ej^d^mEFvv z6R~6m!EaKuwXbr;omL6hLgq3!?$roEs-oiT?oKt}Qdf6jxIj9RyRD=e!`9vJtAe4q zi&P~5KN(=2nb2D%=Uu05yKitIxFTFuay>-{`jph?q$NglAL^d=jmjv(DjZp%59MQc6n&w=HX@Gc^aqg4uov->)PZ3 zzq_)QbNlMgum1e$&#!LRtGl0$crW*Nf64irrPZ^03Qe9}Z3@ME=)U~)@?|A(&!uli z!#860a;Wma6~1B_{xnR(C=KJ%({5i`;(sUBj5kfkZ&xBaZnU(hrviG@Z`MrAgx<7R zgGZ|%#tN*FaldcF{a?bIXz^)!oZ^u3_}B_GO--aGus!RTc$A{pH4ZSb1M*G;Hz$&9 zC%TNS#5rjhM>#JuXc)x9aQ83@BS%mPw~5i0?INrMzCz}(fw>rEVVxF4_*`l zt#V@YZWzeo{F3*FBf5rQX$_par&~kTl~t2RE_ZjWoK9WL#?9YwwBCi_0fl<(BbH7^ zDF*H^vZ%ZyibZcnvYl-N8ip$hobfXPk*FCLd%L6$6z+meelBO}7ZybKoFnmL!fhn^ zkB>_n%g(yuyqk2-FV4F&(IooaZ>uUJ#Q5#6H^sc+%GH63b1r`IXQFO5^C{JlMO{=~ z9l48rf2hmaAJ!oI;}b8GJ3+MmX7*4)cb#On8s=d0v@0C5CPX=%HBm_Vth=uFt$Ki`q3K1s$Vpe zfWVU*6Yhn^({5vS?Ep2e+BE4g?5;v>tfZfX6P>0xu(@?kZdX}S`AR&OF50@1E=09p zQ+NiAybb1$y*llfx+{+=oQY(Xz%5d=Ii=$=I$o2(mb@1`MCBo&Z*hFw=NqwXU0G4E zXGs@@NSFO~smIF8;rs>eV#6)7^Ibme)HyO)`l0uInVAdG+EcXujl^mo6Dbwcc0Y2yB4Wj z!1zIh-8=P6JiQSg5ZewJwmO{U(lAPbSW~UBS5NaIv=}j!b;mFw$n|2+ZL! zvGiWRnu*QiSWa_6y!;)p^4!veAx~qZ(W5xa(R@vCBV}pgi12=5G=X;s-J8BtutOv# zI7Le!-F-$6-zqF}nTSmiQ9lhw>EXcOVnK9VeW&cT zw8}DPFVTB@qtF=Q{m|W;Eb?%F6WwC^$#}UTj>lu%{|7U$$h{Zron|J>N03CVp;oA| zD;t?Rw5!9+YJj2O=%bqz#*1;g#L{OS3%3OCyIx(KM=-4898(vZly^nnT!k_#($XD4 za(TCN4bq3E{ggN3`KKY8UU^Pj+>?J^PHj30E>)`%?J>0Dt|;Q)AKUp@)v?w|c0CZe z%Dz9;HSG$#YZA#u7vQ%ka4(76mn-w{E69Cs&+F0FI`<}}``#e@U0U}dOgTTFteZ_X zf%mV^UfOp&wX;8cN$)+4+`ZfZyJ$3d^CdNtMWM-W8mxq5@~Xn_$`*LCjM~-Ynb%Ir zgM(-%PKm)@$lY8_5-fh@nWNi)WG)aiofPj&*J*+SN1J1QAw!u7 zoE)*qp`BRZp&b)~PX(Oc5+4oX6lEeY;WV*l!sV#f@5SgSv9XSO?XU!T$5`~0m=_~# zF}OOQCtKtM>ICPEV01}H!&BnwS}09FGn%s%K^?kad!yrC*=YBBy?$u{{Sx)9aT*zg zl`=V%*qS7&ZP{fK^Ohwvd1F8G+kwU0FjjZuxbgj1?l$LxI8L_KZS5R^L%?pr?AR~d zxD2Fn!F6}?$Qt>4Gv2iXYCnBeIM^2oCy=fHmPgN=s)A!iJ@%u+h3Imp)GV1xDwY4x z%j7ezF~K1#pHz0cV!o%w1IDV#eyYMPWeRtI>DC(x9`O0Mq%Ldd%az(yUZ(ES-ps!1 zqX^ZW_8X*enZ$fc3$2ZvuIO(X-!J;Jp|D{cDWFEsOldMuraDEt;6GH7EGZQ!gaW7amDyagDP@*3&2kEfzlGEp=+R!&LCO_L}+1t_wrc+5AJx!NqwKCz#q`>Oz{uU%&4ok?(Pj@feM*V+ZC1L%9;wS}-ACG1gU)VBzd0+UY2s z=<=baamGNgFb2+asg@e9ST9$003w}m5tXwR^4BN>14-d_=(`Tpadhc~7P^cHcW6mS z-vVi$bt~nCehrw)C$GWH{ZP-vtZ;{;#cw;hyj(%-m5<)dzCSMf*!AwH58pb&-YPhG zxmH)QVTAI2p?fiDc676irTccZHSlhO$*S7DfH-__syq&oh)wdxbkE?{bX zd``aDIGga6yfJ41{2cM;{4D5124|BHyaC}-29_x|^b!=BoW)_9OB`b&a|s_xp2=Yr zjM6BL&`Uz}RuF9V=<{tE2)Zt0Q3Tm!Y6(1%tITB{pGrm73j`&HQvU64t(KI{=B|yn zo@4->TXEwlJDDv}{gSQ@y;L9f;QO}NV#5{UG^Nis!1vF(U;gFAcvqK!D`EGImZuLYG}_2P1*#h zxCf*5$_dVp&iFn>;f9bI;I}-wTnf{CtPip;kFrX}a_4}H1F?p)T>c8< zM%2MHd>Sx9XWY$=RWE?H0dTVm5UPne>zpA5gNd^UJ+KpCGUg=>Tc%Cm)DnVYZLxQm zW==9;1Gpgg#+(_rcRaS!sVNc28Ah=!``^D12<{Mi!v;c+KE<|VKu|hrr$m(D)y^lX zMSQp=zf%$!AJhD9!Xr7_jp6WbF)B$+zu#`aYYrwa=~s++&{&TfjTimz`{OA}WeZ^= zNZyA{Wl99~M?aQRi^jw-+}lsJw}@y-|MeGxIEfgKMYT9t89541w7sNWC3tWeSO^xT zrBhTGDs|J!7Vvz2ib-U8tmdwjx!IeTyw>!`pL21y9k2b3uO&|O#!oZr7F~&=-7hN{I@B$|QeTzxot;CmS2C(7O`6AE|fq-~H9it54NYr3dd5&%BpL;%hF!&Os-i;dYS(bDtoF z&B7??gh21Wm6}xM?!02&+~Ms$M1b4@90p-zZF-ExKZ0%+7?Q8Nej2Jp9!N9FcdtxIrp5j~46@suDhlxX# zBI}|ihpkpiO{{L0Z9TT*aZJBP$1h&=U$oow{ii{sqg{Y^U{fvm&4dFyV&?dAA^dJUf|6YhN20PM8aolY>wM*joLOXY8Z4=FlcJ)} zGgjB}%0HYB=FEWNT{X~U)X?MUn66H$Y6+*y%M6b!xN=u1zY1|K)_L|yuiu)!@nHqA z*QxZ!50~|5&4hzQ9f50;3J;Z*Ji^Xh6G;|A_szY7@N=bmrNYG1 z?%P#g$yQ?b)8qES-pyu{H%}AIsbG8A;QdIw`+p;vQxi=V-6j?9K3K8|(yNHjTZGu# zd1po7D!c=?yg=X_MlL~#9ZIK}_-KxqIJtY`-Y~omFSE}hg3L4xF?HtZyK_gf!Pw)} z$SINRPB{vRyW1QMBa+>JsGPE3?AA_mL^mfQQ^t%rnmKf|wJBRNkl3ljZ5jr9efEtQ z(=^;DJ36Mvn*<~6im4^@?zYaS`B+;qO^^G%<6gVO)k9=q^ZD~(4$t#+dR|QP>G=Cn zm-J)jVsUdBn$eFVx|ARyf8O|B3)2(s^blYzovK|m{Fz-XtL-wSy`oWZZ>bjEz%Ft% z)|F0GBR4pQRV|$F9pmR$hx}91gUl|@FJ=(g-52x23TGAhc)9TST|Sn5 zFST!fSOMgZcX~*EKLYonko)br$h|Q-`GA{y;R?KYm~z*`I5!V9b>CiZ-pHB1TvclK zN^4+E?0y)$pAf|>qsf~M?cHC{;O&`rt-<@@Q2bTRBY0FrbC`C|6P7y_h&$*$ajZM) z?0|Sj5WJJA8{8?AY%#y!a2u<`oyy;x`*cpH%2`_P{mycWAWk5O$p$9unAoyA5VJW` z05ZoG&u~x(Ag70ol!+j#Oc~iT8S5Oe8RT*BZHTF3kW2>CA;8}`j?H8!*=~~OHc0Xx zN}LnHECw$cSkg(X zR@l|d@}VotW;vpZXByfG7j(}c6(TZ~!$h@}Ka%vsRth%vIWnBoYX#kVP62W5Kq%&g zGk5bA(w{jm~${T-eYdITorgQ_!@%cl7I&p1b4 zsH%jPuzu!*ZTi@_uct*Z9h76bbl}TgpDXWTlstZ1uphDI8&g_Rte-Nj^!lxzE`F@n zvVPnE!wdKJQY`Z0x6ZZir`sD0-H)}EERg!>ao&;#r{Gr;IaeDhU#r&F1z<0QDxYnI z+fPfo7tx$IZ&vqhzK~+_rna23?P6suSIJ#ef3H;Tg~|J*vUi^>WpnD8c-(UFnU~Rp z&lz?mor$aN?!<=wo1azkK>UOeJY)4lvL7(89b?dKa%N=^Pgvt7M3*>_gxsCyF&rsU zz$799=;9U~Roq*Z%PEI>P$32HV8E<7va!kG4$RnyT?~cpNxBly0~3CCf;>J=(OY5+ zEQWD8&JmEbET$`EoV{6NO{Ne-Ib_&sNgSRsk#R0Dn+3($XkUKJU-pIj;5LhHa>h;@(O9qjwE8UbEZMSZA~?+^7mm)P|; zkJ%4;N>(LqBH?d0R0KZQHgz-?!5`+_o4ZSHHnH#P^_R8oz(sxFa%tdwv7Ak-3r~gN zi~8>R_QIPlTmt)kJrutkcF#A@Fr2eZk~`Uiu(|AX zLN|NX;d#lda(6pxH%lh$>*jHsJmXex1GyxS?tBu~5qc$!wy=cTxJ=WjM7QfS6NJD4 z@p`zkB^tIdjW(H}12&#C+b@8hhF~0~@Jv)VlMU6BNWZml8003^?KX<5%!I!2=UkWl z$Y|4$1ySuNElm=IKnm4i*yPJ zg^^ShvO1V#ZQCc)new8{Nmf6f)P<<*A4xM>BX9P`9VSal3%6IxLpjSeR9hcXJ{|vFs_*{t zi)VMQo^62c)zPzBCjR=>PoKQv{c?`iCp&ZSK3JyR5KVSghlUp`ITHr$w8KS#M8e}y zoOLpvglE2;&11n4rtj56L~*ydyQ}XFX5N)cu(mS1fbME=IPfse$Cic{hf(>L%?nOsFhM&0 z%y$cBh&dV?mYsYw3QNQNQvvT((#Iy+T0Pn`WpC8eIMzJfKaIn5lA1iyRU{^`cDf%; zG=vj+cZxx?RI{FI^YZwZ&otc=eYyu$M9jX&dnxK+U7}qRob|^#R(zTWoEFi$cd)GQ z$EQE;_lc!j2kZRwpNO_GReli!c`+I3nKj*Gc@2SQew_f!CyzeF=!_za&eBWLs@jc+g2SBNq6cj$dY!nF(8`L~;tZ!N zjV+S%*J7?zfApr4m0G{02C2J9_V4R<^q__N^6q-TEuGvo+&+4Y&b_3U-24XQu4gId za>-hn@&VvpBi&CXnJ{!Zx%v2gLiMxyBWLrFZHJiw&z_`CpF@|qId7? zL@QN-4Blt#HJNx9po`(~OnlriQK#bFl20o$252*(H>?cKj3y`#&$Kx$KgX#t8IBuS zoQ9D*&*@P*$9sEW-((_>Q)^F6CS#)K>8V6jAU$N7Bd9~n97mEEQUjJUj1p3Xb~qfu z_<+3yqlu?mOB{X_8KC#)NRP*uhHsQwjhl%WxWR%URyNZtOvNzkjmpmimO~+j&V5Hr zx#EH<6uzF1xI!mMr zuP*}eg_^k%a2MX0VGK=cKU>Krk*faN8%`jQaEl>6q{fZjaZd^FLvfCmS!MSgxQ4=_ zdrpvEnf?gA2SlwCdi3*iA?Idp{x)u!-sSaM5LF5mgm~fdLiiCL{F`9t6OT>QTvXug zClEf?&MX&__Nt)$dj;-0ngN%JN>-{}HzM}~u9Bn2;kF0to0~1VOP1?P?r1P^V)yN@ zYl6wrS>^rUef8x1uk|{UH}9X0c-Q>hk3OsP=6rP$qPlQd=&6-mtxMa`)}-Y$NrvLZ80Vdm4?6?2qF{brWHIy^UXbUOKG0;sBBz`r zu7AWfwJqk&ANZ7k9(y^#<=CZiS~e68>07&9FRVactY0%r*aI#dGQ%1;b7iXzx4Zs3 zn5H(Oib*C)&1}=n&HE){#&lIJq&ZVJ|M2*|q>JHRi~zhd!xTK5jK*3HyiX!q@%*1)S;b>Mno_nrMy%b>lW z-cOp%0eV+Ql~1q}{|JBgM!mZ-n*8sZSARdLfO}`>q-Hx=rQNPeFb%=I8MSK|9(boo zuu#AGw+t)7TqG!YULk-BkOy;uPM*anFIN&F&Vyc>#!yjE5GyA!PAw6Xw=p_gqugq% zQTBwiPX}j{B9ke`YYevNk4qCFXFp-Tbw;R>4>O~N?sQF{O^RKBgm_~DZ^U)XD2mcp z)Axh?D~aaAo1u08c<--THMPnmeOi)m5(rBU9Cu;wGq!Lb8*3UVXB5de|qV}jKT@Y%F$9LcO2L>99i&k zo0&9BWBM$U!upNrN`-`cRF-Vr&U0?)BeEW&lsl&fhLhV$^tIZ!r-?hqsYVW;{dTVY zjt}qLUa%Dt9cfgJAgwc%LhHDnqOC+XIN)N-zaID7eI18s^taZb9_(7TNf`vfkNpxB zY2$PiR!<0+tnx>foMdEnS@}!cabs2Y;Z7%uqO$UN8N~5&;}#bR@ANKk8EMX;**GtW z8$b~L!6Z9NfV6P3R;+A0oK9XtZn>DvlH#K4o{q3blDIjs?~6pVeB#F& zDRFHqwJ!W2EVTPgF#UVRYfiYYOC&c-Wq@xt@a;PY_t7?NyMpa)-6cyh_g000b;0D< zxvhJV#$l2B*Cjvq_3F0py~thj25zgD+#bDJ+>UPl4QrLp-aHlUUN#B-7JoN`_vNQg z)!AgVnX|KM?ylV31l>C@3RZFn-Z=AWi4#tUc~3fKUOz?fJ*kyZO_+O2?>C82bkZ>y zfwm>Y4y+-h?v!Q{#igF0;$%YLUBCw(6MCaXkT939({ddwvF@<1>0T9}vast*~YK{4fwJ(#1sDIq=H@`D+C+^r*(QND3 zP6@e&0>Vw=S7@LSROugA4OlqA+np&2?<4eLiL6c@6OUki?X2p2O}ui z32rVCT1|VszI7ME0;+li-yeVPkbPeRcg?WP6F3`a_Z@TZM_Y;9b1V1uqxeHVDI z)R$b>V0&p;_^Lj(uw)Iq-qvFBD6RYUWC|A<(JTHhJo=3%mG5h7mG7Sfyx(u~cRxhD zua~gg`_ByXV;5**Pe8!gA%XvO2MxFnar-&O$lqRNn5umr;RxOB`J0rqAWC z=zo>geEzII6T6<2Nn7j)Us zF{7)@hS@YpGRY}XRb_VKeAgbv8Q|eOF*4zP)o$V%Q>EW+FXl^?(7BZn z(jg@)+G2hj>5mL6(R=3elTE)BT+G{2TyboRtu5zWUk2;aKLE>Fm90tB*)MilSsO_uU|(`TBxB zZRW$B7u~Mv!K1hriv<6-;fa9kzNVk)@_!C&-)SkisrdJ5GvJ1m_ifH57pn?&_WcMy zcRhx)?L1Dss(Wq^^fLE~WU|&|@*wSAa+z$YnVi`0-QpJ7li#?S!{A-7fc?_hoVwn9 zr)KhORqwu<55==&a`V&6lM1UB3k;imCPcJ%;%fG+V&4&Q?@ni~ck>%@$3Vy?sP1s4 zlFup$uQP^h-dP~JUGABzbQQ1w+I&)CcwwB`xEJG?GRR8;Yu;U$W=YPmb=bP6s>xpo=Zf*B4>k<4f6lq`oL{7xHJbx1vuL*#RxFD6s=C#p61@u_ z-tqmg?AuO+R_;LrA4f9n<&X=vz_N`*`7F+iA-~HrXJUS4sj!OUmd{wm#-|XwcJ`4X zo&NC49`@^#E}ty=u%{k#6QDxal0_91!OmR!Nzv5v98bdNoH#* z=DyhyxUX;Twg%3#l$&hbb?&`oobs{O?)N+PpMT`79lZYIpKSbS-d)uQzIm#n%4NO# z&6a1CmEJvG%-uwW-?(* zH$?4#TdHi}?up|V5t~lHC=2o0n%LU0IZO9O=<_C)Em8TZxc-$eoKSZfObP#wG1OiR z=}w$}4l~Z+m@-8HYz&*R5H@$wJ~5QWM{JmNMw<9D=6T|nzFnfC{%Nm- z-fjP1u0yXS)81Z>ev>}q&O(7gHpct8hu)P@rPy5+wi|;l#9|c8MuA?Yc!4 z<7RUWhK+l`X19*x9>tdiasbBxHV0$a2ngecA6%H1kjSc~#F1g|UxXT+ppEKcCWr&4 zfYxr;#r^%lg40bf)xg3|%X`$>v)w4$?RH8}QCK=5YJEPN`QuVvwNxCmL|bC=TwpfM zuWzFED(>$c?{Pc`zmV|!A*G*Zh8X_quJ|7#k!;LMu1>taz0(S~4REhHxwpsdrQ(vU zhT!M^lB-35NquGE&O^%k)$YxS%HMKG`O?O`A0DQ772B7OJ*=$SOzM#Rg~5BR&tz+V zxBI7Hz56GBPPw$1Q{ni*ifFRt?)GAL5S%e^R{(w%(_drUakN`HgEv99L-0U49!@Nr zOHVS%wrs2`7YtNF2{dofF7 z(>VXN!}_L5T-_h<;h;q-VV2#LE-smP1x6JYc#7cDMCdHJ=!#h})??N09V_g_)9oUu zEiCY$C8QDHZ%Z(ML+mcwy4UZa_N9pn4WCAKUw5mVd_jL}Xwucr$WEYqPG9z%MH#vs z|3HAvx(TqG;k)m9ZVA56#s3VICD?p(((-H%HXU6p<8;zJI^J~ z{TO$-uPVsAl8t^7#BpE@)D!3==q#Cf$d*=FhubEK3oA52@^r0I%-)l8 zoG;D*_84R!3~rP>dn~T%*nNFhTX*%=!`{GuOA7wz)zRafCq7kK*}I>r&*aT^K9l?W-B&lC z{ys16KBy3?I>9?J0$Uh(fUj>4aHvJR`=nePrH;GRIrmfSIzXE6ek zv7Df{TY`b3N05LS@g1ig^UyF$*SXcP%JL!SWat8rS#ug=%8Y9UvCDwNN$ws+o`x?6 zAl*Zzhh7=ZINk1?8b)$h2d?p4nkbFZ*nD;^un=Bi6Wb(`#UBX0WwY7T1{h~mRS)HD zBW|+B`pI86wNNbrE9up1pG@~*%Boj2@v(952IpeG@z_P~s~FBexT^&I4A@EQ^_UPR zGp;pcHzE5Wi>liS4`+N%A7Gd`K=vtqukLu_uDAlW)C1=DxR?8+pbNFjvOxe%A9A~A zGv64F3j%M$vBz<@A}N5Wfe+ez2Tmy@>lxwq3#YwyAe^pDY==w~OJ-)sn4r?#*YEb!%WXOZn@X z(!I2H_G~L-_rKBG{ocL2-!fI{%Dbxy@24q&UGjHV(EVmRy?gF6`OjCt?m2Xy?95?& zXOqq3V1e9OZqIl%C+I{DwyO$Qp!sPUxF(Yqo+^f>^xt$_B!l>>AJFm>vYO2|OqCpf)a}GEEJU^>nu>hfM;=vEhlwu|hGb zTTiHx>cB-?)rVB0V*{^wGy7FlIFiV-tlFEPGb0htsPEvE+gOUK-2~xCr4~kTX7$*= zff4V#3eGrZprhkX_?9#7`j+l{Cg(F~MFZcF#nZyhV}6lvqQ1e$vt2eEwu(fF+0PLH zcM~5OsKkv{zJ@5{+fszf!L#neZthCeo~ggGB;o{-y&v|D`}lNl`q$^K1D7s4A{q42 zM4)Y+PIhRw?ILeZ3(Bf4%J~eg1B&FTf*svU9TJ zG&$Ksx_1t0VmH5$+w`*l(T2zSY;Fpi1iZuGklWe3O)_;}o)N$PoCw$i*>PeBy~|E) zq8QcOQxnLsm17MP3B+x8M#*P=xyVt+YEj-{x$7H=bz;rOdsd@Zut+Rhzp+H-Y!exM z!7vA+%iUeJIiuWUh@R~sOTUEPyz36TcNrqP9i!gcsu!-D&FeVG-} z@EJUThVUE9Iq)|Eeu_%AvhI!6!0QJKyYHM^c;elKrK8Fv?0)~|%ku8^K9lW&m36uMlV8kP!tR=4 z64vGJ>a3ELlY^4b`=9^#Q!IR_vhoOWg&-=bczPjY0GHW$`d|N8-1cV)dj>P)ZUXmt zQd+L$cIwH5&mUPbkwsR(3P>NP-=VD7sZB@hQBici8Ku@}qvR0AlU(AHA&&s}hrB6? zuWNocX*#K6NPxxn8yLTBV5dBrE8-t4uu znLv4MQ@J6v7RKF7!ObMfSqxcBaU~W0{9fDqH9?febUlq-B#$B^)xv&jw(hF|s3x=`1CL+<*ORFGYf^zeFbIN^PcLdgj@4G8ZHdsuac&c)ds$9kHFYfQ&pqV_NcVAz7 z!P{f^&CREOy*xRor*rNk-UmDBLA`|PAf}ffPyhJGKkg@7CRhb@f*?vwC(gL6JNK#h zNsuMPZBzderWT>cfM~6aLX*ZO#v+c);t9NhPB+0hq{~wRN^${UhTM%{PM)XxBV#aX ziBD0Lx&q7|k8x`0^^uGR$uijaRMR0XF->rGs2P@>+f(0NBH~dRVfhShaRNw*(@gs0 zT%0p-B0<>Vv4V(xwbPVaQ~lPjtWcbr0%hgR_T{h8GQ5eKtsetj4usngPDI0%PjR1< z=C4isDJVFv&oDXyE_qQ{7D_t-x!|)!t(`9JzVD2Cz5%YnUo2RWnK@?+Ed5@-gbk9Y|4xbqOWuUw$m<+C@1O^7mRGzO^*i9&m+J$Q8yW%E!F#Lp&CStLKj6_L z`1aydvThK3*cN!bz5~Cs1balZ%UUqF(gsg8m<$N~_D1aMXq=>l5BE2yEt7lPs&ufsEq3xI4}Bk|%yG zz9ftZZ}V)JXKrX7@C`4w#b}vVz=6{Vx=$lbz*% z=xHLXvUVI>oILWm8VIUx>)lBI2LYr^e7|5djpN##3a?;0$96@+y*N(zh)o3~-*KLZ zQ$xQr%q$&CHJpwF`<%I$rT3-a!JAq;tD=~PE|Wy*fpTY-zR^S#vu3rPBe<%Y9}e<3 z&od;T;;q7M#&g>r@|EtRE-*9eUUb2*HODNac%IO|9P&0OQYi|^GFlG?yDu65_TtdF z$|0IK%Zcpu8JPQYCCr_8^V;vmaW%MhF&(@<-gE9j`}*|)zGqH``SwmFZ#H_j7lkFY zr2Aa}ezcuf;tBSOvi<0a*PA7+_OJOK<}@> zx|hmK-mmcP_iw)F*zj6^_k(>V*VnZIZ;r&jdO7z9F0k8+CI`z7!Oq+u=zc5b_U=w5 z!u@cXPn_i>%F+~7uNkiZ1G{;)5>g23Cpk~OTY4iCG6>4Rl+xj@3{2`=fF{qg(x8%C zR32|BP1*#i(gT=INT8eqag^e)Ql>qV!|9z9KIiZQVwG`1pjx;%R1&Wz17xv0y*4{tyMZwO@iTK^0#3TwRJOsdZ8s< zC5DO57_#L;xrk2JE8z~4E7PE#gK$CzCvA{~As}=`f)G!*e1uWIRVgmMX3+OeVd}UL zPFqPX93(4lALlbm=Qu2sU_4jOslt;CZhxLjM$Turhr!-$lqrwB%3HU)K5m3j1qZl% zY>DR{i18$D$g*e+pzn8IGq0BJ`|)OuE}W_jVWbb=q3iE<7aJ!s`IIHplU^BXx-7#J zj+#Q2PjDi8F%aJl-LB0_uG>iNEa859*uCm>y}4Oo-~T;N;6rtRt7^#_a@VqyOU}US zjTKZ|uESY>^kKoei*_L|uvcLP1Z6+rt_5SWP!GuBl!0#?Bo4Y-H z$DNMJ#dMmpWe|h$RU;K!0ke$5IdZ}p2-5Krtmt&2Fy=c>{4GBJf^5cmWJ%}0~O!!x#fw}wNA-9&RI z%|j`aZkKv&iMRiF%8C0dh_N3(3bn$%3~H({XWX;&1YtTAL0lU2u1F&9%^}Rn+N<9z zoEJkMZFDD>g^%JuD)-6ugz2)9E#}h&3mxv$WLx?ALDo=`LRCXKb04AdQwiq@JGWI8 znJ;{1UbyIc!Nx$Y-oD^=DeqVG8B26PDMn%pP~cSFN8L zjR6CBE5Wi^*Ae_K;doQAu#U=>b8k7R);Dn^09&=ag0~C2*UlqrdiUdwCl@mJ zwx+<g zZ`3e*zL}Gr?#$7eu=R}Jh$?G$RY`T01w55wGPJw`ydiynexn4ID0pT6%Und>!~vsu zir(%ZcNHXoMYpSU6|X?|i6vyk`|w~SC0u-FLSLGjV`6JM;%#{s%%T6|^T3S^qq*A> zR^&t0&XXa)d)OMbaBydLcbosKsY*MYs(AFvC>+X36h% znk;RLVm6O@5`H(Z81EjRuQ5!H8S@ns`bL{>n7izSUH(6ufk5#!>-g_9c*QRltK(dK)U)9q%*Xt?xtqV+^b|U9qxqDUZej>fQmaE*V zifXC9n>~UjCofOxHo=p%lggc)j+@SL|8;_V8e73&?H131vxyT>;wTF8PQ)rn#&Wm& zjq^FS%EL z=Z9_RwLk3jt^Ex6-ql39VMPz77-XAHp}9b%KyMSlD3RWwsD$XEkV#D*nHRN+YP!tP z@CvNE>;Odc(Q))-fZU?{%r3+Y!3*wAQRXCLbJu+zx3<=G?Nx<#!5-}K4BS=cLN!w6-Tf4M#q>R)jQe&N;m%d%4C)HqzUK>O4@yh=Jb^g=ywyS{ z?f7CgZa2hN5J}dI+v{uYcW=7aG5qKe1yeVRvG>Q|c15#S&MN(@`?>e#80FeL&TYMU zY6-fpSA8ZAjO45(;lG~Ty(*b}VR!dNfA=8wweBuv9i|HlYz?FNbRcr~ZhO?ixatPMlF>C>XtE zOKNr4Je1!l*42lSsCSsgfsNxRH1uPg_Bj8?9pC1&(LG)?MivP45VM+Luib9SLlmcu zdD*K9>oB+U5(p0bTywXRE?BsBYrMWmur(L8-Apm(;|I9Ube`q3YJ(V^>nA!r6c{_Al`e;hG`?%aKiYX{Ne zu9yv)noly5R&v3*2yZtOKbO0Dpc^l=ZV>-Y<;=T9&XWtaoOoP*fu57y)^mDkiRaJx zK)_2rkm{QQjhd@AqWD^u4Z0rm+MxIRPj*PpP^`ec;tLo6k2a@mHW;^8s!29gZ*Mx9 z+*;#4TCtRP|M$(KId@Iu-cBreH~>GN$Jx+5we8lzT|xM(CxdQ}%1cF5Pc3)9Uy8&( zPVZittNi<1G^u0vlE3?4r*wm7olY%Sxs!JC7zRP%`%I!Jjt-(uMsEYQ*&xXCl+JJh z2X`=;WIUn3_>IDCa~yMr3Bh$|WG1eBDg${&07oh|o@8=NNQpvk6p+w|vI3ts%*Av( zWmkCSRwR+VWE}tw!2+U*Rve+{P7|qJD4j6+Pz+lI5PWLoLbY z@9&=m^hCa)U%cp*FrJuL8|8M8iFRAbnM|pkKbOu;H}=a4&J^fI8{Ofb;0{3HQ!;L< zvde|vE+py4WL(W4caadd&k9#2>liBLFPqRmQ0&@u^OdeMu;l=rWpeN7p3PjbAS{OT zM`s&451?Te;lfEWrH+bZ23OzAYx5ULF`LD`RC8^j>j6hho=av6O#s>`+o?+xx$rzY z(8m|_0s32Nv~>d=Rl-dQv#xT%mJ>ycy8r!)cKh)8^XG^7l@NZj`i|ut-*wp3O*QzL zp1&NzN8g|;f_=^%gP{H`(d?%U;`aY8@#N0a$W^EI<C+q)Ato7nf(x0_nY)Z;BB z%k{47BKOV1xP5(xp?f6(f3?xly~P>j9a+k+pmp<~`B$%*ICuB^m95Gzj@{Mx!uI{$ zOLDjGGkG~D-izh47254Qf;$H_lL-TP)H$1e{>LBx@lJ4&3BmW7vz@R|;sg^e?9QFT zWa0&IoJHnb1SO*$vFQ$BceEF<4i2KM@nM-yp-}i}rOb@h#)?FiDPhah45h%VFrjE( z#v@22zAzBlHb}2(dDT_AWnMQPuWjPeDyqrFR1#;IlQyBb`d_X3U3=$;b1*_6xs=rLImmcFF5>k7KvfnrlN=M^U2PT1mH zj!udOgWb$Y*Ur?}g4cx2BVJ+wv=RjBmd~DZRS8!?Rg;&}&qgM^tH~#Vh%x$lR;93n zJacNhNRN+I(Q{{r@`7g)&MWgG;Wy~B^TD)u9-`=;ir0tm>bof~y zwT~Xdw(A2p?yDbT2E19X zcfGw?kxaIL?RCoSU4fo;W7%v)ELlFUyk}APzH`c_zWsEDrLEll^sJhQf3xTid{WKC zXFE6Z?yD8e1i$Lo{hzDgy6gpN}G@&kW0k1$wmCN{8>G$kA#k8PStnIh7j zXUJF%r7!4)EiglEcg9eTswizVmfqPRX9&m$1|@;?P^!a2MI>L0(ReDqJJh8a0tdtW z{ZR<;9)-5-x7&!B^p1^_zIzs|dkS41sUJSFB<2pc9~!z{jjL3?Vk)V`ZI-LMeuk{F zo`9VT-U;q@-7=X^ViJxw2k^o;C1V4dUGd?4m_1ymfd82`A}ZaO(@~m-w$9xKa;mWLW%?^5RoQ=&nTZh=YDG@izN8|UdS z`>8!cP$y7Bj$wKMf}lI+S}HjtfE&_-X)_!W9zgS+Xay`cF>Ax%dQu+hbhKyr+^%WV za42;c#$~uSIv&BMA@=rqy?%qJCrsbwbF7;HZzkY@<<-0)r^H2<9!(YVJ`)ZKVL+05 zO4w#CrMI4Rlghl!8AoS%P6ka;^~KJ*1qxbO!M-@>PuBxq?(Lfgbu$^rf)5@=;-a6k z#0PigZawz2nYWs$H!oF9B}-20wS5#1yj6Z(rVAkW z#RXs0`1u3fGi-5%7M>5Bvv05p>_CD^o{N^t$NqO?HuJLWb;kX6Q%droYLZ3lW^1uz znQh=OfG-=>E+9pYt(zq-VN#dAl&gz6NlY#@lllyYlbJMWY_q-n2`U7g{aZrqMhqu5qjH#8TkdJd-_pPy z7zbESuz5cX!fc|oGHGNc3biBoe2`?V!z$c|M5c$EEy_1nvJJ|+31%P;C*-)!E(_bCl@x3`(+suXI1SNZ36G!amltpG@2Ml7Z}IIpw5Qh4U8nHZ+dZ!$^HAV%X~v)Kx69g>YaZ>*jQj0Y zh+X&fJx<@gxl8MQ6l~Amf1Jp@DgAy&7Uy;)i?dnmepKV@)w8cBoS?V+)n~Bpcj4!= zSH98YN#yPoy?fo?{p+h&zuw>94d_1lgw3;;9E`scyZNAU2Q4H!RWxUA=Vo6Cy-L$E zN{MwJ;G~k(Z5OFzKZ)z3V(!he3=Glmf7mjJ^T1|tobK<%KaSGUWWIXafEg2lr=t-P z>p{mr=+<%n`~Eo3)9F-8sixYpM2Cq;@}ea~Yd+d*Qf&BsCtJF&^^3N)gARNyUl_Zhb|ch;x0^!Y#9|-yL>`mCUr&u5y|+z}5*ph$Zjh7h z9$kMpNzWn1thDs`1G82Oy;gjgQc|MmM?cv)OLcWy~+73*Cjnz%(bnJo%T z1ap39KI)LM`)_|cl=xTjH#cH@C|Lm)?kR?!b$+~mWSwZgT^Vn`c~leNZ(!R?`u3tv z@KL~hvjW?zlkYc=FqT~16{5VY&M0qJMsYT*3O{=ccwc=jUw5rT@cpxAKgGe6UgDpg zefi$*#kJv~O#IPFK0UcvBHq_mwZTe1SNZbgPB2S4%jmt~tTNpRSv~2@v+-xu>cZJU z97UbeXos+Sf}={#Q?k2+D^1vDf_EhQ0VgP(%CWFOw1r>eJA_gzOKai0auEqZkDP`?i9JVGjy+Zyr={l1J!TCaN?cr_Ug9= zbKoz5NAT#=pa1;n&##_6mE8S)PP^aSWifends4)ogP)#l3g`Ix?teMOBoO821DSw_VVcsN(WH}sS@U{Xz{iL#6z|L?oY-;s9K*m)fE-NX zPMDe~v{`0PN0F-z6t3Td7qt21XsNhfgNe( z#PBJl7z$_Zma00%eW#Y=QJ?3&r_iVljKl7S5 zHWX%VVa!AF(X>K^zli#!eRl-f3Vk)(t+(#Dxpj zu7T!W6+dP#Si0cn1q9a*E| zq7HE<{RK{|s@f#S^Q(t7lFjkRO#=6}()J^5fGhfToqgZj-28?Gvs=%;Z{{!C-mW(n zmu&KLv%lo_jv4qR}P@SWZSN&J^R;BvV8A&W96S2h>d+KK<(Qg?v#( z(Es~yul+po8-_sAXQs_-jCpg+($d;%uT>SH6}o_KPYVdR+xytgQ3zdS;RNVi?&pkL zX4-5v0jLt2^_;5VxE|p-3gYd|Mc|a1fO_k$6Q%vMNK@euF?S4)YvnD+iAS!JyPD%z zA+&I7;+`Qw77{Y!zU^?XbXYD{x(wcg=cdkH6Jp>eCd3Wln+ypN)-984I3z5Hg&)JD zCL)iE+9TN_SuTj%7*8J#q1e{Y8^G*4XZaOP^`V~USj?308p*mdA)#024vBdLi7!iq zb?(*S3SyaL1?S&bNb89jU-o>J?`n#4iic}t)btX=vF08*R$&>o1@x4r53V$0w$45g zz&TOqhUH9<5yd?Zgt=)n#xv zoXgfSJyA@N)WYD44J37;Z^k#10VynC6ZNM5CH8gKwhha`GcH~F#D2v8#L^G&o3FRJ zdY5j>kY5x9Jv64d8x<13`R;$3e`I|<^4IH4!^wy1$(|SDy3tay%D%rFw-@aD8K_-y z?k5uNd-V!em+SRr-+=B17jkZnzI^$z&Y2J1y+;gb=l#(NfPckpzkK;CUJjP8_X_v+ z_ST~(5q|mnT=1SpcOR>LozFWvpFe;8?-*6C`@1*pRUVzWd$aKU&5GWARj%gz{$^=Z zxfSMbFGRSq6R%0^-rowg+FQt@>dc`VoIA{Cd$U~Ec%8C6sv1Oy->7V8SohPWVxA&?6y>sgDfZW_0l-PA+&~G0Ni}u!GV$jbaxEo29D)V0wo)@ zm4?o1=Q1_hvR{9QnwVjlW3C<(Q(q|=*4Q$m!Z&?JXhvxiDPSEP#lp>I))gonrVrKW z8#WKKLdHxD16vhc;vx!lG@-9(e&}+REHC1_wjJ0--|r)Dw$=rg?pkB$-eYTAs~L>o z2IqRA1j0f*BNi+hHWqg5vLTbun@(U-SQFI+!BuRLlq~#dIorQJqG&(j+x}jzy~)5` z#+3XZZm-THpTxZvnI(^GP%d^T9|$gaV#&gzbIPwr??d_EU$BNBww36U?? zy&q_FTXpfhCCI<2ii`6*zGTJhd2;v0=_tfaxLDBM++JjWlW^F z0^sezA!l;qT%TRfRwK)7LKvfB2hp%OAuQyFRxxe_!y(cJ3B6r{se&GId7k#CA$`5- zpdF=dOG}Z}YN?W6?u1b#InolR8omT{1ifH=g0nzm2nr^PKD!KsZs<|TwAp^53(N3% zVwr-t%bpx1JF|w4HB7cG3RbJxOioZJ3f6*DB9;#gn|{QeXmIDR(2JgsJNglD)^4=1 z!ZSD|f-QKb9)h^&72}~DV9_1E8iW#>s`v&2$5eDJw#Hb7^ofjt!i}s!3?6(sg5i8( zt83vqnPAV9*Nr%+)+M?<2KDB-rfp25{*7}aT{ohB3hahsFfHgv64EE+QZMo)`{so0 z2eST3vi)BNzdjMY=NP_Z-F{xI)FuPBdiQyolh+&4O75j|Kg(HiRZ1oIh_`eFUaF0p zdx<40{ghYFQA-xKz?(O&xYe{Q-(MorH*dl`XzdXe@6FtBNeuZNw^bLAKMO_G)IiMXBfA(s)WPYOqm9`FGOgRh}$T5KiZa|CnW2BlW_%>tc2g2k(fBI-}7zFJ|ulLe^4-c)VpmX=G*)S4! zIM4!@ZgD}6t-Y2<;AX!LCXO>9^iG9($hBM|;B-w5lSOqxU(2pxw+EZ%2Cpsx zcIQesMxGo)MgL$)!$KYj;s>Xk?aIWPb@)QAQsOc!dUDmBMVDxj+2b+cF^9PHxen9h z6-ht(z%&^?m1Yxm6-X~Ed=PKvE!1&=qm@D6+@zx|#2$Z2Pji*U&!x(3Sn3lI)`)j- zM5Zs3qQgTr7^Bs`O?P5dFSEZC#op8-`Rk*k`y1f>Ou~JAy&6Jw{R0BGLhHG|WUYhp zDYn3pZ7&Pm_j?uAgzlwnoK3+cS5G6|n`?!Ex_{jg`Rwk+i@Pje;?hTF?!^mr+4IEj zb1c*Ri}M$FqUXKbQ@H-+%gxTavy^v(i>Xg=e{gj3gy3$OWwI9kdXID;AH12}{7>lJ z^Eu_sR(SE2j&GOpzwh$$`ts=S@7}DE?!~NfzwqYtd%vu!RAM&+Hn98bOm0@TgHAPf zTX(HnpE$P)Fp-`>sd-l!q*(}&d9YP4XuCni&1RenTRnA=_&RcfT_`SLGss6H8R_9rK4|fgt%rK4AS@ve+ z2BMpAq0q-oz3y{TReRWOwwZbJLu=1VBg-kWPGj5r$$# z-TtqG>&;b?_ptilu}rChXG8aOS)8!Sw!c>@xmmF9^|+Gfbx=Mgb6>3`bZ?qau0r?D z1%-~psd_$@W#5C%Dv5%ZpVdC^_^J9i$S?1^3%uQumSyTp?Kr5D| z!b;8nMipaLwNb_{pn(YK?d}z_04K{VG0zPLQb&T2lmVV^0t(Eisk#(=_TokG=~>8l z}=F5Y)@Bk<%9^^gbNG^2gzUGG>J9dnQ?~<@a3f=9}BBOjVIgZ6OI&A=C)4|2$ai(2sZ`-om z80Hpv=?OX}TEQSdFjzH&MI2{xemD)qqyCYNMEm}gPY!Q=*a*1HzOTQNZr|LiFS}VT zp1gjxR&w=qldoina&JuNzS>kL{B6p;X(eabUUKtZ%p~Qx2jAy=n&#Lpe%&TgJsQQjVL2QPsDf8xt8F`;8;7WTbb;Qw>jhe( zclB5gP92s*V;S#6bX||9La!vmwXq8#2Z=r#q+uK+7$;JWd754L>Y;V#rP$BZ4aOK( z+~VAAHeqaU6~e{b%yTnA54qW`e8{~B`l?op;Jav@&x+ak-rMu@i;KPUJ$K6FwhS-< zI_skJmmsQ%jeC$adfaFb$<|*`ZTbN*t+a?K`wVn4+H;0( z3g1DmFn=9xmYk+)c|T1tQ*GEXn-B?q7&VG0E$je-w?c1${BHWN?G6TZfl1~V*saqK zgfS>!9kI7QJH>SqhLf75Hbr|9bXk~!0zyAot#U#D{ufRfpXjoFUWzFV3@dFYCiMBW zTCLf}@Uns0XSUKH+Jxa-K=_sm^kLPXGJey=pNd8N-$PBn8;SOU93NbN58GZh0~ z?@&sX+4qvRef_*GoE2}$gL^nCy=0|gVY6s*^)2wed{F9MvzK`J-HW~1-a33Ab=)8i ztGQ_5Z)q03TfjZRcZ--}PNXN7S0ClS{rhhzMw%?16h-Lw{{3&g_n#kN-JjW4!kaQ{ z`|ulmg8%P}(C{s{4vv2qyg#q*RX(Jd?5uVTA9UQk7HlV1HwV8iA@-Yf-aR*)_%5A= zi~!w)&Rg(#6LM$S)>-I>i^3d^5$t%Zb8|l>zr*6mXjG0ZIY5vXEuFTEdxeABtGWX{ zBr2|Fn&a^Y^zif)jqsuGinPe~?gZg%6?^jGD9){sUL$ND5ji%%u5*F{Hf)RB36M?& zMLSmgmmdePTVOy*xFF)h>`MI`OETctCb}8T_=JrmW|uc$qMe@-iQ?@Ou>zDl`$c+Eck#VCO8wz;Qw! z!QQ0>O70h`z5!Q6aGzLER@i&ZrN$95x`x9BPD-F&>sEvuFY#g693ILH!NVpL`lY464i;L~2If5Ym7^9VfB1mJrmLF(Y)=JvHz zlJ6kg2M?{?d@tj^URFwO){WdxH3wd8Ucz~B{auPBU+>o|Tt2aqa-+LsUFyCM-{OLh z@nRjmzrM-C&g|%2nDO7zd=`15`ET*Jcb35oC$IhdSMl4w{o8N-qIDrJUcdkE|Ms_H zwg!z$;4SBdpO-b0M=lq_BOu6x`}@uxt9KuNvwMM41i$_@)Xsza%fDVSRGxSq3|-kyK@Tw~T^Cm6`MihUyukOy`U+n}9eJ zRpQ(zf<*aQTWe>T7ZNy&Q4Z^%O@F-f7nrxsUtAP@fjBDLhJtP7JPMS_u2`nj6N|2O zeIyjPwr;l*%q8LG)&o09pnpp%hQaec_!Vkh_y$b_`Q0F-X3T_8m`u&t+t%f2rVib> z$myY#Uod=Id8VD7VzTWOc(mQQ(ZCXK@vxh6xOeW%v>Ypk7*^sTH-&nl6Z<|tKi|vy zY3p3;i@Wo@uMrhz>xSH^6p<)J6PXQY$*hw|E$u@xiRQJKeowc`et91&j>I^|W8G4Q zLY`Z48ezj`I_*o}q70}dU`9j=TM;34q=N7~`)xrHURecA=sb;uXzdBYPO@{2({M>l`Grbvijf%mF3%wDH-#tG~d6tUwTL8E(@BmZr{a+7{ zBk#Za?925Ua4)m(>+hFJuGP-_d^EXI7<~Q2C7cIa6*l1Z*ZZjb@Qm`C$h~2a@{uLV zuWv*yiu>@rb940WVCVBe4*32*TKHuF-+O@X@T~LxuQz2xU@qZ%cG2R?ZNLAwfBW~| z?El-`nDcp^c7Kah!_>0(;+zgM+IJH0<3;zv&eJ>3l)wAx=8b6Gx%&s#@7{kS{*@Rw z*Dvf>3+?XKhsOltN-23)&#Iw&asJj5)lLB2gj zXzN}(bEO&%M+tV|A!{>h1?}$YC^FDX#l-}OciBh?P=pt)+tq>IgzF{{9r1!9jpzXK zmf?HyQKKI%5A~5hburD%t-++gsU3kbB2MztPp#7cYn3U(HyAd)H?i-#^Ybia_|EU{ z6nrCZyeN8Q&w!}4v(U@N~&l9fw3dYvT*x}wVyOC_3Hgxg~Lx@M0XmfGp83*`3M z5t|T^A_!Ls>Vy$eh=W2=L}k4Lp0G69Y+(H8^B#SfVw(+%d^il69Mc_S^mFniJ4ad( zH_w_`%{FR=O1UMrFJnpy94&P^H?UwRVW&1Gjy1cyyb1>Bqzr~b%bND-hix=Jj2q)I z@cWnHWYYNHN8_;q?w@}q-2VCJpNI7F^M`KN>JoFuK9ALv0*YL+m(xy&b3pJAzVGXY z;d&vF94vB4uD@gFW(~N%7q#c{B=^|&&8m_6`U!k{Lp1l*2Hc)EQ7+9VuU3NspV&zG zkh$b?c>(?r{62W^z2DF8!*{uAh%?#qTlZito`8K{pamrgw~prQTZtz)sioJs=>2WZ zzK_?<-7DVi<0shrb}rzKIe+ms^WAql&o>AjAI~BDcpl)r(cirqXHxpR58lIfvi0}5 zU{Z=Eoe{)s`I?t=0N$KNb>?Sx*|aLN1fh6W8NPi?=Vm_OoBoN?97j$nRhpo(oJjJm zOoMFQ_H><4)^n0cFmyuiW5-5@iI+?!dFZ;HD{>f2Y!BAKG@|=z&npVI?brm-YNL@r zTqo2=$Gni$IELefd6;{FTea;ll)LdtLWy}#zN=#ZYe1C0b&`YrjV^(>>C03;FmBx> z5*WkkZOMpMB8^=i3y1`F4h+;->B||u3;WFVUJeiG$Q4cj&lgb<7Ja@q`h<32*q#x7 zYxOAVO*MYVrBchr=u$i1i~0(_BL(01C>>=Aj@}cp%Z6C$SVT%L_SI&l9Bzst<=~MT zgl1nUE0%55#)Z{*{rcxIOE2u_1H;wTaz2YBQ{vzg?AD-%t=B6jj4;O+hLzS?%vhL5ktL&YgdAA|zz0QH{q(xfjz2k07T zx?O8z&33cd+~)Nh;^SkdVNb@BMq|>Ld}site`dxl@p_2o;m<&dnzF{k@d?W|@88ti_gGKfUsOEpuuk za!Z|Cx&l|h`s$(Jsb`r>mazK?@g?-rZ#@LxM{bVs(uEpP&e`|*-QM0_%M-W!8OJxb z#455c+BBaL_s-Jl7dg88yb9fG$=wgoZu%bT3C{|wcV=h8yLfRv%k$aJbLH-3&E#Q! z_qyJ_D9*XO-goy}VjrlzI;tG~?KeW|-+oKBl;uP&=MY|>`L}o4v^wuzsGgmnZ$Uur z)%fPEfa()pf*Zz-Onaz#=%EV=PsM!0g`hzWBb z5!ynx$|@aMwO~hd#EN8?2-KIJh+w+5KwcYc7m>%HF*hPa660ZN5#t7DaobpVhvXoy zC46V;CPGA@uWD<0$_G<(uQav#_dGpyg`bVWfPis z&8W!>p!`+Mf@6?{6FPgCvh`Qo@Bdu{j67c_d9XC$`LR;h>tTSanXdPHgP&YKxx9t* z^^xuOD>bCNx);!WwH{n@^=(_=ecfc|`NfnE!S~G;kCE;?@ny-W@^}hfsVM&P@?VdtuyJp#4lLOf82|0J(QkiC_ElwN>G3Aa_T9T#8g{(S8J2UZGReD2 zzeDRZ58K{H#|z8m1)f#P`J_xW3FW$_jt>x5PKco+OVzVDvAY@!IC6@f5Fl73jCMxI z%5Kw53{l`-x+UVPj~sMfv@^%i3HUwN@!GEEK?)ZxXP4+nEzo%msXM1OZ^SEYysOt4 z!}YEi(Thd@#9mGpa87S5zpSU}T83F?O(o)zG@k{Rh$UKV`xT*N-;Lq0F+4mx9W)vY z-z_>f$Wy#GOJm~nq411)T!+TM=X+USrIcXnvhTJoa_u7Pi&jhYvx|Vod$R7#AcU0@ zNK4AsdStS6EQC~1q~hG;p9_X*pHl<*^9w!{aTzdO5A6cGFh&Er@C85_7mOuEV@PB= zYxr#ZLkCVz&Pchf(u|~k(VzBH=-33xP2erYjLe(q-(8F!twOhJ&FwY-v?)7-+enpZ zGXEyH=k+EWDIKFd7+}-A2Cl8c31}D<%jyzx>+}l#d+gYMn1F9f{GK#kzI^!$ByhrQ zx+c%_f@>M%Dn3p~dZM;+Y2d(NNTG=jg2-97CgR>a^4YTX@YUFz~TG%4bJ)Kg7O?X=^M)3T?iE^YwjkvG9Fs<=W-Z z5utb9PkEQVUu^N(&gYVMA1^F>-&DJQcRg)!@!U6aT>s+H;o*fAzWa~wk-MLvcVDXf zZq<4A*LUxQN5AUUoBN9QejN9H)A!#i?A{6(y0M<)=X;nClqSJWJL?39kjX_(*t?uV zRh32Xl6L3SQ6k|SBTTpBvE|RzadX!Vh<;;@5-q|BTFsn8Ck(4CEwPa%NElAQy7xjW zQenFU$wAu*Gh0vSsp{%Ep2rOjz`{k8dN&?%4;n$WWhREyw&R%48)~*;nZRRTM}n#D zt8R7#Q^m4P-se?I$R|DSL4cGHt8DBE;gGJ!X~fQxVltuceK;KK?hcB8;oH}32J%@S z3U;g$TIza~_5&VVrm4(;jf&JS(zJl3t^lts@EA+!N0FVws;F4UUXBW}61=m5QveJ% z*&$cRJQf~f`k@m#e z1~zRB-Wg)48daWCy^PjEzx^C{xJR->4d-hLLi<`=XJ)Rd^<&hgRunN zwJ~;qILDU7d^RoSlZlm!@2W~zleZUKeTjWv|0v&jvPBSmUS3}8x!D}P-&Bk2?u8b;d-6)W9FZ=?cRy9{mSYULutT7| zg$$E$YtyuHM1M-vEm=0a-{Hl0F3#B}_-+Bdp_{bZodgXG2o&@}x7v}pfinM<&D?4; zN7_uJNgJK;t`j&|jF;IZ&Y=cG91(Ogb#@UgO9urv8)~PTmeEz7*CY6D<$d9{QQB@f zT&IJ*cM$F*0ndYz0hxha-t-}8k9C6VW)>|(7Xx1 z39^F#@6*59H3xS;AvN;;*euvJV;o#$kue`+>h($+3zo=m#l9y@^(KD*qTb`)2iYe9 z&}P369i+y?Ni=8QA0j``KTIY=cA>n+EQ3vfeu!f$B%{}8Tmz9GM_e3APc;J|EFxf!wwQDL z4FI3H-@ZxpB+3gNARg}CL8o_#k&vCz5ubr&%nMn6fabN`z`+4 zZ`J)^Ys=f8GjGE1Gl(Zeh;bz|@1*Lr*(%tsR_CHO)NQ?58cp=lZh{~xl$#;Ho50s5 z{*1!2&^vW?b%_bkxCG3JL81Lei^o*Rih1>d=dGWuEaFophqQA`JR8nDHrr+1+q(=ny!Pvk?cpBB;| z;unj6H1&!zuM0~VyrqUCX?TybOQhAC69~D73_J1N#1!S0eO)xh#IQe%krcxFn~)BA zTzr599E+K)j2jdaOW1?KNBSCFGpg6o-wuyC*fBOT8GU<(^=i8-dwuA~lBVmLy=~hy z19JnU-Ex+cWfQZ;_PV~50EAWTSpT8V;gb3k(h$AZtLxovw*vK~ zVpJ-41@av9B7pa#@c~22p&Vb{(iLvb@mXbRxo+jdkMDPbPOIFHo&}CM3zpsM#y%FU?EBPMe z{=v)5d&$1t75IJ^y8Nf)=BxQrH($OS9UZ-^x}e{ld!Tl6KJRS#(gBv|g?q#c@lTgb zmP~^0&+_t8&E5Am>e@UE_Fmj+!hLuAoCw&RhXH(p-o4ZlfBoy1g;)}L^qsfv8@#K( z{cThw{65=~f;YFGLGC`Q7PsfKDd5}t=(W8zt0>iZe7ACzz~8N_y__=3n;^T&hLg-m z2&8S-&DyBU2}Ou5Vm)C{24mI@N8x$wxWj=$c0bKqFV0&oI4XOFiC6=kGr+hx@*IG+ zZV_vUcZg3O?TtOCmkcr3c!^*HiPj)Ijb+Spx$m;xa0vWEjByO_&-Ev_WS zcW!4{kmZVfi<)IOT|F0}kj@jo@7laPuk~>zAXEPOxHUcG`byLw?s?nVaPbPJ>hq2? zjuqrdCkC&Etbv3c9brBPe~77iETMQ4lr^|lAu43nAT#!&%hC~NdSmrnCL6W~gJ#es zOha!w5oCJS^`hwV>Z24r`aQE}RzUt!sPSFaJutadItORH`Z30pd}%ftIUi_PKi8#; z#I{UcxuGKhlkEO9?cor{y`PpIl8rQ8c(WCbxL=JTr+ZCELipe+ag3R@wJ*Y4DTc0oP-> zzu6qTXb;Bn``4>`l>6$r4e(EBHTy9Tzd1T8#glgjH%nXd@C>|o>xSO`To0|vcKl}J(W90T(yJei!ZWpXXl;c-?r$S+V!)eou{Rl zJY!TT?cJA(cH@8KA76f7@pgx|cbdQdzVw$Yq?6yw{jIb3w^7-4h8KYM*=S0HeLC_q zBHa$E&pOf=sA_XcTc9M|N;YBLgkH51$00J#5mh6{4MD||gl_9%;W9}$Z#&jUNy)|a zk!8D@7t2awF)e~S9O?Q!!Ls%UbbI8v9E%coJgbb$Pc?P9Z7FXG^cI{y1+g2$OoQQF z2UN>+Z$=%zE8);Ir7cf(nG>#Aj>S_^Y~2T$=Lrel>DV4*jyn>BCCc|b)vfeGGILY) zNcM3S_+rmZi^x)u*J)120J;PLzu^lV6bf+KLSXGt+6FmW+cXeSVpuBB3O^WxfvC{i zQBm|#jw!)Z5_8Rnm22#)q;w#FWgJl^AnW`)SvDO7c)r+vW$-4xNk1RXF$l&}vun^9 zL)lDLpZZa)%WF#!Al8IT&Hv=Bd`vJ60KRSTnx&0$P2PXBD#kXX5^PiA$P3M#-G>Tp zEkayEZ&-*Xba9DvSBQO^F&kavH%H`3qmjFLK8?2N2-Dr(?)8yx<9Y6Q95K1qBVM03 z7_=F#K6W0Qc_`H*Owf-#-G~_j_>GN0d(*POcaNm)s?rqFv`Ycd3@F zQSPe;x)rXziQW%`_vMfG!5?YFhYI<3REVvErEN@g8Vg3#`LbBDk3{GFY|ED$&)&`P zypWv^1h^n;@OUMA>iB!IyO#!(2e(3FK+50TJRt)1^KyLmX2oPh@4lS(RkGlHy@uU% zspfkvzjMF#tRoeZYDa~4pLINdH(az+?arIh2eyKbosx5h^AHnd?w&)q6uuEnLbr3; zo|AYkufdO8!)E)*NF;>eOurYXy@cOfVa6YeMLKoqV0Uqw`pJm(+de1r_vvj~^mI%l z(etb86_hM6esd3lX>xp^uAj)@*NTA|rfG7(pycK7ra*A$5g!>q@v^by<9r7v8rxpQP7RCAv@gk@PhD#+Piwjn^9xauU1bf2q_IT5nxwTkO^2w> z*;lwgPV&)9Kb=-Yefuxny6DnpMvhj+Z8cjSiY)`PffxZtqCz|>^x%B0W z_y*xF%_tAB@9*`LtZ%!o&LwY_$@lg14S{M6=W%bzRY||sw37Qe$rE9FWfNzebpN<^ z^7XyA%`%PWMOk($-ppgYIsWZJvL0`4{C*b(tqeu798=g5G6`HQR1)O=2gC01=g;4C z2tHan`5C!Z<>&mzUxf!W^1UxRj~h+a?cK-UT8UrrcVEd-C2J;cR>EMb#l_pay3)NM zyN0*qRy@7(WEPbQqN;{PYtQwo?T*~7lq)%sb2EHbtBQE*3eD+89>QMrQ8fX}cB-7? z?b-;VA{b8?nnAr8zDJTigC!FaPZGn4;!w&Y#H4#u9Pi%xscsshUIgx{E}83_Yz)M0 zr3+9eB=2%>CGcCqF)P~;OOU5zMt)C%w}|T|VTT{--AY%WF@{$zQG5W}O*p4VuBK%j zKXhF}+uI9o`V0p!$d!A^v;Pt?0VNb4;N3wD|CWewqq!8_EV!1x&7wt6;f_ zwJAFYKH{Q%wCWajzvI8bfZG}YE|yyB&w)l@8?{Zn2u<~HA`_oUmhlAI{*Ui^hp(oT{!fkAG>G-mt$eDTb>{8h**JqLoWPX5s zU;hCD_sz{}D)*+Q_oq)MH$|4*e0@kQDM9;cy+L>_=Jo2S*u80ua%nnwx%0=A!n0{m zr7WKl^Vw3xXfwa1uHz@K)WzS4*^BeN*2P;+BJ}bvY%W>H$>Tq?E$9DTgc=rh-rqbP zBlvkW&g2PMRCAA@!tP%;kGA@Oxx zZp6!V9JY2>ms6<1r4k0B)ozfr5#a4GuSQc2y*ZRp31Yj^Td6yQ;0c4bYEqzo2q~yo zdZ~%T1hMJl;x6hFuN(VVx7x|V6dgb1L+e6Jc6V)Hkw{s0+q-zH zwkyHDi8J@om4{rG7N!nu1hNR=o4tCBys8-;@MduPJ8QkHnE>`MS}mZf5Rm#@=)gU` z+r&Y;kq!GFeNfg|(#>GJ)@{2M!DQI?rRvhdP7u7?%+EPPu#bLutb%sU$_av_DhA!n z0s~+x_Q#FxiK$l%Y40O;egeV58tW)Dqr)%ZvNjl;4m5gd1G>9iZuZf~A8O;q5F0^! zOaWZeYYck9y5%!b?>w(oMKuBEuh6T?iIA?9sq&)051IPd>7=7ez1uw`+2s?w-RYn?5xvo+i5c<`M(Pw;+RMmfrJ&+lwrmp@*rJezkOKf&L9b+t^p@gMW+ z(VIElE?XP$?udnl9yiYgmrt-_9x&e3u_d32Ms_Sitvf5aa~l zX-}klt<<|wt;1PaWta(~5Dl|#RD`Itu_wu)u)?onbDGIJKC3)~<^s5|Y+ zns=h0h_&KiR`#pVJyfuD(WDa&aZ*Vt2JbA&K49JG(lIV-z$lMTNo1QOHY>+K?_AHr zJl9>_mgr6VTUJ2OS1`HOOytad3z19o&Lc4=+DOrpoua{RQub<;4x!PbWSr@j~q>{@UUZ9*K_kwdj&?fv0xnxsP_vIgq-Lif` z+5K>732moj-`e8py^CA-K%(M7hx=0i-WQqg9em#5(dF^yn=H(IdbHssf4}pG)>Q7i z4|DC{p#<24Zu0P~@)5mT^6q~esW__N;S`kUEytA1ze9F$Z|y7UEj@zLA$Z2MIgm|w za!cUd*4kk)yK|>uRTZAe)IfH01G)8)>e3Qj#)I>Z$$n%f3aLxPou9Bbn2W~1Nb_WXQr@BAWyqz$noQaOWW$khh#ExL%2W`VrjQ=SV~Ncs zhniO^bvi?#;{gCYIjNlBV~Iug7|hoQnKGk>p^AA7y(?R8=(a??T~3@K8lSuE;3Ko| zkAYE`&xwVcprB^ecJ8y zdvMs->%&1{I}?|MZQVi`S%_1OLVhDYI>>K>!-dbQOc3(v!y%NnmEgaFwG{3@MkrZf z-zzqf>nCd^%lQ42?a5`<&Eeel7AWsoxv!py+?Sgtl+WFRfAZy>E06Ygq5s#?BzWY7 z<+b!8!uLzJmu$|t3*Y)Og_a_^#bv3H@h=r1pS_xTUK+`QXJy;oP_AHHnTyVYK$ zgl;K#E8s4{TUku_O?5iE%l%FnX@Z$0cjjpox%)(0OY#-!X8cmSktyio%o%utmg-w|~b_w|oul-y(A&nlbTlU&&PO{_M`4hBCrruA7WhnGQbzy1~A4`j`|ztYt$< zmEYk-9BJ|G46)vigaFW zH=0cp^VpefyOxW)uU;n#o+J4cs4Os>gz?a^BgD1P)j2cnTm~QTpq2w8S%INP=Cm(< zBzAi<+g^_-Sw-sW?^~a|SuetQbn#s&B`bcwbwkP3y}0hDQSJwVr~YZEz2ZKZ`(~D| zMDpKP`VhU`?0nrR&E3eKI(YZ)&AWF;Sj<`Y1CR3TuGM$%_6o7LC$|0x&G4IRbDkgH zy|kP2kEPWd$-5c6*ZhGPRKiJ;bAC5(zcb+`@Fo^s<+mu!(b{E&jwIhXONLx z#o;t67O>@7JHnRWE#XjD;^L+>N)t#&hLzyDST~asgT9Jtq%kAEj{FUwPX!V9giu|K zC-~u@6nm$qv)%0D>DyL-=1i;?*#W}Id22t{-7>b8@T@T&V`07LqkY#(EYq^pnhmE= zslEki2DG|F{^jTr@J;9UaBOhSQi;~m>t`XGo9z=d^sWn2Ufqibsm*PIRuPqjHDx=}efN#N#|2co?FG4MdV zJ;G`a?AvQQ0!2ggn|m2yI?~1jwr&ulRv^=)5IE*+N`I? zrH>#mh%8g_2LShS2KO@iUR#oU7I0r}*0?1?-)!D{pI5$1lgTo8uS53L2HyR6pV`L9 zz{{PDQ6~SBmy+9lK3=w!>@2E05(ZN25cxIBkbMa>T=rw~|hUxZ_H=T*gLW>YEmpYD+VhJ6@ zdP0}ZKzo8;FeE2O--d_udzW08St`13!C*gN;ja%4D_)G8Lnl4Hfb3BKp+QHHX)8I{O$#-cB8?<*4QOc6%ST z?m+XrAXCtta8>2h-J8*0VyT(T9fEol^cwa*m;j-mXdVmT9898zV#Hu>5iytUlQ8Dx z_^Oh#aZ`Xc-hd^tbREkL99G8xlBmYHTf6l(sLX_+9qH9#5 z3Kumfy`*cko9!ZqieAwx4czdhce%d?yD6CTF#|OL-D6f%rhOr#E0Df8Y#k?1yOGIg zJGC~kT&Oi!bJ%PS8g|Xtrr$5)Wz5=k5DW>q>9@sQ7Dge^8+`lYAP54;CO}l5s5b;I zm^)B#miAMf-6J{&HFDjJAFBRSdI06&6qPp+Kb&@O`sqLalYskh_tQ_ir-L^8|LC9z zzc!2SQ|$Za;PtGkxA9+69~)zwJjm@+oRTR~$FLi8YJ)m7={CfHx!}1ap*GibjQE}J z;@TTBxNkOr_VqI<_XCXkQI&hqW43T~UtO+;mONNz_AGnJ!W#G|p{h6Je zK`9BmPFu^ej-${UeN%+qh^3xN*}Gaw-PMsxm|b;~kntOcjJ*F0o@j!n$DGY=f?_kx1|G}3NgWk21Z)s(6RC7tg7p*GL21~QT+g)R zw2s$vx)wxGBBb=k3?aRXC=_2vQ3b7N#FU|r5?Qa9Fhu(WeqO>|0t@2jUF069zzE!I=3{?yk#qj(UoHjLAp$lZM%C;PYkfiR# zEbVI-9`C)&aFT6eufjse5>sdHRwKq~pR$9SAsw5Xexw`BveBiU_5ssyuAt}L8WT5# z)56DYahKj7*X#zQ!s9>ATkx}$v(rDVbFSBIfI;;y- zcLCK287U}@ekS`~pz<2~zF99%xc;tqzy}!j9rMhj}4c6czK94}z7~xtf zlLGl<0AE`Mx#D%f9el8$_&l%#X~cSb*8qb|!JV;E1F~+l*;wHq!dRc_a}sR>lxPnzd%rCWvcvd%e1-cMa@g4u`T^VVk)3E88$cty!~yh!K6N zRq4`C(X||+!(op5m%)@SUf}lCR(%16ABlb;w}o&@V44-9>#NNhg7t8cWwvV%P=;1} zReQB96G`kgUCXM744FZI090)uT`jifNhQT~UX7M|mQZqY_2ARD8TZ%KeAks4%Bx5F%)S%6 z|ETP#KOVtVRgUy_&y9NXbdePXzVkj8c}5(>JInpEFF%CUM_X?7%&lf$j@Qz=ms}&N> zK@2!h7{1XTfHP%4MO;Zt`ieU2+*p1GnA6*Br)E3sL5UCy8}&G}&xdZ&Q>80C{>Bk+ z0TJ%U(wG3Chw4D6;2MtFkw*=>by2ZP;RkNbe^z!Evm_3hS-zN^e< zg;&osEwFuA`p%$BG<>`;14c~E`FMgAa70lHs}l7KY~0A>j1;%KVBbVuv7U(|fXNH; z`~%~k05E&IW+VooWzDLiEgmT*2y_KJBJCQT1#ZKNwmIgN;L~mfP3bIY4r_+cZp-`(B0dbprlR)=F;HmT)dFH|^ovpH4n0 zY-)3M;2*z8`Nxeaf!@r%%PgpS6~o8N-t5`Co1@vggQMA-qaPyQH|_k^^Ss;KJ6IW2 zuACSge`{8`$TN}H{p*)EWsu4IO=<9+L$|h2PC8qdQ!;e#!&2HAF)#0HV$rX4;?{LJ>E&bjKkHeUyW}Z`y$TVEr5VHgfl4ms;Pmg5csMuzras1}wyxXY-TV!7iQQfhgkkk`Z#UT8{b~2qbGggS=B+-< zwLhJH8agu9t`}QamciM4tkR?aF;QgA2bL0?0pA7ZWOLsF@ny>=qTQczuBlwn;a?S$ zHfsLwU1%ygC&$8@UFjAP8#KxdNv5MUyRhUx<%ev8J?=Q5RE##^cH6E6heHD;$-Ua3 z@%rWAFYVeSs+*SH6ZY$IjvDu$8wjVe45RFgw1~)tUf}R(R&nmB?4Dn_(2qR9xl07i z%EF0J7oWcUO2z^5Aq7)M!fkj!cmqDSU%-udh!o zwC$@6EtF4l1zxU)O|68N{8?s{kN8ZuF=wZYetmM1$$$KqQ1Z^5aXiP&{r&T5diU{T zRm1oF-O6ord3k;P?(Yk!TZty`mlxyJiVhkpwf+75fL?j?mC8=LgV2f&;W<0LI}6}W z%Eihu#$+i%a3m7~M-sP7D`2u%bf>>bRuFJ2QN{-*wpAruHs~4^NEOFwSzeD-QWX>i z9%{0>jhg_xkt9fTS;Usyr^NE4ju>fz?Zikx=o32#+727ZBSp5%x`I^>h%WeeAtJQO zn+URsePx~NMG%U0%Wh1NYlXfC{gkr>v)rxv)s7xI*-ydY?&0B~L~jqL0eKXz-JER7J2ybkTB96*u%Qni<{T|z}Yy6oi=G!E&{>xtm zhngbb=s44X(Yiphq^&&J*v=7V)HS6TY{&%|nQCR(-p9k!A!zsZAVB}SaX7H-Ap!L- zzx?#eFTX@%i(q^F`e$ykp$qr?*2>ow=8~NHw{+>LN@rP^kP~&*LmeGGC{L&u(k-sS z08xzOa>GKX9ND1=rDG9S1Rn!sVqw(Qc?mzyODCr1U^0yFgyV)U;t%}m(V-hYnz=MG zuZJl7$#6IfEC}Gpz-13)fnGS*(i_8}cp!fJ<{taLmjd{ljFS6&`;mqB%|`ChSn_p4 z|K!?qa$V(q?)Li%a9{oj#gb+0R;BO9pI4$^kDnhP_&wT*>&Z}l_Z1VDCuoY7`LAcPWOzTT=2@19;M-VUuCCDTYPD2N z$}Ct0Zx^kV$PcXQW&V`PEJ>0@(yNRRWIT`LEk=o92n%?cSah<#{y>al)@3?(W(> zoWCQ%bd22~sc|zta|sTM!f8+TzC@<{uwPhFA>|a-MY=?K^%^@2SsdXC2BX`pR4Rcj zTO(Ni;lvUiJQ_eTU4;)~p_J8NUFFOQJ^M(n~shUzoCu!R>Q7A^RHoYEAE9$ZDQZgD^LOIDG)gzhpo@c8rb9~M3J<75rG@{!H!R4|x>2`_WgCbmmcccZ z7&9g(yv^f77g=oS=)6Z6MX(gc0-u5?teAra8M%wtVp47CoQN^?=?fbMb}j3o&J-7t zw=XP_`i5b`w^4};Sop>EWR(DOC! zTHLhR1qy>P6Rw&PP!)~~)jv4~z7c} zk^oq1E?eka{5u}oC<=?Dqua6vpDuP!S^qgbm5yr1v~e$6jn|EzGlK757N|`xzcjMO zB=^HS^GTuT)DLa#a3JzYW>0MUusJqr%~!8#z-|U^USz64rwj!UE6p~m?0aPtxwMb-2iUlm1nzGbOC;Z3&3Ijb?hPC9Px1sl z99^=iasTgx>$LoG!w$^zpF44`SNDT z;5}DO_RD!Co&s%48Uq2^`%)^|?}Yi@ix+pU0Cq3a?y9OBmh}r^sB@CHRJGwUagwmi z5ajJjh1EIie@UXW6n(CxnDY)C=@=YYiBz^Rh|(jr@?kcKcM$u*^}-|FAl#1Cawc!> zU>RP9yXvO=3kI3i5g}s6T|+iBV5=tv`sofN(pQYkdcDTB81Cgk z#X~eNh{rG0RrQseC5R8PHh`or7{W1|G6=2%*B&m4(X(#K@eMnoE=;F ziVobePU)g|EmJHT0auOOKOk{mJrWM60s+6Rl>o56Uae*&Ve;bFkCH;V16h)VUP@4*jtKOKSz(~+Ukh`54dif$?@nVitCL$7fj zgIbAL9tu%JX>wU+;ZLLm(w*db3w@JZFW>XyXxPYp9yTUFAHMvF5d5cnO1KPVd4$Du zIy0$pZ%(bk{cls{>B#em9T3tV{`AxCPe1+CdS7fOrHF@{sILDXK^a)0)0@>^Cw6$to{R>C)061i7l`(ca8 z6GZOEh3-Ei%if6IlJ?4FN(G=hN3$(&e`|KI<|EnpqIvt?{p9xEYV162@4oLd znQJEazdQJ{irq4c>dgvtV=V`>%3v#F$-9$DxJLL?iQMfDJ?&RRcQ#}4U2ay6m_HxS-LV~oBz#C2g z-GvRrm;E@3c0(@#M#YMJoA7^g9XwAtg_xiu(u;hPYhJ7vW%33fKAH*!G*;gWOE3wk;Pw7`~BGGPWY!84eByw(Dht*ZAFoPrJK=0i!ntX;>}+5%n>FBQ*9t z?P8y#uHy@0d7qCbFqEKM0cJp7u6Fm-ri*~F8{)lEPMr7ssm#qn6Ks2PuT6A(8Z+J*6YU4 zjmd{e(~$%iTZ&-CaA8}YG|&|S5V8I{=Nv@D4A2H`d?pMKii-OZYOYLUzQ5e^f? za?G@#r_ciFhRn@cPP72-61jb4&5v4ko!*z9Azxk<)S)Ux_;;4_jm7ppB){* zKllUay@>CguT>sDAp^EtipT%q^}*3fYmUNguw9QV3H!{} z*~RTdJqs)5CU76RH(UuZ<6Wggj0{^~QCW&Go3)Pr3FoWr_*A2@fJ=(4Z*#DNYImQV7$0mf@^{ekJ{c z%YkCkFzMN-ebkC#!1CAPs}=YL&dN${Q2b&l6NC(WFALmGcS(lXCs0=9K$&CVPvU4d*XI>@pkWmXy?)n zJOaP77GIx-3tZp%-3rZu-*e3FRAs11yS?Ap*V^r%BjxTu6)W`aRJ`#!{o<$HuPP= zgxf^Is%h!5)z!IP_#_r5X5nkF^32>G>)}N7>pH%P$#fkeNrYfNSh0Ix$7mt0%d*Hi zRzQpjebq!SnCQnSwux+1CpH^{fOR5zcldH}DAC)_##}*(i4BBX*R@f~8o&Gbs z4c5Jo&Zw9-E8Fv3Ti$GntclEpVRb5I$3HAfVyPkc`VX~~Tt4Ng6uB2V_vUQwdrHaG z6V2QYfcNFv3jCiNx#wc{=i^o6mfSlNn(DgR%ly+)CpkW<<}FoVxaWykdHqc%pLrPp zL_TY2YTxFWdiU|?>p;;12-IrIB_Fr93bAYTCiZ#L?Y!88GgbSlb3mPuBgOkpm*4eyIs&})wLr) zu2ImC5LM+Bdxq#ZqR+MLv3_F011x$mB2?qLjND5Yz75vO`A6xR7Lm4B!@+Q{duZFu zmoEn|2SdA=N$MR04IAUQkZ8285%1r-wX_<#9qQHxI%-6{vTcVRTKzPVcF4$2qw0|(IsuxCzE-VBo=BybWu6hM`o@*>w?=<^! zC6_!5+@(LTB)#{{d%ku)ufV*`k4l&h#G;XKFRzx@AGqH6`NhSHySEp2=QDqH{M=dP z@mdts&J*PBMFuQE_rb5rt2u8Li}75$Ac?ok?q=BD`lxNSc{isFp+d)Sm}{Dwdu_yc zcb5I#Nfi!m?#z+xl_8qXMy#Tg<4NiGQ-qstDOC@-b!l;{FtqGYCQl{2lrB5YIP@fz z_T)&1Pn#HaSCn4x5y!?cMyoo)m`B};4M7Lo7l^>Eu5 zynOlca4;M;t!Sd`-iHG_&t-6QdV3)&t)tn%Ht4g)ALsznOBWBVJ-6RO)g*qvez0h| zya2ocvH{=y!n^gYTXCDYsmQXtr+Zp!S8IcJ$FfU-7`!@&$t|Y@i->NHY6LF%f#h#? zy9S=djbRWFcyo(88(pSE-rI+EmxBN+?BhoDj8K+9tisrKFwCsT7}v%u8l&Sar&qq< zp(=Xi5vv$R(x?rz?w{08fZp|!6Z}^}payCaY%_TCfB;k-MagvNlsoRL3zE}STOg`F z`^9`%NtoTA@^WR?%;@}QFrfd5*9~kKVO?}EFe0@mASbJZTyRw_cx+F_4lO+(WPUkc zaC)^EU0y$X(f#H-cHW_zT&f9WX$#z(61dT0^2A1*hc+lL*E?}8|J-uPd?{yzeXs20 z9CWy6wiPf>YWZb-&X+L5-=n&oa9XJ@2WQ^-ohRPX-<@~2=RZBNs>JTki>~3PVz(mR z^xu7TJzvdPXeP@J!S^zMYO8$VrTG0hbTf9JvA_HL#YL{m>a%vTww{x)$wZbg=&G<1 z0kBn$F&W7uWBP+_Qb258{8`9^KT9<@gWe?0e~4g$6~XO zn{b`!k?t5yBGDVhI(WNvDI4%y)8rO-jun9;+~m9vws%Afccx)hAP-}92}m1e0f-l{TgET8m}7!9=0^MWdZM@&{I*U^S3)M zIz9dAr^9ArOh1@N-Q|bYvL3MR(){Y zo-l_ton`!`Rx>4f)2|-V0ccvl8*+F^tadOAu(K46jR~veXzrZo{eDly!3a4Mg8vT{ z2|A#=*Q@t%?m(Pdc9u<37Qi{MRU&klBZ-AKkYwv*zkHrbroFHQMg@m=O<5xmg=N_d zo8z?T{(s%1{{=d>)a=*8*Z}MxPyvf%#LYq6L;YK?_ZvQD ziXV*OzE8NHv_5%x^?3Q@<))a|r*iIx^Gp8B`|s;1f-<%HxU_a3FZ1qY#{4cqqkM}_ zATwf0=dO1n4TCc#-x@u#gLBaDQWXdLzVN557g|4ma@)@F>Pr01gBHO@?A@q4`|{?^ zTKwx$ir~_ya$iX&3$bo$FR}6wZxYDcD zsqgsx5p=PR==XY-jR`G10ndQ0Y!30V3_+~JVb;j9W{}xZBbneCB|(^txSdzudNvK>mrDHzSuu&`nvN$J;H*GO6p^p%5(+ghr zbj~OIF)tu+`>~Su(hT^O`+^~IUwvJRE4jMdu#9uHZZX+;+S9}Adv!qhr-trDjLGqG z2J0GfD-OQ%UR>bME`PH{jQYik?EmNPeSh1=vSm>wXrX0A6e+&V9SO2XHhI8EiH}7% zmYA4A@F2*7b8vipzl=TZm~)MjkFSA;^cSL)4Bo%~R;{%u%RiD%dd|H)8O3pAS(arx zE*5Lms)}C7?T;cXuvDkLT?@aLAH$z+*f*W<_THs?)u*p&+c~_E+;7R_qt)OR>n8l3>9`>lLD`6h;Y9r15eJ%> z%^QpB;j8(~ptm(uo248hKGIXtE4fM$Qbw zXby*;LFmL9vRe=jizQ3ObI!tMjwOa>kL$=_z2i(+kMLYUQh1EkhE9jzS*BWN8wiJd z>lHlkW20H8ML=B=hG)&@xJi7p83fq`S7gAZwK(Kph)?#amse56|Bu#iqAM)-DR+(k zTA!l5i@k)Q9gXq|Ulyt^5&s$sd|R+LTExEJy?aXc?!9a8S)bljd+m3Zh1PEbz2SXl zMrqA#cubgjbLyXMOE@1rF_q{8j2Ri7|IJP+UM3nerUN@k8kj)iTb}EjsJW~QLExz3 z@nW%+@hn9MqtAY|(F|lu?Tb;c<0&imA5)2FB8X}5R z9Gi%efBUyLb6M0872RZBnKk^igt%gqp!!+2JEosk$1}@K9a&H1H77>x(b>9~%gonO zdRg)2Z5;C&K?+@hzZp?rWNG10R%--KK zmVCX^{UH0^`91^_qjvvX`vbXh;Wq0w)eKvqe^g`)z;r+nkW@1u8mib%_YOuJaR)94GHuqB6Pq{(d0!O zTI$Y+p0vgjp9agO%VPqOA&0cmEgg(J0pF0nhqkx_3DrA_orgdIdQwnMMmWI-4J3X} zA4bfvSaM`Xk-K`5sbop;os~i6WaDubWOyAJ^makL`2}6^k+oL{L<8MAT*+RnEB-HZ zLGR}?xjjqqA}A+PS#P{E4Q0H2VR5R}UJS?M$FmXr*Se@aePZ}tcRUoj8L1n`tl7+7 zMo_v@QAUS0^o6MiUoGnn&EPT8MuuGOo=C44#ugqbKIv(vOI577u|QU3yrCMV6Ko-I zOjLc5x&%}HOYhNo#0+_a*j0Y9IEnTL{e$09N;i>5!aYSvvd8Z1JyuP48aa}U8`hk0 zQ00nG?unDRrA#r;O!Zkm?Q4_Of{7^ec63xQP%GpZa>3fjV%rOBfQ8ut;xz*Nw3E59 zDB059U?XqQ<`t&-{C~~=SHk?8pxpW#a)0=G6ZaQaCqFRTzD2m--yKRmz`WmIe^XH4 z=fL~k_WM8ia?WAhyRb>^zQcj_3seQ^cxgnq}q%)Ymv`|wL^m7m|MglO{1i)XJNK<_(gCPp+VS?NZGiGlD2&n9QdYsLzVrX%}J9O=Woyyo(cSFUl!1;XThG9rdbv48_v;8DZQc(-p_%DJ2W46CVbQVWmJ@@B1q2l&@&60+AOHsV%n>? z2)>$`>fcafM-n57&7=`+2wn&F9S$^ssHO6JDM?@$RHF1fNyNs&@Qn>oMsx7pIeLeT z>zjRp%)Ce9g_QpZ^;*x_g~eSvd`w`oC_)9TGojccWQkh@=BT^ic2m^dd1eI&AdVb@ z96xCKfdIwnEDdf_Tb8}V!1PT@$-^e@`)$GEUm{E^*%LSy=_H9(1ks7j0V6OZ`va*>sJ7ip!g2R`S`e?Ssx{K?U~ap(u%>__$R}rKHTxdAJfS2? z$l?gWw^gv!7x830nkOUUGJ%WT z;xgbUj8VB>)w8~f#GCIF%6oYI&%X@6jokPBfm^Km!|O|t2W}(s)~O7qGoa{iRzAU^4qJJyKUrE{OrTMI1^rp|I35CTTFtt<4geG zF}GFT;CEvdU$&ztCeqCwlQ_K_!8}a(pq9nda(7`koWbmOC(*OM%#&v72>p#bMe+LkTMY0BmH-Eu!6wOe_o|mLy#~Uo3O&cgK^74;_Rj zk_Nmhv(b(-i6|;6PSyf4b58`mw=j^?cYZGOMV@xDtD1gzoX{fGHe7)qR_n8iS`Inm zGoQ+~DjhA;wA5+tE3M|ng}+rlY1S|$8JG1e^RPVKtm9ec^F+Mv2_k|=b2_k%7`KsQ zG8~#kOK;xsOkx1sDk!aQp?{gzF6pQ1YNboPq$7rFeb`vIKW_#6ia*yFS>oEYi3j}c zK`Zw?(d4%Lz4O&G$_G~{@7Mybzc13grD{JEGIjX#&flwun>s#Lr<-lbpQ2LWd*`Pr z-eTW`<{#hPxN`yD!oGiM6GJ^6(EoYD#@XQ2&R1(DcP_6^<=Mz3I(@bya<>F{3-SJS zyESLSyYEylJgOIT29M%eG1=uwWuq~Rp3+&n)e!K;n$B&jNjxA99;c@vTqZ{Go^t5| zK|6tWdr%URhW*v{PR?{{O>MQ63TtsDiGa2kRM4@&a4pGz7MJPRHBSPKoI?8GG}+Kq z0Po1gAZ(@V2%)9~>-13_3?PvoXAztAIOH4NlgDlaoF}4dvj|SVw8IsaFpcV2m$)Yh zAvpKAV{YjsUW=vj5f4$J(5oC~6Ato6j1;Th`4UOqfpr%4M@ba-XN8^n0bOz^*d@ zKc;U~WnCn^vRENN98)~2X5O}(@T22qQ15IiG)2mOIp5G$*3+yI6GTv z`V-PUPl`P`uAC)Or=w9D?`M;Mk&?Lrqa=m(WB0^4$;z zKHKyj)z#G=D+632v#;+oQGOQ@RD#?)H+g}zVsSfJWV4|2 zsJeP5?KU?{l!kqac=A7)eb<$ii81rO`?STr=|Q4fmsf`mtW_S~Yl**);Ey8nZ1{2& z?V8n`I!N%REycTr?`L*LkA>SYQ;5574cXnen8Kh|%$HcCQZVzTi zqT;Uj>9mZebaY84VT{s+m2LJY&2IaYS0*`CkegiQtCcmiB%O8Tnw%#xnkG*tcicH_s@c;?IX~tUWlJ zetcP7peFdu8`pzvS^;R#v|wSCezbQc(I{c;L+R%PJS(W?E!L|?tjw^)4+(@r zN?MxL4mL;rpj|DkohYa9b>Hu6mv}TGwV(Q}(x(U4eo1enS*pY3vR}qaI%3&N1t0rl zydV>J|AW%6oscPm1r_+<>+K-stwQm&%j z)}?)GZ|CstO8gh%Om<%LqnpdsW%OugyKDFcyPs`}&z`-$WfR=3+lC3daVAjBwlb(r zd1l#|RaZZLYFo^+2dmS~PP|QjPdVx}gq{+oM7vGsYl9IwE{TALQ9CsgNhO76^Xc5M zZZ(y11!aq~1TK_08wq6{9>dCcVq)tgkV-nSOg`uo?3$;a1maQJhXbx$lyTbDeb zAq9s9k?lG36AuW+u8t(}9uJ2rZ%9O(i;g`BdBS$(ssPL9Ipn&-o7(hop#K1HId~w6 z8*B60p)<_eXk4l9eSXz4BA)g(a@^3@1e~KHXVsBc(n2~x`4@%&h=es97Zr7 zfhzXQMdP)+HwvqxE-#(X^EUu~He1FH;c-cf&{dz0 z6prR7NTT(bUSdxaJ4{Qpw25|Tod0zBG9Hh+UHVBb7UKzBT@d-EKLp+MYGK{S?ysZU zW*sW3JmsfLkUOcL{FOObq zdUJkx@#?nXy_Mg+9o=1b#bcRrmiF3&-W-DsP)hv!1gYY&1M-o-IYJ}La zY}g@8-3^mwf-n>AAD)HKyv4gcHDTRsCQ(dt=O$TjOIZ=ZUGSQv!3BGoOiczJo!^SY zDQGiSeyR!3;>(x4%ky3wXJwQ`Y1?nPth^M=xal{2g-EJ7k#T0#Hl5CQI1iTdGrSdY zoanNedx{%)Acg?{aBBw^!h~Oq;92ev+4I=>i~(c5R79OwERemAd5OrYbNq(WSxIb7 zyD!h5zdR=pkJszo)2RI}754q^)8!Q%7YpCgS(f=uYi)`4t%!)iSFJF*e8)@iN<1bo z4nlEXwbcAV#+Dy165AcVfn0kLU2b0%^3QTDWy>pXUYDjL`;`Ey)R;&TAMNYblPBD5 z<7)Z_Z%rgw+r~x?_SoT)AtVj!>Pv=iI`+9MXwg#nW5~2eBplRVHrR2#K;+kyCEU<| z>j{W4swgUp+bHxC4F@}!gzzU&LdN625+F|wCR&wQMofEY)A1%*qKBifTqfUix9)=Oi4U0g z>0jwu%9hV;K`7ome?HDqpYBG`KC$jByMM7rVIymsaKO*l0UrSG_t)2dz!Ug|q`=SU z+TX>Ta;NSVX36AEj>#9Qa&}%-b?wLCr}{49@BS3UA7srk-GrOKr}FCZS$hV~{%Mm% z_#zz)J`M))E^=2t#?L;~bv-wli7AEn9PO@cCNKW}?AfLk=h=%7oM^&D@%M(6_m*>Z zMecsf%zKw$I{x(IyS5cWLurUv@DvO34YaY%w)ZLtukA(}a&TZ66X#t;(z^iX-&CaS zDOzDAWNKE}^kj$F)ZZ z-SCE>ka+rVPCSvT4d7p3F1hwb-mt^9JQl+X5oLf_QCF4IiGBb4yw^_C*qYhcE!nf; z9{s|1pO3YDQ9Zq?${%}sYliQ4?|{sc=e9?H;V3mS&J(ts@KjWG=ATw0&w^_HuDtNL z$IEweF@k@JFV>uY+v&JI9cM53Ph0+#SJ9fq{6w-k;J7YyS#rQhHbDo@4}O;zsH?(T z(sqQ%ZE#!m0hSJqR;#-B60RK#3;?>OvyHG7Ef{bcdNz9Cc?L)~DHoy>f4jEoiO=Yp zgT);>TPYxMaE2pG(|iEP={S;es{~gya66CaUKbVdV_WmH2gHI4^95<#*Nyn8h6vuy^ERZCTY;X|7NzSDC+xutgT-->=Fe&%aBqWM03 zIrI*nu1=tP_oQF~Ipt&P{k_hzFOcr{(mZ*+-Gj3o$$igE^8Q}T>(|dGzYN}Y^0~i< zvW4wpcs6(6wR8Vo!`aTWm>bnkA6;z}53_YyTCWGZU5TanofjXFIQXbhUcP$u$PzpF zMlIj@>BEN)FP>dK`}dzdumy1w0Q>W8kKpfB4dad9pq{Z@BG~<3zdm~ax^HVH5@qsM zuGIz;d6J>&Ka&`$!Rr37l7pz~DxEM*Pume{h9wjbVJ1Y<;5b>atUcX01fhI$GKr)B zaYYVp68PpVcdYgx>4WIDY*;3SXs_%DGUqa96LH)-pAeKpPB}h5Y91+A4wK3XoqpWc zaewijz4V0bAePA3P`+(%(~9PKN#c20tiBzzUSdp&dlcSCnsy{y^n$af3gy9$GBO*~ zUZ)sxlqleur+o}y3L-i(PtvHeLqgD1HMOuBI4k@yE@4z%ls~?^dP;B%`2P6rs(krr zxo$t#Nvk!qE-v;GtXM9gNwY#gP{xG(lisr~EZ*Q<>ooJ<63(o7mEh?|Q`Bw^`)?;@ zR22+xm*pBjyR8->7bI@UoBcz#asGikZloR62Ldn_`IWSpNxQx1qAnS-)B?H&2sQr6;Ht;JKyBYYXf~S% z8NEITn$5sRk+Op|dAte&dVP}9JLvtveh{?q9_`4T=(#&ww;W{jm%jQS%N##wW=K9D zT2A5D3t#1~)u7+;l5cwy0E1$C@b5Az8!s}KL}W&e+t;SEy8)2-7Hi)VnrUsme@2Y zcniCx-9+y54zak2Z&~pI>ga-iYsul>bcQgY2TazzcUQgM(;v(A)k`b-u}5%zxz-b9 zxvgSdEu-`kR&$oi>cZkBqdXUszOpXl-*ut$5+u>Oz?9|3t9bcw`SD}4E_?u6szV~L z7a!koZ0u;0iZ>t4`8YT)ydlx;3E&R9?O3{8%F0b84!kucvQex9QoEGMq(_}VQ)#eJT1^XzPI1QlBu z-?lg{b5{y&c;^YvX&HWutSXM9G9{9%A!v*z3s#^7J9}N=Hr?86?qj4#-)I6_yfpWl z`$z^OkX9!rgwzbn4nTRIE`by5I}TxZ5HL*BO}HzP2kD*kx7j>y;$DRBM|6D*D0k?Q zo0FsGM@L6p`imn)GxN(}Vtvj2jV!&tf3UvnK_~ZpXW-5sw{zbC@9(2u;dAkUJM8SP zW3wL)GWn*@*hEoH4TReb8wpga21f^SQ~cDlPNHSlguG5`RhwNV;MS0;3+y@)Cok%RSdeSF zz9Qy5WesIIoe8j7cC-qk)yngTaW8G0@4kIYC~*FtPha+WrL7&}l|eJm`YoY75fN z!;oz?BqTt(zRA~n_*o4hZ+z#9ZRv#Y&iyd=Q{g+XD-yzI)=x(@609?l*z-jUY7!K6t zfhRHbfKi;_-1;ozu3zqj18$-B`@8#+@9$-p{3Dw=G$C*a<4cGva7Ki}D? z{Nv5=zqOOgjk~*NJ^JvXy8Q9e$46INfd~tE>O->glER`sc%29>JZjjexzb zv#89l@^7Z}tgeUO+ReG+?S2$C29FrCcL#m?w=aPvyaYePxbiek5p2>QY=^*xM7Pt1 z6y;z>88!gl2%T!!H%$v%Cu48jAd(6U((?*i8jv}rg>57h6ymZ|@Fx3Pt$28u*cGnw zuXknhN_?LP*JKu6UY?(yPv{=YWkJ-BINumyd1Z(Np)~WkP?3<-^;T+5k6)k#%l16? z4g7W%#*PHv(r`AiluS5RHUtK%bGF}qqC*5OvUX5 z5#b)4X_ldrzSa6T%v@lsGWm$fVqV~9?^By{dNV7#Rg$uf!hHocrFmE3Z-0JIC ziw#^cgtx%R=}`!#SrTDErm!kh9au?K;tr*@mKU;DiSOJJN(qz}Cg4l0A#xB>2O?(> zP6q&PfbJ8=X*m!y=t8#z5LxJh6*_(LiN?z%NfIufLD5z|TnCB6c6%Q%p9X{SWoPzxassJ*GoFBGmu!qG~_A zirPO7*qDn6Q?J_iOJv;H`1tNAog-GS4i7g5lfzBo%I{YV*BP*8Soz}BmPhc}>s!#h zd%N^3ZdBE5CYlN1H%j6grsRxX@5cQyCf?nTPq!8;nR*j^_v4W8GKQ}^!b&9rZiDBR z@OA^&?NzjrKq_MnSs8nvIK4r;;Q}NUjyud*1BX{o41jO|@(0e0(?nH;9ffpy|CWAL z7UTZxv@z&)(i$Zs=a^XlR><%0# zBbc|b7qt4}2V3^=JL@%vWSH0NEaurMvcT~XTw{Z6e?I%tm6_w)B-M!zREG_gH%EXMy`7#a^A`ra#{Xo%%yh|yt%n967HXb zZxQJMxsq@fD>++_)+02Y(Ki9kLG0CFQ%TuO^Etm2L^~s##^jUm^@;NYc+IRjptl&n z>3j=!J<*V_PXO4!S0ofP_XU<6L#FqSnL!7Rux&@w5mrz5k@gADf!~l%goeu55*kH&PmcL0r@(7Tx(Y-!)yr2Aog`~6+S{v7#!|1FIBfo#_Y*Koe4 z5#=^?o3)&qqOp52$v*_%!0*V4FVC-fm$7yF3d2kS=8rFSE@x4@ch&1%ezY2|ZaETv zi=&tCdSxYFE=c zA>K$6JdNXWFd*F6-ii;yK^($nqSHaYot5!Q#|Y&HTC;3|nAZ?^3uew;!!n>m9PA1! zlqPT!5wFv!mCTSRh$>4k>O%j(V)s-OaRu;a&<`P&Mz&q)eoRz03gbx|Ca&<55KOCT zrmARheol9jOgLMY*xNyFH}~NVJ?}B6r95_BUiU$%qo>}$K!@3-)YDi)b`vW12Xy-+ z2%{cJ(HOcA!Lt=>E9iC@LHV|%vUll+#1dU1e72eCb&3MXuxS_}Poz7}7UQ(n?eeyc zv|2`(zrmu7V61|%8w)5Fk0=R`w|2R#wQ_al_xWIRk(9k2{%fr-uz{}ZrCx&YZ@Wa+ z7Tvg9o`8Fn#J=BMrk~!$YiSIY?y<_|W(fMW5o-G-v1j7SX;}fPD>N%$1PSK_VKDqC zZr&mkb?N*jb$I!O-hp@NoHuPSNUjYgc?*!uR&$%b7DcxQP_vN;I9f|6AS~eMN3u*9 ziIlq2y>pB!9gPNef^KZqRQ@Lgtt)55z0 zN5qnSL*Rvq^VOgRY{!5&W4Hl!0qkbe95D=AKW+w1BYER5@_zx{^sHR%SR!*@8&jaU z@&I_he}Ha3RH*Q6OE{ll-}fl@cSX9l9VTq--Z`wD-G{fsy8mJ1HX(wKq&B6IvPAM* z?@{{&5>igVcC4z=esRZ8{yM38M6;~+hr{1(&AF|2Z&u>pi`}Shir=yj-d?MezBALC zv&#;XPo;IUT1m(~I3-fsA2j-J>8;(qEXbQ6@APen{%)*R#^Xi^=B?@q9NW@XW=S(#q%I(bWH2YNP(8qwfoJ2I(P90X#!k0qqr8YRevby2cl^PY#r0fTdI^~Qel zcx4aKQppM39B$#wJv7zN3*=J`y*Eg9#+>twH)6*$Z|)N_J-dMYt;pG_j57*gUcq~v z^jQc$p12&=Wm)M&P5NoO4+!vU^wv>ZHs&1yQ!@-+%{FU0aw*zaJ9Apc3m24txwdHAr}lXd2`p&u52E+?2-|nGZZUS>jeh-aQB3aa zW4^e2{kr|^#qIo(ou6J^(ygzyZkEl?509#fPIBK>gAboy&8f$gcjCKcRw<&%X0>t~ zyC1#Yq`y9@3o9AH2fSN(iIk&c!@3#08;zLAH#h0rNG3$P2jPHldx53O0hoBhzJ1}! z_*G-IYN${*=*-?sD{W~zTTOY%#uj(Cv7i9Irx;=K)=sXb8=;)l5{RGUb0Rr}Z;O7M z%;><#S% zv^v&IMgxs*I4K3C{n#*MP2>^3^m*u)IphXpN9Vc>2!_(k&u!Q|>>)io`&X51LZ2epD!yF9 zzi1KepPcYR(w6`TC8!2_#-A3UE&(S$1^%9~=lz6tFNHfdk1=w@K=D|{i%g9Tf8J>1 zB75T~63}PBL+`VG-84dYvnJpymf)f2Yr?H~@O>P<9Qp8CIR|z(iDw4^QSCBwxYvQs zM-+Cp=r9gXk@dmszJJCJctkB8s&|NMNjPszzwhd)Izj4D^wqYt0M?(2Jl%Iht?8$b4qYH}O9UvDi{ z?$)ArpIs*X-QB_LVq?H}r z>`B5NxDx4mrNe$`Rw$=zJejkEJ>~8N!tbcYX)a}$O1hB>r_5#TIE6iscqpCCA7y3t zJhGy68WHXH#9LU{v$F(#1Xpt>qYmB3ULj`C#fuB~VP{AX=nX-;P0xY{;|WKD6P`b| z<|~NUTr^LJ-hr;tnRhz#;p4}iT45)f3v=P%F6=iQgw1lgooAa_rEL~Pkt2$oLs{Nw zfffc&v~1NEHUtL+04g`!8^8A&+#8D_N)0t$6B3ku=9JvYPC3 zgjgYQ%~rl~YT!E-(s32JQIJup$cC65Lgt=b)bPD7mM4&j3-m*x`|*VE?If>38!Qs2 z3Co>P1;$O^CsfS=qzu~*loG|0#pL25kwr`SDD)5$#xk}S?9G!0Bj~h}I?WXaiohpG zX3`rtzSCkOxfrp1&}Fn4Z;li6K&))D$ev|9pkxPMfCCF-Eejn+6M^`#&k_n_|Gs1R zcP)#EB;p9u7R=wjf%6*FnSs}Ox7-V_VBazbWCgIOaiT3|LADq`@#5VGO>QU z<0yHkck&^nUBfGAHg)W%AyyQu%wU1XlGX+ZHAy%-iqTLn zdfhQFE^?}~!bz<5IE-SYoaVm5APjJDc9xtF=FP*F_6fbq5?g?ti(qee2yY-rw`Aod z(%Il~fGAP~vB*6~2G(Pg(@T?1Xa0sy0id7|)OWnc739jO7(EZ9Tsv;y8=e&7e9LAT7~1Cb3f^CQ%Hb!{E2arszA zkutty`P#hZ1Hk^xXjAUr6az}Fx8QO@-vZbU`AO*vN49bId2@W!bW}?}$qs_xpm_x2 z_vFahiYj@3$H)Etp}yeTh40_ih4UHqeOKqc{!W4WCinGj0M&onl=2S&x7o_yvIzb< zfJS=y?6=>oUa0Ne8^N0||MlW8cT|%{w~QujkxPtX!X}eC%%m|(W~j|Mjr$F$9^R5m z*bvw#W7tX{e20xy7?uXM8|0pqjpJeIi{9Y7W0U&rWzY3bl4%L?|B5M{l4zI zHp?Rx2a}-63;ddB_Z#e!gFs?(I_Ihbq*!(47(;@0TOHnPAp|cvlIso3?jY#|N#9r} znoBvGL_u@LH+>frVJk`%kTh%O5(ORPe5YJ5^8(nW!fb=yCGzZoly}c<>G`Sjm^{t1|16b(g%muXp`E)`6k$~y334o>Rf!O*)aghg?dS;~M zo>+{wjyUmxgM$M!x(kj2t>MZBy~fdvg>o1KWq`;C>IYB67096M3n(`YO_ooW%UqMb zl@6eqPXh$YMYcX>Z9Fi-3O{g7yoHP70h`Ax$uxOz8PG#Q7=pk<2ReG;k8X~GU=sK^ zx?#c6Z%)SaW1dWojv%Q(4bL3My1on5?;l{^@9)F**9UWd3B&Is27afcn;mys(7j19 zssGu^G5J3Z;1W7}czdn##k2P7XD>b>8YdX@`u}Ay>S(tGVs2B!DpNYaORpf({!K#8WsavX#rDl&!?sq8$=0IW>AS zbeA!JyVN0JcsL*OHcpvN7RsA*05oR;<{o_#We-~}=8_!s4SC$P=Pq_HIr}8Rc(Oxp zj8Lcp&4th%))NnbR-Ob~VSZ`BIf%?z)dFxUH&o1#S*mB(OJ1C0zJo+)9I}W}iyEMo zs-9X#ak?}t8{$Z@q(?%UwD0uOl*2)Cz&8*7cxorHTm-*`II|mnz zz}yp<=<*YB-f^I6k-3RZ#ZiQF#kMc@P}1?@yaebxsUqiy@slEeXE0;CA3V;pLgY zVK&UH*x7je@>VO56&j|-`@*mVyK!JJpzp8;T)f@%Km^Fg8^Fg0iGaeQN^KexdhVD* z4~`}dA8P2!G5eSSe_j|(pnZ=6-yef(2hF1($i`U3l#NWfb!@%=tc~O|hQXbGuny-= zeek_D%I^!i4eLJK*@o`hX|I2ZSh5`edoR744>or-?+4Z@Z|U6(-TwnIRogxBr)+kZ z4Yov+jpc-(d$+$E1HrlI%#0=n{dmyl-FO*Y8o`_Xa+i*M+D-XFg4A9ZqEr-Ztuqg6W&1U=MyJM4@poaMaHJMlCU`I4qR#y1O9$ zKEEGGEvmU3CfIf2oZv_+>pi){)6l#&9P(ETXx>L6$^nkc4)O0X&o7$?z9Ywr02qGM z1$=*TM0smA`K==Nmx^${uS%TXRZMnjE8y)~`2UTg%CCj)pAYY*ne2QqMeqTeNiCWD z^5WN5uWngQUO%GqX{;Jsv)ygYWEXlj#+Bt@_f$+Kk2pS%Ltxu!+1NIjn3Wy6Eo`?D zY7$QyVO+)osT7tB!I>?kW+)owkSPZA8A0?4% zJ^JG1`B-O>?vBG**lt9#Mk6C=kHfSV<0xd=DPm8O!2)wW+tSE`9Vs=k9xKi#QB|dM zJO0n}@e17AvqEIfjcpDEBn&3}oV#y^_G7>`iYkX*C-Ge9C-lq|mk)P%q}hS;Jra|N zCkh0L(v;WXi6uf%2$VUx7DpqrwSaTmu3ZN;{h(2&2}KE_l4#*#j6=A`GU8$b`r@=M zeLq)d3n0#262oqVPKxXj%s)X-6H5_Yjucx`aD+0jz1&2$a^ztJu|~Jpm)!zb0whnA zqjbmR6IL_=NYEHDLiV6XLE@7Ogm1xa zjWr!UY(Sbm@QEWkB8Jp5I}7dN>|-&+$8Mx?BeJzn=M2Lvg+q&O1;Gh5o`p zLx65078OD@R#{lnUoot6B`(No6*&aJerT3;N+R4Pz&lGbB(v%?lbAxl_L{JhscZmX zFJrwlr8aa(#*(Ckfi3b!ltxF44>L3(S#gv&Q5%!Rz7d=mevBC~Kansk&NLzPsz8HT zSI1yAS+g{v=z(RMg&i0UwsTsdxiD942B6_|@&MJ|4~${Y4{GxYVL9}X90*;DDrUrp zwI6K0x3Jy9A7B)izz|*S^X>S^15Sxz_+`Qj3EOb+jgv(9u|T%3gZ+AvnH!l#cyrTi z!9Q_KzM!062=R9I<>8Onh`7%piP_BIxA-6c*@Uoqf`7W*Bgo!F#36JepfE>L;RN4E z7>I0T{mvfFA5M4uV#MqB4BngC-c4fn%>vHhe@BSP{|3$EOK~Rm@=R`cH=NzL{QKW; zvIB3$cb_Kd6)x?haie_qA90KcV7pOgzam92Zl`I#WwXoMr7a%qC?V zt^jL5l)sFZ#9kTXrVA18*$g;4<;+2@Ur-U<#v$FBMeYzE2?mX1Bt>_%F<*qroi5Iw zw-=L{Wo6HsereC5*e~OVsOc<`_Jx?>*k0#w1!~}q^NnT(0_cv1 zreSX`y$l>=TO_d5cuK3)rclCT!Mo+Ms3L6=z+s#7tdXLs5JgQ`ZRe#nBgQgy0Ny30 zmvkMGdPTw_Nm8iDjSSP4I1+O~&i0IrB+EQ!oyKjo#52g=la}n4Fk;vKX8@TxkqeX& zlsy8!aZk}z3Uhd|_^lR14_;5vkPx7A>^F&K3sk~XvcX&5&#*}@wiQJ75(oD+ySE`J zWH8-4Aqq|S*J6SV+qE1?AhuvZNBku)is$rM93Zp9OG0!P7lMW_hY;bz46h=mI5(#5 zo9ls4@4$#Ec;b1kjP(z~RUnem2}|DW6z7M;qZ;1{EAAq&>>rEw#87bA(K$lgNrpE9 zCzEfJ=0i}9FBu8q*<^g+`_^Z|UcW^u`AYD<{$5vc?rYtLW)c2o75?x6mE`cxgYE}3 zlf#|gwVBjC@v@q8{nOuGJ-gL&CcO+>>D{{xOIp5XyX^Ar!{WUw;4QRUCYA$KL-fo3 z>8*wMMi`%_W!feLkv9JmTsWf$=uK9TbCZujGv8WUpsW#89X-0qbjhVBD~ zWf-O1-qQu}F;`1pLBByzUi|#LZL2iv$8pR7-EUSzhKB`D8(q4E4dPs))0v~9!Fy~I z&mOLjvof^x4?obs06p;_-`<=ceApRw68aj4m|Q~rCNi$rX+q2&Vu?pbAMDu8rAN77 zRbPxS>}V;t@Jlawe-hjpbqesumSkp1R7+Adm5T0Px=mbbvXNO=8>Yn>3GRPpPaLP#LYd;n6j*ag z@`T5cP8|&^A8KAP%|C9Mjd~ouU{&E04vwJB`3RjCZZ;Ki>9! zKeObaoWSe5xh3B#cpsWrr^Ai2`$5Iz!J5iH!`=ORa`yvz_l?Ws`u#62o^1!fZtv#Y z3@0BAX4s2v)ZqPSumNwO-KPVNGNGFg{(4*Q4hQ{4yWL*IA+gzzx%f)#fU9~bzCw)P z9C;@5nLSMilx?NPDMw4M-=j~BKb&1UI13+*^9 z+ubnMOS;c_I-O6aC6e$4sS9DDPuRX(ocG3)zCDZ2TYaBPEnRw(1OEx!5;_cwC&~@u zGS$$qZEub>NPF&j-U{M4(dr`ckT6K-Y`=Nqt+=Has7rV}blthd8QzvP>J(V4AJQXO z$ns{-N++@CL05C^&D)+OYoJRm65vyW5em`h>U@O_8~)`+F1F9WfyHiucG&0C68YIU zu13oxnp;vpx8f{5rT9Gjt^ohMVvc7hRJw9>gbsC}Xp-4(R^j2c73$&Z;%b zxkyGW1Z)f0s04ajKyS-ByFj)UV3^$=HF87HFdL7)u>j_>$&ObTO;)0cFzMCJY+opT z#+ldL8s;->XFS={5(n5~N*(w?eQeu>&%t_Ko4&Jl4h>Ua#($wbNV{j{;|T!e==2MT;_Y zz}xd&`oOudOw7BSf0ALbXkvZ4k^AAzn>&>IemM7cOu9E>_huFTu_ZS3CNtX1yTG2VT~?p@>V9_+>f;j!@xvVO9~y&L_0 zyFG1$r>Bdz1m9)E3-FN%o0@K~#$$46HCCZX@otZ;*=&+pAu-|*E0n|`Lme-Aece94 zIzL}|WShJ`PDZEUxQrSee)0Zo{t=H?WJgb;b74g(K9d{RLSw?EvUbJ6M(iX%S zt~*3;8h7CmxXtKzkXT%7*#VvrI$PeVu%zgWcPkS}!ceujQ+RHBt2Zu@aI~e_Km6bV zg6EyiC`stk;$CybCXS7912CuJD7lXPUx!Ow(|sP_>+z0ujSnAMVezqP>bf0{ZGG2LzP+*`Kp!#|UEZ(VN0lEZJ*yG8Kkjmp1lTH^oT+hvuzo2Fp~?mqo3cl&4@ zesoGSdzV>vY}9Y?@6>4B1m2UB@e6C%-U(C8$H^Y(~puUIRgk8vTbaCfE`smUT5K>){6y=oDZ1GLW&G{}uJ zoc&j=#kp>wjM#QfDi(%@^TPIuywq@-RI(htwm9~in0o4zPBsx%omlJHQdNT3rm&rb zZn!9;3LgkMPUOAzk>eTi0g1md#e5jcmRx$ETUho~gs{pc&TSD+Tg10zHm7p4cLLyZ z1E293ajSqSI=jiY@Fb0)=7b&`N--UZICUgr{KE+Y^xft@u4Ig!Ae)4v+>ij? z9qhwPN1zGwqA%$r^`%vV_N}*pz)i^k6cQcm8-(5-P~HgKa00@NP1t^t*Yq6?40Jxg zN;$M_R5`#T5}1H)<2hu9ieFbT9GhH0etdB=ayB?#8$n6trAOW8M@Ig}YbZ-Ouf4i0 zCzx<-)db{woZ%RTSJtIc_?AibI`qpC3_HK^(`?lPDgoet&V3)xAlzZYqy#e24o5z=@QlEqH?!n+K z;rZJ*Oxx+A-wzT0%H=uSZ8npZGf=%LvBjw@>`bFHZMR?cdY5tk`8c)Jswjw!hO2n8 zSS-@8*F8Uv2M|9}ouz0R$TFMAXbQ;G<9LRC9foDy55cBoXP#Z+Zx`Lg`OC03)@rU$ zZ_ErA1R8mTkQdUZ(RLlwT+0Y(x6U}V+X8-% ztP!1Pj2Cct6Y`=pM=3E4CftOEs>rK%$j~m=h3RTw^9kU!4)VY%4V_?P7sp!XWu7m2 zBa==gcrb}kgd7FfIEZMeFkFT=ZITEbq~l+U$$7CXYyxLwV6{{M^#?8YmJw%MSGxzg zRjk1fM7BHh&^ps^y#X;9&(|4Nt;Lm|y z0)zbkKRJSBM)J&Df}8;w50_2GM(aR0HzGl5k-C;6v}&2KKeH;sE=JjQtZ#yfAsk)& z+(BK5Q&aFQrx-R5ZBqQAkUIc|=*MKhZ;C-iksjwWoWx4wNs`C0b8^8oSw z{-OJ4qnK01UzrRgw0_!fn6yDTHr zZ3}`dl~WyLw8!xUFWhUPn6Zxv&ae;ahRbjf)!{Fq1{|m&+0f4Z3#T# zUSi3C?TqGg^ z?eIHIL@E(h9H9tdlqM9qHC zu?WrLhI}rzYS&%Dc}o#wOGXKs`oxc79EHuy+-88BNi$cMjp<$cW@BCsV*=N?T;F7Y zH)Zj%u34)eg`I+QNP|!U(@B$eb+E0&iC$xPzb9iOdut~}i<@u#Bj9}}aO!&JUqb1= zw~`~gd#6V3!-oj>pQf4oak+b|uJSz#-tQ&6d*kgk*S5L#je3$o?UubtlSj4ND0dso zyg5TK9+YkPzUi%)_vFKVJb<%g(3pm+FpN&)#!Yr0IxC}9*qE}<+qUdkQfXFAR&-}e zrzz<7V$ogMYML(EfTBgOJ4V4oZ=;2ma%0mmzJHzVT0awu||$Mg;>Y&GG07? zxrk;ndOV65C2S=JvN6RgqQn?7&23%z}EgVy<`8^O65Iv#-Bn{;jdNA!|o zN!YHP*+k)UXVMIoT6A{b5pX7;J>DEHn#XMN+XoM(i;11e#!Yr*2jI$xRAh(EKA)GI z)X9Vx;8>V$FqUV;q|B&L*~OEbf|tG*ZZHlTp{h!*tO5;Fh9~NW+bGvLe@c zsh9jg$@(mz&mtvkNK1qf(POOTBj(65LJlvr=UOdu-=}X^_tg`8qM1jT^_jh2y6fF7BHT3h)A;S`^XJUyNjqj(GiL$*^y27WT%sM zNGyA1uf_{a_a6MUkM}uh8nub*PUn#>m&+(!q{SXCg+?$p+G|`bE9g^u4(@8NWIF~4 zexVujEuK%%emL=U86!!%gK8W?ZVoB2y_M$u`V~z(iR&rjbbsf&zp3>2kgEE!dJ$pVc7 z7j|6vSVD)C1IYXb>@^u5b)RE)NihEWdH1>Xm38m8Y$e~lh5IXg-9O)LS~%PiyAS_) zX!qgo*i0U(tK8DNe=&OZ#@cOMg11eAH~kB{u>^RZ67$BavQaZ{4y8Kf`r&w2e1c`8 z(QkuzPor`$1BhcxIh7dhDZ2!1HI<5YNjKrRlBpdnwXJ4WBTFOHQ(i7gD7SNrASV%^ zyRkxnTGU8qiLKiyQTV8@;ROs8V!esC&#^OK_R=+=d%cdVy**Ay<@Vp&TF&v@mg!d` zP99>JApS_#F8X|-J5XKg+$G5@EwdD=ft787L9Hi zKCyA-jFSl!9foj)+XxsXwZlWo8qcM7A(5RI^Oo7M+4i5xyPxj@|z%F-=RH@zG5PkOfA<;g$SNfw#Bdzk49R@9W;#jt)Hh z=OEm7ZrQ5j5v3_#I7J-QX(@}9 zXgXudNt~uBrwPUa=qMgug^h4E=wr*WF%_E$%iU83ZYU|DcLUU?(`dDdB7$B$*6BpY zF=%WuZKv9rp&33&;?z!NVQecf?{>F0(P>HuI}cl{upeTV5H3Nr96Q38HZGtH&%jGO;u#CcoAXQoG&+SUOCg99S1ciOn4jq#|U+ z4J>fuiB1lD&cL!+BuVTRJ#}7@ms~)ey%ifvGz0iDrw>07jTgoaL&-NGsA$CDhBR#C zjfKQQRr5)K*&OE=+t!7ZO3cyY_58{(M4YcTX2 zC08&vyD|=EZSOmq4zsKoh{Sx*tkbBRO;`LzPB#NuS=8CT88uEsNI~m6Gw0^bHcn7G zyqisjOEJyhRCai3J0XOVjGqiE{}WhlCL(fkpf`PnCLA~rx)CqP(utq-OTW*3Pr9O? zvGu#ok~_xj@3Hm$EAZPWCOZ!#b|2mj?EbUUOnyFmAOZI9>-H+I@8k%w(d5~)+vt54 zyLY!DV0Rx4IM8HZ7UEAEyjdv`C-ETdBd4ly+J|xi1gFb%ie<_MqN8{zUK}RVJGGUS zk-!^--Q^;-W=S-jwBt|_lFta7!nCyQNX@O~eilY$+Ma}Ad(lYJ9{pEdsVG|6{gn8+ zUQ7x`ycxUrX8ncU+w1)(mrv`xi{xT&k1&+Gj0vQcvWm`V&dtBAD2m(T?lcK|-RC`` z{wmaEgo6Rr-RDqGJa09GzR}^rc!JZR=M~6@wLQYzk#(Y7F!oTX#I^~Bb9LfCe+Ka; z&aUIIjgLcSlyGd8u$foWGhw|v*^)LawlUgL3}oJyNPtMPxhLVa#XZH)z3F`#I>>UF z^UfvK9x?Ca$dQ`KOD(6xQ6yZ4;6i?pX(m0D$0h(a*uWx(=ApS#_Q3aRBDq;q3gXGQtb)wM(Sg9rGIV4HH9D)u+gwN7WazeogiNj|4y1g#xY+dQSB1P-zBc5 zF%g^b*kAe+>x+ZQ8)M1!Lsa|v`>ld^XNn?yQJCyVZ6me^@o_WOMuF<=qV4sEoRkDF!OPut^3JZqmXbl9i6 zrJ;`6D{H<~=pI8<${fNoE5_O`_Vzx0GWebDnac=rcZl)>RFKh&O^B-)C8v!sot?H9 zX_l6e<+`3tOdrT?N#&XA&EGusT&_{TJaGhM_t0`_!!@p!mP&~xxp2HdwctdkD%YIn zZFM@jy*w+G3?VUiL=d-~Oa9&sXv-qyMx-`_N(eI}sa+5dPQ)_4rZ3d2z|*P25|OVe zS9wZ=jd;H!{uN_XwDt0Y2bqa^5Z+hkMxerN6`qY{{Xi;kpl=)pxrv#T+!i@1pnIV%YsiFDA8p#u znj(uIA0J7&)wpTOECc5FVlJ<>^!-4rCbeXOXXTr;D+1>d{F+zcjm4yy`E32B@1a^o z(7bZ&E1-rI({$fY;W-&g8sU-kJI<1aa!dXtpnGd4XNS#!K=C`i?!(*htA9Fl*Y57G zpxrwU=-oHNN~~7??Ug|H-~V3o?%SG4Et=G|IVi5|LoX4uhT9}IEc|r9O#3u$4BBZs zj!l5K>8Nb1SnHn7IKTVWI{XyND8O6xJ`gvz+ub%{XFIZEqOWlor(sfsA>nhDF6lRP z{5+n`;zefb)D8*U>2(=K@uGJgT63<6na_(=s9Ksweu-UFb3*I*slfNU_Ql!qvP1{D z8@ekr@3?N{N)K1g&n41Rp6UmPuJY!bMa3?0^x~i)$FscEJek{`H%~gsgE-RZ6rMtf zu&2$UNng7W2TB!7jaD;)Qxv0NEmPUadRDSa&oTwXMmw=3aMlwJEOD!>l_Q@Dwv)MR z(91NlkTgRzhMCUrghK`CM|Gk^f(Q5;lQtuzNr7q}?;E9sP6C1(cFepTdWgmz zWy^^9EaGc(Xlj~BR|epeEic=~?;5_3m@ms+$IXpZ(a`PV+IdnJr8S$IV@Sp>?f z&bB%5Zq3=BFL#@@N^{Wpg516H*&M;Td*N@dHiY}{x0>R&nD_4P=I`K9yA8?vR8}h4 z78o~XiP?Ukm#Wby(^z&ZCD8us4;%tBO$_1!#peRfN*vI89?a zRw^$0M8!FfDox8wkK2x8t+OB^9-fAAn%Z+KKEHxPJZf>tV%l$3gx^I-c#S|n zUX<_5hrCpoU^QnbjCkI$72&Sc*FK%)N}(|L^paS0HxxmgR>p+Rf}sH(^1*348*M$ znDo{C{n}K%&*C~gtaKz``g$UM@76xCXFfF0v92C?8UaLFbEImX#SJ+3y5pdE%#!r6 zS+W6wGtLvj2Aj>z=B-%44Ex@BNFllYmr=Uwg~~dyyEX^b0RE>Zc7M)ha`<~Gg7=B{ZOsJT z3xE4X!29(b?B322tZQ>>>b;A?vr{vl9I(&(6gsP_B2KQOzfr@iRTAkQln8z0>_BN* zfCi3G6RCn<$!d-m1*?XgSoE3@Y&$ElYRqS#y;n^RO?%b?40+V&BTMk#j<~*tMQ1xFkf(fQbDT<^ z(}PID4vnkSdzW-WWOsNHflYl{f5LNR4t z(A!V;jrJktZ+iC+zAVJx6Z*!L%~&pVJLtZw*DvX7GP6hSGG;OR_(%vgZ$#EPwt=DE z0ZTgCoC>gWkzFQD^K~49cOOZJH=jq;p7X6$cz)+`4dt8Y!@Al&;G&7lS?VCuFb~4s z&6+n{F=GL5oT*G|;5OTxV?lEG46TQ4fp^2EuK#6#`=%0}weG`Pj=+C1wflZW{1@f! z>w9{)NG1{iD|+{Ty?F8KU+(bkt+n_~64lmaP}6Q01^d{qj9EdMRac*GE>}@9n+{+L zWYQfY#YEO}2)?IMm{aTB5WH8@89N2-RoF+;w;RqZOP5afh#Pt10cy-6t%>2Q#hB=@ zRi^#49Y@tHe)@FMm?HXGL93plDBX6kpyP%d5jc-H)*mMBkifgTeER7Iy`QEZFZL2h zC!v5h28IPUswK&^+jrf!ZKB>pqp?`Yo9lgh$YsRd8=~CAy_qS`tx=I!7Z<1ii}hGD z11rWCRjaNS8xs{NwHK$0GFIs#S|$RkW|9aw#WOPa ze9m9E=PIxEr9=^~&;wTyJv=?iiNl|tP6IqhIJTvQ+r7?%=g9!$oKw(Dlf!his0jjou^I9Y%S->1b+ibF(t7=TtMi@3)2rt7+ zH`tS)>HAEwW&aT-bEFfZ7OnPam_7S_Gx-d7y`CT1cWR<8o9awh1&muRhON0&P0B8& z&xZ~Fpegq|2(}6tOog&(!vTWt^T;sUqy+Mj<9H)`Gko6+E%$>u8XTYOcwekF_y(SE z?+{48qCdt%FJXkfm&sWDB}W z2Jh3xuA$uxdNYOuZdJXfS1+I95B<}t*0ZTB=a^l1)DN#rqRF)GiZ`+ef~jDXSlPP0 z=yfM)6i0J=X6f-!rlUArjKgF$OU~k>(4Ja$nZ8A@!?+vMM@_?t?{b~x92@UkOZ@+H z_pZHdW7)PSW7ueg7EMZLam9ke$E5QB5f&%PR_Lsz+N>~W0zxMsG z3k?WRQn-Kp&N1g&q?|b2)#vPoyOqSY9;Re>_2AH$V~#PDuvEpx?2flmDdv)NQt+NW zZQj3s^zPF;i{8!0?bD|>C*bR7cL?I-Ujfl~$GKnI@;_1gpR%yL8 zb4lJ#A3OEJxpjeKg~&2{wIP#$bw}n4Yd#snj951-&PAMWQ;)ujfV(PLEJiq>hxwy& z>qK+HNo`Hy3P$q)MKrEYKP*1EF4ySrGNMc!110_QO366V@ak6S_I*A*7%~xse%~LP!znP*|csU4Nje?uJ|3c5487hM_Ocd#ikZQtQ z!e(zV16a@5fQ=7;>jcfjgv(qxK#y4upFYj{{r=mxr;i>1!awza-cRAyPLXImI$f^j z&>fo7<+EitTn~rAVi*mB#PRZTs3+*HJWznmbGm+VzBpfSNXWS(dzz!%i55!dBZb%D zanF|+x(Tk+)oLsF%N@dO&#qNU?=y_0MxkNXYxgf5WAVnrVZ`R92D5rOmc{qoSUlp6 zSFgC=a>b3r^vg>cg6cr|95hNF-3krG!0bE+39q2xC@urbkE%dfy$`-mucD2&z-A7{X&bfghd;Bubj|5Tp zaz38V=Ck$s=tu+;&zep=;o^YrH4G+mSR3ZEEnMJ^mu6WRre)@pIq~UvdRm0Y_sDfp zy?D`N3r|l=ELt8W=oAaqffu-m;_?`eIJWX;K*WUyBA)6bNCWiGBrI$bL#GE3e826> zM4&GwIp8d6KHi_)DySg4|ip zG1;)&l@e`aA-~@p>nR-3Vjx|PT1qh*(gicjBb5q!tn>Ctx`LtyV)1&)-Q`@q1(6$7 z>zpyG0*#*{cF_pHot8Q@)5;1-CHooLf_4>G1q%8X#;~$UX4e#e~aALzoku{x*T(RfCo=DR$ zpd1UHaeFIHDkd3Abd@r;TlNzv%85&}ZMi>z6ak-SlsV!L+1rObOt!x;c*{A(YD6}V zaAMP3%z{oXQWN8J*^>xCaO;?bZ-Q|N^5$BGg86pANrTW#u8Uk}^njcNIega6=LVC1 zHRRss-JP%dEBiNB_hG5>w%jeN{13lQygz&`zI$IZ`QIP@(n;Q}-hHe0Y|m%HF@gy0 zHl=4T&00KN%N{owcQ5eplF0VUqq+1A6Xk|6kiZ+s-GtX|tO>vyJMn8UZ!A~RKLQ(_ z%)G6h_H(3hXr#gt%}z8xGwm;%7cb_JMnVk?3v`McZsP5!r_z-u+gQ5cF2t_KT_>OL8Jr>AgP z568r=>8Chx>hU>RF(IHV#^=QL19(hy*ep&?##^lneHK_nPdqp@fiy;lyZ~Q|w7sjV zbi7q72+<-!TgCh4)vFtG*~!9uJG5*K;5gRCIT<3*m7YB}mGX%m@vlK*V8`{4wFp0O zRahXnr2=kOwdaOmpep+4hSOXV91&`Q6Z^q2G2sdZy`W;aR(6LR9I}cn^)@cSP9fnK zSYnH)z+t`PGM4co)>l{(nZ$Zi8`dmHh~c0Z26;n1X3`6x8Lwp0>wMo5+*e7SA%|f> z6Egl3zjcWFd&oHvxt!^C$Zo}MS;jm@lpE`T6hWnA*I{XFGQL!s^(;xZz4EISir=(v z*ne#6=et%ldFtoaZGnS1rQoNH%aC_+0OTe)aLPNEy~4P@>DS0QN>TU?X!aD~o#*Ja zEXsz9r9;2T>3_B9R13bIY)L;=PW<6rIpDH|Il@LgzOR)OJqfd z;9E(o$(E(>`HcP^uA!OC$1{TMeA(AT8+9{6n}8zx8BH^A?JU7C@=dmFLV`HQOG50- zW4nff@mN{j(%&uiOcKQ=3xGJ$-XuWxVxE@AVG#JA1&*yc=OBunX3D zg$b#fw=E1}FZ3z`XTt7i=tM37sfwBb@5z)^Men@{p<@E>a5 z!3n_+-9V5^`Qeu}>vj^jr>4Y{63Jd5{Tl8+WcUHM9S*Rih*Cu5_q?o@3(HCrsa)Fb?s5Grq|SoPK#%kU}@ z@~rU;BhzE zqfh^4{(O4$c6Sat3Kk{nlcC2AIP_E2CrEQ;8QbwP6h%8|XwZ&wBZ8>_BT(!XIj;6q zL>LS%7gnrL`1F;U7G*wIPWyzot{X&Z7>SNTA0^+_)aF#JYEhZcCxLGSpGxisH&7CD z^i!hoJs%62ym-#v6dE%}FV@m*hTgN17vz~4Ynx-pPtuFa30Fws26mmtq8m)h z`st@%zuor<3hTbro+I0pXFREVz-^TR-8`>6lO$M1^6V&sv&1gL1H3`1kJ2OVs+^hD z9O&M%VF`QS40893H{;hML|)IGF@a5<&hzW(2rUZfi#KobgaEM~C*ER~LLNubNZ?5> zICPhVmuMx@@`_!|gm^OoyacKXr_a`?rb%2KVBawbl(BOI#t|0v^rl5|R17D)p+2sg z=LJ)mJj-;d+zoOA3HuNdNaqDLB|=ntNw5WWu63zHLdiVWs@@X8W{XM1*@6hClHExY zVFFIQvyN^)W3>zLC`d!h-w=WZn*zB8jed%o?ESO$&-?z48+#;Uu&!+$i9^pVHWo)^ zTdR9Fffr#HCsGTCsB}c{1mN*=eN_$!yNS^%?nNj@dRY_$2q!Lqdo+yPAaEo4%C$XV z?w;g*`yxy7yyIB&xRG9$UWJ2@kcZ*DCz~%qtwmUnsKAkL<5^{i7ym^$=! zHj?=4h_+6_IJT?qyhU^U{L<(dq3qaOiA9w8$$lb~4NB>Tpmqe>y^&b07%lPN%7))4 ztmM4~;Wb(qO4d~DYwr5dq<^?u!-;#S=9IhI6NoXduwD-Imh+5WHS`q%0~-SA@|u1V z+&_wzIG$!A&l~%c>^WhyX29ONTpK+c^7z2{7lZCEEGAcbiphNn4!mO_{>R@M-u>|I zIFnnm%D)opHgfmtJ57R*ZIa-F#^h2lfWMUW9Q-j^f@fz9hnt|h5|n$+sLd8Zmc82m zDlvA?rE!=o-Gt%DqMFSKY`1I}Jj?s(eAP6|%;QqZEE}A@8I82#_`Mu}o9e_NU`GD7 zv*0M#WQ{@vq(8LLO;|#~COhhB)EdTZd1$~BOH4Oakb1nk6G-JRMtEp&e|nCU6*%D_ zxH#jZX?bzcN35W?9_e}mB0rRv*Ar*RXM-SE+vy@fJlFebwbc!wZ@`Q3oDAq}x$Iyp zG})>iW9~%jg1s?k1=ohALI-4WUVF;8O`M&Beo8oDw)LC^7c3hBW$Jp*3vPTZuC0_$ z>D)#vnr@WS))4ARq};HCE+Si(m|Iqa8DZ|}qM#p)csKSfLA{ZGyRo@}K8q*S9pDZ0 zt~hJZ_tAhx@AgBbM`eNINj3T;Zry$*=L4FOUM)Ro@k-LVt;JiCS8YidC!c*qa=4vqE`U#>U%Xd(r&1`bU_zEO6pP;kH3jrp^Is2>k}xBUDR2nytWW z+tGSP2In%%PE8SH?pezsJ0Rf`kW~Vs8D*XL5Io-QRsCb{p7!kXg-yL%TWcRYsPaY(h8A=vJsDvm?X0kLDOtu6e)m zNTN;FsVQBMjU0k>(B#>SSYonHkFx%9xoq;~G7lEs>f&O0lstR0On92<>14f5)jDAz zffs$a88`{nz`YsaB{o)!dXh-Estw}fP(HeI1OTs6O~4%(nZ@Je?eUlef?=(o$q)d~ zq@2~B6JfU$Y?)&}%(yO@-kc@hLD zX?}H$qlsUnLv;K&wKG>{FOrd)NI$k|#=G-fH@q~)6n2QCIDwG7?k>9N(7QhI4m^6f zNP0y8BLAdeiC+Q%F7(vU&nt(ZoZdi$n79&RBOE}s=-)?PZ{ zbO9me5?&Y6%hBP;^ zRx^9gr=@JOu&3`*at=dFs7q?8OFvewBxS|^anE+}C@u?D8rz&w6J+9R8I(~u zY)=%eQe7DFgHijsOFY5zn6}KKV1%EPBFe|cSqUazi6v#Vsw(=gQu`&ZQNk7|`;$E1 ze2x_z9Q)dC;~2*vm^RS6K*ULRr+g}egggI2oO^F0r?Z$`eI}FKlbxJaz`6SI>gu}ph z;~BJB^!9{l&p67P^I$Q`6c`69M{fe%lMhC^NJpbQ*WTP&7t=7EX;cIcJ(Z&Va-EFw z1iX99Y@T3lu9C!K7VC{Pv~Bb}O8@%Ik(RG5tcJYK;xJ}wz$^m)77}JccnklXVo7DK z*ew@^-cU-63A+K_qrCqj>ks@=8Y?l2+_8__L7{!3`Rw3HM-TU|b2i8dr~{`XJ5dK%SM=)xdekOB_K_+Fi0dvi*5t8>2@*(b8@-o9=LEl;A;CU#;R6%$ z7Xjv66g2D@sj*wnJeLsN4UbVT$tLl5Iv7l+F^G35<4D;JH>EUK^8|X+w-cWRR+k)e zQupMj3TuR zUtuAY(@@N6y;Kfg+dWENtn6K1x4ZCi-=O8-1l`vXEhrxlg;_{zv2gT%3HE)p*9zZl zh6`KR*jpwwG%Z$(E0_RY{Ykfy}DAsO>S)`HH&j~Bvj7aq$h3y1ZUwMv{Z zGGVorv~I%6fY_#T11weIHf}K1I>_=YbJ6XSYQv5>Ut}@Fp^4io;m;h%S4&19_ttD3 z$81wp9!nZ5Oe<3eUz>d!LhDy!}}+H z0nu0YC539w-MuGw|1Ed-9ro^hz1w6_p|SGyudjjMuV1&Kw{>`b_u!UZGP2z{XPn?| zRTKCGo4m=Gd7tf1De-YOlOS*JNW3O!hi9rS_{_oy_vR>Y?jiAK2Xo7rlPoR8q0-O{9GRxLrv4DjtUk z=Q{C{z&lsmbp~KOcbpVk@+$B!;Z!FJC&`3)kFq2IP38^K@%h+8p)lh$+g<9d0oDbF zbK@$IdYdXyNLc-b9}vX{*i9j1mOXn*KwL60F z-i<@!hW9VmM*$#hYRUNg(FvZN*`Lgq^&JZtxa( zOtjkIAOmd$cOhY&xKhwIQy^;)5(Lq5@o`t2D-~PZe~!KKX{iwqQWT|S_&j@rw4*Ra z1py{{En<6&Hw``ZUK{;oB4>t5EQTd7()6C2I<$!iV`c0HCpO4knpa))^C_J+5QW>5 zqO_GXTK6=bv2bmVz_R>xS;#rFGvCV{(s%m3PYBSAQeD`{5UrXNGwH*%I$>ej(8Q^;ZV( z&kWwTas=t)3t7$?Jw7|zVx6-7G8~F94TR#8LRiY&4NX= zAkw5}b8ohoFTD9YI~`;%`h>Kz1z{*qZ#Eu#YsZ-_QpQFcB*nr!<1gAO6}u1}KAh)R zhRWEzm`STJk1C;!FjB68=6w2qVoq0dF!uB)9ASrt=xfsSOVrDYpfXCe&Qb--dAe$v z7~GRl5_83K0bTf6&KLBIsjX6|m7HE`Z^a-kBv(8qSgGVScCW5G&&k*{Gb}i?gk9b| z=^VeBGZyoYM8F-mSmLK^Q5Enj84l4Q9H3Z}k=$32gI0OPzViHSW2ctfZRW=ZDpFPG zOYCcnwi_-!)BGtcmf^IdAO3_R)`#_wen#{W(_^DO+1spKZaUYXy%Cd0lStyLhA_A& ziR7;6Gw)hXB-2E6XleI_h>cFNo~6~`$df(8ICqZqd^f~4BE2^FFGAxi?=~J8gK@~R z927qGW~vqEKsl&b-~enulfS;5N|Y4sn@DZRF0sk9lM1dE4#0KUG&tc^nde=x@WiU@ z&!td8^mtp8iNYKHU7%y4?Cq^o-f{}EKrYxV5=_x6rGq&}7aB~0*ETeeV+F5!*OpnE zreaY{u3NEt$_{l#ev|e+h2%Xjg384|BYd}7$&V(j`(ewzuR0^g9l(8cZ+s?Kzj-76 z!B`9RZWC!@i1(-u;{EdFZRDQKj9x<2dnTk? z%qDBGcdtF8cCWp;+_~j>CBwHj#};F<9E^zlHVrm+#2`JFhJu-4-`>L0Nt&*t7MS3h zxHn;|w^$H_&**XVf$PM?=7KOm)RA$#A10HpY-PIA3qnu=xB%yXJkOIAXQcG={n&lyGv<3|;FLq6FYL`Vyy zZ^kMo5l)@X=blCH0|}Nw^FUZ4p_{?GLd_0cA@+^sqWn(t79aw5F_cA1A

n}wJRZ+@{+KW{E*6eTD<nfJQhrNq+e@h7u6m2{sHY#PI z=sCx(;L5cfcTT4$go{h|ee<%8j3q(KueomL`Zjn2zT1dchW0{iD%XV_S@w*4A~wRo zKbiC7wyoQ+@4dv=tNUmUyrb^yx465%Y^(h9hyBL07QBCX4Z-{MYZgs@y_9+9 zaCT=5;XBPoS*k}l%5zuinP~-s0OFwW9YvM|ga}L}G*ati9ZBe`I09!}Hv=)e-Nf;D z%*jX&%QWs-uhkZKrqhKEl%{vPId<_!2=@uG8I)zsdcELH8*D5B&ZoKGWN9juC%U;9 zg@cB$bc@5zu&b{Sn7xKRLoC?i&3tF8MB3pOCs`#h!c;H;(oHzFoK+kf5y%ry&ojbH zjgDhz*N%oGTt$_bxM4#M>N>*k(2gBz<%Sv|+hL3lSb5-zu)HlsgXcuMgh-(uu)+bY z9B_}f2o2&`w02>$LHj4P4Fwq zhwW8k_`WvLusGVK+2D~dlvq0J4KMH61aO{O5&%owAvV(7n*! zEz?Pg%tHE`X1Xj;CF~c?xF+H%RzpCxPHUI*Q!3L+>1^w5g)l+L8?q^B0-_`j zmax*-i19X}3AYfl%!AEL_7x&#h2;}s@)ZOW`d&wEYBr3}*9RWqInq)hHLP5vT*7Ml zv{_XM#~MoLY&GrBdjwA(odW2=FpmTfPUt%}#HoYOAC)08H3+ilO+m!)EmabbW`-OE zRUw;%z7s?n-8O843uM3YSUlQ$mkBR$7mzJ@Bx$SCD$Z|h{d{FC`{DAY!lRu8rz!vQp1$88Vu5;S*_qBS;g0Z<0SJ}uSPF;b7z&V68cM+>(Likwo3GBwKVf#VlSv5qKA&GhG)s}gf*fp&R}9ZC{+vIZ!QL0olx@P z%3g1=(MDRLZkI3Fw5PQ+R06JXy5qM;WriVSSzMQN)`XV@I!ftJ>G+}bTgOuNPM&UL)^7QhKU2b>dHKPr0RaO{n!Vu&8@Kwe}%Hi*1y~8kV>6zehCc6YhC^1yL z^BqojWys_aN}Z;WR%Bp0>0#5I5m`KjNMdXk-LE^#AcHb*a|&>?A-pGs6Q*enNNH2~;=}jB_6Bq~Ev~JT&X~U1R@FO#FAY?Sb@@@S2|_#;uc*(`Xp zmU$&meLU_z!sYFFJX>(I$yyN&Pm_!Xbxpc;7|apHjYw1M=**lo7T!6f8zwrvBEU=m z-Vj6x$c)K@XMtF9f$7_m-5w8lC#n9Jm5Poz{nIMlZgo!Ro$7p<>t>}s5}_WydR6y& zP%iwbOHVTG)AMRYIJ-)+EJ=|$n|w_2{<42=R@rOtwLq&h*Iu1M0EfXFo|qZ|RFLS| z4FY-|aKK8p3%><+E4kM=Nj&F-0U7f)wP9xpBC^bV^r=FZj|FdIM79s ztekpS`)&|O9pz4(;JTz=Aqzz?z>m;4fW~6N_-KPq+}1r<*?##RM<+44HHp~#9mg`R^xNP+e=q53!-~&_=YRyM z1lyqI2&`hwMzLD$E$swS#vK5hB2S-{ZCT zDvqB|M2+|D%+luxDHic9@LLlJ`}(H6-k#iT1#P>>Lzm0=GCpokOB3EF;)fb&XPJXw zyJw{(L1z)UyIq`aW+{Ha=SCqZup)0dQcMt-V{yhJQw7<+s27`uYox;Aik{(x_VKw*GFR z;F*L83I)e{C1=ADP$x%5^!B9rjOa2CDEUjsCo@x9X$yD8&I}emSh?q5%1)9xGrip+ zgKCixoAn5twd4`<%KBnvjd+H2a}q28eLW0L%#O^ANH=$bIS4gLM=x@nmIS=Izs&n( zKFHCJ{Nh(Jn^%kAxPJA@DXyn!&7(+qi5EqfB#Fa0fvlg5vMgWHB_E!g zqm_&>7Q5|R4?vu(G^jEcyf4I00`9Dib--}$I4LV2h<@dGIPN5_%s`W9-%w!PgQ`&$W##L4!e$w=TJ{H#SMz z6V5SY&0896%&~dgShdZ`5?0kSJ`_$Yml{f=aP!$>Vu?3THVuClC!vLI;~^1w#h3yw zV_V_LoBJZO*!tzpfGEvEERdTz_-hk8)dDu7wQS3?1zcp33!|E_aKh4w8EP_!Uz?~Z z=}4PS3p8rq-=+DkRM@6ZiMjjg>guy`<=!s*{WEv}Bku06Z^RqD+ZM(D^oL)55$64+ zM{vJ9=RpVFw+!CgpL0b2vNIvxFYy`CCPzn!UDa9hpCcYw@^&SzN^vDyyw_qNbk1)O zt%^G0nKxT_X*Sa7A|;}odg*+AG(uNS8W4=vvo%B#NZz#~t}Z@|fbbIYz!~ce40i`? zji!U44j6liegk?v#qva+q|FPg8zS*E-L95zmRWi<&reU6In)vDU^ZFi;Rq=vgw{>t zptK&WTR9%H+5~G!`Esx5X{f<nDFQNgjarG{7|fW6F%dVL_g*EEAHHhpnL=spDTFs$tMa#uE+>e zAHbchBV8sfdN+_v_&YXe77ol=fQvR!E9^seftlRrrX3x^m>4k`WNB$-S}iSv z-;z!I7-O@dXDr=phvShT%6FAw*sdM1VM8GCCEY}_sc?!2%TNbZrM9Oxk>a4FG$?3-}wkRHlHzhHCeOoZCvYiH(#+DB%PfLK9QUV0LS`OkUc~ zindbcnl0PLWMVdNY;s`hK*zMw2dRhk1anQOL*tCG`9 zFrs9w1T>s|g0cuN6H4BYVIMZnAsuc)OQ%Jd5<&-gKbbjmE=QXI);N$tr=tBuPFdnTC<%1m!x_D9@UP@SFeghWr@hbW2aSn4y8kOiZyT zlS=9oomIAQ^P$e3(9kmmK$GB#L=U~%a^lH?3+N>SmSCPx(sN7!G3dMW;0&RjV*v+y z`D0YRIW?bF_>3?fpWnQ?*`ewZ0(=#Cm}0tgplUNz;VNz6+jZ$R4jrQ42LSsMw8Te> z8zdl}AoD*A-9W<@$W;ueBewQG-YX{@b@w3L?8R^3A&E3mVx(7oBVUTfXM{>Vvl??pj*@y;hcLKE(UgEhd4O# z@B5c|()F7eXW+xGRru=GO3q%@!u`vCz54M^x%;=)=6oJ!VzB$CZ+~wo_v_#P`uYyh z#CBD(zgtvq-iqfKDtrWQrT)tCkDM-z6f=u>B)5l$ZiO`38}F& zA8HSN4kuNf#%? zb0GT=>iDpB^VHkQy3RKBh8#hvbXWz)hp0I_3=k6Qy5$t8tW+F^r5lEb)TZkZ9pu1$ z0th_zty02rx9eJYo0F(QV+E9DO9D?6-q5SIh)9q9;#;p~CTnVRvwaBXFv=MKy z^M1TI4Ms-p&|VZVvTy0`BKs@?>kv5_AK?jdpU zAc%%Rs0*LY5w0IjeWKCY54iRd(YFUs#jT|zCbBLfH%Cx$$_Tr>Az^P=izn*q+&tYm zJ36K8cG%vrwdjiJCOX!4&^-q@7w0?zwhq; z61rQDV5^z1N${sXy#5+?e|Nj|?2Nv80pdLx8N|*Wj2<*E`u+asEaS?v)+X3p5?;}P zH&Eu3temcy4H-wSm zupSdIJFlRd2LM98k%;?l`~DN~JG(h2(A-qs@C4&W*HtcOoUCMOiG1!Vfa>5L6Z}?S z>J^<8>)A*2piLJ1J9;s&zBq9J5d66q?Ru_3w<+6_;kU+nzm!G|MuRHWu7T^XaP4L%%8W!) z2{1}_U>w^~q@<&uj7J8KZ0t6hJK~gy+h7z~*oh%W2sjE!pCT@+5I4uOXMPx?cSWO z^z3WId#|(daTf*K?>{&b-Q?^+A1&*-gb1G5B&yq~CNPyqj35K}8htrO={k`tSjq8T zci_!2u;Ad4SDQ_m1)L;F*&qcfL5>G@cHj(5wDyJz4;*~#c@Snt!K_}u{;Zqj$RoHW zRQi~?2Wr&hT+Nz(Ow#_d({w(McjH<+^RmcSNs@ZHS>@=1?>9}Ju?(_afNK*#XL+82 zl@fcW6GW2k#@NY81-_f<>7%7a#Y4KngYl+BN0A9wSw~xv437ICPC@7 zVP(fN4L`NF@RT-yUN45SeL3VbL7Xpuv9mh%yu^)+rO68V$CwsFQ+zVW#d|E2|sTR!S8 z@6#QN>GW;&u6h6Ices2yt#39Pw%pug@99ye+3sn5dg|=*_mAH9cbm9Z+U~N;uoJ;! zu09KW;}5jfa$BTk=8zMXPbShPZ{oWR_D^*_+J?w6`;JdW$&t&bZd&s!IB6t6W@b0g#=Iqr~vgG~C z-Ozn2#Jhv7Vu+IyU z!(mh}>Oh?j5%r>>pwnFuCw)U(aBc`!v5U#!-^85VkkLD_oAN}q>wrL80mEf5sa<-Y z*2mi4sOmTjeU01M&_aKF&N{?vbX6Ti&c>|(=HgLd9_$80q*Z4`0YcWbfH5wQ>J6hD zq?6sF-|bzR9os|j(pUdqdn+Mz1+?AV^xr+|zkT$sf3tn`Zu{{QU3t5!W1Atxe7nMC z=0x@~xfpW7n>fa%XG-HMS$&T!V~@=~CggV(RxH|#l7XSd>6%g{IR z-|RFD%~14qiXi>0m(%uY+zu{%5pnELv&XCP@uX|$5d^<(v#B_GkQ;S+U5}3uy>0yW zh26QlxR7dwfkee(J+t6~o@;sJg%Q6^-1q+=eBY9~ZB5RP4{sy))n^uyt9yyvUoPhS z-5jbfYT|FT<`~ID8Y{oC(cQ22W|iOV*-T93umJez0ik!scEQmZeKC5R9ho#(;odLz zcH;@6&zO0e&a*YdZxo>sJg=3^EroI`wtTNq6+fGeSubG=AnwX?4YHjc&C~gtQ$pKd zHujafN&UYT!a>CF!L(Jwhs>KNUh@zuLfW(Ss}-Vh$obi1I2So-jjDAZ`9a; zA>w@rIGH$GhVOUy^PV+sC@TJLclu6l6!@m^66t)`5bu8fp27WHvqO$6!}r^#PqR;- zob97eb^mvCWw+auCcCOPX%{wamvG#c5c_5q-bM=ghI#`|r`N4S?Xz!>TYk8pp1zq| zZpuN?dinfPdW>y}a?g%J?G}!W*ectqO17n2`JE0fPctdo&7D1sMf@%tZ*JlFxwN5y zce8O@;;O*Ftrt*S;ljc%2Cab7mNyV+Pi?VUA!yHev62Fg56=H2bX!~Z!-qe1TKA8i zhrV_~$^FYR>E!MoyD$^85&xS@bN0d8j4E;cX9DlP{PfG6yn8tiR(#L7p zY-h6+7L`<^GlwH!wO+5a&hr;9a%?l^BOZ&=gzi4R`(;%W!>{l1S&p5Abm4vg3JP1={s zDR6pQ$6~DWcdPer)7{PXJ@EVOjsvq9zIQjf)8A!)@9f>De*JXk8xV~<(~6{185Ko5 zcu;WcK$G1rE(5w1uNk;V75(J znb?3UNmaBti6%IU?k(Gn35M^B=VFN=g3gM3@m#cS4mxQY(c08OqkZ%A(kd_4Qj&JP z7gc2*#YEisADmK}UCM_KyPBLkyn$D@+H&r(-2L!3+Pl9xs@#*iSvL6@^*MKoCUz$W zCX*Zv!3P{_!hiRcD_frZvL)Q&7!=M8?4E&OGx27B_lz^W?VM7!bnw+24e~H}OR>Uy zG2_@Nnds$tUeY5`M9HN%2^JW&UL^^ZZHR??>EKPSbh=#;!!|vRF9zi(0|XR>4)dZY zi9c(?*M8Py4V?tCWVNj~3M-pQlTQhCN7;6j50=v$1T+Zp`FK3ei<}5GB<*ySBD_Qs z-&FG~&j+V{I$aR@f~1Qb-k|sBZooh^;uKp5KHS0SH7+v3!T!OuT|d_Ff0T%k z^+W$SB-HE0A;Pnfj3TOu%XYzPx62;d{4x`@5Xrd%Ju4>35Hs9qQB!@J?)W z%A_lc7t+i6i6zZ4tc)wsIT)`4DU|OhHC|ij$Kf$v5Mo5c{%s21+LcL`Vwmx_s4bu5 z1TZmu6YM$(eN(fB(t9y3PHae_$lb-1@1{GsqO)iF7kXyJvKQNu_05+{vbZVZ@&5U^<74j+ohG^=gztDaqxj3Y1i-GXOVDGu#)xt@ zle)7b8#{%2W?~T(Ja^{K0>QA}Y(ZbnkqSHKI`~njM&4Ryx=v*b=y_SQ()mbdX{NRW z{6x{cMOrz|q*<&yMaY=t+DnS2A@bbR9=o(P^zgy6Q9{_CZoO3oWGB4MF|W+^_9K8D zbIibvlCUf>>`RDEPjinbY+1yh%{^=v>Kp;z9?T!$>EjG8nsiGao$n3k$~%t?R|0s~cqK_X*!KxnPYOz~ir{_!Sgq&R+% zi0jr`*_3U3?XaZ@A@~pnm5&Blg>9Wv(3#;5jlUCG0PT1H!*iQ+%6UP-hlE7eAfiu z4dDCfE<1hqDchNSOy$RY4 zq;-1)WAckRvcc@LXyKlEH{HD#EFKcszXa7g*?-ttq^M}9w{F8JJf6+EsXT zl62;+iej;tb6m+P%~teP^;|m=`I>s$RIf&jsyVyQA&5>IBGyfkq(sv-eM5h_JU#8x z)ilur=*wsCPt&8cKc(Y)CyvTpmBQ>Dq$}d&_#VQulm)W;Aew0U7D(T`7%vMrHEZ4Vf-~!+?p;{-0$-t~(k%9% z_!yj8C6Yw0G~6I`eM9dKDvi{?<1h$(LT$xa+`2x&F&nL-XyJ?_<&9rCsy_FSPeQkI zOm{@+?DKnqN{r0DDAqDsZK!Cvcl%SFw?u)pu;AhnIxX z5N?i-5kYtfLXN&0zltjd3OZWpk$G6(j8EU4)=zJ???1hL`$+FtXXyD3vu}{^`h=z3 zW1~_qux)mILh1KA$L|Wz__F&5`0np2fE?g^dGpkH^zU1S@25|1PJajMN$iK_`y^3t z5}R3~Z<7xNv$;?Kz|Q5y;UAA&t`x^h$Mc?c zRwagR^X+`=(Vwlx8f48DIftmUmsI|sM+AJ7=_X(H-{v2QH8&a#i*=gzpS=kk`c8Gi zLqa0*#6Oc!qOlX7tcc!2SpkHOih^S`xG$2(dV!8KdNN+TEX#B6bb!I4hqRGEbENi4 z)hQi9uVgXCGa=$b+j(XbZ|guY3-T}v)&$#5lwe{gt(j6Jp(KClnmV1Nl3MbVA2NUyTJMR^^tW=)4KaiXda4GUL` zTPdHu4kE;Q2T^oz5FJ1{_g&==ov23Apc@e8A4B55ybNRF;nO%g_Ag_$5!cUb#=+h6w8ZWl3MmX$}gdDJy#l>M6xdktNL7apSvZL@=>@@{p5 zg-yEFe|PHCZ{MBn2)^me>uleHvB%cnV)}V-N(iNsp(WlXg0_MNF6v77$1pY}K7P!7 zXdD>GcEeWomU6S6(O*Q5>2>2q`^*!ofj^(LO=}&$Z!;AqHl=*;BKfd|tn0)R+2kpt zdiWOCzJ6}6iCyM-XDSrPZu4Pzn90t->E-m2&bHI3Ks<1oskZFavpeO&)T%lEo!&q* zqkQ&SKO#W_X&R5e+ZsnOU@BS-`CO|LYcXw<)k<6=cz* zk;dVd`=ymHv&Uwq5@FuRr<(0;>db6cyqHbW8QRdq5D3#Z(xU+3QhEk#Uq}ywLpKqM z>%7QbHpzNK=*>9HnX9|)>bf8<-1lbnjOaBn@obtW$^&zD=Gc&55M<+$I%zs4C`z?Y z(Ar-P@+NBtA#%bgy?pbmNW3J4oRPlJX_muyLNr^p9&4>~B9ey?bMxuNAlCubGwGy2 z-<*Jyf7A#%K}1!SG;r$Xr5>Mqg$wrwK$#P~iOC{2Tm!%{46Fpb*|aUvyjtPiDc|h^Iy^*_Q|D$Q9SggyH4c7y zTN6wlBN{fooXCzL(Q5b!ca=#@!RunNJN+cmw?voRVrh0Te(j#w z_HWM)cHbuMK)a2ovP$^nZRnP&H<0eKEvV>Ci+#H{tKOGVk%nAD?rM9Wp$kJfFhfnB|sT`vC|v9Io>(tS7W-m?h) zBR&&TS9#kb2<-m(=bwN2hQYh-&iU^5W;f@%b|+raOz5jK6KL|%UW}~-LW%SZLkVZZ zJd;6XDuM|QB_VMidB~`mNj8+`w#f=rC^UstL>7m_@|djkCl;!Uhd?&?wGJC!3n!<`;V~5Lp;*0ZR=&+5C#T9H4~2*^?m&=L;6+fZS%5Kr-7aD<<<}eV zy9^hB-W5&^u3zEt!+Ol`8BR_jj57(ppBx-KIXrwqFXDiXdTmC2sZWg={zA6QPT*fQDM!kie{+(9u}uA=~A2YSP5*CQl(gzzYN4M)Kw;!Rd5r7A(6|aO*@F?AcOG7>e^>4csDi8*AYH z4&~Lo#p%E45d87;t;)YkyB~gycelGafBx`S0`H%G_~s8kh-&idXNq?>s^r4TGw3A` z_NsHl*4>hCq`%H26PCLyd0J_`f)WACB@Es=Nn|CS#qRamH05xz;0#Ta#z4sRl^&7m zIdlyO9E9oP?ORms;1B&h-PSrq>i3*^_QC@L&QR)@&bM0+qt4Xh$PR2m_6LJrF*r@O z(^D+J=cl7>qx0qIo1B<)m|y~mqF+@a)wOoa*1DocCTWgHs*ee03Ce{?G=Vh`Tl-iJ zN}zcY&^NuJBu-D<|6JvScoj5h`ac|(uLpD%@L2-qgg|zAOOhhYAe_zJ0=UwZ<>7LH zqg(S}5t@vOI8a;h8Y-i1B>;Ztv$hj~u7lcR;gVwvouP7WK-uYA)Y#F|qCm%5A0E=T zd)!Lt1>tnna_M{b`=n)xjT_gnw#3U6He&egxH&!H>&_(Jab|z_5 zN9&|bHGyyf*hYdNYu{o*K|ardWIgFJl72|Wyg87 zegCPuyidmsLbGSycs%#&RA&UKfNDbhIl$Z7a^@;@@a**2pv;!1gH-2XGt%fNONwQm zS2PJ)L4?(o&K4dKY)?!fj&r^{$&Qk_Bni?5Tb8Q?se<$@-1x96pZC=F(P9{6SwhU* zF9t#!vOsFZM{3daUz6O-R$Z_+t_GDee)Z#t1h#3&~wJG|$AzO5r>!M49mc(-6@ z?^be^=_#}9x?9ST2TgDi@Z&w@gN|RhhsPnSET2i*yfa@KSnovc-t9sL`?GQ!Ei{w~ zI|f0X*)Ir!-Kr!-@3J?&3~l{RZ+dNr_r;qF8|^Lnw*hY%Viqm!7C;xFoR=*x__#d2 zbp9)qZWc`*8uoohg30Hez^i)--CtyP{}#RbuA2DUJ@Fq})#NYVd}F{Ht?{>*pmg4c8D7+pX@G z2$xoA5TIqAUfa<;F9*xA%;{nX^4I>V5!G4nB5v^jP9k>X8jUpsf!M=TJfXA8lLLC9L%JydDW^w;;W6D1R`t!U|48k0eSWh$9}dr(Pakh~C+-s> z?7DK!Pn?tU8(2&})eb#7Mw&p#itQ!uvK?MVwUMEwO9z7>jydQ_RROe*-EIwkVrn7G z*syKH^kqWmo9^S7L&e2J0<5jtZ5jG{BJv2-n_k?eOtnkwrr=)i_c(;m4WLYv;nakBa!J3ow%n4bw2g=z z42rI39_Zd}&I_dXWV2_#C=<(?7ytRA%P;av9zN`Rc3&o#TzyuS^H1XL{`+$G9ro@I zclf(M{QOro3I0IL`wu_xz|!u;KQPSOgqgJB$>>2>d-fUehF@^DzZMUHyUV8X#M5nx z7mj9g_6%mdOGHzFAA@L%@(uW&&j^fWDEI<+&Y?j#Tdf6I>^#Dl0;*M>*oOk`r!;@t9U4!%D2U?sGXHgofQ8)`wn)8K7J%{cj}aW*EyOudB6=ep7VD8Z2y^tYx4JhQO@DE=fOINfw9Lra7cO33VmOeYJ|aeRHz4mde2*7W%N zXSMBo5!NmFC2Z`zy1KQP^EvCjy61BDT_J*hSMa_g&SYQj7JK*4f8_>-Z@wY${s9w9 zZXNz^uPol01R1vlyc=H4;j)}g^XC3DgKf{8g(ulb+d0wWE!JBw##^OIZBa`}MA(_v z+xDUuxmSrw0j*evZ?c>&oXm|q%?z8GPJL3-eIs^r1NOPUJ>WP)c2juHE2N7MG1p$A znJzbhGbXU~=J2JUBX$~2UyN{E{y#k++Lr{qP^ks#Z!}v>aIzry)0LRNE4n$TT4|(J zyn*@~{>%?zHqD_X9N7(jId4Elc!djCM?6CIU@ap@kI;G%xM26Z(<#S{=x~w8$~vni zLx%ex@`y|;Q>$rw=8kGxEg8KzK9JplM7x6sh|Rzq9=nGjvu&cw%&qB13puWe~@`2ERw z1Ne5F0FufRg7AakIqW6xnwv;+Xa$w)ryoBt_kN1J+nQ6c=+_uXzfZ6+>WGXWZQ!5~ zakI74))8BMdcVouuIu=0E9vaora8fI_t+-A(qDuGbUtruSr;({IyV~(dm__x|NPGS zjW#sIvUEE=zKNoeq_e{->NGI*i<)F);>e&!N zQ}ZB-iLsm5oGP^NKv^#?;b!^IVBc4Fgmqi?-46UdZ>HSe$GQ6FkW79{NBmtrleVw& z7V&0}Ab~eT6M%QuowJ{3(!uwG2csN%_shqfN3e^cdU;2LH#*Q-&BXcyO`^9qpEF*k z^Lf)GDe|}H+nFcJlmy)b-@O%*m33C-s+1l)=q zo$~5Dx^DuNFkUAq;p@lM$Fy1I33uPD&=O3KO_sUh^&Uv*V|1l)pwwcFwt1}n&|iAx z^cKLyqKwYN90(b*w6ZISqC9&xXtHe7y<6w^$}nK_YCLE+oBwPdBrMuI#zbhWv`ki# zW>q6^ii-v$3mdaYhEEp}BRXWc1ztoCBgqKH75WsY#V`=)h6+9u863!5sRM2-uDFbT zh_!YQaDq??xq^2k8jf#v`xnQKE%nL`4|RBW7@`oTI`BEPTUINHKL3%p_V?d^e?b4f zH)G5LJo7LjTqg*B0!{qz_>evWe(8yyJUM`4{P6GzVff(??EB_?iy8FxhWPWx9S(nd zc(PmR-ObJUjl)d)#yL2663E5j0p%lS7rDa!5u8%(ws3;KPv!OBKx~on`f7tBOnNuN zJv=5f#0~>}yF5P;Wu@(YXe;mA|2;vtd;Wo4wuvn=i;Ufi&4!Iho;BBQX*c{dateX! zV$l0mzk_{Ymo|#Lvx1v0AHT=-$`jT@TAzq$C%sbO8cVLRS=*86WlwsGO^YSm-CQp} z5JPv@e%YQ4BtUkrpx%r!F&Mq(!c6D?9=acPox)ws!o!DG?ZEGA2`2ZIdS87#MDQQl z%=uvD?!BUTqjp2?{)v(Mn;-u0%eU+myd6i?#dn_p!5ik?ybyn8HSeRAf**CJ!IpQM zAaCy|ovn#~C&+~5o*cq)bWjpxZ)bCl0MrqOH`q5c7P^%{c)ajf^(O3=&I3gJA(IJp zFKDpAtWa&CB&R9&RpL?7CXm55!=u=x|&T^{-zouICsu$x%0!ibYtIx87&ATcQPRfN_`0{`8|_m7^z$@7f< zyzlR}E%(OR<1h?0Tb&OGSqYZ?OW^vRH{I{yjYz%G1B(C=ZFUvhQVBF=sG3;rK1=G-ZFfB5sA{_dY4n?UXc zbkl{g`&L=}E$rs?oCl*9m{&qH5htLf-7mW^lcUcY80>~6W|bZ%3a(8NS|VT0=8!dJ z+dNB6{{knSfL~+QIG25#x%QJBiBAbp-ZW+K=9y-lt`IDeNvmX%CV8K~AUtkTIxEnB z!6nKkb-pY$a$Qd|FU^)kvnBrBr<=Uh;IvG2)1RK^bkg8W9X9SkGm-ssPpwUL@IuVk z-WvA-nAwr1Ky>M{{$33OG!r*D`vRF><3T=%H~iSV7tivyXWS#~9}%4QL=yMQoZDwK zG4@JH=Zr!TqvBC!z$lat3@=gV-wZ zhd>)E_CLLS`-%QHeETjtXOsAW z!}_*~g*_cR^jKWzIE47X>GWn8JmE>H3uKROPWN-b5jp4z0PpC(vixncZQk}BWM9#x zQf4!rg_RAf)v?X^o=p5ne4BX3Hul>;_CuRZIBEUcBCGU{+Y+9MjhFKGLaEFOr6j!a z*t3;ML|2*Is!+3Mg4pUNR+5)YLw1}OB9s`XNpWqyVhUaW?m@y?9Tx|nDP|A`Ui8e8 zChoJR0U_FZO1fCd3z=iuruu8dUpfERrf#d4F#EpRD|`GxFS)wkQun^v-MYKGAM_v5 zO#XbQzgxf?YB$T>-~8~+FTZ?i+Ty=!(@Y*bz75|a+-eDT{+Ly6T+S@-#@}QQy_tER zp)bc2=)fvyQw8Uy_fbS1CfKBj^CCw=^T;A4C+oAU{&6Qx$Zq3;zh$xF8b z;!Zd)oQO7uSV{69EFm7cDCl*K7xePJham+;lQ5|SBA&ycjp^nAJ6Gsm9hhYuw;r2W z<;uL4uQiLtzh+2FMFjt&mSUip#lN0AvLRny zu=y2v=6ucG{dxDo&tTsF?>9euBgp*=i1+K) z`_OHpsJix?7iKxe(DxH%usm z5VI_Wg%HZJH{<%V8HWpEuYE=Te;|ULXzWTRx)~8lmn&xFW3bsI!wTd7Pu=_VwvA^= z!;B!K)s!ev0!d47C=!&wH8WY0mSgD|OXC3qMcoEE+s|H%WlyZ`-rd`ME_N`0044L? z-&1vdq~vsZrf1)qj*>XGtbcLrVzEx0syL1WhokmG9!z&J>d@tWtKDveabgk6=d%7X zjkevVWw(VY_c%d2K!jbq{(V39BdcdBZB%k_BeR|8Xnr9Ie&wpQ3$x!09XN|#4+B5g zIY3UarSl<4^IX8YlNJDQ;JBc+piO zh7s58&?w5i{rUO+d@~SNJTkl-b&k*dh5md-@3ZZGG)oWm27{4+!g75^Bb2;KGRfbvm zMVcIA_gPt;qs=+QZY)>Qbh3_|Bo|C?Z6gPv-qRhD1RWv5uy=Fth(=1*=m>mU!(!z) z=@trz{7~QBC9yY`@7|qBP!;~Yd?i0Ht5{w`l=qx8iQ|)W3(mfZ1>_6)eitwo@b0#@ zC#}=_RvdUiIv>qfjhk$_?4DkoWZjfdz4lmF;}KO6-Zz62yR5KrSrI%p1v&GcP-g}= z2}ondILD4GD*ij7R?)5xIwYo6#h4_%Rk}%|=O}&N@rvP@S zI(3a3HZ|43Z5Mg6!BMqN91I|hz?;{Qm-H<-yg_XOaMQ0t5aEuE;IIv3b`_~rTqm<1 z)6K|h;WXj0JXDvu3gWfix#o9Udws{kvE>#bi?yKuzuRvt*T0mf9n{mi$(?Uoo6YOZ zd2h@Yfk&-Du4&_169vB6oQEBg(c0N0A0J=uPMJckU}KWC#Pekvz2ZZ8$t+8&-8_!)K*wrDO1@ zuGj=&!4Rl0ePfIv#&&|oXUiEIiM2YpDrcyebZJ9T;kyFz?514Ytk}24e&g0hl--bU z>woPHEEjUh1d}&^{%k|em#_~1+}!=<*X~sQ^our=|M}Er0_^_juRjpI|MC|&1poH8 zW4-%jwODEN?z5MgBS@9xfM^>ea!+L7zZJV zKtBnr=}EMWQCB&|n&s}=xlXp%Y#YX;auq*jYtMGzfxXRW!1A zx-$vb)+l>*)5#Lc*(OtT1Vcv|MEtCr5Tge;PP=#3;C_irsW`X2#e5#5f(AjhJxfo& zyXxix*1WF?-D~n|l}0?*t1eoopj+&6)KC*iu*K*mL$vZX3KIFqU(FbT3d-5G3+ z#T$lhVemc2Y0m}E9i`NBooKppA5G0JvSI*|?aBj`bh|Tf@mx4EU?~#6=WK95w}Ru< zC~0FDsWm#_)Y!M2W8D%P?I7N@9t(nj&LJ(~;M!r&#R^Sm*K1y=L_Ea0sJxe_$Bsc; zjuendsEr7UL$Ic1QumE#@b;Duu3M83qU)EJxIH0!tcyMX>9NWtI@DAOP8=7Se%oue zd$(cjRt`5p-*0OWL*PrP*V=;U=jZKP3Mb9_Kpr!Yd$~BLxK-JEEXSc*O>W(U$0fWC zVKooi^RPZFGy67Mf$zD(_YRvrtg|;*J%f_6=)q`GyV{G!ck~lg6w1*`jv?PS2Us^aUs8Aq=r_NbeSbo_D~HKJ z;WnACZ{B>S4*ty-A$K3SyN|4pzdFt2NbXkF{XdmtLWB2Tv05pl+eDiDt+aQys{HP% zaQLk1&EYDJ{Cb%PdSjt7VOzZU#7T7aTr!Ecm$L@rHWD~OV6UfBknNKgM0{#R*GU@0 z*wUF=)9G$;?L=6a*HCWDGHQhrjjZcyFNs{Iy-uSbUQLHZCtY@v6NBC(%j(G0X=+(W zXSJNQn-{LL@L>MFXbe2z`swoiJ{hEr1&JeC4S?|Qc!!=d9o%PyZ?7Fgipg<}vg~@* zwKH}A&ph1%ntN=G-0jk$lYn*uyn`q~<{&~$g6*)-wn~&HK+x7h0Ry5~5-&gcUf_3D zRI?S{q1Xg@CPxDwUX)9;-Ii3+{I2LaxFN*cm}uBiR57*kZ#m4Y93%#oF_k3w)GJE=c8)oBWe!yKU1Ig8d+@(~f5|UMCjU&B$=}zzpA9SF zHTmx!{`D_v?f%o>0N=;7`*>8T?^5VCJC#Y2;4KH1XV6dJ9Bd8VRbBD4cf%M+#HOcX?kt9Lzu65PVJ@~XS+$4^gQku1g)k#+%zBh+e z(2eNjc1&%VQ|9s!W!YN5pvb!2v`A-=J+>WKJRo#y6T3S={jXs3!gUvmo{dOtSh}&LxuCt; zfq$@9bLT?C;e-)V?)5?}&(};~mEe4+yEB|zhRh~G5(#gJKZ5u!CF|lDdb@{_rEAJ6 zZN3@T?9Sz6VhdBQlo%RH+)CpX;1swPevajMptHJ0sIJHz#^v(m*saxW3A{l1G4+-4 ztzO18`Gdd5xSqdj#(z>bN)5r9Au4jYm6tPy(_HRin_J3*^)|tku8+7xyA#z?80a(r5*eL$LcaMrN@nf z^{`yS^!33n^Zc^O46U+B&D5%y@It;2(gpEr5LzCC+rg zJsuG3`E<1F1m3lvT^zYd+U-XvnD+=fkb&p=O#x^0^hPoAtW2&c)eF~+BbMSIX>j2z zu!X-?R_%BI@5o*2N2OVi+}cxTi7FJ(Nr=XC)jVcftH`odP$bhLNIC-CY-}(tZ#w$Q z$SAqPf?gIDq3IC;*;J~TV1T(5^ae0fFW>6x_9<7OX+dy5a&<8V@M~eV3sD%w@wOgR zuq6Vj7h$_%mz{BOHC{w`N3@5I(!EziJ=%0~efS~W));n$` z7GP$iweNyXYu~WnL=2QY^y^Ku6~pE2!eoN{smn{Bk~XClf_0OvKZH?$wM)++x%w@v zhJx;6;p|OLG(oZ9B5}uD0$N~0p8G&Tsj0gFzyZqD40KF{9@h-o*KTVVdSWwEJ^+(% z(%Uk&MmuY>+3ome4%q#+G@LL31#3UYVzv9npvU-vXk892s}{A!BrnBr!nXcGwGR&+1^0FuzXacJp4U>EElRTQ zqr}%wn4g3Y*DKW>yL5YG zq3?{9IgaVcbhvecjdFRI$Xg3|n_;DLZAaHPS5CQO&Z`aytxCrOzwlCwCW8Wb-B=HT zQZnO?WJEW*LvuFgp035>Ge^01&nboUnd8ocWT!4}tR@mXg3DD%w~X+XV^YmEYcPal zm=*OQdRTc!jyJ^cP;i~^^pNl;u)Gf0e`zyAs)k}p064ALHE$8Bi!bca{XOQ`QaF39 zhrp?3evIBE$7ni6tf1ZO$lbo}guS7l|2VXplV+2y6ZtjfK}HZ6K5(ewbtao&!ilv? zpsZ~i+eB?-fY(T>{oEe|y=^}b?7fAYLNJzppaAgtc1;%|je%6d$72;}Tp~AvXnBV= z(YqAdaXVl>Ry`@txYmBu9&OI8^Zh<-Qf9Wvv$56Q1mYg)AzGkZCUsv7%N!}=JW&n2 zk~WHlDc#X9Z*A*2bYqsf$5Ew0>iq_6oUhgBF8wxnmVaeCcXLJi_qP1&mKDPc* zY~Y_Ob0E?CNGkqPHgP_4cJSQX{pKjkZ`Dh<8qZi0BJ~NCk(29n6hjHWcBYEn z;Nw$gN2B*b;C+PRVWG^^sda6|)*Pm7VEpy<+<`)p2nb>&-jiz)7$}JCXatpjwuh_} z)xjNa9SfO`yohlqUIh2{+V<8?nHVnIn~8>NrP^zF1j~d&&#XWyPIIva@vPP%UmL+8 zE8kBGAA31L>IX$W;BF^LcVPD39W6T3d-crG!Qp$=p#V6&^_lhUS%;7lRou;?0$Ebn zh9phrwoOg#+I4|sujherJB&LqiU^Yfg={-L8-7MtJ=SE`Jf!Q{N+-a2$RuOJcMS)k zajBMosG}L8$?>OrWDCg$Nw0;qj?alCR3N-gyD9%9KyT;Uj*##g0KBdnmnI=r!L!-1 z%ME(DfAhF=^5W1{IW)UJCZUkNK~>TZ2JWic(j-%n!%y;I6|8c!31m7Mvc_R)o_0Zy zmtVA$yt zP$sa9_*b+pL{oT6z`miFAoY7Rb+%~Rb&#eSg9_U*mf;~zAkYK>Cp)5H%!Dd$HCuVH zXO;0BB->o3UwdmP+aTEMYSHG}F)E3pf{8nDRW9)ien$-Zo9RM3O@j*FculmL_(fi% z+{B5!qSz(dB#5^dI{FZ+T~Fl4p-q*3M!=cDV^kwhiD0G;&ZFV$ZS- z#U;ejk;|wlLHk9|4FjYQrq5EU#ta$*}pXx2l!7f}9gTf*S&=D1Aw7Lcvi zFa3JC-{W#0lZ3lY5HE!eGw5U$4-F_}(k>Hag~bEGZTEIvv!R|WZrwW18wSjvmD2;B zS2X2}#3r`u#*od7T73dwv|bBYoV)ixc-J)p%`xzr6UT{y-DJ|#ZFG}E2;tZ5@ztpvPiwU{A-lI5p1UnaHk=vF^?b%!Bg!p=Y4@=VDTpxHap|2?9@O);6gnU6W^$Px7oBK>~p%TCanOVqMNO z`}ZoOXwsl2$CgW%MlQc7vS;GSo6oetm+bn@v9;tE2<;c6nf&?lVJ823z5C!ZQN3HS z8%~o?9hN$-L>o?=qDD7fIr1l<6?z+}^==k>W~8W>o&FU&@q837 zALa7F@*q2}9SX)ElB#M8Blk>@$?;_!__XeU@XqP%GrN?5iEUM`tR)KYX$J+NJ6P#L zPO-&dWh*!wpp;z`T(y{8C3B7|djj4NtdZAE+c($WgMy9}Y+!l@z41~Op<2$-Vg?f5 z>$Q8HR~ObO0J{j?9yf{v_8iyNX9!_8k>iX?<23*=(g?X&Nxz_Aw?OsS_Ch98g{Bi{ z0TrhQG2G_zd=Iio*lX9C`JvVl+#4PhVc-5xw=}t28TNXOVHgVa7M?A~hIV_g2)RMY zIiam8Nhx7~c_W#s2?t2sEbP=_^n)wJ)?p;QBs8I5hDnE^97%*s-!6JJo+PA# z@X(o)n*tq;1aFjeKMk||GX$`MrVCHcse2qzY_st*F**oE^t_=?a!xzJ%AwAfbx!`m zJ$RRLty3P@dJf%3Y2E5Dp^xt8;ecr$fSEXT@?IxdWo7 zAl1MP6H+V}^hG75)1EJI2npe(jt3DD2VMtwOh}R_?OFxTk|k&MVQI zP~*B=Y|MxCWAsi2AoIo)D5%|(XB-Rpbb50x#=H50DU?SFtUO)0 zR0*}&)nc@|a`7=!NoX1z8@*(#c5oZCSPkKI3f8rr)dOV?RVNvne==1U{447IrEiZ} z1c4U?n_->mi7^Y}7v&bchUP+oI%ODntys^LBL`0dG_<7&7Yfi0$0GnRI*AR|n$(ew za<Aw=;(q2Y>fag>?Rw+rXDHyf7A#i;h{BucQ-n-Y_uc5D9*9QT45vb)Solg7D2- z^guLB$VsO>&_a(b zhQed5?P)wPQBbgZB6kHrmm8q9M@|w@moaSM!^y<@`s>dHm{i`t=j^*$q5NVP_b-^c ze_fc#PhbB!e|Kr{u4a|w-GBO&d6!c63pI7?gz}{ZcoWIromJTVj;%RxoJ3gAkV7_S_F5D7!-ttr35aN#T4BJ(LyjYik)dR z2)u|Xg7A(+e7jnC%obeXEh7fwSr8LeBZJDI+lLjK2zC-TDm4+TMpO=U`SDLnhE=bbUd#F@KHF%j^NcYddkhbR%7@UPv&-dsf) zm&_XnfH`vnab)1Z0L8=vcZadu@O{jCI0VGoRK4hux9m#*HrVa(Y#_dIqNE=!vn6K@w)mI$K>QSjyCJ~OFxZ`QQVIT zIKY{Hz#;QSG^y1zo-v`TgALQB*^qBQ${2o9dea2`ZbBJvn%&HcYTKvGILz~6ST5@n zCIQ8iW;QOWy?A|&x79SV4zZqUOG77>fYl7s!y&EPZ|MOqr(_z`Cz1Q}oY~ z`pvVQ_%F-c{b`uVn}04x@Tbq@2p+Ke-+%bwcmIm??!Q%f_rE-wRwmV2&I@YY3gLs7 zReerLytO3$jNWbr4W1?G_RPe<62K!JTwb$j7(Hkwj{d!l{CGM&!Kjkld#biU=qFQM zxLi*iZ*<*ScJKQ|Y&pSTkW%ADTY`Xh5F7N~d4z6!}F~oXJt?f>zria|2_lx|p?&taCWCA3136eFcBh9+{ z#0{WA?WpOVj-oeHW-Ip}QCu;*y?fkldVHUc0hbB>@oEugE-b*=ryi~go+Q{DjVe+j z2Y{fAH#{oTsiPR_ghNgpZB`eKS>@)$UO;Hmz$$q!N`>U}of&j*Ujw*lt%hmkI1z=C z$?+;CALLT_?`4y`TIl}dLHO&CsaOF2BG)dSOh=Q$W>v*JoMa{)7Sz8v;kAtM20Y(1 zX#Fr-k#E%k_?BF{+0>aN5&j{sY$aVYdd$I{shJ3fU;3(`^O8|I(G0>&?^agKgL#(` zSaS0$%Z*vQVI9J{)f#9Pa^4)V)}JL#z4>Ce_h%e}hqH~pyP@;*IFrx$yMH?5nf&yh z|E<{lmofp?H0S)DLU*fNuB=kLU!0YTI`U50d#2H^XGHH*SL1=)!og9i9w~aCMTT_4 zar9%*KZ0$TCsh)-{kKNR~^1?^ZBqDV9bnLFnxO!LY1Z zSdogaVs=ErwYT!jDx_<6+#OAH)s!jp%(!c_J?W`O5P^ZzQ|5~~hosb*aR z!c){fXmUyT0K%1hQf0Z#3KhgKW_SF8=pA^7>0SYgSvM9EmsgEedQ-pz=lp^Qp39;H zEZ>A~t&%|8Qe+9yVNCTyXt6^kEqH!wJlDP6Eys)F@D|AK)${1s?+r6IpR_5^DJTV@ z!gU+jq{;Fec@l0d=Ja$6|DND1!PMx~U9&@bviOQ*^d=ej3 zX)6U{P=t`@jiza^A0BpY+%3~Y4cEfGiQS6c5W%UNz+>VO%%g>MO&dp~W67vmkXd8r zl2$;$y%>W_*JDmKVoXd|e9wvefl*c3ZOe<`^;=jAA+CbkT=8@c0j@JvndyFH$M2*8 zG;ehC0COpMtJqE2J|jza*$E%5jBZXtAd>-M|3z zjSyQh^5GB$?JRoc7?dX;b1iZRK$e@$gtpi0TC*wlY@)|ZE=88hJuwChTstpNpVNfg zJyz_d00JItBhhMXf(CVu#x@DF?ik=tnPeR9H=EbV`=@xb@3lh{N+>S_834V|9G`3+ zs_fgIJpOIF*X}9)LT)!qzZSMFtBs0GD&Td_HeD`vDngIxAUBaJJP*(*XL-;84==lt zY$JHvy2fLwh=&KyHW9qzPnyPD$ZehB6^Sl3?_ZQQyq z&JiWvjjS*UCniiqje>w?b!;CMEijx4x5&!YGZ;>C?Wr^^nCdSy$*|giSwVev9Bz`a z%fT0Jo>gl3(3gkzIk`l9_zjD^`_{>Ws$6pR&SX*@b)TK6#rr4(R;YIpfqkDHl3-bz zqYy5L9bXHmJA?RSCp23w@pLNWo6VI|VcbZkqQgW$avHeKRB*KJ#>p}X>h*yiW61`X z9YyilrTo1LO0io@ef14C7#G(X-s;gS7rBl}1*Gl`*j$s3uPKC6*>)TQ->jl>G?}(1 zWH*ReXt212JA~`;@)vlst(!EU--w=q{iU<*2y}ya3l_s}0*&08DO=|Y^_YtID1eY<9|R9Ng2hQ0H1h7Pt#;cH_ZgrZ!CcQ`-SJ$#Hmdu*E9K*4xz-?t%9%QJa0s&CaZ8HY`o@iE#=l+vVm@DOXc>XU1Sl(E4{wO{8I z0X&-+(5C(}d}x?rhsh=66TL-FclSg9Jf9rWtdxHHuqu}HT|WEPQsn-+vIc%8z~qw{ zsxLIld?r7AO1#zHtHsFq%@oywZ#Lp zDRQ42qxZXLo5<}VC??k@W<$q0G0CuNrozH-vWu`Nk2T8cofB_U;5aBZTjYgsk46|_ z3TYD(8}FiR8sNt`igaZrjw5$1tQnm*9{K`+|T!+LND@*JjFp^F*=vu7JT1kq=<~Cg$Ka)8NBWL>2Ny> z{FE^&o+%hc->{0<@R4BI6G4CM!cmL2%S{|Kt_gM@n^Hpl;jB{#K1wU)yu3&QcIaR$ zC&ZR}9nL=iDK5+~k~{FU-9Xg`V;K=B>-aMc7(r2ii8W2E!U7D=`>UAkTP$VX%3nQ9 z_mmWa%nEqc^AE@9trCnj!VAy~1D^@smY;XumPc+1YQu(7Gug57dWMsUo*GPY^jG?j zdna`r4mOc}($tVbOf_A*EX;vRu&IHu*5-Qw+ceMT~A`onTnXV__$a67D;j)&!dlLX$hu?a)>bu0c@E2q;$ zQ?b+xPE8slz7%f+^Qm`Vn1#zKXxl7F5?K|KsfExdD7X!?35AdBrkp<_t_0dg$<~L8 z!2BG*`ttH}2*lQ69@q`phIv!6bv-(8-KPvHY&0xT?l(uPH^*H2&(HjVUrzq(FGwbD z{y`koFW9?(`ZT`Vtmgbx6%(YuB1-UYe>##($h)64p22Q%c2*`*z0*PEbKZS&k|0O0 z5>1qQCudO*zd7_Ay7Yxg;jqKSAufG+6{-ex3GFn7|xg{ zK6hu)41&o_<6S+k)?2uBZ4nMlQ4IwL-=Il94P8e#ORL6#OTywiaz?tCMs7=GST3nRYm(eK# z_vGJxZa|#uS}qe_dnpXhgr77CoeJvkH15y;_{}$e+-$6;_aEPX_0{{2AD?0iQj9&{ zZ=XK0Ip;LpTWat|V=}rfA935SK0eMjZMBtP(bC#{&^vs5w9apd#o>9}e|ma)jQ1Ps zvA^GZ=s)$htm&zOu}ok}jU!AP3cPPMzDiiQuh?BofOqu%LGJ;MRaWkcX4%Md(WwHy z=?^sJ!2GQQa90f}B?p zv(KJ|ctbbA-0~0xyS|=YueqSZB}*tKirrJ%Oa#54eo9lJGib6n|H9V zATjqwc3?Tc<1|ZCdGOGqD9(cbW{2CJ8~{LoQJsk;{UGr5aXb{)c!AJp*!$$rp>34_ zZ=g52gSA`%@v)9a%xB6JoPp@2R2K|)H;K)?x#P|~bmmkG@pNNDvf=%Ef~t|?pQk=+ zkoC~C9FYI2a^hcBL)u2WaB z>v@xfX?}jBdna`*R6rlGO3ieQc*AVc84H#}F!6fro*h!Hf!waHZ_~%n4E*Lmb$b2b zpZGL3^zfN*zkPqGK11D( ztyYxqeD_p-qHpa(?%@m5Z*R6AtLsPS6u5hv*87kB{>P8o*Sph?^Z4|m;P>7#v(EbX z2*i;uBX51VCYiveL}sugjSe-x5mX+KeA+B7tDs!~g2sSKMOV47Lw@ZeJc%o`h` zXhy4{IZosJy$@CuZ21C<*$7uiuXx2ZEbM0;oS1|o@`o0HU7xQvr&Oi3wb zPgsN5$V!`uAiDgLJ3ZXoJb=RITn*Aa9j*mI^@fJhPyrkgkENTGzhngblEC}tK~!&! z*D2rpGi8;}<4h{><~8hzSL|lz*(bca%u8x+Qon7ELFBbEviODoQ;spD;Z4>^L-eHuIU zdJnS6$U*TLb}QWoP7}a)nIna@ofQHDqX@x$4lN=UZ(uoLySL_y(x!T>(R|KgF&j26 zI@(W`E|+)rr-HU^E7CC8V78zl4x6`A2!p5prPUIW4j|tKf}F1LkaJmQi<~EbtT}ql7JHf}jDaaJ-u5 z)G9XXwY@r=ANFyAprX2~&19~e;tPb1A!%@hCIn>n+U?p{-a4$BgpLBz4q}doZw@Tc z(qP-Vm1AGt#YgBJV5kWp8G|apks6IHVdyt*hBo;_4oq{*SJ_25$B z*mZ)ldh&09lVQ`(ISmsKpOBI_m8{pT^FRFIk3XJoHoKO!>3`MVzZN3yqQSnme*_sn zC5E5Q_wIn;9W*U=5(`boCt8~}ZQXJV*`t46s5-CTZrUi}2?f3%Uw^-Se>xKQwpw33 zzJ9&iv=7F?ny&Q#&3%(RZW0S??wAJ~0pJD>JeQ5PZ{M1Dzl+lB0aD&PB%n04>$r2# zsVdXB9Di|K&ZFIG0RBP~1Unji@~j$J$D&PWQ3P=6-Z$)M;MQfKtB`pmg<#>GN{4(R ze<&S;H`u$8uX`iUl&F(8`!pclaL1C1@;RWo7|OZRv+Syy#?A3`RA;IWWtic_`V_K{ zs?FYfIiktWmMZ^=Fq6-@yFZCDIS}uk82_rY``=7meHX`ce&PY>>jXZpGNFV!sf_D=4?>)OrQQfj|*ay=_e|)e4x1N{9JCJkaXfxwN&&+f>&@t|~ z?tC#veu)!00BUaC&mC8_9Cu+^ZHyfkj=-nGwlr+IlMQ>!;cM0vouQ53FW+}HT1r<} z1d!FrF0hH`hG>-GIP}53c-3BeK8ydYGV%$mFHfEVDrZ>nvdANDV=rs2IVj`y% z`yc=C&FJ+8n)K`V-7j&?xtQ)_<< zdt~jly=lqES0DDg{%LfM5UU#Cd$T!z`sxGNx4?KJ2Z&H}u8cFiR#W(Hj&XPz-;RZV z*Jyc^mmw&skUeBG!U4d2Uz1tiUYI5wV@avnj!h&u_b(6mCd#^-{;(?XDYON1SeD4^ zZl|85beM_QY+m}tx7R?*32AYoN+99tJ5=e(yJxo*@$ zRLO>oY{+f-Y$E?3!$u{`WSQ}mHw;-vuFA0N3!-<$dh_RJy7!lOdGoo(oP%WYkKEm# zvv*gc$|KtS(|@9NL9zQk{tfID=TTCg2be43#4wdWw5-@2F`95e-LQ*X0z3* zXxzN*V2={YGf1@?N6Gg7%5^QvluQNj&RZ?7?oPk!BZ&`X?M1ifpppcRRjMRdzTfSl zbb0^OUjn$6r}tNVqv1j@nfV2bCtIvo1}ho^(bzC!pq25N%*p_72PJA)yMcMdTFepN z>Ofit3y1Rr;*RMyo;$aWW&%P+K|~2Bo~$@S=a`mADq@@95E%OoIZ%XaEItAqT{5=)@6dXsvT602Int+Ty0ki~Q-{*qfujSJEn7n?y znNvk?3Ng3hJ%)`5B=HX$TSE@(Ay~Pv?)_#iZ2Nt(54DHQV*mUHd90oA@Ao@&VJiDR zKR(&{CAQnRLZ!&1PL*_;C34EpeNd#zb>PC>{*) zIfZm0F=@DfY}0s8O#WYKI=m<|U@wM8tq>-b_BgOsjVevX+BVVOgL9aSD>gvVe4=?K zWu?3>;=tscUtV5LxcAO2%8Y%OxiIcVF>KH_2($MDlv~L5L<6dB*fmd1-(acQ4X2;* zqv#NyTLic}_5rY3ue*eyBCTtph z2Hr}$xuS!`oWYCq1zNWUCP(mDoC&Qai3z9DfU2{yJO`I8Hw*>6@du&_HYTUEogjni zM8)otZ4$@VR8g!cZsFeq$a;;lD7nc~f$qY9w>(fQ@A|!!(3K)h(`XfMmsyst1UR}~ z2L&TSozYvfidS;eySwGXau84Bq_s@bm0uK{;oDA@eVEPSz_9`})Cl!%oxaMt@*Q7f z{Tn$8WwCtg>a@EIdU8~lt-Rps>gwh#jRM(HfV{)h!Z=Qs{rmf6U(Jy&xll|nm6WTP z*oveTaOj>Umec{@p*#Tn870)3;1H&{GDd{e3w8izTvB9u2Wz^xL)WsvIBd|mURl!{ zg@?`@bx`B80>|UxIeNQx2b(wb0>_V8M_vqqPPnJpZny0sbbUM2y~{C5B^gjs@osg) z;G=cTz(1b*)&!!cRj{ckghI+Gs{p6x=imI{n{WOommkl!>FCEl{em-Ep;Sxh z7l+nL?L0eN%1iXp5NRro@u$*NY_X&+GCRT-wL5+)H75Lq_u|Bbvd|}Dmr9<$~ zpHaL2KI{I~dN;57YbAI82St__^ zCnsm?vs44A;17IveVwFg_r|hi?3~2Nf#p`t3C-P*xrK;d2MLu8L2$HF3T)rp1cJ5k zHctk=pRygC;GHsFz6%?5nr@@j>aLr2m+2}_iq1vWe^ta0a6DbDRxQE#mfTvH^ll~K zz4~@nT-|r&d#8BSf3;o7%Srm*b+@tH=KhMhV&m%m)y+_tcbr^(chya6JuB)2-+Dmr zS48jPqUiSfS!cFGTzJy$cklbDvzumDr}qNhm>c$70d7PILjE?`J)c7YXIt90-nXk+ zkOtp=%Z(fbZ#c>giVJ+tL#K_&WY2LOQiA6} zchIcc?om-$oepV~RI;O!*(Yq9}p-~JG z6FaQ+m=5a?A+i@a3e~v3qr4o+Bd%Fx=d-c9!EkbH$)L0>)N_Dp3#aC4n5#TLKvIZh zc>d!b%;m@Z9%IZOH$5Km<-zFsGg^pcqu@s{-`WwTE!(47@(B2bYlPDG>D;QdH>BtE z6t-Wt-Y++=_fKEN5Kn~S%e$>j+eNwY*wnMJ3y5BnF$>y|MsAzL+q!ResB~avhw$#k z5ox{{R!(p(Wa{U9L0dGZnJ7br@VAY!)uBUUeg??hMSktqn+zSjAqTmoV^ zDl1p3C^pORqiLavTb89LH7K!r5Dn72-_71$G+K9qAdP|`xy$>nmaSE=ExH$-;?=8M zFm=#hM)5XHm#yWp+l{8Xcq;(C6`)LCy}~JKc7K0$Hw|JdekI@?-w9IR%g;uqbJ2bK zcDUPlLH}OhTEIK>;*QXG&+GDzjpBp1?f1J6#cBtv66XE1+{R9vY=xY6eFzvfvbzH; zMtT;|Tg@oIZ46ZzYPEvH##kNnXT9_)LqB2 zxq)ee09hLtjTM^w8G75$#%tepum&00jT`LC+a3JGPnvWu7I&=2Y}0|r0Ea+$zXJsp zgvMnyNjX*JG2pPpNE&Y3EPVRg-Ytn8GMv5MmlFOV8g_b=po z49wf~=ztmXmL=;p1YK#k>73WTV#C2JsiZkPcu<;%m(|rwwz3t)WT-h-Y7j*8%|&VD z6A&IYn~*$=l>|4=6nv{28LBNe$%TUx$Md0YI6VwPh0Z%Eqhw|-+R!J|eH}f7VfVs8Ly1n#21#q#8VsPD3GqBw9z&IzCxPQ!R~$tPRUXQ5Xt- z9dA2@lloC4r{Y`up9h5>xOtHdRs%!4I74nw}q<%+R=Ffg>t9o2owu+dp*;_4xb1) zwx`7oP(x<$?@_{LYAs^Mg@5aIJP^YRxMArBwpYO-WQefT!^iCVt(noGjR~R61VHYk z1D0xG%`S;AvYaSdVA)5WS>QEKy<_yAaTYnYhv3^oY);lYO^T(2;H=-z;XeeqZnt~L zPvP?m4`%`(V`2%1Haq8e4!~)tNgNER%#Y1r^A<7VHEw^BV!!_W_4nUH{oZ^(`bJo| z#)Z54oiPHQ1{(`;FSMR;a`|Mn>n>%L{w7qdJlvC}C%gFZqY+i)F*fPPk55k@pW@fM z)6@9z^y&0t-#Wk5<4WxoJ#1w>VY$BvX$hg>OjSY7%PoyP<`lx$X{=8x^hC9iGH096 z-7tw)m4Y&?nlOh(F$a1pId2>X7t%1;EK7Zw6ZQg|b~Z$f42%50{VVlc6HFkM_-Gr2 zV>45~AS9NKX`diQgi3H5H}-T&_g<1;xn3BEWY-Y+Vj_Y3+1(^iX%Ittp`ca=jB z;C+@34E2s+_HMP3L3Fm|PGxeJo<;BCNboy4!_*QN-tq)s4Y~Vdy^gX}AbA=Mrn{*C z`AsJOnS}|1FA%zFIr1G51ogE;@D>(-e}8w~`PLfk8vdx$2u6eZ`>tyx-(AJKnKi%Y zXo$BnYW?5Dy36uyC!U^k`~78Vjl7QB>*m${eKbn5rsKv@D-gclx;nkfd~bT<&A#7! zJDhooUOTv2!i47zin=4vJ)ED9I-On7?e^tyMt&fudVO}%x_Y|L1jtY1F|M+$j{p*v zVXx3XJawDIWZpAp(OVFlXERW5lif|eUGZ)U0a)@;CC5yDSWk|oky>O~bvl?zh@sXX zE7~j79v+1jHVu5k8D0T39E3x_cO{Awl^c@_wT?45a0tB`-jrNr6q7jHDH}3j`xc5_ zV6(o&@4NwrILWuXGt@mzkaB_eT+QyBjW#TZ(6%P0@h2!T<-O=>xAuuYbJ;Kj*Z9ZHJl4)Si63y8&0zP6%lfJK~l z%WMDxp*M4!QFPTUf{yJ4Eg|xGFmtAZ`-eb&m;`Bus3)@vWUmT*x{;rP`C@Bx=JdSL z>ygmzPS9B)@gs@l@YP=i^6vHYI=){5ys@YgXt@qG?`;xO%Jw{GAqS(LqvbmuwsX91 zwMUKS?s-*+Njw+4o+IIe2J)~+BRMR49`Lo4yvgD?y>zw4LH^m$m?&@vUlhQmKtiFT z4s`cmT&b~zp~kr<39O6AJ#Oa^e|%;}p@zUVMPzjXH9Ioxns$*vkZzI`=Y#k-rAp9f ztne#HRzL#1z#(KZ#NnnVh@N+IU>pz*Nm(``O<0={Dwn60f_U$mYg{Mtxm#m|soaF^ zwrg(5v=+6B@4r9)@#q5aWTVs8@!op+_)*dLX}76i&)xUkeexCI+xHE8hs{eGMJ%h@ z=8?;CKSTFssKRXVcAh%#@3p{U%)kfBo@{gX2>379+=7$^LjOn&7w0vT;lbK1CJ)+q;w36ff{X^CvMyd^CN0|)s z(xHum%7oiCR6dLt!lp{Iewk%A!niZ8W^#@RcAg_SC4=0aP1I^q>F!KD(PjIt5l_Ax z`u&TGIlnf{uAkR_bGAOca(98lmkSp?mfPws71Xj__13S;708_nu z892Rlnk@(3!m%C4w`tz6<$Epgf_!<0g`Gjx?dH%Xy`VeDJ!=tqf&9oiJvZ;a$^wre zC)O_avA2%$0x!6WBFmFgyWrixAz+@s%hyGxXWeHe)uh$Rauo*`(fC-!a^?G2gh4p1-lBv8}=$2+d zPw>yZ*!ZE}K){3J_d7w8+ zddIe(`T5N-pMbQEnO4%Yp{x73k2M_h1bYqikVERfib)-wQm#zhg^e^ zzs5XS5QgvCI`hP$`yc=C{PM^1wyW{7z0H2K-)*nBM!A_|6;ocT5l`k51K*pTf7$de z^9Or_UHbR$KR!K?eFvzS@jG(p?${i9c2My)!+8kT_c6WH7#6VaW`M7uekJq#PK9=M z)x!bqqGU~%{nb2Ep40HO28BE}o&*@Ic_u*JMuokTM&VD4%cPoU9!V1Pt(4J%Mm;gn zR|RPHzhGs&_oRo`9t$i6ml{UeQ!6hnLGere5cLNCB$hBiF;{s-RKh3Agvx%8o zfyFl-Ci)*!n|J!?|#{W-9*59dz3~+uQ#anHc{5CvI&%vq!pc=tfN*7aVLZ1Oki4= z=NaHyO(#(jB-=ENS&sWd!(sCl7MKQ} zop-w^I`^|z87jprsOyG|Te`^)dq%iIIHsMU}X#jTbv)T;bG?k-;DDP`fY zx)RA2Sw@BtW*roF?4rpF29jpuay-6EoMZI%hgh>2)7A$LKSTgG)>v#VX*TaBcRn-y zD6pH39h*XN$d*cGw6OoZrg^ouOy;haO*{;%4H+yoW|p|#8u#sOU_ANe=In(9JwDofPGJUb7AFx7h1J~u2j*@OP zG62C-0(mhIXcpp~3?ljjqgY7yyBLL%LcWtALbRZ~Cx|VF@GQ+@>$+jGD$Ce~3<8{> zaOimp%SsZ*5=uMp;*;s_WOovu#O#7Mgg%av77gX<&eOe4y3Da9Byex8NmIF2E@+oT z@Q7TIZU@^|3vZKjDTjjuO+C5rdpR-;fGGVeqHoN2BeLQdcX7lJFtn$C6>6rkz$Z062N$zLEn zx3z=8W8XXEbW^gx2tWC$_U5S1v1j3dh7$lhpf+oyWDPG$!mOzBy z?bYh0Kv{>o2azaE)z!IEsqYC`HtSq;2g3yRmy9vA{ouKB(&^BFft$kn-DFlZIc5l! zFK~6&RF-Ko!JDY(%4tA2uBjN$IM+Ij-As+O$-!NnTB1HUyseFo9E}GjIwDWLIe&K9 z_aHUHXwzm&%Y46tr2S!!BZ3^Z_wh%d`QG;SE!DVrTEG*8p0$TS0%N$`080l*A+$Pq zeNqS*PjtxXW8PTzv&k`V^Q8;1xJ)mFdf#Q)U0%p}2d-~kvNn=8flgDGL(4+7tXj=1 zDurfJjMEPU={Bpi%F=!^^s8oiwT~3Eq`bY+WzLH-`kQJvzsMx>rLKNZ!iQD7IGfmX zcVDBsGn7!8fR^E;VXBDf^JcYePlro7<|3Gh`Ws^RAn^;h{qwAKlVf5@ zXK6<6jWag+Il+#O9nLK$S>E3dqV)dsDnKQBlnem8{eG0hb3T5u&HAnAgL#%#KhY$Rq@yE?Q4*4eaEZwghsw23>QrA_-7v>}p*^cvQTf-I;%-+c3jA33wM+Vi$$?a!^A zIpYv6jhyeXMIYe%Xm23jvaaOA)h3+NYO)1<<17d1^-hwOo}T|G>aW#;K=V5; zb<#-V!%r?Ik&xrdi)!QMEscl#JdYC8z)hE$7TuV-GGjF_vWda^<`7~wh;n9FF`}k) zzrCc|FbbkwXHt^!3z)_M-0JpbldlRIaEml=EhA_7Doy23P%QgT-(97i zlgiO&xy74)|GwpXf6`(x8Ax}k)$S$!@)q=?mj?izG6Z_6@Rv1^{jT= zLWX~!H95ZPF;}9cj4Q+E7Va*H z)&x7xkZjL2%a$Iyzl2YFL>z9-3wIAy4o8@FGw5lNC1a*scn3}KquU$TZL^)@+6GzJ zk5C87kD+R?;1LyTY_dTM4MJh-rhyVD>K|9i$AQx`Zax>L!CuWaP4KK2u0hDBSWvqS z@r;7b;G%47mlONCc?#Qf$8&ZHtfy=a5vHk5Mr@?xxKJzC|0}hD?E6RI+?!Dd3n8*k z+Bmeip|y{9oBjTL!-?ca%d%bhpL1^6$oB%XkGLos`9F9A)+v?FGJ-@VnRU z0m&Bv>y*NvS#^T4u%~02M*2?E$l9$#ryQCYA!-X^{>FcWJa9$VG!DlTlpo z8!AQ+m70^dUMrvzd4tv#VZV=Ki4=>Wj|!FCJOm*0Z5d71=HTktzJP)^jA-=n>?Ik!56KihWPV4$gj7K9MX z^5loy4g7TAQkNIfoeQvL>A(k|qhLbYDCQ%+_~FLCvR-zF~MZH@l~In;Te_BPH{$n=Mo3{WDJ3Dd^nc%4Ev z+tq;1^a?gjuL5Z6kU1hSCIZWwRL>2FLs)Nbbm{V&A2+@8&2IO4AMZCffCf_8)iq8jO_VJ>XkVU3k4fyZp7c zW< zqUWNm$HxCvPmsOcE4||5l8hU_Vb$}XDO4z%A8M$SnPxT^@hzPE2C8_bEeVJ9cpX+0NWT*hZ(#Reo!$)w*U{a;hYK_- z2G-Q4alf;TN7mrRccPU5dgeDH$FbHeXVL2RTdn)kQ=!_aUu0KTH%a=`U*7kHfG_)r zWkpMY>DC<@3;cZ9KkX0hytV~;Jf8;w#Y=MQZcV=PTg$9}e-KSU z=)SsNCIvbE{nb^s7^X?O#Bt;Pv|9*=@E6|J+v0q2Ty(oZuP1mN$a#dHrhaIhlGcUblAcDOJT*aJ|{fgi|8L)w9%JXlz6qz&`}?ua8NcI$3r z=*|$u8o0Juc4X;-7M&?!N8$)dj&)OBZP|o0ADT9{ag?T0mH@Q!BUO^sT#Xf(nx-oO zRs1_f%3S(mbzApB?pg}=QhyF$s%FdM%O}Z&nwQWQ7|qf&zB+rXu8dl(Nq=Fd!$~LZ2Bn831|2Fsw)V!O;}Tv$ ztjcdT$?0hvpKdoj6-l^7`SGI$#>Sg4+^47gxh1sxlxA=iHpCnBpy4^&*y1s_f1hr? zz1vxQP60-x}$Y>lSh~sk#=+y}_A33LBb3q>roq`x;WyXAvk--DN z>GwB=?;91;aU{6VULW1Z6oUSnW#5(B{pZif-M?}%=j+cw_a`1f!@CdI{jY~GsuI0l zdpIqvL>qP!?t_K)!2nWqp)2S0U4UV_3EvI0KPMX&pckEb#V2i~%>n{63ywe~T z5-Z(uuGzIqB{3@e`=s9s*)#cHpDJED-vQZ5n@4mn#N&p8E2&Sa?Fp1;-(L zdji!ooMS2&kZlHPJ}^v}o;ue>%`c1NQHI8CdC#oUhy1BVErVS~R1vpB)yzq=867g_ z9Fq)|{tX6d`}tkr*G-+IAa!qiS;yE6Rc31QtK-JZeWjThSNnPV482{Z?lqf&M*w#| z7)NGffp8ojprG8k?9E{|2z}+yN8Dz;OkRPfjsi*DY=mMwij)?VDAQ4>_lI-=(@K** zy)p)+wtsyNYPw!7ZzJGc;eSf;!b4%4%iH9oGL;yR({y0jQa|}96br6$4 zIOA09q^imECwF(3e*W+v_?E-Jw;yiDMgH z23mahu*}gbSTZ8S(!Mn2xx=*Nir>(4|UGeHRiQgpx zeCv~BaB`9Wt5YNkYGZtK7QrVd^jpANcsDS65DhN#Zgd?D1}D?tW;=}`pA@4}oLa$+ zFm4~IsMibU`q~|&u00X>4&7*B4epbZ{(UYu=QvI<^pgI4Uog4Vzgo6Ni_vIgEnDB8 zqzfQ+yW71FET=?oYcxovv7q}x=U~5BH*h3oj(!;jt2Jv(p|Fdt}ylNYPlU2 zS-MSIErI&3fO$4yG(^U@V!YSLtn+igcdr*@*<@z5=jUi57ZTnU6hC*1ZJ?=wt{rjv zaTYYW=_uzE@}c7f_(9$ZXs3RZ;@dsncC2%SDQ`l_|uWmQZB-aqZ)QxNAlJuKe2)q27X<@?je z-R8Vk3$6HZYlX0@#C?9^DZw&*ovOZDv-Xdt?{Ns|e~_!?HOrUA1^e!QeB8f&`s#7_ z^wm?`N0=3i=@g*G+`nWQ?U%>9O zmxBSMlNW=Rt-*_JDhPgdh%@f!fe^}fM`gpUEJ+4vB3_>i`rTxG5^+PGt?>{} zzYp;MwXK% zu@jBv*VAOlzRA>?`_brHDD&0w>V8=-0#uzXy31G~yN%u)dzlHYI&I6_jey_T@_dxu z1uo}`qtSUBpcT9wXRlrn;78tF94C}a`mI*>*bTn-UcE{zD`_Qn|M$DAelEDZB>}(b zzUm6J%lBzVfO^EcWB!Oo7Bt_>(cxTh{oIP#Rp|xjj0^zYj%NpfI{?<$0nFzEzeq{L z{Gxj=zly*lebe&o26da`O4|rNO8HP$X7}e3um0{ zlE)koN3q&`vwwX5G=KeC5VpVH^w?w^?l%^O79Rw>Ei^;`=;wH_`Fs##c@gPA<3bXuM2bo|)B3wVHr;57HM)R>hl< zrSR>vwN1{Fv%wkS1e0YeS~Joc%zN!jRq#G>t~sORB^EM~-^n}I-ufDil?6=G(eAxEdgk^9!1M2yGz~WdcIC$uM>IRB25D{yIY9g3kHw(r&m|YJoiR+9(eP` z!trYht0xF;E%PE+w2=rE#pfe=d*9kcLCro*64h6p0`F;d(gkX z&w|nS-+#ZFudVuaVEORfe;Zq~KtUdcDt z%9{qhnYd~WKzM2V2;1cFcmwK!a6~4KA{VWFF5kP|JC~sujkh5J;&t zVH>=Bv){MdwJJXsFHOEh;5FP^Z3J{9BN0M7R(|#7ocL;{?)m)m(@{3y%N6n z?c0#ChqRXCOR7@;xJpvj1CBPj$?Fu*(;c3i=5c{TPG=Rpc@yrMQabbbAJNqH%=)F^ zIPm+mPB-OZjpU~Qc6is;fr4wI#f+GOW4Z!3gAKVSkAb4e9Y1uK-BgvuT3{^i=CnuV z%9oLeNbfgW8q~Bxvu|#8m>N0KWp6mWR0^LNPl*ui370wn?0PbgA1BGOM{|-}za`@R z=FR^iy89n&=6trU^1!=MoO4uI`OG4CWHhNv$OQEl^(kU zPtx?{U8?mt*C5$xE4e;H{wrg>Pe8EO(b;->J#~oRcMsj{I(oRfiMYBc~|3Uu|beiZ&&Q# z*~_b9d$&g8I@}mJ%XkI8ui|2I@h`uh#q)WXRr9(0{N-^!D?K`VWBlN9Lvwp7O#SL= zABOW;UtZurpuW2HguMvV#_6*WUd!{6i&yd48CEg-zl;BHwdsd5xh{+Z;o%Qi%5`pk zeU%E2I6p7X*6noO&L19LL~;;ZBZdXLKlx?@@V?$$gM70AGo{lz$#s@UKZ#~oCBW_^ zPK1*e^9Ec0%}#Fev)$ipQ1Wh3fI!YDGud14AJDO8{jifmbVrZ9@u^Q$f?RE>5^$8M zpE`u2ySBJ03tI(j`=(l$&;eK`EmuHA>YvUg@u1q(s9}2S%0XRYplvi+GfqEJPL`SK z9(edQW%3Y(4Q4Pz!+o>N^mP*5pR~#a{rJPcMtT@n63yuo#4M8^xi<1>kP2KK4b>i! zOKRbfEnXt5#eW<>#}qR1AMd{T;{AswTFV(Ez&!J$4$ZQnkzO^M-286QvGl*TUDHJO znRJeT=vRU7SKmMX=I-SY`+gb(oj1rEqw^UVFipKyLUYOtv3Q5H0OKk3_LLMzF z8H?@0EG_03^EJ&WFDS3LELh0lba~I{OJPXKX!%djOlCUdgu{D=WR%%k7yODh9GP-% zg_ss~0@glfbjott9Tggs^7enn=<-dcEe{;809^|13?&39>)qJa!(w@Ei> ztMmpNLE)>kpEuJiYcs5%;{q|`L}&vipO=>Mk5c0_1DEv%{(6*qnwfodb#+FLel|~% zT(G_$uXYz%KDfF`=g(fe&il{i>rI&FGYBI0{ao-Nk#~>^Klhp`%6Ojj=MOK=r|}iE z@3X-eOFCEH<_gY}63cxrH}fp-x7dd7^Vng`2~FHd6~Y{dZO1S#jc}HHe|#Oc$R3OH(b#2TbRaO5^R_lZgU@AfG8q4BPyU-l3J?qJyhj{+?)xW(0%K7 zF{^=X_#shA;f9b;Fo&3mm$Ced2wRqCC5_hH_!bb%?mt3r#97gzLipBlO3E^d`&f`C z2=V1mMMB@9B~2zIm%34|hY)oGo~r`^mFWzRh2}c#(S_wl~F#*WoIwFm$|q^{Rk*PHrf9jMH?Ff3_R4 z@4LG=9p@F-(g$%qpCjWW^jW4mC4CLSr zO+VWtv&|pmthoCye>MsS_>sTOXJL6JuOlZwzdwgoa-FQbo2r?PI3mwcezT3iyoG~r zAb3B$^wR6=^64>OuTv*t3*KS{9xXWuo!xBH#7EuaNj7f~nU%zYd@koixK=Mo5~i+& zjD-){m6@bEqb#9ru;_;U!WjToMe8V3!JCS4qc6pLxL#`d_MNkkK5BA29-sy~|twBkp}S;rmjqPL&1c%7~Q>wJIk;a6ij5+C*W@ zfW>y>L(>UDOJCtBl&Py57Zq#n>*#uAXERB{#WD&O8EUJ6Pc{bSqR-RI-t+Ox$H$j< z-!w0;Q_XP=35fuHbFY}6oGa>yo932+-zhZ}%{tVw&Ds=@v#0Ox9-qGd{%JgsGh*Vs z+)O?^ovBiS)5^XMz8rV>I^%1sX@mx*_TYX5uxT3k+t}X&C69k2-Sj z-7R@dfMA3w+3)u-r~teZ9T_B1*7@OmdrbZx=uErTxG-dZn;uO?1v=&;;?ua*$ zWk$J2a{}R0fm3p+uEA&BwxufU`bx9WoYlo2evu9cP49p!_mW><%n{~1w+a6q}qgj?# zo3#+=ekNB5nXvgLd%BXx#kItX!h>@#9t(IsdHC!4EdRrYHXY>YhUq404o~(vN3@{) zmc)a7g5NFqY~;dL(7T@t|1LsQ#iwPMX9C^1MHaDzA?X4{Q&-NQu_h_6h=U{@ltlC( zOk7e^h|NW6*P#w4x!g_%h`>WqJ5fUy{J0cfyZ*D9X;h&VH`s4_=-LqQmRfTOMYYz} z2H*dvlz2P|m7A8e7N7Zk$NKDDQ!0bN3z*OsiO&*u8kyMBDUhSC3t)yLOo`U;#J)CbNTxC2VxkDZ^iUY6{d^Hp-GyOS)i zayflM#{)Xj)x(ujReXTAJZ`Xi#i6zQ5ZuP{L$;?EQ?m%nS#ImA`V4ROdHQ-zTM`O4 zbq+0;tcC{!gKBd;$^9KD+d7k6DkGn&m4qS?aQvAol-IIiX2;^jpcI-9S%Qq|snr@& zLeXrj|3UaZiV*ydxV!&$64mGZ-GA<|```ZYxP0Lw!MpRBoS4*oB7dC>i^)lIqPTqs zq#6q8-u0lFJoI#B#~}Ljv~7#wesBKno7J#T@kCx$&~*~ic(S@#?U`wE-rS65)4kkX zT?~QH`y^g{5bPfBuTUyKfBj;56Tkl5v)_%q)z!rV3gDr9Y^&H4)}0DK3+*1n-ZuS! zxuxJ`JZ4L85(@PO|CW~tobS{0mf#KMod7t!GzVps{{_B*^aAo}DBOFDf+%@Gl8rct zluJ-NkqO66*V*Q3-N)N(LV20oH%hO(JHhw4JksoS=501l-W)_>;IVN*up5Mav)-hX z>uK_q8|3aJStGj@S%EQ6A#c0crX<(vJkN4L@g&~H0Cs_IrUXU>)ofdPN3e9DaU}{T zthNz2*OG?hwu}>M;(fC z+yy^`;>fgbeJ#J!tCg`chDkp2@+_2VC&#@h6GzeJvHgL!Z`g~5s}obnov0jy%jJR- z-%+PIgOTfCK_hYlo@zX8d~6>P#Y=6JfRIz3XijRN%`laa9riG+c>k*$g1^|^{Zsbt&*u{Nq0( zzx$_`;=AP>mM^sO55r(jh}=%`R%LtAE85=0MX%^;EBQ~=w#`r%bL6kFPALVfPxq5% za=H@E9m6;%PsH&}EUzIH{bt{b_i^k^&fC>WFg=FuJ)S??Ry+B~n~0rc>sLcZSCyFSCJVxFXV zA%B9ZN{S*+D%k7B0^wCY##&>)!C3JwZ^LBG2r2m|@Ava$bCr5mX(&&RWLvrC^G7tn8>`wEh#g1iOVP=_N{XGvW4e$KHS| z2Z#}7sy)L6Qa)4+0Ur+%L2`lgBF`fW5RFU50smrx2ELTWHDW`_JvwFZ?bj@Ix^tDqV}w1#tuv4uF3 zu&#Pb(w(p_nF;8;s==`tn3{i|X+#&3ckS${eFo~(54O+uL#-1hRH6(eS|bv7XfVwyFAbgud7AKlxW^gmv3Ps{GWjDuW$=&}k z-u>AWL6_fs=oc6L}h?l|#dCdb}?&n!Ie9-9@i= z=!<_dfjR;NAMV}IvZA|NKpT)fsrCSAKr;wA5ZgYwYu49q2=@(s4n0RJIb>x zZ?bUo;sssc(`lE*xe}s-&G>G9HY>8yOn2wm$5vAz;H7c?9Qr`UP3Ph zKJOEjig|)*Ld*sK@*)pgnm?*!oK{(0tp)DoR;?NT2mFjTvCniq-jeoC{_1Cu&~p?t zjQVMVJlLkmnkLbe>pp%=+etNG{J1diO?sDMJ-%pj`Hjj$O5XCph4z@l?)`RvkG(|7 zw|tPm?LAj%z_jI84!%A=9tsx7&)Bs6Hx4_(54U}otjktt zL?#`}TbCPTy+YmC_{5w@c{gH8)g3N?%;}-Y$~AQhP)IJ!XcT#5oeCtY_%zQ{DB;(u z)@gt`Ry4GcgW_5jSuOc{dB4D5f&u5Xjfjh@~Pha=WoCJ)?qi1n?{r09yL}TW4Ec@uy+^iT@dsxE*mBZ4m+pG zo8if%w;K*8ZPS}v4m;XCoD3)Dy@@WxBZKPZ2II>8X{9qvVcVy0c*{TW9sqv2UyUd8 zBD=pwm8G|eKitG{3*M~ur%4I{{3gz)OJU04!-ITF$19=T0^i#-sm8!p%pl9t6oPl0 zjN=VhHz~Xz_4X_lJT1~a6b6B8c>lIlvWK$+jy;GKg6~M>=Cgw2I0bUp#^si*VsxFw zTPFIY6{mNlyg(TAd|t34VGY52&4llZ9nuQ1IlsI1tQMSL-EO_JtLr~pUtPsHpD%J0 z=dj=`U1OOhPu8I_ZDHW?Ace*a4jzR2808BYW|0D>0}Lwpn^=aLlS+^dvOF;6-5G`{ zWheSu9oC6L9_g}GG;p@5>|3)=xi_O#i}J*+&)?Ttoe#hd--+NlMzlj9U^E|nYUJ`u z@?H!cBZN-%g$T-r@DX~Ci?s?d%Hl?SuA#@w+;h7mH!!|lb%T&wZ09SIbljA zb2>amnn=RERo$9lT@KZE8}q?z`E_EWKwqI2pHvh&$B8a0VQJKzrb55(xojGmbX41X znU^BehEN$=-l9PW4)jFNu)t)GBT_7YFkJgq>Vl}7o2bbq zT4aeISgfK_cD{9B5`VT>E*7)5OLQU6mWT=XZy#NLR_#{W{pBxdJ^T4l<&TJW=Mn^X zANfo^S&Bc_Oh~xpnPSLXs>}A+Cx|4$OC(-jP8!t1cQM{?CMZSgp@mo%;!Qa@jhSjv zA<|o(+>hg%n|NO}&1_cenG7S~Uf^n6_0alBS&}505Ky8n0dlwKzZa$*tv0KfqF9N>BR+72L-+_-t}JX27Ug#60Dn6 z4vp(8f$!@pCR3rLAwilqKWcdf+BQ{s;C7-<0LqgfAEOelz8|QRRANPqxq3Uo7CpcTh=w>07w#BY~saHZQVS49r^!OOFzS;J{lUBktVS9S!X8I7Y5z4 zi@*+SPD2&C-33u*xh(J{f^=hdl3Iv-efwc%^gEz~1sg)({{xfCFF$p6|H9kfjx+gDo(YR{+_dr^6uVXM{_3kw zM3c+T=PiGbM0I&0?7Cp4ple^SVP#Kns%R#clgV&*?;=g!oQ@~$i+4qExGM}pVEv6Y!~d# zp^0NB296iT_T}pYr3snv;xyiFw~$T1z`eNi&`&7<9(w~cfcs?{j+G$;W^;5==9}?k z$H>^-#rdm?hv(;gVPP49s9K@so6Q#6@mJo}Rm*8*PT3?^pI@KbIu)07z`k?(2=Aco zgn5@#qHaRgEu?#&%1fY2(w&BxxSw-vr}T}UC%Vz1oj1Bt0(xvPsp^0LdB)XBv+?=2 zDtWUuQU{lTjU?6179=)iOH>jMg*gF2G^SM$BwGTC^jE!}9oJfpCrL=*gb=XI4oTfd zXy@&oZY<2kyNPrWT?0A?SfeX@nz4 zGb8Go$omUzH8rCkqJdYL;f!1hfOL=4vlnR-7%VFDWfUx3atR@AW^Qu|LQx&**jJ?} z-^7%Xa9h^)eN?5yeM&CywXRLJ4s}7Z zlI}Qg5nhq8e*1~84Zz9U7mG+R9Lt^ThW_tdi2suUw*&7lKjPiLKF;JXKg#d!X!l>f z{quL<9f&uxs1Dfu+fVgwC=d)%NuiEj=?0o8NJzcWA zfovk!I)DB88NyjZZ=1*MhhYV?dykomDEvp>%K#Qc;q?f)8VCrYd7g#vVa~ST z&0Vps9m>o+BxMPFUtf=N_A#U&-Z}Ov^E?9gW;HU3ki#|1 zC=^rH4DT*Ns`Y}$;cYxffXWPib!_PBzcm3>xwu;*qRY@X0Chl$zo{b3Fw4#CfZ#Tysu)4g zp@Cw35`?GrUw8Q1}h75)MURk*R>Plrv*VtfMXr6kjM> zEp@!dK&Is=Qt3oNnpjRXT-TvGHQKFS+Vz7@b#1O;J3)%+kWxx@rr^Xh>yKX}C_Jp) z2oi9eguwy8?W&6kMPx-kdWFV=pJd(wWK@VUlFor-=H`z9(H|-jE{}A^9GbaN&%S8s zpj|hL@U`TaQ>P1#fn&PSmB#6O^CR=@d?sIhR`34JZ~o&Y@t@7_ zR=pd7w^O|TuM0E*cz?pXRq1v%lgrCSE#B=(dsz&J&7~pt&|HG;C0*Z_5P2IHNX5+V zVS8$X8wn@Py*j?*J!h6N;!ThyczUxh?kCOc6jeC_+tuoBIt5>bX!7EjkZ#z#SF8Nq z-wH9FzJ4+4T{Po#8=v2M&184c8yACtptE)r#OUcI%EBiO`VH9Mz<(0w)W5g-V&MA~ z2b=qSq8fL#&WnD^I!S@}q{y>2G5!whhK4Rcp3=*bLLi5T6 zg0%s9B$cM)V*%Xbp@F+>wTCpq-2@S2jLxtCV5LtLbXdZnYYqN~9 zIOsAVdck)Gp*+*^FhTi%-)tH(>B%W)QD!+VitGa98PMGOZ;?#?^bvj^HsZhhS>FBa zPwL&DsXTLGRNuO)_>OpgPBSr+V29l&#qh-PV1;3yn90N{bcRj)X4pHKut29dG!XOF zB0>1_;v#S7Q`Eg<-CZse$1(lU1m>IV3RIcu$%?2A$Q9XvKq zxWM;*BS4)B@h&PlK8pNI?yvG9!~ZGyHpG~%NAVlaB?EAHc`alR4p{3jV6Fj?wz4bPZ$eh1n6@ekhJdW}l?bsw^On1?awb|wc%h@ssE z#b>2Jd4feurk-p{JOCUZiF_cNvjJ%-uJ;8tHz@UbM2aaf8wuIidY6xpZ4ElI3uyN> z3X5SKrWIJ@$3r$A`+^E~3mh zv)V!+fxBT?KoSWgSVWzK!}QxkRae3_m0b`(zR^M`oZFs$DmX6?+a>W3}{mZQdldlKh-WMPO% z!39pU(NeE*-Yz&g?sqbkr9kp4z365J%Dv4^M9f|U^s}%TRLS`Azm$D{`Ps&tqY%OW zDDVChx{vhkKmYkVOe_EO2)q9Z-u=~&eI~kESvZ3?Q@n=-1@B8O9JV;BA*_Qv-L@=x zyU78#nH-3{OA_yDubdm3mBYQ+1yA=Zd*|eGzvo63BJ<{LwYtH&ybIOjUd8hLV zu4qKrj3XFJ;=$Rzm`~?ZjWt1hNKAvYl5PGg=LGa`5M$x$SjdU@^0&v=LiiInceuxF zaL*OTidGXWW9I#g5rt_*s~~siDWDjd^M*a2!9WmvP?jLj*mNJKUOHjz@Ex+ar?a+b zrsprtd+Z~oup-#qFPc`U_aFZ7m_jDOc8;)YirP?bFnSD&G)cY3mvVdDP&vWj5+-t& z-1!8HU~(o;JwBCq2vETC>GAQy_XsTAJU)6XTbJLlv>rUkt37(!u7zd!QjL4WKVLVw z4e(rJqGoyH_nn=Sx8`G0F6SI8hZHLATM}jjz2)*8h>&R#t6CI7(m*Wd13*5iwH!}C z$kwj=7}o;++Qb3{yjuUYO99_50J!|)9CT)|aH4ovtD>X(hEXRLb7mUpl|C;SY7O}& zRB&nrWUr}v9GwE)bqSe!BacN$d8Be}=W^y8 z6Kmsqa|@kPQm(SETS1C6w}tL%XhLV@*{z*Q8e`~oT)DC8R_{X&D|`p!swzc=CV&UF z`i}1^EhdWvp_;~%EIP^-kmEVb1HHV+Ot}xu1fpy>I&g5qad#b|i?D9dDdKkhT;m1d z@_wsRT|sa%2YkZ3^1!*o(-ASr@;<3XsrQ9iyE<5)p5P*8k=fqRf2DZRIRua8?oRFg zvBq$d8mqXGsbny6&rp!=&&u-kYys)kPh-zP%3(Zb+TV0Fb(@Viy) z2JvnthxHuzOVkkv46nvOZ=f~{&ol^BEv^YlD;?4$EC-i$Zp6G$-@DXq5*7Ly`dr}*tk*WOe6PHyAJl&d5N3>-X7 z`G;Q71!(Ia{zNeQnecMOzB=_X*J%hUQho#+~j zI{y^(IR~s0m>_O%yEXY*6>tqZG5EHwMa^r~fgw)==f9}wH?A#=PyWq5LGQ%xhyGd~ z=@8@X2sc+e%)?^Gh`P@?nxl?l9~j>!KQz@%@j3?trs`s|zW_mfOBbP-gc>@VsTTqX zdJBSp2{Vz2_j(4{I8PX!K!sqCIUh2OfsJO%w=k-Z8puNb((U|+6ws=R^= zicDn+ZU-#%tyw_gd>W26n$CK%_Se>paM6<85d>qI3g=Psd z-9#|>24--NGs|r}uePg75cLeOS(RQfEufZ+tK@E+j7iqzB`am$du{F&gy#BAx>EPx zK34Ef@rV9Aq1{`q#~{HkA$H4?Ow=ygl*D_>H;T6#knGseZ#h5)^1A}~E(czm=j*&_ z?#AQ17505MZ|2V!g3-@r^9h*6yjGwf5)TcNjw z_tMZCxLcOEz%@GooFKR5tu|P4Yp2#iE?bwc&BMUo8WeJIYml)`2?v`rn+QI^qE@PD z4IUj#EkEJjsfKp+QF$}!A7@Fa+aNThq~qR!9VIlt2%u~HVbCofIroU=BaOd2;Kw%eSxP`GxXw z9wbX+hk+e3I>Ixmy0FDW-eaW(8HlN_zbxr9q>2!ldz`s0{HnSz-BPzXf#B*uDNSHe zrNuYbzK`##X0MpdL(e+_K5c~V0tU@zNXH5XskK`Po6j@mlj*EEbTPJ(4KgWs*x*1R z{O}#^N37fd_12r^+%9dIM~;NK0D==@LYf5&6;MJ4)yfYbNG&pZmpVKpuzUY4n#pgD zwkm(wQsuYb{*2!JaZmi8zy0nzDBk}H)dWlN|EzlVS0D3k-Kp$ml_$l?eGkxlc``)2 z3AF7uN6R^a=R>Feo!wVJ=4HS>HP z3&myUR zev!)wl-{-No!sOHaQVB@8t6^8$t2&T@^I@s6lzZQ2}ST^vxzb+|G;CyWN%dKByxnT zH=AVh*eDc#xE>^mjdEHL(ZA@ultbgO_r(|A+&vN4OGHz%Pw|^?6yP@us|tehrJ%f= z0fWGK`yy2|=uN1Nof4pMZO$z`>{H)rB3g}WS*^8A*y!$3Aw6<&Qm{0$ zfWTHZZ~gE-Kb~3^uq(nT-tSVb+~qb`Hv((b4BXzl@$D#bTO)Gm13dCAtS~VIqRqkT zcI=E%5aHf`=xdK>=(1a=nNyUo>=5o`cBcR};EdMFz{HcKjnfRsLm`mZ16pVRpDN)Y zF6=e-Zw^s{+ zbWh*L4l0(Luh6J;cHAMVM>1!Y{3^|sG{L`pP5G2N_EG5U`n(+BMVMv)XBsyKNrkwL zX(gS4c5y;FE>C*@6}0;!clXE9-CzEPZ6==^Rk}En@8C4~?*9S2LA$%f%CCO=G?O>Q3GusVb|;h5(_v-IyAr&foUSa)yAU9+kUNFjDR?xa zVXH||V9#FJHxMYi6mlGgyAuEzUn5|48fsbhTjAX@DC%)!QF?|7`7q-fcdQ0lw@e%hf6BSzzVWhf|V&PIOd?58kI3BsT zaqXy+5CpxuzRi${PsXZs@guT5q(C3FOq@yDb!67G%w!8*igRaD&#B0~7Yk%Lg%&@c z;%f#Qw??vBerib0yo^Q*%I%}YNNevS&g4L(p_Fts37h$43#HS2KC&JPT?ZuKdu0DA zoVhlJr7mI3@*=ph$$2`Y<)-WzH77mm6pGA6#9<9{`Z2a(C?{8BNr zUDJAl?ve#YpdizIOUhH~0+I{S|Kd?)=k5LlEAij{4WCJ;nf&EPeU;F=zx(#j$JkBc z{c-uiWmlbpop^b2c!CjSfu(o>=#ysRJSM80Q0pdmx4n1o8eOZTYSL>a2hZS8IQOI) z78NTP_8eUjV^5oA-o*PALSe@Z0wCwv&0KJL*9!YiX!E;S-Ha;?9>>*v8W-HCX|t25>~%kSJ{&*0nbcUVd^usk8ViaIZ? zT_!U_sm3q7F6&^)y8hUBLOHp%@gM~1>@71?Y2*VhFSYQiG|fBk2fmMDG?MSs+8L-) zC%X1c^Mj5<4+&4T)mM`L+ede_G|$l5TfcT0;ZRT9iNo2ZPBgpCQgajP8jyyW`&RX! z6I+!~)p{dXlxR(4Tj%V>5JSU18~&59W68(FSXG@?z9*;Ty0U9Idc$m3WCvf03N~o6_WpCR`^(SROn#}}{q5iM zcmL(beU;s?@;h2h{>=is|EhZTZ$BfbzAbcj(fx6UDtt&iB$^kL}ob!P_l+Vxenve zvQV4hgy131E@st7y_RsQaM2#SEn&9<9)%;_GEw!zw_}6>Sm$4d{<%`;h{{n?TitT+asm+9b}rts9Po~6_72Wq`}&5y4YFHHPvMoEh4#| zcRF>(avS(G-p-(BFEW+R6{Rs5Ay#6Z*SDRNOqX2<-YA!0F(hNOmm`>@XmavN z>6wFW2iikA1&45*^xEOj=_Qwf)WhyJd2>2xf#^D|95;<)-771qWVFeCIHY)j;uz7ae#SI!*63g#v%0@{H}>LkylW=a*z>$mQAEqx}%;w6x z*T{ffCwZS)CzHFoP(E~QR1&*m7FpsnkYiLj)yZ{Fj@bbOR^GS1beQd@x}UNNv1 zFg~<)F4*BAfMae8x3Nt`KU@w7$TRB$citKwSFoW2GSN!~HB$u4T}%!&W})`Pbts(a zH9qc20!Yzvhnyo!z0$Q7{TkFA$icM?Yctdr7};#iXC_a}n};)FiBVt<=_s=e)4meW zOl{(9fXFOyRttiSkg}6KaJukvIfMI-Iy+p6eGAE&Jp=p4{59(gANmHg6t!+ACiq#T{sKcPmWbU|Vo;(&)J znP%WNCnH>=%$5sGE{We6H7gr`nw8P5KFMFRdwgl{XNdA@Xw|2VviSRrgJ1rHyZgx8 z{R{N&Z$Cr2kM!1(m)5-fB1*7J}wlIjmu@ zr*hW;yeCj|-&9sy`R2`}nzR~6<*LtUG`YFqQaqO9R{(Ev?|pnahh3i>TL3+-KEw?Q zclL4iyJzz|aB^?89|OGe$*gJP%{EOZz1d_oZ{o>rwu4|XPHj5}n>}TzC`^$WYId?` zc@9PJiYZUAs>+Ffi^2RrXm>^6RL!|$ddWsL?Ho(;&3vxAmVj_9S;jiT6t11kQF5c` zT~R&}_Kk<}u2U3NdUHYVS1%r3z2biSC*y4mh13)tV8bSVAThW?emlg@IV`mi=vZXWrP@JDP)ZXD*=&%1VHx zBcyq`l#s}>ish_uMiWi0@)0{u<;2>1D23?Q!Fn~BWVWCVqO}fsffaTcX6EiQvq==F zOP^|6%>{jzOKjs=b={aLFt9jWyRKL)bq8c&!6~6LnK)~Gfrro+tMYxHE#C@&FSC61 z_Wpi(FDKaF%f3IScK@onv%lrKMr!$)ve7D@qVTTU% zlgWX0zqxELNxUzqcu(41ubm9L{v31+81F7FnhL}l|BVH{kx5les#9c|>?=gU((H|C zrn>dVX zVnG4ZsdCgRK=tOL4kwrdS%Jnez12R-(5}1^@vjM05Y9daFk?DJl zj>BRbGv51d-OguCo~)^P#}#{VP{D)8*=(|@_vAf&{qX8R!26>4z9RKbtOU;6{czIg>5x_(2mkdRuNo|~vL5%SWy!)=vIjiT8-$8EV? zW28Xztsi#HXxde&H3H<`Gr{cmNcWca)whSyd=lFytQpfC>VPtf2-UaFF=&ktfw6E# zv+#C1V3u{q#lh}w1^LF7Gpp) z=RAAZV!-2J#K>G6B$-2ftp_@`WJgw=#uZLCHNZ}+7K$ci7cRwBOyBmhc)BK?^;M#bI@1CTN>LweYB=d&8oa+>*k#C(wjIfD z%A)(^3yqpx-e=M5?SiBmS3UQCr+9K4A^4-poG*X#%QWv_8fS8(cmG9MH;A{>yZ_H$ zf7>lqo_tb!W+~o+*hn-%s7ZU$pcTG#>NWu!Pt*N9q1B}6H9Z?u4o|Cg+IGXr)ufpW z1+pjP;5Vl?H{%JUlgUbcVNqWx3|n9vnZJntozU66-+#DS_4oY|EPAW)>PnEmDSEr} z=4yY}Oy`p#t*UWvw>zaNPwjiUR4Mo==#Xl~OqHuO#4q<_knt+4pm*nRePfD=AlMvb zXjk5V$*UW0gK=Uk%zKRz->QW6EpNzr2TeGM$>0I(P`d?(^9&(`&{eP+DWp1G%VTV4 z<>q`d-(00grrI@mg;+sSba`RHr5*VY)-k$-)39I}TcXW5y1krgx6T@x3h8Y6MD671 z@rk@z$TXyCpU#tu$0xz`Z@yRfz7|$Zq2-&&HLc*hVRWgq%CYZ3s00*QSG9?}w&|jZ zfi*Ueqt;#dmVeth7#t6;b&sCB%Agy2_$4A?v8EZg=u>@BNwT->jX&nUydjtf(cV|pu$mNYQJo6+-WQX-ydW=xv*vjb%ZtZV-aHfVZu54+eM(UB)y=rY znohdf@8fZ?+g&_7|Ci>Uu)Gc zXPV{X_uqW+P4DH)m(Wn2KRx+LD!)6%zDcOxgM@Q*S#q1_oBT-)DC+w@qx-GyMwe$= zU+$Q)t|{saE()A($*E=7%?G)2W_vvwMDJAc!pPxufr5U^K-SmDLK` z`WId|&{dzs-1|>fyML*>`zOM?Kb};66eEbvv+q>!{`M2>{_3mG1)7+>yFhq%@3Pkj zXzQ?2;JbA`6Gy*E#EIz5?&6j4ZmK4eH{;Xe+prn}ri7pi*DU0}n+lnNdqjB8nqtB0s>AyJVt_O!wt(Rwa#6Tojz}Q)wB<~?Z6wU zuMkB-RO85df^HJwZ3;L_@Te*m$5M5=h=#FLkV>j|{) z@2}<8O)cURf$zJE_b{elZAYOfaO~T&1iQp1O-$e(88KmlK%0=%2d8#$0XQ?mtAA%8u5|1Guq7lHRLv3GZICJw#-tRb-9 zf_fig_aA=}yPe>Da&mupk1&&yUPIZtom@7;y^EnR^4<_m6D8qD6D+FUt6i^gu_kig zk-?ii@tS8+wD(OR*e$n-fcH(j7x)+FS#xm_6THz#44e0rM=#-a zwd?IJ+TJ+cdskO%*onvIyUH8HD-V?mP$MW=b0vppDL^-X;hWtu(8T3|#!0f@GS>u8 z7En);w5pOmG>Q#7Yvc~hx3FP6;F>(tmx_SD+3q)6*3_qn5rkU8mU);2!KP!y?l{$8 zS=Hb{oss0)PMpzuv&R0tdwxwU4-uh~W_cn%y8IZz84?CVnh2B7=kiWSL;B!)0}%e^ z2l?*{Q%?jSYJ=}||4rM#ebTH5>;9hs-S_nq4v@4e(n6soW#MsHedle6cesvLJg>Cs_7C_`I;J{ z>YJ5NO~`If-nBd)4Dq#7!x0Zf_aFrd!WSd+A}!~M7N&bI4@C}U(m-Qmhpt?(ckO9f zD`yFMx<9_4GCW#DN2z_0MS&Q&(+h1`x7{*m#N~6M@q&q}s>uWzHm+H&k?#F3U%&0l z(l?#nF1oTE^QLR*&aZ^;pGfZh`MQN) zD|dHsCMKFN&g9#VHIqM@&*Zm1-p#SnGbVToYWI*R*lXJ1*$w zrSfhez{1X*W-_i0(Sj9rcyer7PT=we^~OyI_$qJqtD74XF;oSH$un3^s(AWhTJ6X4 z>Fd1*hafWrSNjk9ySRQxs|vz{ zmgs1eyfE48$sxex3wi=+**5q-yV`($zoK{oaR4$n3@T-LcKvcf_`YVENgcSYOV3Yq zNkWYAb8wV`I}!@R{1mb?&H16&LjApMw%S+?mvDuzx$&!sv-Dxani$D&Sg7+ z-hI-bO}F>12O2&(eM7xlxp(iPxcL1=<=}c!v0SHB4&F|hrfqs~mz-94W!NpZ>a>|P zrwA{pisf{+&!jZ^`h*_*6Y3F?TP$RI$6t%^{L9j}=b| zcAp`#M1Ypl%xVp!?zDBobHVrooSk7)^3Zw42g1S*9|o(Q*m8%w?wB@R+kGTgsfhIR6oRAZc*n9f zQN*emxNoVNg>#T`L%y^;eqLLbom5_bir(6w5Zd)PA3z&iLgyJ#1p`F>whoRxjCQ1a z3g5R*oDV`=Q9-)VfAw~&HS49ETHNYkB|9=zYil>)YKeU=*3YYjX@MqFX(K&MIT1rT zm|Uf9Wo4=CQNtFbt$~{s4I_7A`Lk-1w;aQ6liwm&qeGv}LZR&K@-4UU^>ril-O+gx zIN@fgeB8`|dOWyr!f2t=1onkyB(=8LILhV%+I`DS83|+q)bSyYp4ooT97sN2!qGhhErdQBra(S?L_by)TPK(Z8GHj;9suJGb6Yv(Q zK5qrUds9Ivc(?b}L=Zg3@UnrsyVwg{<8~jmNF}uw5^k z2{ekIz8ME=Yw&@Og^+!FFrT=^p~GO6kyVt(al{P>-#DrmrbGpvnh8pmVRTmmI}Tl+Xo63AQ5`2${J$qJY>w6dL~B-Sk>TyWpaL8HZ<<4XF}c=`No@@d><{ zYEP6=ve}$lm9Cclt%~*Z;^54o9Wc@c)2_P|y9r%1R$$$4&X)Mg#FL*?yFXs4{PNdt z#Q){z^zJ{K+>Q2}fB2EV`=cQ~+ z4juDudc&rfqQ7xcP4M#hq!rpe>p?6TSGu)RjdLO7^LbJ2t86-_Q82FBVztNKWz`Bv zUwJqC$`j%Z<4L@V$Ho10HW6YiKsC8%sL8p!=Z9Ap7w_L+T+9u66euz& zAdYXl>=U0eO!bzzm&rYe^7Co?5%+F&hewMRvas)lm`>RaT-+2P!5t84U(_r>{qRk+ zuQh_nM0zHnmS@b=vn`awxAc|-vFre7c>vSNk$yd3*&U7pL>F?JsT^N*)-L`-_ZAmg z=@=~+IwIV)UNA1y`;GXR+cVjly5 zd(;p6+U78FQ%6b>+`kVro6jxrckmr)42{bQuT2&j=@2u*CZ`??O?UN75|Uav*=s{!`u>E-aUvkVqJA>{9NyJl!g_oQfs!?wkm zCB~Wv4uq3XkQ#pppbIWnD;NcvCM)uNRm?O45ogo7 ziyK`G0*C89BLaotR~3_|@*>%%MKf;-N+`m!VI{Psd*R%J#0#^;+v*Mv*f1kjp?Ys{ zm;5^O3Y?%%SsI)hcr0fK&4MWjGmYIWu|!``U#>}V+tTTWYr49#lvz|j{-74-hBZr_2c<+bzjSK1AgLNVEbJA(!3-W@ zMexV9mf+rfzOma2VLk~cWnagObQ5wRrtSzfFAPjtwP(r8Z_O@Px&?U*FaaHk$=Kv^ z$t~#rEPXoejCMK%==roq5`LkM?djuGQ5zqS@QU^F@)% z_zLwJ#zDG?)4^ef6H7!RJzPc>c*PYVQgMAg(DYk@?osASBoxRkXNq~PhT=yp65R>! z0>}v7_b~aXAN<{*-446|-C_5!(d6>56@QdQb#iil!p318O5%1x7)Pnu zo72fLb`M(t?-twfL$i3F4toeTf$)vOvo~)}hfPs6vv%HVdQIE5)%bMM^E96qSMkHE z_kz_IyNicubAIsv;{EF3q1au>S>4-B1<&6-Jgno*CNIW_AMwgKE(N~#EEyKy257?U zHWOaEq$~4)3lc0yDeTTVj+8{Mtm+s>@ zq~~VRrrsvM>*w>Pq2}F!dS~#w$VY<{C)Ua2AWk%>MK@a5{XR%k^-kQ9OH@C7_<=d! zh(HZDT&cWx+{o{P!S@D!z?OVFy)JR#Up_tdemI(SBBF{?baKYgrQO==K~S6cOG+yA zv$S*+EmqNMeB(KtLGNgWSqF8OHpk~JSnx<|0et)NsR)L=b?BWM_g2l+H*!q_HtI34 zXz9AvNwPy_+p3P}%=GrQK4er;6vu-6z(D#I>!9*1kegyki3U^<@`2F7!9X?G&=$T+ z1r~Lf<06C)Rni|Gb|O2i@reRxXmWgDRg??P373YLnX^zV)F&QhZ{NOtyHqO9l?Vc=T*<(gyc2(`&xXn>0i`A8n**=Te~oK-M~@S(vbqo|*msE{1>(g&`p z-U7L7!QM$D)UO$^La8V-2zQJ4(53C>Dmry(NbY{SwAG(Q=Yb4Dr?;`Rh=m(WwpqMg z-Y@W978F>UEaWRyKse3r6|NSV}JK=fBR{m$&XBeK8yl@n74<`TizGR$wz*-3WkJ<5pfn zSmv~d^JKhQ-R$?m+GB6hOnSQ)yWQJaj-tkWp7qfTxtq?XaeRMY^ccL|e+pTPU&Q6|UP z-M>6S@MrYyW4ZfC?>_c-|GQ?ue)ZMohLsMzhbJc|x)OhK`7vtSQst>a_v8q>cfD!* zJyWQJb`PsbufQ|KWHJ=EE(8rHMKJ*lpA_iM`94RyM~iLy$*QU1swy6e)&9ecVEK4g ztj^EFI4z2On(w!(Rh|_Ugqg|oe4js@&$6~!rQ2;I7d_Qvn9l^XoAYVg$iKzK#cX!* zuoLVS=KXHBJHG&S&(6>1&G~uOUwdgI#J{&gV#qp;y$zil*kaVZ$!(m1d$SIK@`vRK zT3`xREYTkCVT;FePQkp7GI%H*Ip&o40Lpj5!6wRrP5b89QvNO&OqIs~@AVoP;5k*3 zHA^j1I|m?~#Az9q=~fd4(~>(r+_!|)MCh*{t920KxBR%5$nAdgw1PGmJn@G5c)sBJ z$`7)zyyCsrzS6CF;5|Nmz#n)!5~a)3w%96OpNCeUXrefay7X=V$!Q*^A1fz}|E{g>nA*55%{xoCHv5H$F^?&Gi+ zXEzJSX%+1E`yAO-`=Z+K&L4WG*eZ{>WH&uO$D_^h3cLBdDf$y()`IEh^FA`~*IW2OQo%t%ZZFQqXf#XPj7vB0 z=J}-|G`-`3-rE?jLfzYo;l184z`MVR*Ya~wtu;?7O}DPtf$f>FjBvx9ns@#^n0K76 zoB4W8$(ufJgviqBl7jh1VZJY+nRtUuoD2qlYc07UrlWl_#gaF|NK_IJlY#dnl+m!k zXB>H{RSPi8tRt+%m1ox;UkOuxq<@rWSJ#iYU0-{p&W`Ft-l5!$N=`JporN?gfO95b z-lcBd@Z#MM-DPQTm=Jb8-k`oM>qF7IHMf|8((PO7on%YG;03+MNAO)Fwj1eeEw=ol z%RW}oB7_{LR=4gMK;v}|Y+dNH%CC|=y@P?z?&^V>1J%_nFTh$BBf#ZB(Elh8I3Nvo zCjp=xZ&fEiYE8d};3DuXf5E1r0kn|W%QLJ1sl!DdA+W^r$kc08GFl>_vPX5TP!q5+ zM@_Ttr1X%o3SyVCBiTE0d{gBkkaA8c7jFDWllj6e!vj=RxNvx94`Itd3qx2QHWq># zm~GuQh9bsn!GYh8`h8eWgwo@`5kD$j>4BdS{%%HUYXNhXx%_eaz#w!uOZ?HLgv-MU z*t+I&4AB%<6b9i@7Idya6`@>=x~f-t@h1my5>d{kkIepaQ`uUACkNO z^tpxjFMp}I`={;QA2$tu;t~8#p<8+PK{WY{W^&xUfW`QG+*M#`Y2fXUx&!aYadBm@ zH=hajo*?_R;%a=ao%D9Ys;Gv;RnZfc-GHC(1it%NZ#BL$p z?;ikfK#;#)Rew0eQ81nN=jZ1S=W}#w_GYu4+En`4eAGvfYaS1_9#D2K^cV#T+mzW= z(4T`+;5#i1it{|)%7?Uxv0qumdT-3Fdcj^O(oj;;B%yTF9XeiTRlT@w zq(!VujMG?L2)c9di-82xnnJ-DP&okvxs61K20?fA$*QzEAz$VCg)Z-*mr<82!Z2}h zeqC_(A%c+Dt#Nh6bIZd@eQgVO_(#zD!}zEgZIX28UxvEgPB0El>JHS1b|?bS{oux&giUA*C@F+L{Z#U^0kLO&{tK2)dh2< zy3RbFxeP;jFJ$5-pTG{T+KQt4GE-lTTkg-Orm)I0GD|iIx<+?LMx^;cvo-@qJb$dh zOn6EWXedmk<#cWl$K~AUqJ5pIEl_`?oI6RaD-6ovotZZBShiS@-5z5AoxoFm$;{_gM0-z_(@cYo>;bPJWo%{juln*#ee4HfUplTJLbSd+^`I@M%C z@Se|m&6`tH3v0b_?|#=J&7>-@9KRRz?)7%(=RM%o8ztbASl+g2cC(%QvznbZlX*UR z){n+$>MK2D2xyGrN97Ov_oIqeBuKF@`G=lwS8XQO_WUKQaWtx~p{ZBfCH zYg1(?6gCxjt1u^ZiQy^aj8rqItG05A3S*L7UC`~WX3d&f(54FB$XSk~Ymrv*MP!4# zN3@Qje_Zu2xZiBRq3E4T$YJjma8@E8I9?O8uHSLW-~%O?h1X4 zlj4Ss%FHHgC~w8wkAY9MlHt-n3^v^YW}VIQ5Apa2y>)@UtE)7h_nNv%pG6O)7N94t zvJFQI%QtzL&}ER#ml`L+eCo67vjOyL-+X{(N{5sqAEe43gER2vLr{lvu;_Wtmi$s0r+$2JnJ+H_3DQ1|FX6msqKRN>gR2PDU+Z24nj09{`fHQlsu=-7C8KlCI8^_9Z zp!!2Y$|%?fHZ>*F%~HhoQg*|SbQV|^%tE{P*!~u1Q<9Zf2O7~5=!Dr?Cjxk>yuZ~` zdBE;prg;B+n#s3E!^%(f?jLC;f3?oDALW^x=w6N?x2D0K^e%fUoLs7O;+iWjU4%EW zn99HN6~evmt9B1IK0lxC7+u{f3dQf!YJ#A_W+rc6HPhAUyq&(D zPtJGyaogO$DY&mzlS$RPxDXtE=^@mg zOj2;w8I*RDWh-q$P-)?ERLDoKR!}5OtNq^}*D9NmF$gELaC0Sqc=E2-$ME?RBHX3dw<@KwBc!6~H%GzHF-7^(QJX)GpbcRi&vkl4#>^Pgw5D@K8@xEHF|(Zu%9 z@H-3+70Skbb);$n3-ZI+n5L^fw(G7TSRn5JYA*f^1q$CsU1xv#^6%i?zxi38 z$wwZ+Bf0x%H|HNd@d%!L#Jdkkf&lG?i2X(gbz*UGIJYLK^p z_g*u+FJ{eY)tk4c`|)XfS`@n-x^{u!)dYdCryoGTb9qVCzNp5%$!PlG;o{=e!$nn` z?^ba&u8Q9D;{4sNsm6Em233v~8o=WAYL%w@{aDbOz%5Ul4hHgsP<)}^*&8{c2H2?o; zd%NDo(KJhtCMY0=6fH_1nI;@G1&UyY+_Ndk9yzAMhAxCiVGLw;)lGXc7o$OK*KO}b zFB&kAfyVyzea|`1OUaRuT{XSC&WK2dKP88B-iPNo9}Xiy)Bu+qe4_y^Zr08U&ZK;1L|-GF z;@~@XU&28NLq|}$z)>7n4OS%t+{Sfy?z+I^dxK{!D{N>==#;|E91sXpEU_A>k+IQ` zwZo)iW*kPrkKhdh6n1)WM+*H$00_hP?aPV_pwlC>;aCOooEOzrqfis1KX#Ap*p^z~ znebiff(2AK=57$+Gg3$l{MJvQHl5+@l3j2!uV%NHL@C=zqO+QbvO|pDfO$>cT!k`X z#Ttcb7J8aS;%p>#umxHI1z-xGq6x*Tmp9LTls2Zp$LS5saAAczi3Jc6-=oC7hF@bQ z45*1V1BR<&fmO(MBqU;30PezVt&M#}g^ljY&mvzFb+#C^c|IZOjd@#%ehMwTA#rcD zaEZL6h1loK&kO?;iu1Yy`^}+rC+2l#N3*6niz9X-Lr$8Q6<#5XcK>az#!!QYBcz$` zgEq>r;(i@qjz|RFtKge#_giPq-vr@;?cYr^8OHA4dg6V4_dol>%CGg^XTHjdGlR~> z@xl$=7uW9p*VhhjwVQ0;`}poR+LP;pdry13ZjQ?q5<%iO2W_s7xl%lZCgN|j+dS%be>x*6SJHSGS& ztE;P*<@#oI3pRX@Z(Wt~Y!UqNkIkQ+gM4 zYs}v^e%I^)uPrT`@+#TMM05aKb9D`eq4F}kFf0>8j=9*J=QDJlaeQY#FbQcPqQh_@ zt2pisyG(MBxBzgou!X`gCD!;F&fGhu6LzX0aFbhYl4*YukYZuiT30Lh1Q_ZN6yMl= zWP#Z`Jwxx0kTAk92c`pOL*03!JOM-bSA*e$<1y4H8DmtS;*aCCgYZP>Mp5#Iz~~lb z)S3?nFz(=%bM_9$8r~=B+q|V*a?T(S>~`dr9600k0m~sj%)py)ZikZmlJQsO@s$2y zh`wf-!C+4H;e_6LQ?RAjMB(IxarsmMUh51v%rsiQ;tlU?pcf^sL@Mqs)zAP5^p5J{#~5Mj$3x-`D%tySDh|BqK-=f>#Q%- zEUK*~u6we`q^9_o2q+%>m*1mI{^q)~f2Sq>D@**p{N+t;&Y%Cum!y ze7DWs@KUyXwYt8zt`GxzeD57OCNsG{P2Mfwx;d_oBVn}mm7}KW8~56F^w6$)#=#Q3 zN2BWgYTP#CasT{$gjBFqfE7MtJ};Z;d|xh~o94J5e|GTv3N_zy z`Q_NBvG)G4Z2%OlPJ#4 zY7L}335lN!?%`aL`ItT5VUt1pn@QYiMKn=low2}v25&|&W#52l>I}($gqf`0087qL z44NV|g6G}AC#h|ncf{8MRR_JhgKH-;aR<}0aZZp?C*eZi*HbTYv-erf z$>*k3mm=Kjkmm_)JFy+%#|eYDLupWyb~HGH(47<0_0B7lD1$a+7?rbP!iJ03qW7X0 zaSXD)tE>Vc!{8i!9!F8JnPS6WMwIsvo z*|NIoCU*BN&`LgniG8w#;?>&D~UG(m? ze*C_bGyeJr28E3G2n`$c&9K5fW(|+Wp;lp~h#^AkeEA;7XNB!8r z_jo+U_}!16$IZNLzZh3uHcgYx-7viWuNbAco&o24diLxub0d1hw7^0&Dm3v zvfdNC-6Xz;{1LCbjBg9HB$Tr}S_F&W<5B5U3`TjvOr0Wqo14p$;EirgIPlY_h0iug znOF63Ql|OrDFt%7={qJH?xt;V-g7c0AX3m&X$i1UbU)4D2dYyJ+T=(8;gQF1KxxL5 zR*v1B-^cj&cJ9Medt#Tx_&PcU0OQy()|q8;gwor^T0F{fo{<%dJCzZW`@lE!U1#|I zR&bD!h>5#dtt2Z25!p`PgyraAF(RO@*3&fP1YkFj<1#1<4A zYj*F{YiUBnP7xp$r{bq@aP;s7MMVi@cK=E^h-Rww(a({~Fg~wi*^sEIA=!;NoT9*v z;_yrSBC(_cLS@E0&D;!bI1P!Q`&~n_B3mbRp_d>}YA;R%kIs+6Qj<~!zzy)N1|M) z!~`ykAY<@~AeLsDq$p0Uo`tO+qsed(=#$NaE56;x9}(jd1ZjowgrT_FeT(xibhN0g zawCI$a%!QA{B;UXjcDL-6y;t(m8i=CA-C>W75h^88&XP}^A_sN?xKzDV0 zxb7>|SGJAcS8h>Y**5*sy>SgJpSMR$-rG3~(MFX+-~DxSJoddCsrS!6VGzXt{s0Y% z8=#NR%keM!DGJXRI5Vy<36ul?z>8)DO-xqq2D@LjJzEpJNmqUVQsK1b)yJe_&$ zt`E%@_rEVyKVCcVzKL^KEZvb%6vxSO>b}7|D39rw+H&^|m--*r6#lxJ?r*R1Y_(di zZ_39w3qE`ZEIbNI5-J#Zj376|! zPh!p{g!42&QniEd9X2~+x&az8!oZJ{g={{EJ4xh*9ldcdTJteQj`T;yVC>F1XvBb0 zqTqGk_^!%Z4V98jC5kp~#@`n`(Ax{XKYwn$Rfa63f9YzkMA00s%JxoGnP^L?j(ngyA4vCY>Ti3P=oixyEJt54H5Eu(RG zDzfNo;W&u7W3?&c-(^zxL|aD3!ne7Rbso2Ab!SXqY+-@1br%oy&*y>ar+N-Imz#jr zo(o*}xc_nZad%D9);Q!A-~DUs+)2!1JTvb5x6$4IYre{F$-7Tu_g}u50n73Q%Yaq+ z!W-;c9jmf3EdQ$n7z`C;RJ6H-tXU6)fwUa9$p*dn6w~94hIL{htYL4YR8A` z@pU_HN)X+n`NOust89Kt899;dTgJc z(tg}GUNK4Jk_-Y(bE>3Z^MRiJ79W67p6^v9=7lh0;lzi#TLnO&w|nqdg<`*Qxd zSWTDfc(PtikIj{PbyCLe9YF72dK?-1=`T}F;JN|LblSUDKfPNQboP{}cdrTBWOKxJC?>N&nBp;-SC-%D7NNDN{O$+7TTN`kQd|{I#o(b-1(v5xK z7bqj|GAT|nPS4cvb;|Z|fNyhQW-0odsCA>1Oh^qDDdWucc=72PKqWjO6P#mTP-FfX zIWf60<1rPldO)|0-%TU*j!jJxS&uJk+jwh2FTjfv3-Fd*$A?O1LRvw4%=vm}49@Ug zB##zDEe)HK)w)CWWJgW78SHDFBX~0)80d?yhwFkJ4WZtuR7-|}gG3S)uZ$#fjvHiN zOyGOHQ`QyLC^$QC4)Av9hdt!Q5`Trpk@XLwy%-o?DA+YA;!M|HMKrm)lSMsFRO)Ct zZ_(R?%Pi75(Nr3-R(|lcl+vfj#?MxRjR^sV@&h$6=yq6faG}zJ$TG?!Bj~8!_IN8K z_Dw}{{JTHyNTD!19Jd8F0?1mpb{GAIhb9hLOD{>1Q;BGI<|`nIXSnVPt(q0TQ1ifQ z4I6F99cCFe6%3^0N(Xl{cvE-wzd(2Y`LE@f{P|mB_ZfD(vHSl#&+q<by>dgaFD9`fpP=0?=M&-(T1WeoIo zzvox?x3_S$92{`Z-FUlNE*&Hus*m~2dQug|$F$!!Gt~5aY4w6Bw|5Y|o=hBs=hdoR zxmVXKk|g`-%M_3e#%3(?`)WFU(Hr-x>8hBl-!0cDv%k!X0=+%IUV{GK%_uxk5+ITM z5mmye5#zH*6srm4AAOb15fN99kAb^el;9w`)}cKO@aZgy%1k-1i0oz(IV%=UbF%T) znH9Klji_r=bLs2KKhOc8gnXS$*BGO91t04pC?m;? zG^T7iP6QHUfivm$>MZkQqy=%99L82k?zG613s@xbQOM66spp`;^n2I8iT8HsEf5X6 zNrX?Ig#J)Cl^z?LP6z}^ZS=R6v1Tp;*Y2kL+T2DoR))IO9MB8Y7)=}smJleD|F5&q zK2*apwcrN+nIOD23}!V%eYs<@coYr$fY8d2yFp_Juy+5n3L0lqM0X;Q9GL9P40^eX z?H@$h<>Dacg~c;z_~sEs)Z*~Mp4SYZB+OBEt_R@VmFMWyfSe~y@du#w?Nzman@ z`2UOU_E{!hrBPW1ti$gA`46_MBy@Z1{=-RTVo8DoaR=EK<1tp0Nb(+!#^dYp*q~by zZ#Q?Jtd^v^D~E*FOrjcU;yGWB`m1(3uNsHjsb|9RD*DVEem`svpVlRS{Gsg|#Oi&S z15{t0tHXTjKjFy@&&O)N+BXio`>IUSvVtYCLJe?$aKA-y@4k*qi&=AM`t@|xKbPww ze+t&{E`pX>1pzUevv=DVio02Rirnwp=?X6S)$P7Hj;|b81F>IT2G-uULF zxdvBLAiZ@xxygbL?!N#W$x^+Fc~-HqGS_sSy9b^d-L-2B<%GA4L7BfXk$2Vspn`ch&7p?t=zxDy_Re;6 zA~8t;7*|d;W|WhFEdgZ5b*7aa{Xca1#dbB{d5evX3;7ondxFoy6d87=IRJnpiagR+ z=@fZH`Wrp8oP@iG7$?rRCT}k0L|RaycWv=ivf9vpVZY=)XQw7h+`x(|L#lug|I?BKgl-Zp4= zDrIa+FRW@}qhd*=#A4SH5mvh)$#5bFXVHZ0n!LN6Y_&kz#9vV=8O59gL#*Y{+-JVw zT}%%&=k83S2z$1X6OLV_w1+f{Weh!cH#hhXsJs9A*!^45^0t@O-c_cwNx18Z^` zy0yBzAZz00P5h-*7OeY=dmVGPg;BNbo5B0KIv#s^;yrXbXl_Y+kE&%mx=zub;Qoq< z8!w~R2lv||`{{D+hSxGLmt!|%-|qMKO&O#m*oo$g`*x?7zFz{o z9eS_b(0&}X{hy8v$dZ>U{wSbDaY!ygd^w%o-Y(b2cW~n`k)LuuEoTU-`tad0&x6I& z?(*{K!vYbmu=BHm0qNgQDMQ3lh*faOkh1v9{hm?y{nRjDv1AG@i;_zR90xagr!~0m z%mKQCfydb)1XY&_oQd3+iL=lEn@=_ypEUF;txpIZ+HOYKP#FX$oVH_2;l{;f4d%j) zr!l42n4?WUEvQo6uJSu&(;@10KI?~?H+Hh)$${1byVmzgfoCDlL{zDLllG_e4-r$;6mk{_jgXjfJtd%>fFUdQ4Nw zW6#!wv;wKH*qYNsr6>%Xj5LRS<4FoH5==zD6dLLy`YP|_^pA~ykzX^mjNGX3c`h3h zlk-T4rF!Js)%clM$Q8}?%Epb&gXW<-@j+A`uunn278o3HRI-8#Bp!;9 zN|%yhi-|`>(qZ~OE2{htrJ#IxlfDvv6*jQUq_>0yLCU+21RI;YnSQcV_O{Evk{Xw)`G|N zdhM|GWqO2iZ?*qr|I2cEb^m|gU-fZ=F?fbJtkF4qBie9HE%TnUGFh?PoWHVQ}-=u*Osel>7e`myQ|ft-0#Z|kN<4}GW&6M8KkpCn#n%jWcgG2 zNQrm$h)8c@_fwDqyvyT}v`P@nK3BZw?BfA^v&9mvX?YfvQU+4#otqISE7XLW(VQ;a z4!zh-iy4cQ?lkV%sIA#q%>ry83oV{R3S&?xQk^I(FYdx2EVbi~4zd;|QK`$(o+mrS z_{Y+Z$K2@IVv#IN7aO<}z7z8*$29oFypG_|A17+b3BAZqd~$sEwir!L`IzK~yhT=E zY-uOMg6~bMrY9~e&MM}lti!^6#;*1xwC+3z9c*(k%yZ1<&m+^1o>Xbkf6U5|b2yEZ zwT<1iEf|N5rVZhBI2ea;sO~Ont~Ax&0e+?S8gQv-Z1s$PVO|)aO2Vp*u~<_}1a`&r z%nP_fpQz~FhjBE7JW1ay@J?)*xnZ3T*O*2}M<+(ypq9AZsTsM5?D|R@O`ZtdN#!v} z3oR_gKEmflt)fo7Z;7>~W|h}hODu1Z_MqTD{eM82{1&|b<-B{rB48ymfv=L_ z{g1!lyU!}m^jF50AWZP0M-pu7K>7XqV}EgMFTBtM(0%e%3cJz0(2l)I(BbvA`eocy z)$uT2Q{KIuAHj`a#0Fgg_8Y7TjL#rZShn!sUbbU5#uB^RV>PZ?huBrsHf}738n2nZ zKA`t(ixj_-j>@?M@nf9M8TiLlWqN4(chjXCiP5LyW^M{c9OO>FyWg*2(U@dzO8z(j z=`!%&TtCS^^VGIPs)5=4uY%P_C+?r8Cq{^k|KDnm(HGCnO<73V7 zT^$Z0W=)3oP=jBPCx^I}>V-?*6}1N%Cw2s4_S`>a7ta`xguRYba%f`h2+ zp5IpM%uC4{iB-x-@fQg6^#je%Cio$$n_;a;ctuAJgDy1N%ZG_&Aq3zS70&HKs6I=I z{5s#J!$0Bva^M}urSagGijy@*rZQ)t8=R@HVPK@ZOt9u#0oSujg`OCi*E^}@Gqv(` zJ1J6PdizZo zNS~q-Ssb6%oD_TmcC89oN}@!&OxWr-zL41}ez5b{@Vg=CR)H*3BSLL$B)D#yNo7#; zKu?nF^EaCtV)q^2xbYX6iL$!<0cFIESIX<(*Cz){6CQi%H;HdOFcrd+nS2U99cwL4R#MAL9HtP{7-)F{=aPQR-TFYZm%ve&B@z1sxiEkEMzg{j#v2>UYPxURxtqk>hJap;=h{+^0O5zj$RYOVkUzXSC_kiW z@0Qb-rn;is?-%}BuWpy?e$}IH4WX+LY9sb90B_N}nZTb{>$~-8TC65FWxs64>-0l9 zdKsr~lIJEn>CKa51O3@~vr#EWQysd9LR zO{;eSB)o7~b>JGmP~3otPv#(v(4o?(<8!9h%Rs;()Y;~I_HKaQwdLkzv3%*=m7X%L zWH)CogU^8S2`vzJ??~&D#0Y&>2T*y}DIA22nx4PTxWUXsHuG`>cNN{x{c2UKuvp(z zB#pXtb~Qs$5N5JtmY|U%J4pr|vR@LlFE3TbgX9y^@fgD;c$Xlu7Ci$l3UY38RpC$> zhHC}NAgS2VJGh_@Ez}loB*$TrXjIvg4Nt^x(#^s!yjoeIjVb@+3Po_BtsNC%E&|6&dAL(0&a*KXvn`XqEzyKM&gg4{FLa~NxcPZ$ zB|x%-B8{7|SG<~Ip8`$+Oxy%^rlT?YMD&L)581)Y0B{IORgLEUv2bG1XGxt&07|J=S)yM+{0e!-+;-w8TZxpFf!!{=j{iFTCdwzGzz=n{9*BM zI5eoNY|?Epb}-w|=WaMIzsv)N=k0Oa1dFFEeM}dx^QYh;$je#ENRyG`o{!}mYU;qj z_wCC|k+(G0lc`1`m7A1rk!d&{?~An0p!7Z-kMrE!&gZr~P2ld8{&~M#7saGlzD$d< zSoN!_EQ9^3{{?Ibh2=|!+b>g%-Y@&U=Si_F%jpVs&DCTwVJcwVGC_{bbcin8GquL zlp)++*N^cq!K>Idi+ma(G~Th|RflRXU3aRTJ<^nHWD5m^e$UzIzybDhB#eChV`s{9 z>CQodawW>!CG`q*bi?E3`kSa~V2bp~&w zZah!$#sU;LxnYp`CLvDCn$($J|I^QRH&zy*zD$nh7Q(U-HLp?!2EXEX@Az2IQv*^G z+EvxNgzeCd64718%g7xQxHdyNy;=M9!{~y)hTVU2ir_aif}S+N*!>TdMfH#WHV945 z)4Sh$6nC$VFRpuNyHPmoX6fU_`2Fz$YW4Y+OwQymm& zvW0Z8YM?ba%%So|niOFC0T7N=rUPyV!=?L}hiw^eoB1}SxZul|(tY5QL;vxy!T_5F zLHWFT2pl4oPr)lSg#z$nKbPY%9qp&9HC>YTzl^cFTq7*y#SQcT@0agh@(EfiaqHXW zcspGkdqeMX(4njg2hk41vwZ2kKrxvF<8k0d?{~{j)8!4&`(C3rz?;j=>DBbOrZMyC z$8}szCh_EBUBjf~3oya%ut628v|V&ESgJ)v8bTUvG7FXJG=@Y>9zmmU68q{BseZ{v(1^p=DW(X0 z#RB;ePa$$Pvq*{1TEZw<y_W!p?>)LZ~lmU5mK0NnCiH$<9+V=?a7Pj`a_;)AOI9 z<~eXV(=~wC*bG-HNEt~IZc0O?S0}o9p#fi~s{3MLY|Y1{gnj#^iq5o8j)sU4iAx=f{ zh*YZg7cInsM@D%MW4BL*^$PE6ZY#%#rW%kNHk!j|yM=wwq4zu;4GC3*@dLFdqx504 zY(S#85qwL~Ez8di*XQ$tgEr)NgCKF!cUewGPeJhTgzJFq(;}F+t8xDF96SYXt_>cU z*FUm}>{vC2^iVFBtMz))v{x_Rjoq~D#^qa}tUHPzW_kJXWfrf6olVp4ZTx0PM1e)D@q{ za^tu^4irof#XA#HTfc%7BVHaQFG^=^TZx7Lb*gsUS#OxC%(URw#G>h#Dw5D=C2>U= znKv`??g#VeBtv;l=;Kww(5m7=A_Jq`(<0#zEG$i=m`S{gALzHE9W$)O^onVxl?Nkw zmn@HO!29zt_VSn50KQWTn@ZI}H`WhpX;c(&ARCs4qlsFhsMp=RDnC64o+UZwwPIQ-dz}) zrVw-d48d5+k0rQv-a8vJ@3a7-);`p*i@V5gXi4LM(7_k-ZhIMJEr6GcL%JLbxuc{r zA*)S7L$#AO=gQvBM?-9W0^2`&i+W;pzdTv+Y1v@VA}VuZP3MjeCH)iZN zymqtq&+MJYy9?eLHS%ma1p}%aUiuqp$&*M#4JA7uL^53*B9+`)8@h~r)JPV?nDUHc zaFD7X1rZtMk%C*$TBK;%XcPR$<=wxh5%ltISabf#V>buyujg*V?-O~Vw&4r>*^i0Y zZlFG1RO%gmgWcEdn`Pzo=zuQyLv!%8!$(L5uiI5~JepcN9c_W;4zmw#uBJ}Vp?FHs zx0}83o^-o?O%CK#QR z2z|Teuw1PBpuNAUdN(Vt`rERYO%<9n}LW~WM41yUVb5NX6{2lQBC8ZFl;n4cN(9_Sh(wt{5keC0JMcHCyh!_L4s$DxT$5C9XK z+&&s4==Ds_AjGiPBA}k>=(FpLj&_~Uq%xr`a7FbX48~#br3yH(O(>$+TAQ(^<~dDg zRBVfgu=Dq-)`Avwp-4EC;3m_$Q`aVxQ&=&XS#h){p&~W*^_M6}C~O}o5qNA{6Lc%k$<`@88$=ynepnf7>FZG@(j<~@LLeVx$pdU;QOzo znf&?N@!dWI)~_mk=hS5))FPIu2ZkH`OYEm=rldmRz-Ju`c9~{k;YUoLlB$8cMa=PAVnb0GSmf6NznVd^ z;b23oLjeO$j3m|uv{UAHs2IJ>G#(24km(146%?brRSfb7QWAg;jG;+*R|}pZpR(G) zOCQc^t9*z;B_8_37fG)fN+|1I##C@=9m(jZjNFdU%#fHC99;nxv3m2b+gb4l0bU1PC51@2``NjX8DD7wG<`c z4wnWbXn57NqnR`6{E9UkL`h=83(Iois*%g!STV2^h5$mrG89(+z@W*f*d#+FlxgcM z>niaGu64Dxi1HVyE;v@H8s5kOgaf#$mi34>k+&9~n-w%HOhX(Noqi7*Me&(G-jZN9 zM$|`S6uVljNqjiCldE*I12bK+9iAg*57=el@Jxy$_9x%j*VNAnPpU5XkEy$VckK28 z?|)U}+28-e8Fv4jVfQ&xGUhMC^UB`QUsU^xF`Sj}&&uLY;Qf_IP|XVi-+hh1B^nb~ zEx7Ggg=i00RzlQGz&?yhIxRJg!_)&M;k+v6D+k4W)6Ua}z#%x%I|vrY{_FF0v~cG^ z-+rFA&rgdFk7b!RWs^3a-81RY0eJA39ue$4|EXaPmBVJFc(0J?U7*{coVVkv@$u!y z{r+XyqOsvvVn2x%wyRr6!+SKqH)S=wT>-$+meA&aZ-=t|%Ax#pxth8!v|0r%vcJnk zetUoW;c^JL(CY>-NrK4p;DG;?>K zYWJ=K1Fqb!#wv3x0+w_9EER}z-&hN~BkkI7{fdWYMxf9L5L~YF|ykl72=FzFfGmzR4864sOPC~3Csoqr4JjbMGebtpNUdo3L!%86LY!I z-Y;7}y_fn#>9!Hinn5`JTl6kt!Zujg&iBrfR?xX56MPrTJdG(B?6`dLk{5>B_U%Hy z<)z}pJ=2T0X22Y`uDbl-P)sd?25{O-p&WVg{7Yx~yIOlD`az@ENai11tT2pxr@|lR z6(Y*S>*70a@(*iYoI#2HuEYF@+>;r*-4sONS%3Gv+}FFj+=;g^vAj1J@`RbOFIuBG zWjsLi1lS%9x{Ab$3OA9(U8#Tp%z#z~GF(QCBn5QkXMnp;a_Q4zquJ7Ee_u)w|%;N=CO6&n`T2 z3VkB=;Y_{P-n>&TeAL-lRQO9;+bD^A3cd;6e=FbpMriU+fA)O$KM&abhBLAB*K?X% z1j@5l2?CsZ_UC}g9*-}6GU!GPgF$!u2ED6ul?hW#+GEu|kM~#2!|2#-AB^fg9Plcp zaHLYDTm9aq5DjkAG6k6;`9+&T^gSmP96SUM4#F1;R8(de&V>r#JujD)o4z0V=k@Yf zeV#Xm-2sbCH{6zPn4UL72vxswFLBWFMN7BBtcM8`bUmFd?cIG>4Ob!xx*>3XY$(6-&k=quMqqlkjwfqBG)t$x1 zN?}rCHqPXXj!8&!I^ts*sj)gDKs&~v7c43VDpLrz;El+cb<}%z+MJ3}A9}x)#}euA zLFN?m$Twh4^0SEVGK)SMSa-(M)Lsu64(1GBw1TuM?f^phd&1b{Dv_z4a64fIEq)`;)qYh!olxR;&J}4p|p5BawnD1}5CjLhqqsGiK~T zmJ$=Q7#4{o)P&OUpW1lLdC98-D=SsWBnRw7OHeDO6q@q~gml`Ui{ys(OQuob1Ssyr zmBco++rNrcwJFI;R{^L`X4jj!e2A$VmF@U^TD3>v+C`<@Fvspf)o1KZLcpDQcQ{;R zlI36}l*z0Uc1h<$3Oh5VWei{ozPYOW>(-oa@!ix2{;Sd5hTVfk&f1wetVY-Us;5Y>IX0ZNF@Cd);b5Lh z`vo*lNAqI7ojd5Rm`Vjyf7o(g=@5AV>ic-*Mz6GCc^cacKbPZlvG~w``r-I6f8FlV zr=Tb?eh29Rd%x35J6n_`}dS32V z6_fp{YLN~bOh3?1m+RH^)=lASm~vK2H>gjKA3x1M?2R`0Wp(f1`#X19#AHZj7^JPR z0X6X~BF^NGM;oTYca$?UkFTFUqnYPvW~6sY+~y01?^?sQxNgMQDYMFq-I-Ymm{Y~_ z7oU(SUUR5W&pLmRD|R?mD_N*KTMvCsl4n~*NQ`t(TNUq#Oab0${3Sw zD@ME`bw-G^j+-R5B&$%g5RkYg{}lR~WlIm_vB==?5W#{vTjgxr&1T+xL_s5^jP9i~ zk-Hm~^#jDJ^i;nozbCChyBUHFkbPx&t-46j!cIHN0R^cGx9clLHf<71w_-kRD6&KC zIUCD*O=8h6Y(X|!B~m9e)#i6hKVKmQ-ZZV}#pXU58liy?pNE6UqglQAgo-u-b6e|&ZHgvn1oxv9H)|9)s1 z9=MZX+y>piE1`O_2vU$sSj$eQ_D&)e$!JAT9fTU%FQw%hnwt?Rvbv`TmF1xG#aX4QLd| zwTa#CM%tHbk1J3p4!b9b`@)d3RO@%|CX04jF$er*fA!;c_bY_I%2~dW$vkhw3?jLTijsr*DD(P|nLj>tD8~NE(DJ;soun6DMF(s(VV0YwXnBw#8!u*y zR77Tu9MgeVg$=)^G2pS5Mdp*E4#2b%Lmg%Erq&X?w;}*zT`+Lm&Z0MPZ18P6z6Fi$CU*=%5sI4f zoDO`POvp;H=&y{^cjn2a)4!-C_1RuB8m8x1xdw#HWS~IQZxeUclqubb@hbx(4FkLh zNa)06WQ@8M3hqha?%{(n_OrfBmMTQv6n5z-CWcYBXTE$^*C$>j3#AE5;w(ms)Cz6z zxY8?pCCI6|A@r#z5nqimu0@IbUC4X688lXQH54kPa3D{9pYQ(d*!>%Cj&+`SzWeXr zgi%=t)%oE4-lQhuU*L>?|BTXjgm$}`dp{lb=Yid4e0Mvza}2$k(fP}vsiy51vJRw9 zRiL=HhxS0;Tio`RTgwNAn!q%_Ei3LVkJWg&a#L)N&_N8{4`oqd_QwA4FrTM~s;FQn z2M<1X;O$WNdEGxPJ}ew~SL3w2Nf%EynHt;6V+k_5;eTJK0POe6$>bwEH`7&|{ZA;^d7}0qgmj zcQ=#I!ThBi?XUX&f564FEYV?h$WrtQ9|Cu*fHiUOoji$v2a%bF4SQbbL_g&$=i|2)}AZ{i!c ztcNS>yn!zi_)F96ccKbunq|JJ-1`}#$R@`+Q>bd>t=8wIK0u$W&U_DAD44^_FyrkK ziK*aJ3NXY))9o1+K=1U#oP2Iia`D)3GL%x?@|n6JPh_AhZ4Ur*B`ikFNRrqb))}U} znnEn%B9JmZ+D>)JATM>uG+ibDaI7n$A;2o?ym?jP8!Obj^bCvlyW)mM?20#mBZ5-c za6~vwEECwz=qoa6LdhO^|Cs7U{6WBDzp>ijlL#rZ5F5%X#B&%#dn`YWl!P;? z#JM{lYlE6M{_B(MmPAO8tWYy{mz;RuZfLa87>p%MroD<$8fI2kIyi0gh1S3BJZ1c4 z7~3OD^LoO5<-}JmZ%zdZk=YD3s?p}1FdCg(Rt^Fibx{@;fLv&6{bsL!D%_FvbO^BW zDBeMV-tBm&?g~4ql;hJyk{AGKK$gEMd^q?keD_z&N~^0JIFogEhSzVQ6F`}5lR;(bu}1(%fk)mGoYZn51^cOOi{jq%z+bo*R26=v_}b+a{HiL$7+ zkeyh-AU>zuDt~bM&@f_ZyFH*;xbMrYoIAm&s^Fzen?pJ;`|41ZRogGu>+REgJRLjq zKDuf5_!NBjESg1CY`Cp$c`9zMNV z1;Fn`koNcYpMLoC!}k-g8F^L}Wf@lvQXf;$9gSyDh~DlkZQrjQcyADRfAjs?9S)!R z#lCvze|-7z$MJMo%7*MGFFXFUE3H<9I_a>L^LzTanf>~i765vu{KnU#3HOaH5bP=+A?B~)r_5xoE>P! zA}g3g`D;FPCH68CBT!Tq&jJ8C*%%=xrG`!LG?@&c;pUx>ed>5@s&UUkDQF_)c zIeWjJ(A#|<2_EfA!fR-D;aUDI;X66Gc+_91<1JL!A@;r}$|Wi)JC68e0DI9SR$7<3 z9N0F`(VN3^rp+5O{DG=FhonPxxICa<_-Ex5pia>_goahEGqoWdh;2oP@DnhJm(@@i zU=0gc3-f+h<{@E|F@vGiQSctj*l`TC4YCcBsPi{LazEADb-q`Eaz=MrT<#z{*R*R5 z&yw4Pg9R*BbV(=4KQ{}M5>&MB1C|NdMpt+eq)vQ zg&a6uqrzLn8%B|#wwxx2p#bsJ@D>$kyGBNqNUURzrz{*U!)#SzN#4AFj1+JW!Pq@+ zNCmlz3kJ3Gts+|Ra|uq2$$$Fu-xOzZ$}^$7+w0^cr3*n zq-RRoFe#sxyP0v0BejHimh9oll8*XdDV}((-dW^nrVx6pzGC*lD5{%0YBWS_niV_L z99A1*`b*cLb&6>$;99d}V@V+)2eQ~VSNbd|hZC2XSv8dPo#`YB?P;WeNsSN@kv6(> z=$)ST61SOs&0!mBe*Rid&4B|Mcog5UqJ-@v{s_$qM8camjPF)IuYTt3c9-6I8dIy& zS$Kej9EnreDcxJU#?HLz6x!G}AtSzf>!^xi;z7&ZdBPmsJ%y_5L;L5jQIT0I9V4=; zqNs4`UnyFQDkPv4y_CvtSM9DzeI{;XJu|Ax93Qie)RGgea8A+=4dS&iWg!(A;*qs9 zWJpe=?W_CTNn#NLp+k>Jr7Fu{u$mI_N-z4zDw?I zZs3HEhFWeN4=QZm$URn9Ul>c3uA$J=F1=a+%7(=8?MO|VF}|pn z1$%w{{+uuQ=_l+jzcqNf*A8#!lEFVYn)lDo&+BDte9GLXoACb!$^^Bvl;Y%Ji*&)Z ztj2wN1bXMC1OJA$ouFYGG1`gO{c_*To6@1T1JnjvyRt9K??0^{USFH78^0G<-&G&V z+aKOd%G^Df%f@}#vbb57`NyJX{*?b!9{Z|o=fMHX#5jL?oIQPbI#&IH=>7O^_3mBy znx^6GvEMHR?0kK6|NRi>DO<(+&1| ze`z}m)X`~=src7UWbengC<`KcOJkW3Vx-^ec#-z`Ok=z4dz7$f*}IScD> z;7lTGNw#!wP#$7BI)(}8S+6vJj!KZsKA7pG%H?KE3H1??RP)v}Q^rXdvr^I=>P#bv zL)9Y1GO>%Ho)kCu&rRW0=2P=Wonh0-CW??Lx}A)iILD0A;O0Q0Q#VArvtlzOXA>m( z$YJeGXca}BxA<1;@UBNv%6}wYzEg$?+ujp#hU+D4TEU~?02fp8DMo`EC%_7U& zVr!e{WRoe(D)^nU%HNIeJ_~^znit-1Ccg#m_ZNf0Lr9DX%PX#;tyetn5`WGIy zn9JRJ*Q*}by-2D0b3@j6Sw62CxF?tE=hlIETtB5{nU&>qKOcQ@Zv}kc-`*DA-xOKZ z_qZM}$Ir{@bP498SWU-dPQ-$PU2ao$o)MLQ*W8;t*AiY?8{9!%$?2eSWz6`3D zt6bon=Ve^N$nK!ED8PX?ZTj%Jlm-PDe(YE4n`1BVUKYhm5rBN*rV?y-*+AcoTq<`= zJjow_tQyp%xvARZh`H=Z5D&&VPm3I;%FH}Fn7OfH@?o(VMPgFIS*E^1pd$lZJ-jkY zlgcC`ut;NFxPvUf)q3YCboW%8(a?>tB05v7MVUFGxf3Nr-I*_>%alANfg1OMu{G?_ z3vG(K$c7_jNKxsWX%dWl0eK<^sLjX*8a^+U^2NB@tmbL{rWq|ZZ68i5trbI4+IYC` z2J$~T>y@-?7EY;a^N znsF`SX<|wE$hVMu$t*9NekpDaRN)(<-X;&J>ZcDCS-};4Qk6}%$~BJ-z7_PMvLhUX zY;ntA&P0P=R2al(fNLwS=)49+We{Oz318e~LeP?7)Q^$U!XIN6Cer8InpQKYvSf@H z^KGdK>x;dDUxpqXY8zf!;m4$hLu^T`QGz`0JClLq&lL+Zf$AG24jQ+8$K(ET{LEmp2d(~m^ zO}_hE5wLIgZn@$;-EF(dvkcg;x0Pr3?I8Ptm1pm%64WmrMMb{*`jkg?LhqlXGC4=@ zX1pIAyk7@ow%jnqdb)-i?Dbhw1YM`^j`$R!#bl9?SG$@vyBbc_#b* zF?gNN$NOnt(TOv6AeTAxF5Jl8jHf^R@O|*%kBc9E_~9ll9gMn9zpP{BZLi9tSWZ_} z1_q_^q&0juZThr*nq39}Q-{m#v7F?K#p1P$)8Ju_`m(@X633K~6TC|_4nKVeDA*=| zL)=&rzZ+~ckNtT1^0JC2%a{B7vZTy}7R%UuN(FwKfv_mlX^y-NC6$D!Y02GZJRv~# zX_g`umXdA+RncF`btT4KpA}2fFJCW)mEwuNh<%zL^~%(ECuhlW9w{kMGj|Qm=4x%Q zSPU8SBvR=tSBQ zOR-DPCCSvQwT zr$z+}=86?_TZdww$uF4Xq&8X3NmSD*OSmN z^H$+A9AYn54z-s{hu}AEz`mK_-RNnEd=yrp;O`>3xzkTViB@4uq6lA0r&Ofc_zY{! zLeg}rEb+|@L~ZHMdC%REvl@0pk)@)0!;v1)X5JB#7Tb8_{tW)TIFrA;;Y`l*OxS() zKcx};hrd4=E8i5w4+(;2@g^0Ql`Tpb`iuAHj0q#C0N!VW_W<6bsvWT<-ZwBb*G+}K z-l`dGw`Yi+jvO#k=$$@T3vp^Z3W#q9;1An}L*DKy4B-a~QQV0B`ugC|a|;Z2sCdW@ zZseW^EnPC@{MgRXWsE|x)D5)miQB$heLwk_r+>V87b{-1Igb0ho&vnr>m?*1aee^e zYJ+)74+K%6*?O@^A0NN};nQ^QPK86dSj_4m_%*l$8UBb~g%Z2a914{W3pWv$Sw?Q% zUcQvpP+uOG{bY&6syugR!ht@WG)GMizSC2%c!CWkpN;c&Hz7c3?Cg+d z2Q=vvai(~aR8}1^-x*z$W+m^anqYo+rulc+rc3)B?=s)$q&TAFqype@9Em%RJtHFI z-i6lE9r{{8qro|ysJ>-LTl3bmxahD%!IDi zn`yzZyWQo^*d`J%u`<4>^p7HQued>-0w7t8pcfgG{#r;5$&Oqqk^+w`Nb1fC)i%ix z59q6@3!9rE6A5vtMpop8VS=DWN|{=r7>p5BQQjaFR=M8_gOzLZCJ}|M!k^M$x+u83 za5E0bmCO#_%-3~-hv}rT_iES8hKYz=7jZ1N>@tc<;Z#!eAVYu=jN;7?!S8AW|MGjD zc-H2edvpHlzkOACcCzOfhL6WKYAcQkLEhKn{qnvq1N~qF>*(^glWERVF<2yfm5d$7bS#&ZLaH2U~=tYAd))qE?$RN{fX877XI*Nzt z3~dzUommpAjnvjw&u16Ee~pW6kDcz@qcoAGmBe;eqP4Bc9@PPuDl@K}!f;SCB37T! z)G_nIO2lY$JV)}r33<#*jD!ttJif?ebSOzv-z7-v z*{(D7oybldRI)(f)+3@&GKy}-xx7|UhEJ5mgk5MqL0w*`g+j;?6yS^R-a!mVf+Mq| zLdDG?*{ci;6iPd5EEI4u;5LV>JK`qW7Zh2pEq7~-B6klJw$JYvf`FXDSb}s4a#U`7 zsaHb_E0Zk4O2ynAbpXB#eFLgL1C@c*sqWpVZB-u28@V|XId#&SNY}jqw<8LqkSU*0 z-9VTFlS$(K!^C~Vd{_|D1?TkTyVcDd$s;PhW0nZJFCg{H zM!5}{84Hl7sPlsxAqgpU@NB5=4m;ms;ciD5S->EJ0U}8rwNK4V78?cU(EYdQyUBO^ zvD;(!-+hhU@88bd)R}PFet)by$p&tg=$JR2EXw@hVcw)}E@vwP(K~&BEgo?v!9!V9?io5ixQ|#Y`f|Qp zuSfC@V>wL<>fm!c)$DPz`IEEL)Ksc<7V}K zbu7X}zY~XOVld+g`1`Zmv5us3+#4S1PV97`)znr`_tX z!8LLix^M<_$836xX;dfwoYA8Lv_x_&2H1*2tnvgy8+(~Es|6^n?A(j%Eb2@-N6uVg z!=lRYR~*lsUH+&{hbln}NlfhDe6RwVvr^vfoj>T^D1J#z3DknS%bAW4_icCwvRE0E zj6q-yi%+-m@Rn>kt6O7sq#jatn_{(z21)8^Rcwz%k=7V@H!A@&AUUy^sfa6G0V>lC z3GxaoH}B;&8J$Q=2PwT;b((DJ5cGJbZt1S@}(U_Zz-joo67tFaB^MOnmp5k>A%;l3cv6 zE)f0d#%_vD-Vae!;JUBB4c=@$8=bKu+fjo=reCh`mt(v2NrMm4n2dny2l_2Zds9HT zeZUeEW_K7b^H((MY@2-hxOEfn;^ATO5V$wBZq6QknFs0ddF4K@Y@Uz3n{~@FY7pW* zdP;)@DC?kquBz33?H=)HJ?PuEM?LV>^yR8w1h@CM@3J%ic;_I>WA_`;C5=aLH!*)c z_DveFb`nvAbVl~e>Dr<9hhHy$y}U%h4L-e$-B%IO@*$W#qQs2aZK_a=LLqj45wYG^ z4xHvgUxS~Gbm-pPEx)F=fm)m~-5FQWArkp~W02*ZyQ!C{+mujyk%eHL zw*>D(E9ERy$|!~UJCpOU4UKyANWov3ANCb6t41;E@K~@Y61|9(n{L@7;h8yzv0qWe zgF03nm=$nzsOV%E3L0bB7S=H)b{B?nC>AkWO%utl2g+=>Q?XCyBUvK5O>CarkVfza zgr$*?KIu+pr=o9}G0;iEV<}h+aorTw=p%n^5nHV>Vih16)HI*qN0XSckQq}X)E#ga z6B6rG-N?fk^IvVyFp>W*3pcBa7n74nP#h<`>PliYdRr(MuRw=$O4nSWB!!APVYPF? ziXRw>#K3#B558@Q|3-fIS$wzcD$gQdy^+!{D2+B5kF}trH^+_9?Zx%Qet*8Kd{4sU zeOpyufp>d7QfK99Q;9#u`*n4_oIV4#=iZt_E4-Vw-RS(9HYWAv;7y%3D|8?L!F1|S zJ7rZv%9)#(yeP}6Oh-RmT~)!hUoTeb0or+pGR|S6+bMH^}UFnm&+=vA7?r9 zvitS^{(f05_v>;oUw>HzEBT!ql2kCmB~irI z4Zkz<5${~4vU+tX#{PSSXT!2c>(2kG<7NMvz7n`ocrGz}L!3BV+IQyix7pJ)Z46?q zXQ%#0UHz(hQ~hQKp%rED|8udZgt3eb=Nm5%bhk6n?b*>!dwOK( zfGFiUhPm`N~b5#8(~jp(IMG>|wvPaGg8lS#}J%R5A!rP4{~fZW|b3gkD5_1^L7R?3^*4t2>|#3!UpsOO4(34N!0#0lAaob&Fm zR7Y#@JJ@~JH2gK+O?~$n-F?ys4sJ@mGXCX4OgBdD%Aqz8dc5Di|7qY%Br$p49^apX zH@X(q$AeEcIT%2*iDBEfqix&65T8n2GSc!As*+c@Cdr-5%dPDznFl-HZkuE8Ap124 zUJ2|D1=EMcb_?&!wkg-;=(QT}pZj2u7k%YM^|IaHPY+K`T$X(~cX$Zwb_l+BUY4`G z$rtFRL4fw^YFgebZ_Cx~yJhMAejrdE`?3UoUB;TO%|+j|QjE0Y=LT*XMv?^cWaT47Ou7+pz zjM0M_zL^V7Eh4S=wO85+Xl+**QmkoR9GNmqvaZnff#HT(tO#6OH=N=XLyeFdyCf0O z#Av}#@)$A;;gE6LMMH~+{=Jj4)b7|$*18)mb8HXNMV3l)G99QHX{XKT&i1vy&dtX7 zhC-_odVFZbiHC}uLO=G{0*KvZ+@0mk;OI?mk{jjA;@5_Bx+;+GEY>zk))c4|s_87E zFwt6*i-^Qid@7RXBNREBcsG?R9V4@Fg}`*&h^vKq(462V7<%J|Zi>6r-CgjlRpoi< znK9#U_1$m5+oAOz&T1D7ybMikY?1Tbx~YBcChznCtI7wuE`#7< z@c=%%tT-1xk6~LJq5Njvl;i3CSR8_^sFQ~6xdPSZz^@Fn>PMed)7H5PH>s331bUxms3_i%SgNfbL&E zEK(3Jc=-ql+YSD~BhH)j5$6TR<}_~#3q$dNgeBed$Nss>;I70A%$nf54?yoMFDrN7 zkhe0!Y>s3>7%$!IhD<780sK0ldn2`Vrg?}v^GS+@&1?lOd0y9bZ;U%hbpBd5M7Hut zl$oZF2DHpug(Ghn7GB1d++;c4x^`qmAeT*9=(p}9V0WQ~MYBuTo~$&o>v)J2J>7*S zd?b?cvVx3*kA4Fe(^;jC4kSNKN2}wj8@=4mmY1qq=A4K z7bP;8Yt@^vfsG14i_ik$SoxuoRvv&H|!s&HMvplRBW@c&Dkpkz$Em@7R98KMv5%Kq{fN*>mhK>dqmGyZ0O~#%}T^d^64Dr|Usu^1i)z!EBXHaH$2szw%FphZT2#flukg&L#eK1uH=oN2!6ofH1qLn<8@QY< z->pkDAe4+aX_XGxj~iPyVgS$l0FIBD=OX}ZHFxi6m&@{T5zHKPU;g^x*I$9)d1Jy8 zhZ&dHWd_VGaTv^kN{8PK%oHYTDWz&DIo4xE`P}E}VFreU3rlDKXF&$HC3C6*1jf3X z|M-zb!_arLPA5}^Whes0q|=m``r_euFtO1l9iJo}e4=X0lALwOcUDxO&sOGiWW1@u zQ%$UEoQMTpS%rggBTNCVMg+(r)Obeb9KRxiTj9T_Gi6sHOS$8H>!|KirFg>lmL=D?Slh3NC%2h{#miu5Ne|Ez&wGb|A7;tQkAy%`P8D z7RzL5hqX4t78e3nkPYZNr5^J0l2cqvXa`3)yoiWlBNEfC@F^hJ`Biv^bnJrI%`SID z{~bq!jjt{B1djHImU|Xk-~hexg)at{SHL`>33Vg!M6ZSuU^=SKCh?>w{Q6m>I=GTJ zq%tRq%EB^XI&dNxqXgs3$U8-|NVt!mHRp1C)r}QKaAXhVnrA_rgt6F`@-ia$U3s@z zbN>7`i^}JjoJmdIgb8ZyrbZA&IuLsI7vueOf6-Syjmm?!`(M?*1@B|~6T<@s!uvs` z!p%?p^>zfgNn@pGerwr4e}WW21_=@`S;;VO(N{S~PkWE?lOLg)1_#^Qb{+)V02jrN z*l$+V@~W?@dE;hqK;YWp;(R@>DuH)B%SVfJ{u+>>pm3wiA7_ijBgWj|-McJx-->1N zP1AUd$#Goe2ZRSIwzZ*)9`s2$*SLIqF8ie$+T9gElg~iT27v7r0y=IYCdz= zo?=s(%b1gf%=3=a#>Hn~H-L9^(sLW(XccIlSBZz7%Wkms@Jqy=&WkLJduXKbRl35@ z_!QmL4OSlsvl0>#Hr+v~fk%5+@F7mtK=YQhl(TOPK~8iafko#FdXL z2M~J807C9#VkMcXj@i90uPvA`^AY7_=LOIbJ`%Jvfs1~^J-}Uo+8d%rc3Ores8?dI z(HN19=b|q_sI!ZnWA~1lncZcW88fG0K2%VY#e7AEn?TY4P5; zx~mzzIuPrL1?ecd%7D~Jn_?r@hXctb@j+G=z2bhh$sMm^CSYC?5=W5h$IJ^*KWC!U zlV@6y5eTDIM@BrqgC0D}m4O1~3%iSv@?FrsOBJGoF;>|vt}qf=Q>fZ4VSig3{LAlS zH+teZcmHpO-8Oh@UHOMMrW|!wdaDk7@DQ0iOS!!tzxN97VeTet^8PL3jXw`V_kw$I z_<5ZkTQBT3=pGC_IZ|Q!p2Cyd$PzbWYgJhSz7O-hor5Z2v^QEV$(b~LInT=yD#F?0 zAqN_lW#&G1`HVo=raJcS<+<<6JgZiPn`B{hEFYV`LUc)4P9|~s^cYYx?Z(>_%!R|h zy#3OgIx4xr%nvz}WS^e0{@J2mso2J#-Y-jlH;RDs#}6Ma%f)|Q0K0*?4nCOyh?V89 z0gaPD;;i|I8yo299Tz4Z&1!!eR0TYcfk`H50M&n(b%S z2+K?;=%Co9mqkT!9+^4#cC}Sg=V5HWr5%n=Z1oxIZOMTgy*ndTd<1<{gm&$_>_Rrp+mFzf8S@lSy(b;C+^1erTVCgKoG0>x zcWmvkRB%OPak<8EF!8~KWV9K|WMaoeD5wwVSiV_@$_k_`E)MO?!VkJ;OBkDpL#3(f zWv9*tWuS2Q79ABU`itfo`ePGsO;m_ZGNjb7oyPs!pf+fy$gSAt&qS6Trp;<+yiTEN z8?(;?svVRTY+LB!qVqN%M(*G~CniJGb0A@!?5f}oZ(XQUxgbz`PXfu90%>33#X++~ z39LMk!~F;sPCoGpO;YevP#d1Gcf*=blCv-&o5z)cDAqj*{_+jJTlw9_nVhiu@BZ!Y z{_uydoRz1VVIxqWD!JhAi+p$u)H5H*T?Y~9LgLU zNfs{9ibLjv`L2iNkSnR1-W)~>j-V0*Z-PFwV5{OY`g1^pSE!C8*U%`@d;U4i1Bc~f z2d9(Ijk_plpP$FiRXHiv%jK$yn>qJ_Ws_9%`LS`&rRRnlE)k@je9q8 zx6AS)DfRs0=l{k^9$YGXDK*xgP2f#?tjg@kom&<+TQ+%}KR%`*A`IOukC{8o4q=KO z2I)XD3-XLD63`&{?OxJfd#d1FWy7)8-X?=LesD;3mdWb7j3W!@SH3Jp4+CwYp|9}r z-a3M@RS~d~%Y(g|q- znCg3H#l}qIUutN zTarqB6eH#^W3D3$-m+N2@GSOfdM^=GzLlS9xFAWA;9q`YtbCi_{TpB9K$!@z1>J)0 zu^?G*dVc<8{2sfqGm)TQPM&P>0&nR9**APRAj})n_VIeOJx-VHxMaON{&s9B~ zKD@r-?T5o$F(>I<8%(U2s7Yz&oVqb~2Uu4k)Wl8IZZIvILsN}=2hzv+{EGwTEJx0X zo4oTDwxIE9+)m2L?d|e8f_0}UEBEgNyT;`sJwFKJtRJZoY#Sv6T?W5C&REs%g9d5R z$)C0ik>U~)WXG3QDY6#)y6(#u0vCtwXlXcRV796FcF@d9__PL)yN^Qh3HlbY)Xn`s zeE2Z)yjqQqU{Bi9_}y^wCSRVB94~=F`J+2-m`ddk$<1F%r^4zopSk~^vOgm(`%Zhw zF8(T2P<)8G7*DK8WS7Osu)kztRhA9H*vu1&+_1xtlE5dhMq-^~<$1vl!ZJ${Ed{A{+!3kC!`OaiNbZ1}Q}vx$ z$D-z4oh1ftxR6IS9vtZ#{ga!?72m}@6Bvd__fN-qF*Rj$*5ON~<&MV>o=3n(c3<*F z?8s)DD~$QFq2jD+MTN*o8~X0l*b>&21s?N=synS|AfM+JrI4*Qvnih|6iI71U{lh* z*_d(0-JOZZ@Z>Jy=D}*FW1mnZcaHQb5!EYRMHuO{V}lP(n6%I1%CX??$G2ZT!`n&o zXIy86jUEa=&@diDf_|6KH80thBw(5XBK7)3!C8=?f%jQorOn;{_-}vs9lm>DyvJNs zR&30XKYsknetah8R+-Klru%(cF~QrSs1Dbs^lpdFO|>2M(|zxz=mYbnpzKche)uWL zgfOHEoVI&{;Z0?krVkGf@J?>|PPQ~`gN2n7KLo*p!)WB19NO`CKR#Bk^YXa=@xDy! z<~S+cQ?+_t_5I30{LRg$PyY{HZ`<3pwQh?t1dRryC{Gh4W5Ho0NCdasle=U&uzh!> zr2>MhRRgQL`+SLOG`i~#oKF`Q5TNwp{`EV@7|*1ft{$h&i{r?)UIw2zp7HW_l+;}X zyLknZXMs$q)jC%k=V}-gD-69&!_e1ZG(*KfF*brk0KR`3uk(^n3em{;shgUQW*Ra} z1{L;{!0Niv#xh@#H$hzkwchaf__^z$R{a^+n9^VAsP!vLIeFmV>4$HK0}FU5tp;tv zz2|K0%5{+!8%R-hg{pHxjioakm-Gxx5ET=45*0sHVgeL~m%NgmNL~_%?Y@~LQFU6d zSCZ6q%0`jQ%rw%9?u#}5rmv>>kUMBvhfIH_sRo?4WyYFZB(qJZ3DNb%wN^q9Sm>m+ z>=V)n>aoJK6WhB;VFL^@1jLf~_D?Q9e0%hUotsQ*VRJ98ISs?2{I%erQKP*iAwh1F zB_Z%`nVLee0SsbqnVOn0vC5V#HTs`Zuo{NhI3YG9WRl zeo;yQ)ZI!4BtZ>tr8!e51TUz~qgc^KXEiY>VStCTluR@kSf(*8mx*lz8B&skY)I7U zFz`@evZ?hyAb&OMQ(RMUI7qkhpXQc+dlUX-!2@Ohj7zEslcXQ1c-Y$58k{vj%*Ni> zvV|8``~&b`t*!@&bsI0Um<$b%2y_?4!u=HaRLi9tX=af0zd|vNUI(YaK!N7)?qGGf zG_Q}PoM-ZCQU*@px72@`P2xcZWl4u@Yvb@;^&|So+zmQ=E_JlA-4a&MWZz75!%-oL z`uuK?CS*;B-F^4M|M?%M$@`=a9DI{$0&NN1IeWr1td&<+Pjpv8Bl!O6FTzYlAy%-j ztn7OjrdQK$bk;qMZh&)Rlb_IPLo@u{nd;6c?4FQ9ne5I?4hZ-jPuVtnhtZquXIg3c z;TsxnOx}KMoz#ob<81c0z5G1Bo**0h{QU8;ei{r$-P74D`r-Q@-d29*-j6)Mp4auL zs~fBr{rno2!)R4Bt7BA*YgY_c(Qy_Xk2C+?Jcy2O)pq z7=4j(c23f8}=3z(NQ1OSl!(Y07fG#sYEusdtaAeby!;v6RK)=mKQ9c3xw zRHQ~%WwMhx-mdW$L`l*N({{ttL7FKJo;(xE$*RocIvB)t#^_alJm8RX!F7=1JX^MrVqQqgE? zVt2jyO%5Nx>u(f<|H987@^}iYL4V%jo-~DgcJsnYU zawejLvp15wndUv-UTi(McSy%OSt}v+rXNTBX!u9@okC#m#@uFl^u8ZMO_)#jW8@3o zi#6Frv-|wuUxJ`d?(-4ga_50~HJ&`)JU*6+f?egg8~xA?22b_l&HnIfbo0Y)J@Vi^ z^&dtNcIRx!UIE3C4ah&`D@gvJ?K{p^!{HE0!ohxg+EGpsTgAA-wJsvLG$H1Bw?6uA zaZ~vTA4zn%3_<>KQp#dko`XWE!M5*8s~vVbe>o^L)t7j8o|+Dv)App`ClZk|$#)Hk z7(DI+ve)Z10LUq=h$AFkrOxoxaqJ70mh_~SP21PX5(~W4$EDxW;~D|2(vjj7T_M0K zC}cS-DdXT;mf56jSvP5J9TV(+o3C;z97+2Ml?;L`r4c1*=<7+9(9tqO10Mrn+r|>^ zvSr3>IBPpd!fdOmcaNheXYjZU<{Ojup?s``hgg9&EL@M95ObSm;!#pIdP!iy$(nLz z^$c@q7g7mh&H82yviv8~(=@U($+gfP75K!v&x0faef<|%HlcA0=6!uA{;01njoV;_ zXV4QYIDHf@~R#qYF6tU1TQCK#OY*(xN3vP zzbN`_iOA5K*iF9szy1${?mwGzY+E@9n2qiQ%-@1-q4!`rc(Z+Tc6HL3Fwx{sgZGGg zOY_6;uD;3e?zR_$!QQ|7>y{1cAI5dg_j$aYOzsZgqNxN2 zWdh%P6#4(*rk|8|Q9jN+W+Icd06XDls+-T(1mgPX`ulBt{fN@`A8xKacvr-}2WYH! zbyxZ!dj`er*a17nh#h7j(|oQf29D$8`27tVRyhV9<}@1GB7?4+!` zo+86AuSZ03Kg^>ag6QpcV?~h;D3uIZ9}z1sKcQ&L>#b`hN&*D56mE?(|yC_KjDAFEE3Q- zOnsup2J(1Q0AW1lfLbMLIs!B;<$LkqM@I@t)kf5gZ7^ENb%qU}7`8}TQW{643#0k` zU5DBT=h2(1Z;Fw0`UtVU*j8kr@{O&S!RJbo7RVioVIXX(7l`f31sjfs&&T>OZ!(S3 z{{AkcuE%d1(B){cw}T%)fH7XfjpX>j!kI3l`vY)oM%coSwSDeCQod$Uv32P9?_Tg4)A}8SvTOe9`fuvwe zT&R&EzVoc%XCD6@xMH)xf_6fA`aF{$H5vOc8uev&_=~&g7837!mI^~=f~{sQ%Ouv7i0Q5- zWqx-sHTUlRezLDUVvnXU;@sW)p?jCp86QRW(cJ;!Z_*cy>Lpjv;c>sc{QL=pW%*!x z`R>0z-~8~y+Ydi~xURBMb-wSA6tZ*vAMW zy3Ts$Ys2rZg93c#+zye3u3kVQ{*|>0Ur!YHn9aogZ?CUAI_5=l=jFo#?3wEo1HApz zz2hj4B_>qm{&pc=T#pu0p|^*4PT{DJFYxi;PKv_i4M5-jZe6fKXNQro+^F@?B_XfM znsOAatm)WVno_n3Do37any-v5ZSuMzCt-<-GzY4E@UJ*T{7W`SY>O>d8_F@;S6Ts} z8b^X_F(|;=5QlXttWobeP=L;oQ$tx|bG+GUBuC+Zg}t2`jOo+>X%yR;)s!zpZ-`C~ zOd2HbP0B-LtO2ZELQY5?JC(p$F;*=32@bz;V@14x|Da0NQ6{EDx(O>v);`DxiP4^! zPn;LSOkBo1*Rv*qm1|CZBalR~)|1Zqi;^V7jEFvt8IcR4d}|dnmM|jY5%;Mumo4MLa5@26Lplj)b1I(kXraUdXpWy4VZ#W z0sltMNq=N|US0lv8AZ%DfjW@6iC`0A3l@{Fl{0aMQiu&>v70zP1t4zhTa69J85h~w zBt9$><+-#{@o<-#rDRjgMWia?Y^i3>^cI~$$+?oJj3}?Fw%^S5$5V-Qf^VzcNQ{I) z9xRb7eK^<^wmf5-!1B?gT9S6cLKSmVtEe)}MY6m*wmT`dp-5V(`C%J1%O(B@Ou zi$zzKRaN`Zn97m|+h(FSjm!zUFbVAbe=IQl4d>B%)JY)d{6~oN_U8te?weh)&i$x? zjFWg*L~H0zD3_o^hifVA$v9)DieO7DT`53#+P+#J(Hu7FwZS*;jQF4`4+roV z=&hX}8vvwn7U-*mxIM)+o50*8-m$!TZO~Fl3X|HbYbZjqh1lfRyHCuRkf_lRnW+&- z1?dV#aRg(huK83Er@vwL#zAjF!61a+_|jVyql>v{Orb~`p>g6~q=jGwP{Nm2A0DgC z9P_o5Se=?eU1tu25t6iEiy2U^SB|HO`%hzkDg%6ug3CzFkJNRyY~pNZMFLHD`pb5 zvTmiVdW9-wgmWrr?6_iSHoC9_zL`GGlZgNAFg6PT82K!?2qZ1kSurDFVqrBpxG{-@ z=~sz`lW+-;NCT4^4bq=fQ&TBf`Wt457~h+Y5EiH0CX9!vcxd%c9g6CClJHkRl_|v$ zf&@?93kai9fcG~U-mhgQ?@y+9{&-J$$!H{h{CmqYL5KXG(_i0@f?DwFU^{+Inb53* zn3F*#D8IWu>kw{ow)4N6jHjH!a|U>G_^!wPSM&ns2N2-n$@XGR6y_2}~RbyZ#8oJX^~*uVYh?e+Jc_x1N3 zc#N*@rjzk_;^%L+EO@w%j@A%gtXIVfSbmJ=M#(Z|vo0aaArf32J`GY&OV3Kt|d}JOL^>Kw9;QwnsFz ztKAGwa~B5!Jn+I~Dw(|0D&*L;fkb~5T6jv3OGBD|(+3l^TB2INNtK55kj(TFP=DgY-{T^ZMWE~u^JHVqBx9^w2LWcyD@=8AYYe}10Z+weK^=>6Txb5kuUS^W!t z!ktHs5}CxZvf1!6N4lGM;Z345S4%Zbct+vI*%HYk$xxrb-z%G8p{EL#y#7*xNtejm zSDRU~q{S$LaI!k$>V}T_%9`tA8g`&R!2^+HcyL6@g-qHiL-rsqDq01lwt`3)z`%Kl zEEayagc1U`k&kRcqgYW$xP?nf^uPYs{}5;Lf2*+a{{?ct{Kub!Cja@q*O^!#Y!Ba8 zBM;kGZ{F;;Z+b!C`&WV9r*-ADqq=){HQk-DJ?C2pN78F|WkDyCo15L8K4y1TFZPq2 zZ1I$L=Vud&QF8Sy9LDwb;=*4&wih?`zP!_Hy;|p^dhJ0Ul?xsXM{w?}vByLnAKS`S zWB&or7Otboxc1|2<^RQOcJtHq4;MH4?-z^fuJ-3&lYQEOJLub72#yimH07pQ$zbS+wNKUz#_Tb$!C^ubIYp`az z$qGqTL)(((pwHJk2kHb-;(6(RS1;3i7yDTa`CW9A2A-t39H+zGSrxJZ9|l+cs`rJ<$!mZFAJvGe0#Ti<`h7Bors~ zwxA#p?DwEHyDIcmb%Of)SS9gQjb(kO-jVoKu}uiW+Jtpih+qnTqz{wld<|lb%RT?f zBB6V`z|JyfH2j1a-;Xe3vkRFsG7qtdva*?t-o&9hQEHqx4#(xRzazA7HCsLN{|wL3 z0BNP~G0O{p$r~jRCTZK>h%}-e97ezgrY+JYk6AUS>SZ*?J?x;TF6imE^sd;W)KGTK z5Z-DbT^cvFC3S+LM7dwuadPSl!M~{rjFUFB4!42NSJY3P$n z735)OFY{3Hymx$FVL;;BbM)fT`!YJV7FgTNpE)f(&q5yuet5|L_#E;5M}9l0?ZOqj z=Hl@DF={U6&G=7qe4ZDU$@r7yel)8S`ZJ6ygVo151W>?Modb_v!qxvSYR`x7RbT+ z6i5FRGGLkD{h!}>;=fHadGqGv)4A$-?>B?(%ge=_c!1@3TcA9ozl4OT_|CY zntLaHgd5D!lzNgoY$5Nun;QgB(Vc@a{C->`TF{T;ll#MdJegi>x8sY&hyBgs1~O?3 z-+pfG_NbHxLlGBi|KWc0X0^?lQ}QaB@Kx$>Z-pB6^BM%QpRW(s=ljp2@pf^OmS|J} znO+tpK$IkjSnk>UIQQrstx#`n~An#IaKWVc`Boe%G0fzP*KXZlTKBj#qtx*n~uCVzt+orOOLI6fg znn>wJN@xdz8ctP8=Yj>7~^QrO!a8d7=y1h zQLkkq2aja)iBTu^I9Vol!(gjQX-g;;sGu#urQT{VtKNX43p~^qSzB1bSi(eu)C49% zXbIc1${JU0%MtVD|oUcrHx3*c@m3OZ-(A0bXrS z9{VAE|MKO_r!SZL<8g?hdfwHIRGuyHFa(J4n=X#g^o5^eu$mWrLQh;gA0*eB)?Z8F zH@{Aa3e{ED!e(&GejPgmLJj^TutpAw>^(~+J)8vL3ElDxNx{w^SIK4AQsTl#51hlz zwvFP4C7T>d4~lY#UdWQ#hGwb`D#=7pML?}f&5ne0$J=g-J7Su8;{-H z>p+u#o4cX#9>@%T#c_JK3#&^0)+q4Zt}h%Ojjo>9yCA$CcP89s_rg6V>ZynJ!J^yc zJLvAPF0A&@T>!oBIbP>ehOYXLb?fNhf%)zZ+=kj8qhPc5So#S0UBn#Nn}?Z4;_Gg4 zU6l2h_QxrhlkpUt!SiS~9Igt@;eOTzr93P=W;YSg``4&ITN(V9oE}gRUk*#NVU7`Y z)zxmCuTdgT1>yC80>X)D2){~1*o`3tME|54KTtAQ((>bg+`0dxZj|mA*`51eQ4GI* zdaU)`B4QBE%yqNV#?r(0rgTd3jyEN>q8=Wag_v3 zdb~kHdmIRF?EUP^*VNl&fzswIovP_0Y^8jmbS#uCw31Zo8?u;=BkLvU9m{tW6NFq|iY72NI*F9Y&Qx-vB!qNl zYe9bD%cXc`eC{L#P^O_eo}ueFqA9Y|kgN%K5;_uV&d?;f9V zpQPC+YmSG@-}Ti1OcE9X?*?q&8FnnrfkZloz_jmVa=I#b8_!r zQ}+iZ!}<^L6Ss%H1ss%jyNO~3B|*8%*Ua)>-A5DQ8DMjg*MM$6B%|jYmUGR?cW`8s zV^jj?bz0s0^nDHZKBv+;Wy&0QZ!Q**kZSXWcX&A29(tH-x6}`D29r;tHje z(a=xlt6@Ei@{q^Pss^N3xq9qCYWp+A^$os-z?^(F6yHDXS@d4k=csIWr00IkIeMqa zL7gDhqs5bl;RkoSXNrpfI7soe|H{DX?P3H|38{;nlZB4&aFV)#!I0y^nS6__UV+j` z+tAX`ZxyY+p;eJfVu6IzvxczMw)ZP@OQ>Ojn@`IaQO$~Sx!blshHIs0f(9d0!+I6?4KbhPA*Axh=^cAxsaYIY95#L2~a&j(!HB zw~Ez)_COe!&?O2Z`P49;F|`2`T4Kuu(87!2lODZwCy>~Q#R{c;Z;=%Z+kr$vb`c`2 zm4o`}8#qVOq+#b=SRq@|cdG&hegyt=R%<3Kb&|ob4y~otGFa{tYwl9aYpTB9Sab|~ zLiq;ArHW?ab`#d3P;}$=v!VuEcH%sU&o{(CTiHZ~`L7V`nBA zHXUNm(%L2}eZ^#ib{$Twu{^weMOg3hA+a3-u(i8nN@(Mx;Y#7SW=%_*+8ByqS-F_j z>)5t`D)2#4h%N8cc#vB7YeK&!Fx2v)=s2g4FbT8wMglr!lK{Jil=|6g&|1H7YrpOL z*_-7$IW#8?qtN|`)v9HTD?HgVm@cI4lvF3mISpyCq2mitOqPMGuby238_GV!H)Tm| z!*OAON`3jVHF!!yt>g?!3!RKccu`9&X#UxLpIS8b5po9MtiyXsMMQ}OgU4z;6W!6$wEJg_!;vZO6Y ze-UsQ8J)tz_a9#d9Y^rrC(rF|rf2W)h@1F>Z(pLJ)xRq*QrSA<&is#zmR>Vq>C4N+ zVW+D2US^@Pf$Y397tc}#ONa=UMmzfFgD5v#K`H1aZX?U94Pw)n!3+{|O0$alJA%;U z&oYzur}ne=uSt`zti+E2%Fm|n&n$xK{q*XuChx%|^?_Gc=Fi!gLNK^>cDu>l1hmOy zCp+a`n96C_VOQnh-jYpVnuPRZd@=BUJNXKtgdIDPu^@NRJ@FkCmiL%sN3QWN!0Eob z_`b@=<8lY6_t?6gMVQeM!B_f;bU3cvxSmAg@kKXAD}#qfOymfaC9z@QQcokqZ0~A^ z`Wq^#qhf_BGt^YB^61xy%*l}R_fX34dAXN89{&@;r-OQ3j{NAo=r}8PH{CSsE^BoU z*KCfr{UzikVoLm+zaw=|3+FCDx4a*nN1*B+VFAJgtIQjOkT=C@UF;gA2|AD9aLPCM z6Ki!E$p}=a4K6h#!x2W?UZ$5?a!A|f#v60O5aQsf=~srzL=FDKS34xWi^AuG&NX1o zsWvn0zp_47_T;fVk>J4)?IiSTNq>uzp`IjMFXG-bZC}=Avw20tBQ>y5_N+F2!Tp@H z3(npL<($BdJ1JL9sBpHmpE=$Gm=dd0jQ(84lCb209tIVngbeYgqm3=`{DHfFH>Cs4&zR9D9Z)S#9 z=a3?4Y2*R?SPowN+vU68|9JdZ#3~e06D96w1c#1}wu{;$yX!iL@;nlb_unW( zo@nsQVUizufLyPNXf~hEAtvO;6374>CTQaqDUeylL}n-rFxGdJrtwD|Es6COW z4HI_^t)SVOohVUNI!SzI%kN+eH1fn!^-oHWpw8x;N&K{tJ4BZ#(b^d{`j^V4ahB*u z1~|4=PRe>KcCZ?6un94qebiv`>e>*rXmq1XXvf)kW9^i2=*Nt;0W`C;&^z9=$*axP z2IH%Ym_dfl?P$9Y?=9e-Ou(zH3P2M0W@mx2(6`AOGVI`=hD7~_P%hr3DNpRO^ z1n4v3BUQVeNJ^e6ey=yJhqxE3OEbX-l$ecjZC#dxN>6%bVVU1Z3Bw&U`X5YTDA}55 z5kO69TgG0PZASvLtTyDv*dnX|YV)2rXYFm0kEExChe5Y`3izO_%n?s2m{0u7NI72G z_mqjK2)W);@PB}GnhOp8Vl0O9j~_p>C44KOB`=ip$RKu1u$HU9Zem3{lOUG}^e*pzvq0R7lf+>Fb5tlz$``bCD z@0X9yl%CA(q7y3s7wij34jgF#;L4vTJIFLIJ`zc+FmztN*uGX#`R))0(Aoorq`{@X zvg1BnYO90Gdc)Tx?vf_$ooe#kwlTe6JTUrCIvjHD$fEx+?EcRlxnI9YX>#@cm4oul z)pqbYM{qQK^XJJMsokT&<>yZ@P+q-C@J0c{H{>^q79>7l5wU8CA@SaIR0xj!7=#qq zdsPpgEe6|*>zmrYyy|+o^W!!n1<89y$T{&pp}U5SHhy@{CpQ=0|MdOM_M+QQ_mjgJ z?HJHzkLwcp?G+r9c{ybDfqaf-H@Mz54Vx%kxBpfaGS2V7YDe_Y%-A6uts-J9LKqku zTVU)4b%N)}JQ^*g;Q|l>RLOUM!P$*!L$%H968c6U`H@C7g`JNR%N^-@V zsXlo*HFvrx+7jEr1Q(@t#PTmP3pfl0KMqnZ ztV&}s?ab76t*PEjl1G{_VFZQ=y*J`dSj%hXLiNNrrV+9%C&?Cj4c>W=-V6b)|_z}luElPi_eoAwT#wx7GXoE-e;=>3S*IUKyFqrC_3KM&r1+}>|Le;y3B->ACJ zemU{pr`6@XX->qKhzREza||Yh{Wu)1>DalSTyL+Z_1Qh%Gaikx=Zt2kt~?-OkkfZ` z=MiuM)z`??)y+>oU4Q@iW-+b1o6*_9-|k^D&R2f&E*U(9Q5-Q-gUgcP*d7nJi^1m+ z+7aN2nJlKS@q4E29krKQg`Qa04QZS$U7fX() z{&=%18k3i>jsd!F$8EV}!jc!TsgO;QE_hwyw4VUu-USnf2tbP*P89OmhJe`EQa;5H zE4gyfrd+sCtqmlK*tm&&DSEGl}_$U6BDM6{#MIRGgA#mD-K(!VMdx7FAil z6Sdy5SQ)Afqdmy&(pTtQxafHqvBMJ(DIT&<>Sv+9SrY z?=&VS2sTH3s~hV>ZF_iFx*iKs^-KRUsW(NxrJkl@c7^KM}u8 zLLhBw>9)-MU`T4{^|kO=$e5S9!qV(He%t3&d;?boF$Dzel)q*u30+=WQ4 z5|7`Idm=TQK~=X**~XKoxeWahmf*!xnW1;&C+~m!J-q!m|M*NdrUzG$9WV2tpOU|D zr^!i`H;6kU;s(`k0NL_#9HwclBV&Z=`x39? z`NuiAKE`cUNfTT2><0FAH2NshHAzqsnsBKI;+nq})Rk6CV0YZGz=I|6W)28N#Z-Q0 zVF5}>mU6EuRE%H^uQQXKlMvP!r|14F`5B4iGyz2?oyq&xvv>EV7YPRD$Br%?h)ggovs4G@eZSv7 zPNrjw;)i@cVn(e0KQdMvDW(5`)_Dxy z!(19}{1e@z2XMTy*HMW?a(H#tIRZ^oq2o419$Slm6ojb~;Te&UWfpIuDup<;`N*B*F9Z`l8~f!u2<3E$eMn_0}P7MU4~z$J`DXnGq+~d&PT0El9QZq#Oo; zxYAK6wQJ1r*r>^us$Vryh87AbDEjc$Ce=3pC}=Ez15LV{O>3FqGoA^wFTrV^ETF^(Q)mHUF1>1L;YE#UiHb!ExAzi8_{jhz7-U_&oVTaBSppu>qMJ9YvUfS;oc~ zoLwA6mtVfT19kEe9l3^_Q!bCD3iAI|;=*DNI+X1hlc0;su5 z`E|-)Jz(!hmB5yhAMOtKhx^GrdeFvrWnJA9t0y1{THIR>@G6GT|~gG0?#BzT#1UJu5v zlS%dq2vYouYu6OA|IFqdz4PH}hSaM0k$cPttoN_u#bR-N(~Zj=O8yD7CK(a(?+aQ3U_(74hZBj8#)DG``Ob}UhElpdd zt&r_us~3f8yy5J^qc@VhsTd@BkB5!9m{{YOs?iryFhs=i-=!fGlwUy1yHM_G3*;uA zimqum{@d1)H8c8h)pYN;j|?r)_=jaWGILPV+ae_nqVzg+Dq1Fr|3sEJW#e`dtJ9ue zzWzde$E~Gmq*hHpafU8Z_$q^_o@WXYS(ZY@bZXY*hG22?TV+aaRBa?oss5YUFbReU z+-iXfQ+jJBl`K0|psMudiX{KF|CVj zKYaf&IpWIKGBThTBJ-+y_s5sXQA*S%1|V+crAZUtO`juFs}Z8pSHi(}gXcNyuLh!I zq8P{kYYk+u%OtjqXRJgwMKD;82IV^0ZH0ssT6MYdX&fDAtVg4MQ>+WeX^Y4yo9D6av=G|yA`2I8AK7G0vdGN0GIly}|-q)PI3qO0W(2#TNrcqa; z@bYo8{q)awmq_-8>TU-+eO{9O{wg{H?K#kk>~`n?=H7EYUxRcp!keW#!{IzSu73SE zTXb~}ex&wOc&{AnC-Cm6E@jUVpnS=hDr%2Q^Og~;;NEYsUxvj`QlKz&^wC_!b2sc z8g|=_C{c5Mlf^~4Wvr-ZqjT94Vm=!qTr5>e`olDcoYPQGVzLs&KAk+CeU1fZTj}MP zuib1;-g(QJlSYDSS*BZne#lbOu(TTcgx=DeOlDnedW{i>!elvxLw*%yBTgFpMjezCb2U4)VO&T8y{FS8*+oO37_YMd#9B zx6vCenynabXSK{8CY#m-GYr#H2@dUpne`^7!Kg`76&n*0*076%;kT%Uu#7RgjWsb^ z)(p>BT;<|%AwfiWvR&RY3n@$)(#x(oQyCG$6WKkPM6S);^Bm|s861B6`;X6u1OIeP zM~M?Y59UqU!#58*a95^DL?+vh*+cLYJpWJ&RLqZuLo^?%4poH^&HV6357Wn}z5NaP znYdk1IB0tF{qry$7O{xM+b|B`MpH%sGL2TY-qem;>JRcSLD?*saRSdxtGzBRbFl@% zK|I1&WE<*TabaHEE|n#YOJ`NtOH@xoypnD`a(@7Pf1v*U8~6?={{B^#;1y~sudW8~ ztt|dMNR#R4-y%)0s~m_dx$28^{t~|LjPfu9(*25w(q_?-Q7j^5oi_I$!7>I$Wb%{fnSdC{PF8}u#d)DWWj#^^yS^BQH>ge zn<-S{fNzi8Ww|OI8TL9m=HFv{eZ-4)>Y={!Xi%)+SEODqFCAHpXf?Oy+UEZj=P86Ew$P2)LaUB(S#7)MZqIRa}*)wYpLGy48O+ zYNyG`P)V0z(if+j!=yhx2cVR_!72JQmVaCF!^T;pl)5Hur7mxuDde~s?CT4ZV%3Bt zs(zoQeHKdaF=G8MeMBG6uLPx5D?}0X>Pv$#NL?!y!c6=ouw3s~D6}N!9nf3sb<36$ zS}aNRvl9SYq$KXIBNFB4(vz`$@u3LP#9Qu+qwMUab`q0ohW|slX;Ng<{h$bJ^rTTTR-3 zmekpwaG|NB09Wz4U41QPm^+8K*{G7&siI()>bYQq)a@cBoN z*UvAPfbWl!m#-ebe>^_;r^-t3?NK!ne9w&!0|690W3Tz$&X^iq{!_r(E zg(fa!;!Tlp;$L`~C@`1l)s}M4gtceF2(6TXIsok3YJuQfR;ban$+J+)hPDqM&NGbN zKyLpB{~&#cdcu2P#K}mbcYyCV19Ms;Nf73o|BXy=aQQR}=zYpHxw|5G-<`b@bf2Ml zSUfly&(6;3$@F^BDevU&e%ygL!P*kk_k^0c$=6Bu`Q7Jkx4j(P>^#OZc#1aq6?TVQ zR^q2e;P-yCz21Jly!?c>FQ4;SeN%NeRe8p_s@~^l?OoN=$zbHCHlK}dZt9tTpdfLq~;vj$~(z3lKi;`h#9DzGZ03I)UoApEOPx_{dXz3~;X#L^>n-av*z&cx5$r2#Y| z1vm0Z0E4)GW2l97F#@{@URB*!K7|n@2?H|83AL}A%`)!eO;U^ZP&s(W@lNTE*@P%0 zViQ%IAhY%qThr7Xm3CxN))u$$7dXZ>|G8Tpa3buf8vg2xdRnb_7f%!?tU zHdda@+*sY$6#UpuqSZngZjJtXDMPz z(^*$QO2(hNSU{t+v#=6nZh};cW=qlus!`6cuJ(KqWg+y1PgD|Y*lip=T>tCibN52{ zK6)7cmxuGne=6g?pW*BQeAmZRjYa+*jh?5Nr!QB}Lq5x}l+fpfIi}!6T$LESJ~nfR z10&4q-@S{XY`MH$AkKSuJU%}kj|W^QeqTk5!wE!L!c<)8&@1gFSTmZj$(JY;{Us`KUThYWR_ znMd--p!4cQHu;K-`YXna>TmApAS z_}X&pFX@DtPN6b6yBl9mb6GFhUP*+G^87H`ZoAQCx6Ai8ln8=7$!XN_12l(jM7sK) zrn~xSwEgr+=zV!PczGIiXmPg&`pL9Ih~RWOan~!%?jF2}-%l8iA0J0mRgX$#{N>0S zK^MZ4jlG7y9=}V@*t20Vo2|KhTuCYz&1ttpYPVwxW$G})BWWe?2DR}g^{Z9rs8E9r zOV5yl($%u>@WZD6_QqkHq=}!rOMlZWix=UINLYrN#G2ydzjk!w3AV)z%b!OEHDTms zmAp!8?F|(ipEP*8G&D{208ZON-zum~WoDQ-#Dy!AKZMR&4wbOJW!_XJ$dg2cJ?J(P zrdA)>pv5KFIkox3VUq2eq{f-tsv=G6?`gRfG@1H_FKxIRP4s1DyqTqjQ*TW2+@trm zv-e}&uv?J-2Kp3*D`}Zx^`-y!8aGGE{iqd@|3~YZ_5~r z74PDl1(26KN+cub1*r=}9ivf4)Mf}RWxcaQyDd~3i(f(6y3PH4eVJO|;w&-Ya7+U^ z+STRjGiu*SZo+@<|LKFXisaTJt$4w-M~$ATgx6iiuSR=OK46s!MEj>xX31hnzqH)g zU@ocCD6x(!#)ChKTp35falP17xNceP0~F7$K<(93O?%bP)R9Y4#%N{ zD9O^2cN#3HheOBDt6DpJBaOd;Hb;*0zki+cRDojm77v#jetZP3KhDVsV*1UjYMy#O z6zAM*A6bh_KsV~=kW8hBtnjKHF- z?;;SE_xEQ9Li7G<^t8SF^!f7h7ytj|b}-m(Z_<%Ofs@HEe){enfs4+KRvv0?^d4Vd zTu=S)ANO5#bG>kkXN}nM4$sV}W9Ne0mwqhnFf>Es!SIxle^?>6IGUq&XP(z1KMxmv zKF`NF9q!~v#!u77@zhY+EIRez$;mdFTY(NLE5BM;%h&o9VKNnavY&qS@5c@l1;oRs zWOz}|kc+&5-eeO?^AQL8q7-hNAGsmai?gO`u&PEJ9#1h#y{Flq{L;`U6&ss~bc2Z+ts<0rc-gloS`iKCJYsaNo(vPU{qL?L!gJP9sZJV5$ z7{b!4=>w?<)H>6{oul{I{0#fjMjF~aCkfO;dR-rw?Hy+C{IM=^fM_TP5p%;A{g6NZ z9RJLcT%tEtePn`d)7lyd#lU_=blK;|{7t5to*vNgO(;)mCB&|lffxxo>dLNyER@0R zF;m)u_Je$QB1?3M;hiA;htOQ#9xl{Le z_kz9lu@c5X^mF?tys@g9H6&GW!AN{-Ndzbog7u^TFN0D2deW}a4-HSCWK7_{e&`4T7uLd3Yg z`W4TzT^{w!gC4v9s~sN?pwS;u(Z)+kYH?|qjBB{YWoV8_i;Zn@%yFYuCqlB>AJXs_ ziPaYsDV2pdhb0!FjO!eT6KYOixWY9$%akcWZXY}254UfzvsAo5MwvX|d(`vYr%4+# z^|tHYzh?|A!TT>blQ-Sf+12)a@KRp&vp2&8&k(h``zLg7+Ou zhEW8mf=X;N$9pU;5$Sz**zKlWjgrfI1qEX6Ugxy!KqmMI#^BLkNj$I)K7GEvxqP{} z*s?XbD#slr;nlj}XoUd5308&}uOA;Lewcl_=oVA3=KJmC<#sXh&)HIu;F$6u3K{ID z)06(Bo^~B#T0P#T?m5E8BJ%qPvEUp|ooZCOaUop`H(RvY}SXksy)C3j@{cyjbmfS3rTbOp(zAm{Djq+CgKk{VAN ztGk{5iY>|tHRd31bEh(kG_z{4<5S`m4b?u_!Ob%*tV_hJ-lnFAsh2 zbsV(yX}AG<(5*a=f}oJ=j@u~2)#$=xY2s<0@RDI7H~g~uUCw$L_gP}&AN*yERJ}G0 zplDY*cp9HEYY&efKmPiUzyIT-AHxrr$DbSj1s?0)(Y!MseuV4t%WN33x{fQM_eTbG zM~!wT+L|=;)!=1+JhEIl<8yP!B=KfAmrWC@6i0h~g!iLf6Sx2SAxc{-@rV_mxj7}A zw;@J8iTma`%Dm!@CE!Bj)E0bZYsV5pqY0*JsCMZhiFf{`wrTM1VO7AEKclCEi40Y| z!CD>L(Da-e%eNoY8NJL>5B9f!Z|jN=lsDIqZ%!!QgZH1u?z3rk)$PL64R7V{?AuhT zU7sU(*2kG(w4R)?BK~ZW)0Km6ot^a%AMP0(c!pscjRSXg2SD`MxV!0gxrMx9GQL|= zSh&8+4`{U#jBD#bL)SuHSdq;F&pz!T6c z4K1}AF5?bb+g=jBHSJm{fHt0)NDu;roHMb;ZxG&%wb`ior?pUUHSeaOcp)?dNKP2{ zGin_A(h}?4F?o6{gNk`XD5OvfbLD665>Grs?{e~3TRWxG?v&q7VVm2S{okz^UbC{Q zaZ*=4-KvuJ2yu={UH%owkP}_Tobml;*x!&mGKacx9uTs?F=-3{UjCK3h8uoDveA+u z@-CG~K>kF)D+AkFQZ@1Wkrb8*rE%WvX#Rlo$g~V!I&3RI;$KH?wdnIF)>MkZ$D4dy7LdX=Rf|-Pv7`T z=Z8Y*4r1YKzA%0bEShe+9pxjB*q5I#UM|6!__t4& z-SrKeHU2+H>q-y4tZvWC@#JxmcNdpWH8KgO1Mn@~C@spW+C$ai0eKb}>AW`gC5K{+ z&wi>WU+tn5>K9hCBhpX&2>x+ambgdJYoVk!U8#mdjy9#aH?FYuev4wqw@oJ zLGcOJm=5_<0Pj&Zq7y!)>>K+}|GNSoftGlduN13djka^TbNu{mJIk0k94?6Qv>?Idr4?<@4JF+_snS?i8c(t3O*|T$4a+j`v$t~X*D9_Vf00+_A*i_XzXFl zB=CDloiXh?vB#E-n6zo^vX?D0D;K7A5M>UOw(#T09jnb_Dcb<<4rkI&Z5nW|SGUW) z=2%)9MEcp6sQzFGPkubc{#TlJ{{G{yA3uUT8TxNjuK3?CS>o{S@Jzj_|2)x(a_!&$ zu%PZJ4f4{&1=r;>Eyv=Nqv+jt@6ZK7_27Vkw0Irh_W$^Tpe$ymJV*532yn4%-o$~k z+wkcQ=48X*0mUOjI#}pPSl}t_jH%}HG^0PEp%frx-$QCv99%G6b;}2?N!3T)nsZIl z5e++8b)J35&Skyu510Qd58vK7>Qp7yIudmBq@GKQma_qsyo z?(Xaxvc&k3o&G?Rq~3jhw`2PPSd+VZlnyZNl|}OYUDIhd*pKhTtH{7}*X6VOh}y!4 z0Vnqu!1MidG=2K~`O@Q@NAFp*{q*JYXVNAfyDu(1cz>v_5ds^{R_n-PzN#H^wB7iD z`{}x#PA22W8sPoq^ER57W!2R%#77Og9WY@Nb~}yV>RmwfaJ^!bRLNl1dgYPZqjx#` z=;v)zp_LfMBRDG8(QHkFJ}(BN#eO=)?dVcKmIUS;@%ho(^_xjVu#mHdhB3(@Ov!Tz zyc}+Z>Z){ zHYXi^ZNs{77Rv%`hlTzn0zmk(;;o0oLE6}r+tx0K-X)tE=-cw+TQO9&e<(MI6+=xV z+mQC(Y?72WP93=ax`DQRWpip7qOBrHT4^3kZ>i*Q9O6S&Lu*mvnAT!{L3VvaE1N4> zTV{l^6%136Y3ooq-c`v!w+QuSjDDh>yun9O_pKum{3De%V|-#XDtn7{Raq)vOT_{D zbcNXntrka}?iG7Fmd4Xs{z9dPwGu_f;Ss8H3Wh4};xd%AI|ZkZYeFvw@=S)jdy9D3 z#Dwqp5FMEF=YRe9ckthS9)IS^>G{yxYJTsYqqI`_#dELXreOPV&X!=fR2c#**QL|6 zi}TTN_T^RHcN8(L+u-|@8-9#PTXT)eu^_=%z)YW3I~Ke(vL2&8Aq_DuddTBGP{3KZ zGLA+Z!euWeXF}~bY_I+ytC(k-Rw3u!pK4S?)D7yhpAKHHtW?moNgt8;qd+e7bei~#Q)mX;o;4*=`?yRn<( zK<|5y+0)7R<kll`EE*mFMVtaK(^wzhl~V z-tEJ@{8a+JMU5B|TnW0W_M`C3qjz1eo>v~vJ!+#CbB1`@oB)o7pPk$7)@wIFu^Ctx z&f#B4i%f4ihZ4)N`6B(YsWqWl6&&X756g%E1VuTqiphuxEM0{$Kil=!tCNaPS~1 zvx0$69c5x^3E*s_h3Qt)u?aK#vUar;>-FARG89#kBu-;zmmCk-E=R7qB=LzoW3NCe0dGu&p_Ep$;+$iNI8w^8sA8X6I)ThrTVX(6Gk9 z)VM_HqlmLqVr&IVg3=WwN6Cgtg!o*7adF9BCs~hphhotPo#2s?^228j;Pa1jkKxa} z)(@Y*8u0!xIL<<7SbU5wfBz%Aar(}dbV0&i)f~G&;JQ=-BLlpK$7!(V{P7Y!7nTVe zm&ZdWig-7OkYtsmDCF}OC+hFz-xd9DNj(-jm6G%)oNq+YB}>&yDdio{pf;mx$71QT z)c7Xz%WqWWvrHk0R}ye+WmeMRXXh!j-uT)7;T8|0i-6603lAJ@FW=Cc1H67Sng*fC zH{d_NS)et z+kbxd&+YaJ1q}B)E;46#Q8dlh$P;Ac8S3I^6Zj3slRDkG(ZzN(Yf>EH}vEyR=ZOa z;_A+VU*+Ga$NR+y91JvqwTF0Aqg5XJ-A%{OxL#xA=lq?^mlLS%d@=AC9sD?4Vot%4 zl&&60)$LR-@1Ij1?x76KoAr=WxJQ443cB*)ficc3ATBp9E}4!YaiF8P)xS9TtSp%j zom72VUm60d0vVF^1vdacg$Bwd9>SJFD`j9aZE}po7U+paNedKJ3i?rWbdZRc!8i!L zL;kFwq@unqHibvqzS1Lx-ZAj(o3`Ja%H+dO%^*R8K+B2}t3u8K*|E@dZQ{^cuQq1l z1uErP%}}CNhv==yp`W45MmrTa6NSreh~BYe;6W@&Yk1SDcu?+Y^K|&hw^bF7!fTt2 zof^Pg=&lHtL!NTvXOFFoQYI@5%zPvmQI{kZhAXIJQ<6u8j59NLkO0g^)o2t8H;Q9r z@HBiqGGk?O$D?cwseTDwhco6~L?-D%wnsY#djLq)}2?#i~a+19$+D z#W58@#Lp>fIMw?=zecL;WhQnVhXmfq$LD|i{m18sd(s9SRv&--`#;E?_?s%84}(iT zYQ0R3^G%;++#C;+{_XKF8pg&G1ey~;G7Y-4P_6R1bO7-kueYXD+sD;O!gm2j?T*f+1mT~{u zXba2o#MDu#cqnz7STB|(PcYeebqnA8ZH8oY@F@OU^Jx9PlQAALyMg~BdeElt-y3Sb zpH7M0_<1xPV@VlusCKVulB;i6Zx79obWgOsl)-W`$@9@@w7|#b_uxe))4hlHt_H6% z^VnVPyXp3FdwD&bjOsJQzbeUlc7N6lV0A=Myhrc*sHD#8a5#*Tw0zjUTnwW1U9=dl zrhX8o;$(Y?@%#FwKL1dH1|j)8fz|P$-d7hFi*7LWlQ*6Wp9kB)bo4ZM8Z7pYn59_- zjER|yhX2F}j2bVd7?sI;5Wx2fS7M)-CjR9=Ty+by#MjlLD-}lQ|BKe;m^(|1-AXFV z^8yhlq)e;{!v7Yv@U<*Cqj7zG#HevtwZ^VJg>mB?zXdAE00whN`QIE^OZ0N^tKW#^nkz)YIABzp| z;H;QGA7{to^L!Xv(~Qe6vK_}7AdnKY z!QnM@mH5Y^h%@Uq!Nz2hs5y|u^-IQBoipkrJLe7)!6&yLZVBIS_I~nydNTkn`-%I_ zbP9XrNdewZ-uqw9UMswNp8Fok2%_>g{0R`6fv{|2@Nx&UC)MQOAVan+M-cRE^`tY`{A8S9e z`jMIC44A%g<;cr!0J$|h?X=JPe{_v}@Ll~_`T_jLgLmpi)gE{a=>ijJz~TDA=Y}Z5b}&(h2^;m(l3 zrW@lQ%(U$+pxR0EKo3Ch$Lmz97~)p)3cmE{;8qP8onGvkyx?Wgw;eSV_v@kMD z)ArS(3y-vp83f(T;V+_&4!a2_-WZQn^eY(e=jUTI zoJT_MkHd}Ow||I{>{)D*SNnD%Y2p8BL&+W^4hf=5>HF2WTtq_&Lir^%g-RrFSGdL> zPW_{c6;U~i{JFc)hE`jnkY;PQjML(hCyOk_l_I0cog4U!cNTWNi3OYc`;)#Wjo&d} z2`McJsy~T!-bDt3N{Lej!zLM}{<_`Ne;enwx0(MB5Pp06mMWCDw;w>ByqUgv@xwO* zP2MohB*;##ro?NB3D3xKU+u2W{`@wbZU@^}6*`k0V0=P3HzQ!7ErHUT;_fr?5zvt2 zNse|I9Clqa`uw>o%k-hU zSl!KLcir~I2`TgbP=lbG$52tB&UZ0P52BjX2@)@aawo$Iv zsx>2nO#+39ueh~tPb%iC2kf$}(vke|W8t=2uYu?;$AU5~*AY4xO8@>8#l)z1D^sQ* z6>R--szPBMg9%eZtALcdE_7|#%o_%xkY{EDO00j>hLGq)-8pjTkV@@mDV~rU9@vHG zA(YiD`Re}->Jy7))85N`8_bSYrIe}opo35zom1U54yg<>O>O8^f|V65V07c$*@Shc z@;8M;v5pcOU1eg1B7*$@o56c#al?cvp!WfqZ|c1@6~?gX4MRDjvre@KjE@_S-W$=M zTmo*$r3Za;D=tCBa4xVdjl!adtO=>(*JYlJdE%hYgu+lc!7#cM86~M%ceq)0+#1v4 zs3=%6BN+=SEOkXGBK(OD?2=*dQ?-aHglH0{hDaoA;(#xl;5*AlXf}zS@ZBHQ(5nTz`SlAqb z@2|!*9s8LqykO$Qu^!Jqho9OsM6)fH7(%k%5ybn~KbRTsv#i}%oEeXYyz1ax)K-yy zNo|EwLER%r_g?`#Tp4Ym1+8ES;QNDz@9g%6AKt$G@b-tly}kWggjMDHK8@=A^nJg_ z#K`>~u_eInD;v819lLkCvniUrM$`Tse#)NYcRQsBlKe*D8QLnT`reu51b;^25@Mt- zJc>eJGE(s{g@L2}Xp*n*cNgDxV|1Y8D|{&N^`@TO{BSgW4G;jaW2+ih2G zw-=u;FE6hb^-WcMKn-tovseKA?+@y&?4G*CE~>hh&!0YB4!X|I|BJ!X=<(t4*VUuH z@$;Jx9&M-Fx=`vMVh23}Bd2PBvHR;-_-%^6vL5+)zD9e3+e2@{RBjq}_!Ge&eG90l zw`h}b=|)d`+HX*~GphGfNW9D3rRZbG;e$tv3Fm82-qZ*1rxL~SFm09CSQ5h>yM+nf z$cJ~WCB-s1qr!`GMEf0=P|Vy8tyQTNHQ8&y+KL0~!k7H*Z&@mZU>h1`JTB1Wg}yZKg&L({4xMnkdX1x7F$ZT z5#k%WK&gekL98GRNdEH<3&rm#Q9XQRNvld6vZoSa_(cJs0P@Ouqs^{e~ns|7T1-7(3}saTIYE&@S|swq*BhuZQqv>+Ah>e#}$Gf z0@>%F!LW(##3PW23E$uohP(=K8`nphg+pI(Txr+Wv<p}d7Xs{jhncgStCSSte zoc(fk1uaTHdGG#I7%#Hqmz(S9oq|m~Hs6yiVRNP4cSZ`^k_JJ49P&Gw zFzMT$TMoH=Fdpf~i~aQJx|>cQ%q_u$myeUjy1Tjg>FrN%AGc!<-udLbsy*NhzP$T% zF|D^AyDxsbIj^e^H-7Ry2Y7!tzu8a5he&aM8+Un8rOn{em(Or%c0liXvU+%Yz?Gp| zy#48?qTXI~Q31AM-Alib{k@nfwqzPike#31Ywj66D%a&MH;wm9qjnxPmYBLrkR)r` zecTA`mQ(U3{`Y$i-u}4ZUx;XM@Dsh%#BhJ++F^RI-T~2bFy44Bu9!JVd4S$u5kO!K$~b|R&% zgLR`yt5xb&qL+6X&isfI;cGj#P73CqBxYk}%>%cisyAwp7n_{h*8DA;w?}=q7)XYS@@&Xp4DJcx*!ttuSQ>9b~9G*8o((vq0Ov0Jsjk? zKgXAVwWrprpuD8j4_;HdtC+|`c?Q0`qL@Ep0LR-uew;tA;zSthXw_6q%*F^SU6o@E z02v@OwCT~H#h{oVJx`vN{uw7yN_Jl^Y$2?K22o@q5M3aS{z_c(oJGX=+1bBlmZPk4 z4cjf*GFXX>Q$rEH$t7NF3|=Q~h$lIB%xM@XlD490( zc zDepr*mD=Jta^JB7-kRa>4tICs3DhRcDcN36C-sz^FuHXjdMj6vAGY_~i)%6{U?vem zvc6kAez>`L`_tbZ$`6n09s1#;J1YCepSIQZ;_~~;i$!;igux03?!mkA7`~XoZVBCp z+ih}xDk{_Mr%Qii7Rq!a-uQ`OOjL2AorEV(u8(nPQ2}g=^s3`rzeArf<+~&NLk)sg~Zvi3c%7@ zPHftSL_EIwoyKv|<|*NjP>9!_J88sW;!yx$Q%G;JQ9=`kapL_(s=-ty&E&Vv4+$i^ z^T`2Q%lxsnh}y6(wHiezbyakXhzqv~@)I1jrD$ojOVo^tYgCr;rHHKc7Uh#_P=kG% zc1%WG&~Qp1C6_Pk){<7cM|eS)`r1-4=onf^^@wdY*plElw|mrejmhJA*PyG|$}uu3 ztNTl~*neu3t3)R$Tqp|T^GRFLo?@-=mBQHx-wZePw^te2vtx`j z7MASo@4kol0SqxB6I1JT(&G&`5>I*TGfj&j;wS#)-{$ipc<5|ttQHLCd~`P9nu@D& z;h1}6S1LR(*j5)@Q=%nUjC{qO5K!-Ft4>d}C>La}aBNK~)x!Cgnrc=3i1D=4!U9(| zgrv0I(mz7mc683nhNz>~qW1@7o_ffcs_{TF`fY8zlH7u4H<37S!FlGY;n9w<#3d zO~ShJr1PfN(o8!!SQB-c(X?}>Uif?1E63w*FdbZ9-`x1|`{F6@-{`!&kMizf0dfVU z@H>CVeaxeKk8U?_|Ms`HkHpK`58mb7>@H%wYjwW;e6hIMcME@{c=X`CxW4eViX5>LuKOf(w!)8q_7m&S8~>7qLc^kCg<2~ zxJ|F6#J@YjqH9#9MU}Ax8Cp}eX)ilrJxedwtA6`UyRMq%xyFAQ9<4XARW~Z3yNyG* zH`{NRb}TNuuZ5yPS|!DS7j4tNp-e1fXruRs!A--Rz0yv^I`S|;*3TrebdqptX7-hw zIW|RG(5UJW<1jw8+DziL(gs_++!Rgd#3c1%4m_m>WI*qd=v`7ch>Stk29=BLIaTJ9 zDujw0PI~I7+#rh=1P`Wuklfm^wo+o!cjz{ShG!1xt+Pv#)b2_*Y2u*oiIEFy<(HD5 zarxLNcNPoM4Ig$9rZKxI8HZ97f!omG!Qx{r{2*hesDcXUo7%)7o>8obv(`9_$xEV! zQ=^O>n~-#ugk&itpDcA5NYpNrWLXFwwwH8;lC4O*{v2hQ1?Lpw39cwAN(PirHQ!)lv~R ze0tfw2j6jPZFb`F{1{QOHdGaOv_OeNgg0N`YMRu@5>tRT<0fx$J=zpu_@G(IH0JCf z4OQJ$aGNguKk}#L!aw2#T|BsDt`sVz8e}xaW(Xf_DCEEOrYPs>R24JB z`~9DNl~-4zr|tH7&+&WwN@n7*dp~_0ZUPBl-eWi1@%hQMlUsKs!21sL$Ozo_;SMQ+ z`_6;w08xHtcjJ0DD)W_$m%BUVRz;&J6kYk5zfySIt@n7};rzqj-u~@oF!pd7J?zi@ z)OxqRM;_~}{7`Kd-JOi(Ro?q0?`)O?fQUvlEhRO9x(h{II z;QEdc-VuXhS#egE!gl}r@gBta9!+of1(P>os$8RR!-7SYEWY2B(4M&d4T3=xG3>M< z1aq>nb{D}naU8>x4c@Al)gF>p|LnJ=@ukk=w{vxs21SPTd~rgy)4jde+R#5{=xvL) zRIH1wj5OJ*B8SVpO>DA6#b#j9m`UW;Dor%A*b!MdAzZ`p!8m#P0G;KxwKhi!nv`k6 z@`5I|$Q4@~4VysGV;4vaRLguK$qH7XNp{WIThh~#QB_3mID~3*A%Gx0ee%pMX3FT= zi0tKcW8>6-82)K&p)Nc>fCT`l+-wwnj)w(zV5J&i=q{9JBvv3+vK50rB$?EoAzdNq zPJ^YnG!u(~b}slrDYFQcR2|uqBvc|KI`m}Zdr7iWFYoOBZ2KY(h1#0NL*Mc;V|-*E zhZ7DCr zH|3}eS+_|AbCM+gKU?qG+cuJQ3ljv535udsB1pzUA6kS=2vHD>BnOs($fE{4Zp|3z z!91Vr4m!g83;{}j_piUT*4jm9o^#Y4$MHoMirlqp?RDASu@x`ac9S#+3H^Z|x7()a z7VFS-B6wzd+TJva<8l!eh>m6_7sX+hgd$8USPc5$Y;s4LdDk5f#8B)O%cdyCrd!svCWK{QUdxzrTdN0Mw05-3hEVH^7RNzquI!f&(5tSx(uQ z1L-C`kiB!);U6nRlP0T^7PagB(W!bBClodEVL*$ zJ*k!KR-z4%1}RU<(r9HwytRano^sq!ougQv$q=QIfI!Ls$ujKQ5ihSYjp)n07yX`n zc(2{HfOEJGmLT`_3|H$F2jK;L<$3l7B=`0Z>c%spX^Q@#C7RcM=)xj z2t8vg8;dj4JVd`_z`BPW^KrAWHGzJ+q0cD)J1b%x?S z|36csc>ha0lcjsTx4>Mgr% z*UXlaFUuvcaQvB_0D9BN`v60en=SJaLg!5b=5BX-+Wm9<*X7I0GyeTd3#iZz-x028 zLKk_BEyWDL$IC}B2ft1xqeb1+&y&fj9?cB;4z=@f<;t?DYyair`u?e@s>$ci%cszI zpNj43^Y5QuK3|0|j>ofy55;oj3CI`8j&*of7R}n~_iRoV!q9@RrkYJYJUm$au427^ z(AYBk4`⁣#s^ODxxpPBQTW*SO*>;k~b412cZs`CT9IwwU#qnk>2Fx=_!e|k3w@V zqlq`I4wAK2f844BGa*rSRSdRl>ghCh#upX`z!@okf_f)Qrrt&2MXcV@x4u`x`#v?} zYA@AUYPhwT@>!xw7NvYyI?#1Zi;pOh_NPdD7Uy0GUkpq{tWAo)3rXX}R3fXuEZW;N!j4&!e#> zOI-UI)HyE*oy%UXFqw6a9bZJ*YJ#hIszJj`D#3z zNigXs>*9AAYKr2ykpp5sq+Mo84s}XxhtmgZ7P-ZPvUy{v0U-G_+Ah2kgn}(3I0<_!;W} zpKMO39*a<&hawJxShP%=8U-9I6lCtWa5DP_K@Q1)QPa0DB^5F#LC1E|;qXVHGOl*>f`<_~zy=q2lra zWZbUXp5eFt>Gk~2r_m!Pn97I`AGZ%h7d~^>DBi`rJC0x$JGlz=`{U#BY1f3t8@rcL z$JU$qHj8psG}CZMSJzL?)9GoV;$1bfZvETGmu2J2uo^UgGw!dmLum5ZMw9r5;tck; z)bqN-P>@#*eNDjjK5)jVUYxiKBH$CY-?4ZTHbL$waV+zG%)DuplX#*mm&_)($MYXG0COqr84~@1Z zePm_yE@psaJO$B)?&DxS#tZibdAx~yjH+1M6@$b!^N| z>)#S4#Tsta<=e{e7CE6BA0;rP3v$P<-W&dcfWINS1adMk55-ZT`yRL0J~z=!I=Dt* zPY)ho`{oIt2ux{E)se&ZY9HMOoqe#ahR#AWN$izALklKx=h?w_{L_To!n?;%+#TCsd8@r=6*v~ zdUne_O*+_O#?TNgoQ|esq`ja41|}unavd6(+H=_ISU=IKrv{qqGHL~-w5_?+_fAxg z&?B2WamG*vozFbaLh*Rco>%Z(1|-AT$cDw6Eqv?MTW2*+pHhpL5v!;qiU#MNf+AjN zG`1jAo~7J7(4ug24NMB<`?kJzp+8-_alN{|zP+s(S)BYAYNEI^Q3Q#4cW>hOQ2+Ej za7_S{5F)u_*Nr&KgQX9XaMDeIigX7Oyl3mh{BVK(w_wOH)6g!~%g6PiqYa@XJfRpD zhYEJEcd$0O>AIOhzt5i%^v0*;(<@VOcBtO4BuVb73a)%jDBivVQ+#!GHCl$^{c^Q@ z8oyhWmy5bA>dA7^#pb&?9(Psa-D>i2iR!)nxCq6&>K0coliz;(ZQVQ+OgaP1Ja(Zs z{$OKE71>a}tJTpeH-$Iz?rC;hbq^X@9tP_$FHc`V+(iOweByFNp*CYUSJ zS`Jcl<3~Gs>ZjqcS+H0vYoRmVTH}pDMY(%xvE%LV3x;VnrQRP zLcm{^YM%RAlSXC{Jg~=)jw^Ap*a}`r&5VkzAxBIslf2Mm_hydb;injDd7{k;`QE7B zCOfryP1R~0(RhBEDtKE@iQ z4mq6D_cSZqc!F&2U*Hxf4Pm#|!Hz*@LhjOy2PBx8i+aPOt}RCu7aN`)OP$tmH7{#xt?9*lx)Y3|~Xu zz^teWAQGYLMjTluqW4Ke!ceoP;b*!#Wa+>_5GLQroys>XVYf;{{r>D>G6Z`Z1 z_fM}k$*F+*6yq0?0%>Dy5nhx7PCkA7comBG%gbclTsO;)??PW*U9LtS9~a$Qy5!oU zcu!V~V^v=_;|85~_xI)I!6 zdnPkj2SMef%=a^?7aeIwY&VEZ)~1_aac*GxoVf^XGjU8bF~{^6%SRlT8rZ-YaiQ2?}}6W^Hg}K}p_| z&LaFieM5}WXe_ud>6tQ2Bs{~LEnd0AhDG_muD4LTo&gE82psND_qeCI;{LKVA{rSH zN-Src&G=keNO%RHmPHWfIVlUyF{$@^&B zp5{i+;i5;zG|)DfEo>P2Ro{ls9J=Gwr9H5xo~L# zb%Il%AO#80Dqt?Zm^3DGa9o`s+Dxst<8IGEYU!zUsu(7Uk}AqLw?D0jGYmQ6F36d! zgb0Jyw`dwe>IgLR4&%!@e1Hg5-oW%=Ml2ltz3BrcA~{0}Jp*1D+#uI3m|yW>H@RjzuHC((R><97*P;7{qH;c+vvgYlpI!Vn;=N^K zeP@J{J8=aIGpi~PJABuL^2@RwZcQk>7hThxz!gLshE@ciRKV zd3UpBx|o?i?8AXX@2Bp#cwD@G`ZWKh+ws$vjIGrFZ^nWeNRD)Ysl5q6!qGo_HtGXtrR|N$f#}yOx?-yy0!*n;X*Rb2w$YJ* zoa*1$Etw*3au5q^0?OLi^kl`OwH*d60Q9v5>KSLF*c#PlbQ}~8^s;hDsqxZ0hK~{h zTR9Ih`^8YZiB5%Pp~ff@fq~>Lru0(F5zJ8H0FpkU35W?#_u@WT^&bAn047r|Qjf;i z8M*%w)?(rCVNQzGn@SwMl-wNPscs4nUz1(H5ki{Y$0R&lySJNbwCgPMVHG6=&NRL7 zt7D{HI(Fal(fk)tyMHLn?leI{6}W<)ItBhzxF6dT-~8 zW78cFB)?_$LMYxh)5UUeI3RPNfUn;SwjmVgz~>JYe^xb44~ z5tOr;M_BJURP^(GSd6Y$A75TV@BK1rn&bS05`TU@SIdvf)%ErAIP36F@JP?eZg)N> zWzkL_7rRsS^!zgU>un7J|yz|R=5sqvYKYKh+*;b z(8!TMxL8%@a8i_qGNC;c=awwqjf!_;PT^QR;060|Kr0aLnG_?B&0W}Ujh*pEm{+OJ zhAIH2hdCmIv=mk6Evpk6Qqk-^RPR5Y?JhvUeanys*cRG^M)ar{9w{TcL1-~_+|pxY zE@}>yP!p>U(E*KpG6eiFBm$*P`(IXL%Yn}M`SLx*(YNf($qyc2DC9;j5 zr0+?a#=OB;zYR}`BQ2&gGU76Ri6^>b*dAS`%N2}PnaAL%fKpzTNrO%=vo*;gemvn4 zo5&expHbeKW)_3|^ZtMePm)Ro`KBV+Q(eLlJ7=v&K7q{Hok^wPjzu!IfLIxI!37(5 zcTL}pl>6^m7(&gd1pPL0vKmu6VI0Q{rlsYKk#cs5a8mX6;sbGszX#(I+I7Q2d}^)- zEeMCMt>j>pNfuAaK4^%WETYh8vHS31P`nWhSKo?D;`IwMergpwAX9qQNMR+0D?vCz zR{186#w(7i6BaaCW`*;#=OdF?AL^dikaBJ)!Mulg8>YZcQ$$()gg4(XZ0U1)8RBE+ z>vZxfUW!9vtZum|moe-;qwgy>TAb0;8@hja8kzy+Z$x^hvJ>YV1qd{ffi)KGC$V3q z)qw{Su-;e-Lv(A=EE;DE;Xc-Riu=P4-!g^-p0ezpEFh!hY%7^hL-)P-msRio%h1F= z9-{dDFsJNYGfKAOmDvk2_KZDw=(WKH2WK0|NYRXri_vNhCZPe{;fIdP$8hxk%NDY{ z^YyeVWCvTIpRKyZ?~~%gzkkZVV9fNVo144BcOGK(tt)CX?lOd_NwCKK&kq zXpi?`u}~yh=#mepvrWB#Lse+!)qV^AMg(T)zeyRCQ`G@xS0s%O#d`+Gn?5OjtftPF zVFd~08pLilo#IVvlz~&nyu+~BYl)AvUVvw-uhW)Qnq;CLsT`8LmrN#9Zw$rrsWao{ zZ1CU5$=dL~6ogJ_wrU$MDUT zj8#$d11j{I3r zmN>UajU(ht#VYSveJjp$1&Ul0=Z&<&pRn!6a&30LZ7YbCfYy zxDjL_pUx7aDe{CK6IHcJHNb3{F`UUMJj;ZUll~Ch3^LA4DMN>|$%bRoJ(a2&130k- z#geNzs;sT&-h0txV9(=?3zA2)EENYP;$WEti((Cu-8#TS54S^&YQ-U4To-d$W3@>K?n9%gfa9-3qlkr(IS!uOaHs%`n*F9k^pMH+Vc1w&r!N-7o<^ zU7+BvdQiUW{N9;cmP`Ki%Nyby5tGBk;o^TK#2=7O8H)BVv#zilOH<|`B%VAJHrD`C z?wZhuhw=?keE8>Lw3v?`58xJVlbg_scOaT1^En74oNb1m2Ghb#k-$?V$*h}o&GmXc zS{y%|zy0Og*LVw`C!Y#*O^49_Ca>q?w;w;gRp;wI3E9X%rN?6RqjwecV%6_8&fq8_4*DO z!sx@RiiWSDY(LH30_dMtp1EoXyJ|2_5U454d)mY#hFMj)=V^Gk4@fu*ck8G1GwjW> zW-#cks`SvB9zHb$#q{s2(n_%;U4j}pxmd7zd+8Ozn?HrU#anW`n69z4w#}bBePZ;a z%PpqMydN~rV)bTSLYh=bKPd(K34Ej%xWdz{#}Uv$C7|{`1321Z=A zY5V4|CmC}u#|jriBtt8dMz8L@Sl?o&_r{Yq&!^sWufRm7nIrL0YZGA+v#xa{KiD39 z7*K;vUha)4sRE6Ie2K13p$r^cx2?+!8G{fKD|?@7Q`9qEz%r3IlA}+z^qknmXRMAG zjHC4fCbB_jj%<>gW#(?wh;l0;=Mec$$qXx+k!5;J#_)L*Szz0oC#J??VO}3G4FDQ_ zCaW^z){7ON4ZiG|wWWZRTb@b?Jb>{vd+@wY!Nqe^M|?Xx8oc^?^|MsK3d>S4#hn8` z*40xi&qSBs}B19@kBN&v|F+ z5>ZTkff)X052~MT8d=V^{8(7srX=S=E+=bhRfyYpL0p1y(c z;_~Bfzb)T|#vQk-cYkdFxp$B6ACsy1q$`kcBBhS#VX0TZH>xhx*rqMC+Nbc9 zn8iRAmY64Q81jkp7t6QTb{&m4;KXPHt-&dVOYAhf4YW8VbsBr3bjwYoAMA>AOLkFR zkbjAw!jvR2Yr0dlUo7Et@}ND7#%6+pJfnE2EmZ1wYBF?R8oOlAi!7D*&whwdjwzEW z`bL#AOy9k?X8aZ;4XZ4?einOwSaQ7@wP3ukDs z7=NR7x9N}!s*IhM1|xz;u*bmBvt?&L(BAu&yCkh1vVlb+Oe-tD-f(9UX{23ssz7_r zZIN@4$D|~d?<~fl5sMJ40w?sId2B7M$9x)H6r71@d!gy{5d+Fn3z;FUe3SdsEQUi- zNyW^;_-r8RJL7q?1x5MZ+{y%9Y|fn2LC9LXDSEjONCKW)5SvmEqS+bTwVcA@3<+e% zfiY>za~x+$Lq1-4{koF~)tR#YW81GCeQ4h}p~wKdXA0$h4fa6rIsA?<`8W$2h` zSZ`2aZ=F%UrwJLVvNvt0wmh6m^`zn6Zh$qB%iu_YB*VgC*Bpkqga9 z0jTK)V9(yRROy~m>e@eVJcUObc!E4QcA@_!K!2YQ^gdk7-Wu-1U=zqMY!M27FsNB+p>f!*w4VZ%mnw#8#>wR%I8?6@e*?jSMF$XWD0&X&&Ek?(|++@c( zewUo?l3n3l!vW)bF=QI?-jb!EAqvsmP$a%BTr`r)Tf+Vf+lC)CyqgCy;AR~c{J7l)79il(nq@|rCbi= zZIy$X+{HhZPZaAEguP)9TRhFmff+_TfrB(GsF{uM*nIbI2?rVk*yE~8l;NQ9VVpWz zNBb^pBrf|*z6IXOc*cRIeEoD}Mh9CWX+)^qIJ7^@h!LsFQhA$U4!yU2c3&v#gPN zHj_)oVBL-`wBESBkE%xGDM9wAp57^>gW`JjtRNCvW}hq@t=WL?#f(|P;h(}SF`NSM zNXD{@_sRpCq6c}-bmpkfi4*LM1|-8K!N@GKz)U^vNBnl&56@4-xp!;k? zN3Y&lXcf)~w-OszfQhC?F2B9UkSwt(eHdny;0&t6?u>SFHw(r67m6uOW_cm}8eUY} zqC??EfQ};Ji%`F3p}2*fe6$F4`>sM3+8x0Mas;bRKL`Fcp~z&L+&tXvpquHM(PX{+ z?c-!IdR)xj%J)D1{*Qlz^43lNA-W7^_^5Js)5oD9)#ESP*Xvmt;)p7Ci`QviYgtPI!sVW3s z%8sg#+3S5JAMfIMVePm2ZzRLdR}B)*JQybQlMThYo;LEfn&I3y__81qwGMwm@y-Z! z%N|xAsO1pr1b}4Gnk$3?eZfD=YkA{gBt(&)@J6RR7f7j5Y>hXoA&&wMB65#dHczWs|D6e^ayCM|2mpAhOcSlrNBnZepyijFX zZnT`JQpwErm26n7Ns0l=Npz<$qE83R#Fl|9E@O-*R$iHt>#3j}m4VRVtR9~@c?Rx% z!W!Jk-&;z53Rik1<)o4aw)A=#i|55?iCm6HkvXRqM+iiPf~yVZX!thXp3BQp(@S3N z3l&@5Zy0+T99AZ~88>bSWL;_gMNzg*k}eKX_W3kNiX zDJeiCG`&JTw5iug(t2<6H!~K4A2k`;l(N$;D>rTrpM9;_rPfGG(cuo1<4+k<^a z*gc!#-n|G*O5(F^NIxio&6zP~prO%cs5ebmaAt-r2Hq<>DNw+3QN6-OhgH?1z2>U6 zstwBbnM{9j1W`aEM?l>RdMUl!1zCZ0CCCWEX>YN~(2d6nH1zpn3ZTK3@))>+C)4&V z5frY0^?e)K@C42Gzb+2{kAY=`x2GM+fd{iPIfQy0zHz`;5C9*2sScb<7Bq&vn9q-g z?eTFmgH`qpGRqx&yos5F0v>+wp`Z`cX$#@|%?)UV&FnZ|gqk{;JkK8IOorTjGVtWX zhldZZp9*&0fDaGF>(h_-^Y8CjzOR>|^?tlsRF9L#_@#L&;?t9em`%H7oKg)r}0sL4DWh%$Mo)K)hctZaNzxyDU1Z;DDI zdedf#Gq;!rHbB;>eP#M45CqQA@~qX6vhC%B!C&((!ro-$IzQkh=1f%^F`Ohcjxxh1 zo_fO6;1zG^iKi>4qm(4o5Qo6W-lXyP_5AtS(a|Z*hUl2CWHOMdI=trqZp@}XH_t)NMb*+XdwxHpPG_=Mr7#^< zQv5m@gTU7Im*vk*f-?oVtEZXzoc0pSL0uC?$28FI_m>jEmYm3E^^_)w>ftRDi2j24 zCXMR}Nk65T90K~s71!@eMmRx*iil&fEThmNyulh&6XufDfcWBgE@7uZs07PMkN8b$ zD}lB^w4^O2lczl?x*Ff4(&MP9#>LqCnpP(ERZ^aCGUN&qq&lINIuolbe014;|1yvS z|5qKqxHFH}y9;0^Kt~P-)@pnPr>VmXkoH}1Ivp6F1MDR9?Z?OU^UKQuej&T9_1J() zh`MY62ZvI4mxN0SBAuIUGMgQj%h_W2+i%O`vw>NPo@KAlv)>(S%a(c|w|3v}P3zx?IT(Wl+hysGZUV=@Y#0di2nDQM+KcZR9= z%ZpFymzU-B6N-1YUA%w)`3e@Zq2xETA-e>u zdTSJ}s6(EmHDx#C%DNcwq${1w1PZz(N6E}rR?rDgc0jN?4r=P_oiFHWkFK^$}62kjoPg+Bmfab;HHZ zk+0ecna;SQ!5VqV{}D|pb7Uokly(wpu7E`|#}j~n(|GFAvEvj*&Bj(%`JiIuIU2U! z+Ta%&P27bWGDlN6b)kC?)t3V!u2jnP24OyHIa6sdm?Tdu{8b9u#QWYVBopPj1v@bJ zv=;ks$=An8lZ5X2{pr&g zx6pjACdh9fOpQOu8O`_A>u$XQWU@=f>tmIis@dalJ9_y%S=CLwT91#YpiL;^RpqPQ z!ywry3L2X{z=yk7j2h7gnLDosm@gOg{75zCVzD^VSGMzInXOjOn{1jPXt+=WL*{29 zAh|brjvDUFh$flpZRQ3u!KQT_aB?Ue2uhk2b|2g12%S(cVW~WvJ5rX^mTF2;o6e>J zeaIuRLRoJV)E1fDsf*5mLS*w8WS&V;m~S!@r3emZ9SgtC-W%E0iq<(PTSvPOkjGh@6miD-SDTO(508jgu_3%?^d^ zvEHI}xKcWE(oW5|T$?1*&1jdSDWH?bA6>37C`M!5TMMjAf{Af^B`?R&9wYyw#?4N2z2P- zNYZHp>eP)Z!=lwr$Z17Fv;(I}`M%ASaE4b2xVmSaMw-I8ic1D&31*^;BP|z5kibi4 z7PX9dD*LtsD5FCP`clT9@=*U^g-CM@9GIYyTVQQI9y=l`GoJVfK}Vx~e4%J&6rxVI;`2O{>2#wTEqgq8;4!td)Z>w5e&V_-oNI`4#*R6Axc zY(v>zO;P*r9$J*|WP7un9UoWS>dPbc*HS|6%Y(=)T{dUz2hd_7hc= zTqdvVzP~4rpI=6wUl?=w1nB$y{P^|i>g(}*UWabFUJWpH_uBmk&H4PbEY>g3SJubs zbXq*FUVeXh`TTWJ*SD+n{nNPdK(DJ^dvIRnuN55xA8tO-Kae{Em{&#H@9(oGPA?I| z08Zh2v0AY6o^{m}0rb-%rM|K({Gke`-T}5$2l-14xQ1ci2JT6wqnSr<#-4WbrfFpL zHv9dI9Rx10HWfTU|0x23B(L~hoLLv8b+YIgLKn1=6dKB?Cg|L#k7+d=byk|J4wGcw zo9c02rUPx)z>+++qS0%J;Z$DC=TiP`uA=LnVu3wT;+VAt5=0+Gp{d{qmgi_Sq6ROn zXtGM=F^P&zvp4-?)S+S*QtKd`0ogi2`n8i`M2cvcZJWjfQ2vO(SqZ-5c-S=US~bj? zPqX0Ou=((EXq;y#Je;Cac?=Rn7ATSPAdv<>n0B+SDae6oXmqYh`+>-v8fTa?R}`zr zO0G0U#uQLb%SEffxY{vYCM9<31X#N?B0<<*v19GUy6;6nVT@P|$TLnj&$O_P)p-_u zbj>_!I5NU@Hjb*vsF=@e;ZjyBAZOHkdzp;vS@?RuJAvi z=*o=0EDZ{z^lC365PD*Uf0oh9b8&-h{Q2ztuQnR zzkmL?e0+SFjLy68r9Xd=I{4?+ zDY+kC*X+K(qd87qp#u7Lb6!kB@lM?s3sETkldI9_Ybd znr>rxqdr?WeAHH^1I3~rR3fRE7luk>8W_%BpZyUNkxy6+vrT(7Fl!k@ybu-RDr|r#|jnu6q@di`IhXxoy`DL zOH4UL&xQ4BcmgdaM z{e`m{D0ZERPlls_q39*=B(FCXEF+u4eX0ZsN!D`?2FWldPA?9J1V+j1Q)9k>8&K$E|a5FhcR zZV+;jq>_{E)=>+W(e&JW)1@NwoQve5@ zKYensTEQ^zC(gIp@X)Cu5uVyfat9fE#tbw{*Wl6(^HL4Ko6@> zthdSI90ss=Q}9$m`R=-Ay<9a+m=CwRu3L>3i(~Ut>`w62CQc!XktAXF{o&WY|Lt#o z`};pWo&NlM{&Y^=KmDvhBF(u&`JO$!yiDrD;_7O0Jf2TKe&Tn3J@3Mmx;#dM60*Pl zJf2tK7reiJV%FyTafBUp)41`vUN7t9LxpmBpAhygkp)33Z+IFOjIsoWFg(58Y{}Tm zX7&X3Ajv260zV#&=Iygk@{^KL@l`k{pzA58VWlraFU~hJ5A^wS)(cDjWRrNa%iMNA{LvMti_F^AYQD;Q}rKLG4LsaYhc5e5i$% zP0?C=c9H%kB8pkW_HS_wnPsU_p&?o?qGxpC0rV`rY_D<|tgylN%op=I(OG?>BVH`r z#23v+1-`C|Drhxq)xNuz3|@?w{Et`)xI2A2TGA3pC zWEK`C6@Co0G)O7aAlfVxYFT_!RbR_pt0f35{iS6NX^BInr}C0ZK)*Lp zZKe!N0($_YO3GYlb6f*XXa8N+T2g9djP>fE*@JUS(R-?7N`_IAq6sbsMLXhM>jME5 zj+i~a<#VsilAP6gQa_x8{b*xAZp4Wceh*YjnCXK5nzhWZPuZA@We5QhWHoGh1`g*xst?KLC$;nDVJGZy>IKR%v_cTCArjwbe;xA@LV|xQ9 z=|};*s9-H97{z2d7vhV|JR*m~kDM^zJU|K=E)p^W!OtoVg)G0rPfcb3ND%dYliY1* z#}(s;L-B5=V0y#;t$6}bgw9aNC{D;qL3=Ln&lPOdY`(2vVe{`GOMAsrfZqtl3{Kr{)H@8S+gZ>mjS#HuGC7$O!Ksl4Dgsd@D_bF z3GMCaHv=y9w?l%MWa!~{FA;{m2N$B1Sqtt2FAj1L znd&+-(vG1u1GiFYYoS2&h2h~<-PHs#8^EbHayc9k6_~H1SxhZZm}LxaPit(pf$o~w)V^^Wv@(kdu$5oEM-4| zrSLX1%#e3d2nxng-&z_(&y&sN`_j{UH&pQ2NCh~R6orjv3y7rVpYZARb$xxiW|G0Z zqeE4Fd!4UtLtRIRSa^TaG?6JReZ6P%@K*sZ?~WEG_`fR(BcL4AcWVZ@4duD(E<*KA zPDePy0#5-v!swiBsK1BMcHeb(=+BSyyNm5{)l9?P&7M}P1%^nWcpukNIUXBS>kf#7 zyu2Ckz6<4Zw|gCkgC9P;f_aj>mb;ysRet7Ik2`kX-_P~>aN{2r^Z9b}gzo##(eC{E z#76tIo=lcT4C&6vd$#1E5yM8L>uz3Olk@BAdDoqG=j42Xdw5aO-NZ(fsMvx|^at{t zqVmjQI6Q#;jl#{TB|z}GuI&24IB1CT8TS~EL%^Gm>YQ*Mt&wN)|n^;o3FdG$aLE~*i&6VAjItyw` zFE2TZit)&5fNdfb9&a4&Q*b}tD$Q!aM4ih1gpZ+md&LOQw@a?MT=ux!q4mzyR1*ov zHBl2z66r5k7ibtomb0-0Zt#xx!hv%QxloW8s+x;|2a_0tx{a+S4(Zq+iI zGhNf~cc2fdQf9q+m~yD`0uAi5@xFJUa;Ppi4$@0}6NsUff;^ zF0Z8qowBwY#5XWfZ0Vzp{f7t}aQ33>l)@P{j8Vq_eP%JrQaH+#0nNXIOsdYpebXO{ zo-})kddar}h@`C)9uY;H3c8ev=Q?|?3AA`FrjjFtuDc~Hk1XUB?hud%gXt*r-}lOD zLkvpys!X1#zAQJV%dxef?#%T;JY0Np-?gxCXCw&HkIm^1oy| zm@Rg+fQ177gs3vb#iIoWmI80V&|x3$PIpBUn(feNZy|Iqwn-?~)0sS}P8e5K7OHbd zw$1#wJ{}k7NvEUr9AnE+>K5yF>rg<$XHP;)Y+QMB0~@P^{OaQ7jd}8SF;9|LADZ7; z77F~P_dP za+?VS@n*vLX1Z#PyiV~9Dcxb2XPg$#FGhLsSrE513q#ViqbS{?T;1T*?4m<8lP61S z^Kf-s0`E>u^Vv#BNAHcCG!I;gEb3mDl`S)t^8)m@hZ~8L4$?&(VqDfTqs5c#ND`db z>7ja8@P<7h*AfX0U09*p)Rs8FvljA`ieeHrzd#)bswmQ3@ipRo#Nja!ZARP3>Q4d} z8j_bWjgxLACW*usO8ac@nWgJ8Wy>MIuq}I$Xt;UsW>Qc`=BLUx+HfEpX2%!%*i0_8 zEO&^W(NGh|f6w-wUZ^J2i|e*1NqD}OFmIA2qBEL3xcgH2z&ei}A+~VTnPPktY1+q3 z_!bTJzNdyfSE8efp&Cp%Qns?7CJYWk$%oaSq(S+H2t40s3-b|=umta zE!%RY6Jc9HQ!#Ykn?Hy~mO32;3JS|3)RX4|0b7}pqo;vN3WChuUSP_6IF@YX?(`Nr z1xinuZnCg-LpTp|8RXXwBh}mMTJz8FGRLUhx8$00Wp~Lz#@$921oY8CS&7#A03UCS zEAQ?)`o9*e?F`K6y3k$2lDk1}{PuJ=TO5$XaKrvQITXx0E4t=*9Ia4W7Yk&jg<{_< zP`lr)pWwARZ#p&Gr%f7S=#AHynkY`-3p#4QY)fFr1+cl{Bq6 zWYguD@hWoOrj?S1kRXDR<_pEo)Y*r{_Tmvx3aRJ^jJz-7!EM|)}@= z@A36|A!5ks_4wys{__8Qe@&8V5t^HB_jxjDBoZIygI#x&O6lS>M*q3 zg@HMtj_>s3Si8ewlkBQyxxn=DyGi3wy{jD{UdVKaZx_C{;pCzG3FRJaPNJcpc)mPK zOT{}H?K&0vJIX}Z(aIlUDEVgSsU2!IL@U}hJ+Em~m_|rie+|AQ49?ELKC=4ZDUTCzD&Ul3LG{j9fQ_Qwx-kv%QX`+!_2qd(r26*b{p2h ziIqGchAhi$=)kSUNm`$_WsGceh_&o08_QIH>_YF&QEczCr~qQ5LT@o+Y|NQ8pRrqw zF5mXz?7*3URGLLXI3@c4O`sqVY+?#MaeaoVvx0wUd*I&u7x@a+;~9h0mfyEAH6e7_ zVzs32fWmnRIU@t!Sk!1mXf`ap#5~yC_nfu$_7-FF0$&co5|`!>hDy!7M=M$=GvMWN z&Ym4Gu1r}p?`AH%zcU@%rqk!Zi__jxr7tM0-+<@*PF1qc*-APbxt!e&S#n7>NX5) zP8pj3&nl8NiBzZTb_C&vd)h>HKYFQY{YSk4S)~pSxaX!AQb?G|U{p%xduX{C{t4%= z+f7FInAL5qg)iHi4%7(#txd69Z#-1Qsi9_%YjC~cDM-3a=qFY{`jB}^{De_{;eAY^ zx^gQ`yjb1R)=)C8lD{rnA-C{DMIDQ*y=1!_~z~3P3A-5rkqsw3a@$0Yu3ElVS zoAcpNR5R~)p$aE+c%B@S-T6F!LG}LpdAS2-a+M@!!^Owbr(FV$OLs%b&bRZwcTL!r zOpd2h@_KxK{QiDE`tjq(*Y3yHZ{f~fZ9G#is3p{IIXnXu^k8v_)-_m%;||r+v=zRq~D%kVVkchEG09s zlLnAFPG-|3z92CJ*Y0CBQI@|YH=D3LReV5dD~`hL1V&p{BHdrMkAc;ag3lM>^X(0|f*Nqn7@l*u3k~@6 zxR}zA>e$TJ>*ezJy%~L;^KNH_jVVFO)8rEWZklkl9jifg3F6?dAJ}~tuDSQK>ci>V z`}ZUX{&@fX>vo_6!oO{m|+E8I~2T)bA!PgkqQ3P}&A z&sSI9zQ4aZUAKYcFReSz=_h@fX?5K!>Tkp&SMfos18LN zUWqS5{co`blojFP5`DOA`#oFSH*;9e6Gp5-(E+20MeoxX${S-3;+#v(R3?XPx<50` zg`Ky!eJbItTh+Zudj<(i{KPs!^M>Ng-9@$_1z*wLr;JW3F#%ovQ)UyMzmZJhm`t6c zmlh;CGNnWfSo2Nb9a};htvY67>4YcKKxN$+*Ot3h|C}}+w;*q^0+a^fN=DgO$v=Bn*3)qX{EfdE!{#Q{e26SII&?*HF_vdmjH2*uxW<9 zU<~#mt!UxYUP(N5GST%3&2Kh+Ydv9F#@82KQJWgs1j?4)yb86aDx=9b``#=~4co%9 zZ(Ai)JgLnz8-YR*1Zf#t!k~qI*32S-O%)m$Vkarduc3j>rV19K_z|JN7;ysrhVCns zNf~LjT7frSBpQ04^|sf`Ym`U!C~w(=IfJQsOEYfOPDFGZ`-hA{q@kfkPYvE*Mz){d zJZJK_2wUow`$hmmec8J*RfrTQFNmS58KkzU6)Gew%*i+&r&y-3eMTN)e@Q$~5k4DC z6WT0pmTFiGjO%r1yI0G4yuM!Fu9nNynu!jH4KBlfQ-0*w@{Z{X-32M%1xJ>cUnZx} z#7>__$ZA|X7TsZ+91pDO+q-VHo+rsR6gGKz7qhOg&*sx38}HflI3K@TuEy@^@ntj$ zHT#5Kn}0MUObCBdwo^6J8p53aR$T)7_Kk-slEpaQzMU4T-jn0*{Fcx2zB@0*$=C4h z1ZipX8ayS{bn>}@-^x={ov;4APnEbQoT(PAs<&YI zuv6Go#|6y>8&L(Dt}4r_*j2uGU<4Zf_V5!fN?G`^5pGShZuqy43%sFwyvk||7mI2< z8~j`AYkjgb-W0@FY1F!>O#72g2JVEdJeYa~=)8G{n8PL8c<(Hx-Vk`YA)B_D{WJai zdL!cYvXWLELQiVOAubwS3kmgfM%EomPZOF5-&%KMwNTtSc zsW4IBN42HxM1C4v(kv!7=k9QIP39-!-E6(_F?0`2YjPz678pv1OGn(1oM5<*B1})_%`q7!=`syU(IpCX?exzc&jQ<6pO?5RWc1!}bS$ zS9<_5m*&^yvb`z<3cUWuvmEQ}3V<@!Y;we5COOH*o+hiip zAeXY2u%wNqPQvAF+Cqp0m^C@@gwQY~iF1&ox8I#BZ&^QD@{fULTG`9@`q)t+{N$sIr!6$?2u9LH}dV zQv%a&bwAw95%Nb@o?FZ-nxuZ=XA->>td3$}0 zz{NCS6;byZ}ap0>OT4UXDHttScBn5N9St!`Q?ww z-98E0o(q4m`J6r3tzm+Nf@#t~*N#}QTU=--fOh?D)STr{tpAr~vwUURTQM*_r@ z?!%5wBB|xKXVQXYN=VDp$@hCr^DPWD&i{Dv(SO9$D(c_WWRzrVQ-r#1%Jeo0-3Na(h zaky|vc*I&lA&=1|@DsRIJ=LDF46EL>LWL1Ys-i;W1h>wuM+Kxud2dP`*Soj@>6ry? z$@6=WOsJ*of!yxV8&Zc@LLS&}BH1%#EE^3=N@c;JDv}IIy}5;NK%Gs4k`mu4%Qog? zI=vB^E$-v&7;8CWe1IgRdqovp+HXm|W@se@&u}s%6_A8Kn673Z;A814 zc~HaZi)yKt-)qJqotP`p^1$}SJu{CjEN$Vm-FrXHs%*s!mtoqGj!36k4WOpxlk&Z9tilGt=Ze6!3gqud#mRDCMD$BW^yq z8+=Wm%;~@vEU2z5wh&cXXvp`l+cA0L;C zm{Qyw9=7zW!sjz&tIy`$;;~skez@xRjh$lSiJ0s#G7OzbIz%KZ>ENrkl3 zJMjtOa^4uiiOG8`MGWb@C3Z2J&8aEn;=v0VohcMIWFZdW z^vWh;gV?6x+sL{Je25*yW`_zIhssD@otECQ*U`!Y?C|iQHo{;C}!Tw z4vWWiGl1PY@i=bqp%76pk=D|>^1<)>KV}%4z%aH71@k)mEOO(|U}`6?pI+xzqusW7 ze7u@8>+$Xk8D(-l{}Y%|U7c^L?-*Ue@cX7&)nLg@msR)s?=N+@mk&3upFVy1clba2 z{hE}l)F#fU*n1}h_$DM0hUy(^cy<3o&;*q4?;x9m!d{kz0*0Mq^)3k=6f&cT**Ur* z28F!)iSw;_Ab|@{4hE~Y4f+RZ9-UPgC4T#iNDsMOIg{^j%0Z`Mvd4_yL9{WCKKrcR z%D=?6GtV{1Hm^Ng6UN^ni$d7y%VYT_qRL%7^Tt8OrXM!^_!O2lyd(m;Ot8_s z+}de5(OZu#&8R^kwB7P?*qP#0=egx_*&s1KpKJ(3hX!RxVh+m~riW;}FHyX~afj*Raoy(45nDFe8kchMp3GKj^lm zxkd$K1}Y)b66k@Qq+%p);I%~1s22`PJA+uK&D$jURysG#y4lXRjDX^C>){xTlc<-) zFua`PrXouzZVGdY?908GsX=Gv1S#+=qO_-_4G$;~XTwiZIeah{JEV%>}Ek`yPURg!uFP0od6mYwz8+Y550=ZooV`Q^(x z)aUu(uB#A8Fr}0+w4N8uDpc*~B`6r(U13f41CkiFq2kROdc$@|?wz5_4t=Un?;--; zH>}{HQEJeKQ>=dTAsWUm&d^_mKR3tFeZMwScNkYUHx*t^{dKZB-LF?4*W<+%0*4<@ zi+AhhDYVDCe})C?-MT)mEKZn)-%pD*{fg@QCMghT8P<=`%74H*B2-(Bg3#|Ha@ap; zglPoAgg;Zk;RKEMcZxYXj})}9L4g{+g2^m&^1vhxRBXlMvwfs1U(r47yZo?fNwzIot0N#FZ@><{5EZ3Z=13~qs5Gs+5YAZ+yVY;QAi*^}nkCVCH>UQ9z&w~=oLStJ`y`|yqsT+F%)fG1rS3e@2+n~%Ef@ylw8LO7p>HvV`#q8uLA;kyO( zId>H_Ii1;hC*e!Ly&q2D7cRgi3|~5NAh;85Qte{#PIfcY=c;O+k}9!4o1|i?4CNcl z61)BQ3!;j{mD${X*wyQBn=Fs(^}CN>R+GustB;|8FSpHVIr%u5tjG1c)oR@&J1gIG zm6|t;17p823Qj$Iq%ioo0B2+4@y@tQ4ZTDu?&@(X+X3^+2SJhnE$n+o(*mxE_%hH4MTA% z75dN`#E>sJuvE0piEdSzT4vc0RfICx3*%H1YA&1@Wn#|(55>!U44O>sKuF*SQU{kb zASZjY!KG5p6j8rdhyf5YN!emVwTJoPMlUcy?A-IC`V;WkUn(x%ML)l5F4$Jv{{P{})r{e#2>rv!?(Ysl{){f>*ei7!<{m1slTH`GTXojCKD z zrimD`++0(dY{+FL)kDfe0(CFBggJA|E$U{IDS5fqxR9Kh{oVwXbOwN2!A zs{&CenbGDHQ$@_WT88dW<(Uew;PR?*aqjkJ+toAW2t?;LHF_i8W`Y8#3}{id;WEH3 zoSu20gago_5F9aLsf(%9jC8>2;6=X#E`Xd!Im`4A+#7hpvZ_e*C#YXuI-)bFvusr6P z{6&+XVK7-LfHhnMo`9nQr1#O{3#W08q>2nkBl-%CD+so@s;y{2o3?dUaS_AZ)Lr&H zU@aQBUwWtfI12*GO@XY(p(O-}K*;v&6?aUMIQ??C($ioKuSF6jKZ;=Tk5Pi`ioI__#ogr?5Vh@!5Q}Tu$cv4ajqdk0hu0Vts&jRRTRFZi}mr zD=08;w#8`|U7!kL+zDBOl>|F%x{C&GBT?#@B!@%t=`}g+PPpwL&wPE|&3q`}<0iD; zO@e?%ne1sbrbsZ>$QcNSz_>FvHJL&gv*|TQUE1T zzlVzuGW^hOKRhT;9$v8(B|FK((4RjP9Sy3!12%aA&L6(py0R?7sau6ztE496dRJcY z)v-eVB!g76snPUeeV2?k6WWnygTr8C30v|)?OYV8@7t-1xyH0$%H{FhTY`8l#YvkE zRK8}T6A9j3Z$2<@S;I;xXvqYW;IeHi{5bus*@@HWiA}6j z zM}3dvch6X1oRy)Ksr38>Bq@ZA&P_}}9&CAJ!W#Ei#yn5`=DFT%_<&$zrc5!$S;Vc5 zH;h=PAQnU_)Byj5a$40c<|4tk5#2)QO<>D5&Cq*80f}`Fy>lwmU2ILzxx-pZK0CkD zGw1@B0a!3?e45-gA(P&dpIf?oiVK7Ik%P&RL0NRAqoiNdoZj}MI_K!l!<^NO#%Szr zQU&+$h)~)|lC7^p%e~KeLFGi-zl zBMu*C3ouP4pXcnei@OJ?Ekhw6Et(F=y~SzHsP#FfnWyc|&CPshv5VbXnhqN8=r0J- zd`CXD%woa#*frJp_4N~S(LV9-^A3Ze`@&rx>-F->@=GY*%XgE>R|Uq0+hVas;~lE^ zb>qkN^>{rJ^o?MJ@L@5z3LR_3IccI=O*~sgyU^6qH}@6j+oBAXw2M{oM(d4KV)WiV zH1H1(Z7BH#ggGqT*ctPDtYUah6u)~#!duHBm4lrM#%f^0Nda&!9+|e@@_+ComUwba zq{-o8oLW+*83IaM<}_Di70(9Zml6-OAShV$pEJDRj*kUx9iTrUo2-qHx6fQT>_7JAhY*Fc_xJq zs7Z<1%}brrLLx&tY(4zGqst8VZA_Eni{S_sFEbz_7i6Ive-6c)FxhmMRWG77#YzB>Fcvo)e zXJ)o1T1-;L`Gz$w=BEmi7pW2XzkBPdb5(bQKzc&@#?{P8P7>!{@<`>XIqpGt?gB?g zRv1XyVs&dxYbE5$YZo;_G`#Yhzd|_!oN*%+MJRSvYul#qn&Gxf>;$?RfY6F}uX|a{ z(~(3{QoJu{aWCoYT)REvh+VybK_KvzUL37FCFXuvhOVaq5xgWJg@#u6eXnyhYp`Lw zt-0oyT46))MaL;5EDkfNcW(1Ex9L^R6f2wiZ*oF7CDxwIB2jI_>XH+>X(ls-@;$q| z_~oMe9&WSc$58RWAUr6VpqMq&i@Vd^1@g|ei{;~TbajRDPHsu4@(gH<%% zyB!;Gu}%tg=MM!NZ`hl_Q;-08_y&U1XiUX+JKa~dUG?Go@kT~=X^bBpW|luyato&M zrgb;h5)zuTi11-##j$l%#4`dOzygg&1&ESFW(FR%BFKP0BEIT7V-%a>xV$+OGH+{}nqgStwwUA=OfL2c0$Z&Vo4BuyK);4%gNzZbLoC3wcth)y zrQ?hNs7MEjV06gV=3<(C|H8>NP@Le3sL zBNAhWTagygK$!HN@bB=%_g8s`U+JSg&9wNY zvKA)M(Ai##X_Ylyj#CR%l^)E6x55J?;m{I-me%CCY`^jHmFt>`3Qp=FiPIYbF=AN) z0E0n0UfJcIKvVCK=^0vOj1fTy#9*nU$O?=a3irWV>049M&^D1{s6AuISSZ0~7jNQ6v!7oiQ2QGMnelDXb8RuQ0QLmPd*+nVx<$ z9J}-4DPtlPWIJG(ps8-U=9f@&zklzV`MclNP+Asu2(;V+w=Nc|#T=YLB<74(%f}h) zP$;^DFL+ijj$JXEHsJ#j)}I%%u6vqw$Mtx3T8!pH!%Yfaa`VBg1zF8GsoZI*xl=u_ z`17dq57i-*@PlvMtZF=tF3i50<>bq9QG;eOUbA|KKa=&bUZEXdj~$A4?Z)+Fazxk7 z?i=-cv1sMuy@O*Qk&&X}L+uJB>F9ycd5eppbm9YzsTj!+n(wOQk^>tmPz2M12i<#r zFawX?;)h!?1$mwd6qGoAfWV`1N7T~vLzv5(r7J}Tob&Z@3dpw2lk-fT9crLAhM43* zQI;5m*lls1&*X*-CM(m|d+I5gsuOA@#^lq}(o%4VDfRnW*d3(P=S zRY819iBX;ySmGQ=a?vZDxodffchX*}QerYO8qz^RDRiFOx!T!$5Jha?TFNtF1=?h_ zj4~G=LNo|T05+V;;$?!iA;5@s>m-p#*@K#pTZS249^ZYh{5CEdIBHnj%nyJgZnW;X z(e@lwr7YyGku*IOm6}@fO)cKHIo=WmuQQXd_id=)+?NodAR84WsufjTgcRSBk;{3e zSE#~9Ap0CV{F%7xhP&f>? z8W!&y3J3Fu&#d_Y2dbB=b5hWT3YyC8zh?jHzAJ9v*i2_A)uAwNcXu?Q>XxI`YJCS? z{Cv4ujykF<`C-=0vZisc@rE@@ahNZj=TBXCaRK5j3h`hii2t@|!FQc6tOY0CyP{Q< z+VX^0NO2zx#yT6X_@0-wf zyU=>Se4fnJdWVnQ4A^&xkz^67_s)VV^;j?nc=7Rwt$c)pDIsSC~@gq zBPwAL;%HKCSM2@FHjBvz-0an)@6}AW(ZoKBMr;&};XrIQF&j*xPcp-6&fqd_OaFhW z-o3SrWZfQaiW(+VyQNCgt=RnNNJxdShp=rq*oG~gKH%-6Gl6}`{%bsDV)n-nD1rB@ zzqQtSO3wCVa`8o%zC88Rde+5>hsE$^P+9`(B&MlS+>4&$X54?Fo0)L$SOb=*S;bq# zcVb(Hb&2>TS2xdG2IXAh)DQBdz!4;6Hh2C&<+$re6S>}?eIGG1tue`G)ofvpix#*w zJ#!dxZAB$VGJKNDt!^IV$K!=_0meoI>QKwTKy;c>LWyy6fID#XTPH>X3Dh=oc2DBw zz$CWXa*Kg0>2igUaFu)S<$U?e^6dXmxF2%^dvi1UW&ir_3b;43;sJ^`)%@!E>v=BTS4#~#@0vL*y)Q!duwKs=#y`2sjrVLG*N@9$XRon;<|MC8@pUpnLL-D?Ochj+W zhv`)=-npn7@npULw6k7^d2X6fxtmn<<=F$LjfKArnHg%CuNdZV=&dLbl*&XC=IgdJ81^R44%QwSlK8+FT(I|U$HBG}S}^k76*d@A{TIiOhG%0utdX#k{zc!8BS;cF zIf2sYu)0nrci@&oC4M_42&hoGfvN-;Vc$rNHC$FmKz7xW^N1Ei1y zH5Ye4GayE`kxEiIATXbIq4@`Ju%8~XVq(Bp=2*uJjH{Z7m!;yba ztRq8_WCjF3DWcYt96wA){n84 zgf*YT6x$+#GE@%V7!Xo~(47f&md;au8Cy<>fZVtAD(Bg%drV!xYeaJdwjox`Hg5rY zKM9tI;!|s>*|{srKP(x62WW!UIWG&Fj~_|m7T+I(6DggNcrY6(fMrNL4ccN44ym31 zjoMTjrx!`{^Yz8q#rNgea=t$Q<8l2uhcIV$^T(N72M_nT+UEMbUq9xiJO6+7w7fdI zncsoReMfhbT&ZW>!)&qW?hqY+zgr=ZD#nYYN#DzS66`_JzCkqE!bE5emNk3x)#`GU ztM}zm%1gM#s&-e^^Vd&bF}+-E#R%z|VLQtW_G}7W&ZL_C_BeZ(-n_d46a4Dx>fLnu z5T-Y|DSuo~!}TkJ;OEPyLzQdr`r1b(pvlf#y+7+UpO0>_#$DX)E-z8TIrUT^!wd#U z%q=c)IYZO+M({3^%ILc2#Vg^2#uS$Vg=NcMn-vc$7YJqEoL-}OTJjR-j*RwIVA}?< zPx?^8)MV7;3_6fbqz}oAV}p3#?kCT}U@2=3icHpb8P};ojqG69q`bk-76IT*ZfEf# z#Ymj*0cDlrI%%-A*?TkM=B!Rmhq1`NlNm=DU?DELB-O!Nx@|8B(IBXJAn7DZvBJuG z!hyuW4B=``)Vq_(H}R8Py+@HTIH@Dq+h%Rz$$Rq)WZN7pcfB?K94ad6wsboqQS3NQ zWa-W10M5BizAnrIl}|t_F$YdDLg>ij2oAHDCIoL}Fv3-0(&ieIH)nq61`B~k|Jq8G zRreP`glwaOl4|5e`ISnsG>}%PfvIBy-V#+GY`raGR1e-Hc(`(_)+? zk4Bwvb`0ccD)|}onW66^E(zIFMcSj|R)D-`)00bx*(pYpa9uIyxBLlACo!rY6mEoa z8>tg;leUjzxL{<}sEI;qv5TO4K}#ci$YqFv`=P9b(X4QR8)}FBFqqvH+nWFL*}v)l?# zb1`o2*gdbR>GHfETrR^0QB8`C35)r*vvxc;*WG;9SvHz*X0_>C*~U@|`SsJMIkyVZXkyyO!`aLKN*33l{CI>cDU!@_jq0u5yHW3rJ>Zz+ z71cUR{vuW(PZm-t-wa)xsrMBf%bMD6$fnU&X zq$L*Kf9YX=oi{PN2{s1kp`lPriU{$}DerRPKg#gjgW zJrzO`8QYozMNck_wca+NO^7&SwlU8LIb(Hx1$`~%>m>AfJ2tk#{JLmL*3&+aXA;O2 zI|R-ERzRu0DDel`vuwQb5zIHi16%Z=O){il_0B6q-s4qg>-qn!U;g;xY(KwPF3+xR z{`Nmt@6R}r{N;jz99D182QO~c>oZVJu5F09qdsT8zIwl&Kh5ULi(eqOT;1I-9?veW zLNTRM_;6`&i(bdtag*l=e9r$`G+P1|`eJU$bJaeaQ?m2z@Ch04xz(TbH<0DL14Zy= z+I1-2SEu4V?H>B`&wu3N4f*Pg<;*YV3(g(aUl=;6*kMpdwkNxlRx{0&L_E9PdAF$9 zb7OkX7F9I>>)y2;-AwZK5K+Wt#c^T;0#b=q)Xc{_NbO*G?6tYAn(<$+B=(bet0tV} z3xIbeq?mvMhv{?rc$z;k~SGEF5Dcjf_pPp4gM`rje*4OjRUP+pi|ui6zlp8 zDIumpiApu(;9aU2j@Jh5H;vq=aGrdBQsE+B|5kv?=!zAW>44ru+sTTO7Plasf3Gl> zXbSTv&0vZ}Uhj*}UzI%it2JA1gvyKTo%d--B~D{{i&p3A!B!odJ4=yJ2Aa7l4iuuQ zd_#F|ffH!GTUktlE?p38u0K)cRY5fJ{9~=14J1?s8d{MU!X^zMcuS9~{Kc`Py4PC9 zdkn>9684Y@7-W%7I-e|Gd&%?&eo}z~l*;wO$}CUA6YAz6mu&~5aQT`PZy%%-2Npd9 z*>;QT#10b$j8SjOEM>qb;Aox^TX!R?i>F-)qv*8?($gF5Fm#f5!&2Fb`{ZqAVkDs2 zbM9bCQhoX<+n&vAE&tqnxlq2yMEbhl)VJ5TF#160D&F}9B`)6zc~^uJIMO&VSe$%5 zkTvB~9vY-v8odIGNNDsMk_~BTNU%Pob~2)c_f*jLsO}MDx1KiZ0KwyzjYldbmez@P zrh-Kmukoe8L-yQ!c<{i$K3dQyuQ8th*V>i?@7MaHg&39n4c0qF^S}GkhUl0 z@(s=jJiZB8z)LXZmb>W+QogE=pFVwBn&k2oj#6FhhBl~p-@LoNnIgXD?^iePSiEm; zKE8YRbaQ?cI+r&!;r(ydXW)B(r)GX}*j9_DZWgz@b`M@4#+EDiQ0=x=OO<8ALQYff z6)EMSMBq@Q&|GjvX2DQd)J@vfX3*;KL6Skj8ABPotGV>MSC zRlSK3(PvMiRFZPY@HVZdf=*O&sD`a4Hg`TP@Xn&o_1QX@agLZT+Vj%XVH7lwblDqm z1@ZzwkgR7&P9Iyk%#EDmsnD|F9+|BriH8i2;E1deQ6ASo64hCL$6(ERI(dZKY|bwH zLSzH>$m-7Sd(g<%?r)p#vHfFHgJ_*bLrXEf7YC_z%wj5;;Vpg!)3sK|&H7{|wlLAg zX^2)6MjCN|MrsxDW`!ybDZ10h0P7?5j{^%OI`d(oK>^N>pm3ynVR00VgiZQ{$(TjW zmrDwC1I2%mrc1Hx*LcE!u;qp?5#csRb_lgG)4d>`!WDM3tD&~!BeS{z|HM0!RVg8v zLrv4p$eobL0}TRz77rw^j~tYR4W~P{OJq_U>}k1ibZ~9brQ%Zo(`fR9U5ThMLSz`q zW^Q1ETwTmx6AJS*)IA|54!3PO4MlHmI(xGSMxM_GxkudD^K z)NR{Pd4V=0;NTX^Ybe#M-W(V&JcBy0zTzOr8G(lN{tKRq*vv?7ujd=XiIt*xl0ejC zeo%yq3fCJrsnZEX!>qi*AU=R`^v% z@>&v6mVAJ~O$nMhI9EM>{`@5u=J|AaPd(1r%SA55doa20mRDzIch$wk9jPg~TFSNQe* z>gw;}P&W1UgMyZChEMY|(n}S{a+hSdOXH7!PSn-0O;Vkm8a33(0^Chc1byr%$BPe7*xX%JJ$s6 zoAk6v1|*^eArW$vMOlgSjMT&@g!!hLb{pvXL@$iy+RCJbQ}XCrEL7cJ-*TK8YK})I zC~6x|FplGtp)6a5+0^EbrG}F`HTnz#_=eH90_;vPc0lf6-`C0nW-#N2G;)n(q9rsJ zy$C4S1#CSjUSKSL;1MZaAADW9Kdx;@3IK_ua*Lu6<`$R|{w@?@*f8xp*&`HoROca=~6M zuCABAG>iTGVsThii@U}A?0T`jo}WCsQ3sniXG>es<5yKx)bmQ0H;+O71`amqr9JVt8CGS3d?0+XFeyo1KxxPC8{Q0-ve*631A0PWI%k*<~_4xk% z)tM1b7OUsOD;9yp^W}tAC5Cwm^xo0So0vD2no08nTN9B5=N(MD+lCQ38d#3)4oZ2W zt_nS2j5rw`ayAa4H<$ql@m)1V+DDS-$B@bs4Ui?AF5X^RNc%ZO<4|Bj*$U&l`5h*% zHXjoX+l`rIuydiWdEPpd>X>z)sk~hY?KSRmV1i*PHltGeDD2_XC6hK-!pyB}?`iqu zk}I)ZCoPCG{&e~0sh&G+EX1-QCZdIffKp6Wha4lvcMa8HSjdRxwir0Dl$(mQM_dz~c`ZxS1n$>3Vo*7NF(}oOx^Z%Ui*qc|_|c{e z*m3|!VW*8ocqCbRP^=fHy0`(Qz{oc^JY^YB!&Q>A6Sl_)t&C%VyCZB?9mglwpfd&n zk|B)WCTs^OGvvrqBuvL)Nxou(%mV$UhsU5;cgV^V&SmbTHTQtE*^{w}<|HN{h6k4p z)-IqV;Ka!-H@Er_CPiMbno(~I6XBZ7kQsvrO{9a?G(SpPpmuffwv?Yd$f;3xNg*Zd zeNgF=21Zz?z#qNNg}dHhO3)HK)X0eziTMo>Q*ko9B$X-P@OcH61lIc`m6~2hPioL) z5+Uu`c#Uw0m2hV(>ov@uK>o;AWgRJ%q*gfZwAx&;Y3oQeRG8$mnim|nskDO*?3h}z zag%!p^~c+3eH$K>_Ji%uG!)&GlYt!AlYx=*a@pWU8?RMtb7s5Y(#48e-OLuK+Q=J* zbxC(OUt>(!+}#_~J?b+|_;QhKtQ?C$oquYZ zJ6MY20g9lj-gc;%rmkEa-=sSE3tcBW6nrx}WH=6f_{NX(Z{I%rilq5)adY$W<|cQb zzaJL}W;j0_Z$AI?pMT`yeUv*UAj{^7&7u6qCern|T?yV&EA@t42;`s1bgnhW%9 z+gAVau_F9V*ksocHUZ|nT*9H;#fGpqaP7Rz?#5js+yv|=G~AtK=R_F|X}Te@_M6pd z3DMzY8Vjcm#FVa3!F7J5Ni0DpKrZC57bJxiQcB{~?+uAjtX6t!y*2!j5tSjxu6S;hClPy%)K|2#`JSj# zVI~5;@kYFndIciJO-Xr>oIk}@$%W1Wkr~rv$pfKhtR;M^)O(ZiJ)3bTYl{V0e_X2C zR)SWm<`950l#>}1UPHymlj8(qPbLJ7h^4fEy#Zd6EIyu+n~hP)p1d_(NXzzgFtq+; z*<@04FpyhW%eDrqn85l*g{yLC!;T1QIzl7+Jf*-Sx>Cyt?f%FuFYp!98nS;MfOh| zJmZ=fki9O#cumeXUc;#IHGEiWj0-)(rcIato0b}I5BPj=8uTXp%B2(e?MMq!zTOvN zl|3kRpvz)x0fjtaC#!%`@&W+CZY4ku$q<{8sS|0}V_btcnIu2%@)Pe8c}9$(&u3h0 z7e?^p_t%U3i#Ti&<_GXhS`G|29r?G zZBfyX-`yc?=liG2{IR;c{IvK1!`P~t^&k6w`f+;PenUO}YkBU?ugNdH^ft18qV=i`H4XKal9Dl9 z8*idO?3(4ReHutQ|D`W8(Ih8k#b{Gb6p8B60-RoU#)L{IHzn55;C(R#cgz)#YCb4% zmLXTg^okW-8NU=13)-+4Vez)W!PEDp60@7+0Y$`w$+& zW{p-1E+jG#pt%%pQugB5VjE$DRgOe3Ho?R(hEqth(@vx0NE2@1a8f0nEJE(XEcr$| z0Yx&o*cBj7dvw=Mgz>V`Cl3*HL#I@mU^7a_rBh@=_@wr>HsXg=PG#X*pE&sp`EW&r z2@-03{ZVQ2VnI-yz#};*;4^=%7d&Ip88|N^ap_GjpoXb5^86*MTj)rt4Gpt`O(kX` z-I7nm9CbR=^icK+Fp+V*MS%2-b?~z2j!qO2vhLtE!$YwN2Ib`&3Z44Ub+9ReA`HIWW(fH~Xo=wXbTq?o zBFtj-p<{2}Gf(^5`XT=vEjw)4!3?AnbFksL*$m}(O>0>KCk`8sTU-&V|MwsN^^gDk?@tG0 zT{cxao!)%>7{c~=_N&VG_P5{OzkfV`IX^!?s}|qvv(HsC>#x_GTppfZfx>+F_Ca6T zo~&uNG>8RmvLo+%*O6)h)cgB<(FpNwbGh4gxx^q=$HlfGjO>T1?Zn%|$YQUV3ma?8 zN)YUQO4BJ71=TBBHreqnw2_qQb6Y5|_qTi#9Gldq^HkIX? z$>=T8E(X5#(KzFpHCQn5gsa5pq9L&O0jOYVqa(>PWYnbC zc6rsOtswXsXuiKlWu^SNz>Bx%xKS2pBv@_){88(YPKhDrf1g`-Z^IUg{Q<`&4jKh` z1+l@^kaC@th9J12iH18)j}*}z3BU{Sp0uG)t?XlD6VXzJ-$@#sZ=;@Gj&$7RfxwbI zqMmxxY~pu4;chyN?MX*r&XVJSX$KF#oY5lJEccGK4%sTBnp(z}z`IIj~p z3LAhnbPLVz=C(EqB=jrhcU$}mAI%&r@A=|s`HK7k z6z$jb>!MpQw}t^!i^VUCN#HsPuXo{ z9JK{&oKX%~0`|>UmG6J#^8JthM$-K8m>YBEF3+ab;)50HsCT+ENFG<`!#GH({m)YSf z_fI^L;OxBw1^;k$P|8FJ>ZDzYd8R6xKAo(j#T@p&2pwel$Bxt?#b#8%E7u=qQhynd z4Dz+*rwH9pTaDfuHYd0q*@7QR^{zu1lbUHByD6Iy@D9Zdns1MYwx4O?Eg^^~f-R9F z*Mdqmp;H>wbC^|)^ajy_Bu}VNY#=>HbAzlBy(yqoT>SXv>~K!pV?tF9ZvulaT?AWO(94L{}#8`7;{d0~YU{8P9v7$3b2> zwJ*pUmpxymrDnA$3KfONy-_d`et`CsB=>=joGUgHrzoP}$d(HNhlHF=YFUshE<{W8 z0Fj=vmYUCt*=v6>`U{5w9?2<_dX<}%1Ub@#!)fL7fn((3NIylOJWP#+fPy|0bzYYv z91(-`%sO1)Yx6ie+J(~?UsZvYgJdZnKGluN?F6F6VJZ1TWES_{?8dl6DJnL#uBP?| z6U%#&16Qm2=B~P{U=52td@;)-5wzjVJeizh_u%x>PjMvV5l^}3Qt zx5kc2vLwD;1UqIZQhHvL><&Q6s%wg4D}I(d6n$%F-S_3??(*N4N}7M33{x_^uYLy{ z^5GlH_v6b;ZoSVI%g@WhkH22Ne^dGHX5so3sS1nZ;z$1G!}IESkxToB>iM{;S`%Bg zv_D}6aWhvI1HyFX`EJXt_CQj~p0O@1BQ4RZH4tLK-iEEWvvFmT@P;*$zEmb)Hxfvs zbV0e|eLrKgd^(Zak{N=Rf|itCtg~ea@rEkX?Sat+imnn-&xAr6T$ZFA_HUqYNK>hu zyk%di^_KaQZVftSIJO@oOPGQmbv~S|V-0qfV>M~PG5~dIp1iz6h?kD#yF-a9_sPiG zS~~2SRmLq42YLLR99$Fq6b(~{n!lLtex1?&*U!=7-;<20yW3^$zM)clI6uPW61Fu)_EP+(4 zXfUaFT3V)%NoX;~UW8DZ%PO1&Riz8P=8H1FgIzDBFRsWd!9j10UBuHQ6L_riV3~4e z$96w-Z3V-uda(Ap;CdwuV>Fppfi<{c8d$&F>1t4DDtC_9XKo~1f5T#!=#H153|=p3 z1DJgvYljQuMZr1Nn-MpRv}z*e+H;xvd;lRkA5?CIU`l>_T{F3dPbXhbIp+8IB?2rK z#VBu@f|*YR&2Sli!I8M5ETK;t4)u8Ekk8}=r{=9R&-tt%6|<#ZLBI-+qnkGm$QT~P zQ~?|rAlmdAICEn2KslC~z5=Q5P2IlfBY=3iT{5yyadJd(z(f(`hRYz;8=PU@fO#dt zT}9(6Ip)_TDJnPM8@#=`Vl1&b?kbn><(ia1wBrE5=dZ8O8s0%2kJ=4G!3CZ0*^TGo z{qCk~siJI{yFf%_RTZZ`kOe^s+)|moEiCY@;P8f~C(S%o1uy}eV#IK1cP=fe7$5%z z_I-SA+uL`4|NHyD&z_fm{rcneh2{I~@%)d^kIR=2pJ&zC_vh-HAtc@W8Z*dTzQ5u5gB4dO+{Y&oG_7V~*Dgj=2rA`^<+Vl93uX|zroM9Md5KIDw1$8Bt_PCH0x z8BBMn36l{|l6lwJN3k8zDyL|)LL4XbE-pw3>EYhN8`n-r?ciQ(2Y~GZ?&@1a>okXw zYl%%Erj{}3>A2H(uJqeVU>?n!1UzBPye5hZW)!%SCHYCt4;9XYmergCaM+kcT`@L$ zC`re?y+|2G+3H2s3u^zwXoK{JRY)Uo=usINAT5m+dP(Xa{ihsVSx|yE3`0|U&!aII z?QoRwA|so9u=>a1I&cQ#1*nrs-W8?^=J zPHgEIklTn3BTgUlqAiZEb|b*40Ug<(lH4*xok6>$EeBX(gzG%}bEvC?s!2?RJGmZ^ zbgV2%ac--&LDcU|_Y+#T(x% zL)d)LHp6~bwR?oc@AFwexkmMl*s20Fq1>7F4&H`&W=3TpmQjN$%VRK|p`3cf>eeJt zXrCPUQYb72v3>>cnlesgKMbvJZo?q+YmJ=V{AGnBTRubTc@sy$(6kzMiZ)^0rm{{` z9PXoiFlw8S7pDk7fXH;*NXB2R4apl6UC21#kEn*Xl;#zTOP$=c_N=CPW zF(*!rPH96bOc}A3SRKUaOq|;9mXl1K1f>OWhhZCqQRV}ZZDOeoBHWo<81r}7uuC8- z7@W+Wz^r@2#MLgc;s7+2*BLC5P#SC~q83w4A^f*w9y(}QH1m?6nHOpt3KlOd(66cH zoCG4_F}5^0>uYkx0p!_s!=*xIqo7EyZ7_Q)z&%d%qd^HAES_p!YSk?#);{+O5hKLh zM4DqTI9d+kdt6biouW}!dmK&sQ!81yMs5#W3L`H>FjxNk^Y#nKgNXaZnvkzN@VkL7 z&};;P-yo54lw~_x8pP_5FYoxokfiCp8kt#q5r!g<9?@wB*d^ox)(80@GZ|X9KyKJ4 z0by$-2C}OMj+Fl&Kp!&(8C<5=Zm6~^WpyCCl9oCI#sanfxnjFXn>6OdN$bTvX)Rx( zM&L&MaU&9tX2iDBuIt=!H$=Mc_WS*!xxZe^=LG#YjH+@O2da|W?>!hNY|ZbQ#q4o? z_1o3e&Fu9_hJtX(mSOi+5juoEG@evzUCCdtF=|SsF9KEBFZMUx%+pmg8OEY7aT-Zt=L z@#*;)Y?Z%WKdtzBcSvPuTf8=8Fg(qT=Dp2*cm5hW@`3(Sks+43`*vguHq5s|-@SM7 zBwS#riprL^5F3L)Vme9tXrHQL&#Z)!Oz8^&p!BNpyRu|qQ`2DM4eTsNZr9_? z%UP>c!$ggMutv%Msa*$ax^=<5iA+7ij`Wtz@8-7m+LXZftM%-T`F7E-@C|T_fhCai!ws7dGE?a~Jjm*Tin)B3 z;INa4*it%+J|#|&yhAQJmf%QV!rtV0eS{-bULV>)ifdHmsX8kyJ?aBO{@b*7w@6V*yucvIw{DQ75|VIe02Sfdpd zxSQsG3NKq3YYmG8@c|9fZH_i;MyX76sM$8GMgU%o!Ge1Cd+{P54;-e29s zZa$5Rw&|tFBHUpz|n!#LJNjDS9p`2dEqszgjP@cstf=|4yj57=e>FWvq_^NR+6;V0>nCyF>;JQ4GcBn%fF4D73@laB>Yd|8anF*y#%i zr=~Czg}V_R^Y?v}JsLt8ZZ`_Q;pEJW;NLBk)qka@^9zlOtJl+@YOJYgyk9GBtn(GnDCg4P>0wTcbJd z=hBHZG$7#0DhA36R66(Hz)#>}a({;eH0aqDa5<^&?mLVQUuUzY=BMD{W?NF@6;z4A zWLz|>ZGOCx!9ZBV90secG8#z!&cE%`}V&+3u)~Cwv&9>b6qdnQF+GG&A3kJ)pwI1t!C##MW7vHOQ|* zrCZZM%jOk_Dk*bY@N~YcE~pp|&OAnn%}*%2G1=qs@v-k7Tczd@rYOR7#)0RXR{)IC znJ9FWy~c<&hNe+T+;u&Rmve1@3+ta?vDjw6;*nGhheBOGy_R!N1LppwDbbQ0*Ka|mBtC6cbp9juD9KaxGaOrXeVrl<>ZKJjn_h^-Dq!h z{8^Jaszt|6f8gpx=W~SEv}VQtZDXv1+(?R!l{T*s@Zfdv1ksb1mMlWrv>?@%9dz3t9tgAY|B$QiB;oek>8oa1R8iA7nN;C{IkDc)14NDzlEjj{Li7+oA#ZkrQI9 zjZerf#q}F0a2zK?JRmlVqtFqB6|>L82nO}^BxXQ-&XpCXwcp$V%>$P^-wiBsszYJ`90-IiSKh;x7*J-0+Fnz%RK_kaK6AK-nHdGavL z{rAK6=|?WmUys7RpJ%T(>sf4Oud&N@`6%$@Qxj+X8u}Z|E)U=SqkMxSDCWs_FblSUc;m3NAz?=%y`hn=jV(^C&Y6rsP6JtzZ9rnV z;kfZ5P5R^@E88GeJ?t(mC9O8GtSrGL>eg1AByw^@;t)<9cj++`tC~1j5(J_0viAmZ zn`BTc9$xT9dc)mWldHy2xMp8f{fz z_~oFRj!}yiJ_mr4c1Q>@vhX?EPUt&Ec77oI&|R3?Z$u79*;|VRBAGvtyTJyRgC){K ztOy>`Sh9IIZ_Zub1Ui%gg{#}FRvP~v}0ZekXVyot74{2dFMfHCs7lo$;$#?J3+q6 zWKLd~=xyxURV*Bpy7W;eMQVgSW8X)1@DaY+V3*hh>FGh0TUib=nQKU;XFhYSf73HL zNTXUP>MP_0LtHuLHEiVEGS^yITG7;<9+nXDJ9E6z-bmUo-0T|!ZtxaOVN;h~Oc~7U z!U_pCE8s4{C~g9XW+KRr1$&c9l%8msBf#hT1Ic~&_xEsM(x4Ie$G*DHU%r#Fr)lQP zU3(`(@9uT_I$O-<7A>|th2*S=k8DLP5vbBN`i&V3avvl$#qbqLd-7-ZNMfigYUen= zhrUPG#q2_sCr|Uk^Wo*g zj~_oiyzpzEs$Df%ef{*DpZvI5Jk7Vy$NVVp9BhG^w7a~X?3AyE?qb(~;O%Uf6kPGr z@BIlGwuu})J80!m2Qxc~lB}C7r=+3zVrxLs*(s#K}%-mI8E$;VFfO2fLn z+)i{=ChIjAt)t*!zPuoKtC)$ZFJ(KP+pehzmTaBbNc)Y#34Q9ju#tHm% zL{kg1lG4eJffx|Kp^S4;Hffej4yB87G66;r4CCg8BN(^Oi_%PpDJWRCbf0{z>uU@v zbH^>8lY`Vc3;=T)fdM5cjW{42fD@zRE=ZxlCVKZG<*>H#)M8&ld% zER-#sxFh~z>YJoYv`C1#wOB&tAhDN||3H-6cNj(GAvrd)%XBS^m# zaLT*~4w@xAwLl12%MuqSnD6Bt6W|v`;gK1%F=R;N-lQc+3uA6W(M;r*wdqT=BMt5& zb5RqWc=8i$Xn-D)(E}8oDOdE3m(X{!fzD==8)=SH03_xMyr;gd)nKA+4T2Cj2O$^m zB=L0mTR0m&M7Vj!)G8rV@z7x+Ya4VEv;_qmO5WcPx?yI63N&ko#p$t8NlK5(i#ZiM z`P?hfM;5`- zOO6&B%669X{fyN+w>VEvPaVJ2f`^f7V39gabE^NS%_WCnTjCffOc&n5)?3aeh(*YC zHg=TkZ>xN;nK6G-UH)(BzCS%o!^3n7DEr5^Z{I#cOZnp)NrDd?p?3SYGVD7)#(KS& zV|Y2A=URVQEEZy(9KJ%P^L$)vkH_k8teX7)`S(xH$Eqb^aJS1#OUtV-?}>6rk6jng zcFXF&8#-7F7NVRl-7-yXU;>X@ycd0sLch6P^-ZP!bMK(S}Nb#YH_R z_%TI3fx2;B|K?Is5O8izhhR~SLlh~=*o*=~$xXoXsz3H}DV3&P0l>Jw)S5-%AtDz} zKi<|(KoMu=DB)fyR-ue8Y3E6u@TNC-L2fTc`*3u*wOtve7(e7-oB zJ40Hoz-h|SORr^+7^*C_M7WIwQCosBa&nMb8?;?P7IEPmAmTXI~gShyxkp!qOPw-%NJo4Zr?p|xyoY05_9qeSO@i@CR?T3M* zt6)->N=L!K@HQaTL+Ht3O41YHc97NwQrgfGJaA6t%nSZDMNfo8(`NA{~1XVLHj-RCW@@pIsnh$evqu74NL@kc4>W| zn*qFwVWxNmVl0zUQQHv3^O_t>%T1@=M1UV|RGwm1>>Ed3wUEtCV3mulz&KzJ&JcPp z>l$rjaYkV&Ro!jxk#W{ULDnqbpkSd8-&c}cE|>pz_WAs7wOza}%(q)8H3KS-#6niv zt}$F>OIIo-6chJet=OsWau;v7Ny%i`mb8T2`p)*S^vivBCmeqF{2!`IVBgOV57Vp1 z!{NivMufkfAGZ$=4RssMemLG2?7O>OKhg69l7BSo&z}yUpd6oBz7HQ>p1;22mY$zq zSFhXW?ck6ezuU(SD}O@i9{2gIc8m{fL8W6_p?T94S*7h7HI`&rjHWh4B;q(tB%?`I z--@i!#IQ^`1KSUYG_0VQG$aniEyERFh8)}3mx{P14D>|%7BSiAYe9{9?X{&AT7upf ztIQyThR{9t#NL^IQj~F$5dq*UG@O8Yq9Ynyh9HVsv9a)G;*3kqZteuc)Ie}G;9ed- zfKG(mdTIqvJ^_lLsZVr`w9%!DMds=n!3>6+959tp?=9&%sm5+H8e7k4b4=mYz&V{< zr7cSi&2}n8Yix5y<75w%+n|E;`x)KX4kDnS!126rH6bHi1aitrZ4=>XjfBf3oPs^c z_ZgV?Qgco^fjJ7#bl%^`_V<=htXU85X(!l9^{tHE$SU{jzxlMST2}9b&d8w1n~474o|sNAV?hVAGj04HO{-Q*M(;pn0aq7 z&}cC9AbIB<))<8E^fONiB|4cn)#4o{Q0H1=N=wI2K3i)J_jTT&Z7BU56lhq(){%!r zF{nw~vk_BpaHH~uqDBtAAI92-HFZTe8{^0d&L7*RI-pf%3}kb^0?Rw!AoJzp=kq^4 zFPn?m)w>vO?eF!rjGvuHL!x z-ZA;+Q&C<1`x4BPzkq#To&WLv`{DfO>iyTtu>$zQ2>I3OlepcVj#UNGrMM^C3itYo zJ}EC>FPZam{PtmW{BV9eJRP17KhDm6yi}LW+-bor30;HWoP8UUoCVPjdF9EHJQ1x^ zPGUxxc-~?XcwyD)CvFI7e3C~bsRj*(DCB1FuKMD>hkH)jq(Uha16&zv1=Ce3BADln zok|U_%G?`b(>|WU(X5;Ywk$Qp*&vJbbdI1+ltnp2(wK`_$j}|Rhl=Y0BC64BIJPvM zVC0TK#AIW8Z)i74;h3i|Q>}AiLmB0oI~2=WZU?Xu#Z=~j?qtcz`>9kGlv;mvO{ort zmQABxWAS9xrD9wd!Nd~A0k;q4=`1g;wu>Wcy&tWa1$@M2Xlw_=tHHh=RK!x8Q1zld zbY!4++i**CI7XBU}OK>fElkTS^=-u33ZKPH+3O*^v48{dkt&_+v zP*}ByTIM6!a1^=C%4@PShFq939H(fp&BwmC-4_kkOkRME0P8ngoe~8rj@q7(+wbcQ z&0*0v0KBdl3a6|!@h0=b4Jf)?j*WQ3`&D|mU& z&#qq=ca74_l!ddH&p|)Ahn4Jd`Tx%U_0P|bv)SwGJRTM= zXJ=Adq84MN;r8FiAK{5P< zEb8K*8jL^Wdv7=jNg1_BgXYgEjdZZU2VQFKRJ<)Z(i~Jvw2tf%f^I!$L~yfdqg>d_ ziqbr+Xylf}(bX)q%u`giOID@ifOHqc@0bNawQrhBiaNRcY>YJ16Md{L--P?UT8v(H zxJj0+UJfK`!IU(?02p6<5KG8HFw|aqj(pF*zv((sP8P=cM!@ClC;ok4>~1o{C}xV~ zI}ZCNJ*W~)S{_4owc=qboXbK0*d#LkS2B6RAd^8^Y0R{={kc;pK+E~kY0dNb;fKUR zGRUM5sCKZVVc;_iQN*gjPTm+Pa%km`3{I|05zdjCgp7uoSk*FSyceUysFLz_A6iRD z<_hA>BUXi85L=4L?EY9Zk~8xW&7Pe&9FEbC+*v?<3I7jU7TFt)Ein)}0dfneL1n9Lt(Ezwam~-QJ{AXY%GryrlbphlRTfH6B~TFrb>wgEt=GxL5b_84->15F z^+1!}n3v;`c2r#WdZkjPFPzr!t@Iekvhg)mjQK2rxiZN|b&&h(;3)zgxEZFH2L~#6 zY-uJfJTvkwllKYN*VlEAAv~$Cq^=b2ev0hLE}3uv&quZ2jK%nf;;T^!;G~v_nmW{q zogm8XlPe7T4OvoY(vJQVe^Tvf5wTbpecRFt$PcuUWz#IL-o1Z(UCf@g%~EM+P03p@ z<{(>f1dTyOK?}jA2;^6&!&{3+(||K}dv)ro)z?e3-rJ(qL~t-__wKHtmVNj2KZt|C zz7IFAkDouEpKV!;KS{QO5Vb0A9FEO!tX{r-`yfR8+spB3Dd@X7F2B7j7vEog5NcV? zAjVuA4%kgP3fT?p+=L~n1i4qh|Nv$w-GD-g8#VDQxA(e0WwM01iViDu; zj!{U!GU!)=bqAAIN!>+&sf|oI3}$~#_Mcr#ZUCx?${S3hOT-UG<#kUg0Fx}epgOw5 zS{x~$sL{z4gwNH}+XdPkLF=&aLw>KTjTuDpJ*?vMGW-S4kFd(tBbO4vm)vOJE}AHu zl;B1HCr}RCf(R$H#o{f++c}avN{M^TbByRh*yHkU$V)*?U(l~lr-1}`%nx)3$eaor zXng4?!FL7IglV{~4bXOK6_}7g?GY-u$JnI4-LMHl1y2g74ZhNNF?ZW{)ty1r7D1Em zjk_H{@x%X256EHI$~e%7ewuI6U8*zX4#u4Od9}50%gdD@lkFSGEi0-m$D-h?d}Yif zzt$8*CY)QV7J|t9pRn)Ao9ePUK7Rh!zdk?yadk7DwcC}+cB&?q?Y~}f|9uH;yL^18 zx~0N)4g^j9#ps?7i{}MZI#1Q}`Hv4ThY#n~`G@t7v+qC7o^$uzIObM*U?&|o-%-#h zT@ci6Qc6RK0nsg@2lQYnq%CFS6e~fiymBZxNoCl$M-j)_-m>78+O2vSWUAsyfUC%f zE)-WP^2!VG#mX%B#z;hvKZd9Fp_fAr#w?qYrF2r?Y>dQ2D_KnvdoKb_Nn13kU?^EM zC6ZHbq(n!gG9ZPsGbdO5$yZLH4TEt=PVz&p8mj8PF1Cgow$`LR;sBDaTKS04bT+T`{q;tEF6ys? z!dE@#x`^!6B@J6{Q^EDzbr`TBT2K#G6RuOT>WPoc0vjLPN>r!`2Fj~oJ5CZ)i|7TO z>pHz5T3Ll(GgCP)V;ksp;ARsy%Co|P1xHp)AaZlf?i;-JL~)d?&rG%xm9LU-uG`yd zreM8=^7j6q9WM3XLcKjR} z4d%L#YD1@++@5ZCr_hyzdn3;S$tS8KKxjsd{Z(J zn}$4*CW?UZ(}>cW12g+*^1P!4ioq^{7~gokux)qd>zYE@UmLzG_=V=LUaDg`Ym>(< zkOq8Yj;gik60JIxmEja;qh-VJnpif`0_HbFGK8RSHletf$_G#Axmx)#8r`*4R-XYH z1>_MI43-ZAl{!g)5glHW5og3-puJ{Y7q1uMvYxX_Fyd5(*>*FGCa9fd&s{5+*QnwI z89e{Q0|Tso|H{gJu-?0)Sf16}5+N7?QMj@&e5L0UyTKUDpAmZ+dcchM+F-DFYs5Y^ zuww3}K|Z5Efzfd*sL^~HDe?;%fN}Nn(%TRWY6B4vT8+?XmO!Uip7fj@MWHjq4Hbfe z3A0GZwH>ooC;MoBA+e1SL=fpNYY@e(zo{VJ47HrAv&^0D!7V^+VI+QQ)kjxw{ z5h_x8&?!}CwAjhKXyJ0z;h}hS9HfR(Ha2i(SX7~1b1CI}S zh-h%``%SGo2C-}&{A`|k&uDoz<^-6D@oY9Gtpv#gd$2*r z+E`y6z_|4^d8xU+%~jl~y~m;hTJGi}7C*Yn<|U8{O3j`L(~P2aa!-UtK55;C;-9cP z{Rxnx$Fn|6ELM&yW6uFqa@Bnp=~tF9{TJbB^UqR15bf=2;2P<{Fet3p>ixSNRIke2rRAK(eP@8v%~ z{C0J9)kE!`@7?3!>}6d&SKapbbhbF|y5sQ`koXzHjhDyStYoECpnd=KzOv~g$t;etCFj!g%@9?a+lm=w3(3F-LklVE z*l=S>3lwy=DOok8W_u{Ye8tzg6Fa;wm=P!J0qF_$dvBF!C@A zbl5{?d~JQAi~*!RQ?>M##v;>D>gqL`HD?z_$}?QY@NYmTPu(aHpP4u2g@pi7K(4>u zidc~*%s?S9f}jn~2FWBG4PkC4rnZ@g?43@C4Z{#AHRpuq&)rg8+#E@5_vz#oh>#z6q^ihA@Kya73v8Dx(T7;n29B$m(xL>` zM#7g9hE$?-0N`dTXyNq8?9wm*%E^ISFXfQc$dSn#^j2XII*?H6=B)#^A44=#8Yc6S zWP{mR&&>cDeab&^srRUXNV}*_gRr4Xb}rx7w}0MJ4A$3XcFmDHq^q~N2;Xi(OofX@ zmlk}>z)PBVOn#ZSw;Ocq8^ZR9 zI4Z4&E{DXzNP4d$&4mMHZZIh^q$fp~!P z_%S^ADR}mgI7d{jbP2mfQO4iNns>F_jp1c7(8oRZ`6DkE{O)Ml!{;6$Om%rLBQ}>u z*Lq(8Xg;tiFW3_=7TxmvY;jkuzE<;_d~;N)-s;tlA`2=t9x@rB*TPA5_{Q11+TN+! z%Xx6Mx)j&DbnqzJ`v4FnKi;Jjn=1v<=f1m%dxGox=A^o0+Rpa>%iZ_;_blEh?nCTW z&(EJeJ=0HR^?bRFPut_OK0e`NyPj)wId6`~3O2X7VsCTxUNA?et)4$UUsiaC%lx?JKI(rDT4phj~G}Bq2rBk651J4G5(GqOTZ^>JTyqQ)JBv?aS zo-F08r=7LUMo$TnntO-3{wd?qd_7bYsOY1=VA9wQFOqv~Y_$m{f;nP&H~HqAjIPW; zHPg3n34j@52ase{lO5RSho~dFQ#F@0{KG+rpb8ln4CIk=Tvk2tGTS!$5r)Z#7O^qeY2q)wjD6%>6#--=878X|TL9G(Ug3&Tbi~Ny>gp!lu8QWGO0eupN zBTlaUW687OPjV(21SBZ<8vKH&f=Fcwe3xX8rHcd-4kSL}QbIUFEZKFs9PoAk*QB9% zop8g}Du4~UbHQeyjn_6M<~0s41tH#0K}Jw*+?#VLmfAQ07ljY)RUOfYa7+rPJcwoT z&x1s`(Fs$?0f2g3iILuf+PHw)H=)x@P4{|#iZ;XgItK9wDPIDQJJEq*vk|<=N6Ovq zfY(G%UFT^pQr`kpQrI5DG6!kq5lKYG6HW;(!+h)IhW-nl8ADe$?k0YdIL?O23H@zB zv+={2|LqB&OZCa@OY||hI6UN=V;ZK2kiV%1gZpE zR(DUc3zg=rCFG#eN;z5hB?=lQhQ8evx2pZVD#OS^{g#h+E5?e@?p&w2T$mY3A%MS) zMTvbc6^(Ow`TRY1-`iZg;|}7ShzcGb@N`WltCmRiV16}E4=rEr%z}!+`-YS3Gm1Dm z?*`$OT|Plo)o$CNYj*_e0i2*^Y9h_Z^4bZlAhk6y1`D0EmN*sTJENXZ@)FIk!xF2| zya)M)ILk$)(@*r~+y|=Q`nvZvj0^(AOFo*nfxa5=@)vIv@w7rDW$~b)WCR#F0JzXM zl&?`*X{FGx=-e^s+7Se?R#I7zf5-%Iw6x_E6-F$VkM}}w6ibd zM<8}AE0Q|Et2GMz4)WoNWVreg8Km_`#sa*Z;R_8PCoA~%=KZTos)&0NILX!f$p#N* zENke84@FSJ02x+|wk10#$i5mURAhd-5Vo4ClJY@pL7NTI#!L!2=9?M1Js4WG4C$mL zBpXusZ=-zz?lMw3>A-bxtyi+7+2@K%;H`WU&F(G3I8r3Wq}ve|;SnXsAaa~W5qm^) z2K<1qo0`dCh!G=o1lx@X1t4TzM;Zpwc7w^kqoyI!M&+YY6P{59wlx@7aX6*S3maPZ zjSXG_QuE{OMuc+4?r2s=I*=%3XNcDkE1LSeSxsVH4Uf*&B1ghUEmDf&H-MstT-=>HA*~9h}fVNe@LDy7w+tYlrlxXQEg>2KsyD?H=-sA4= z8>G`|np5D;cDvt;OPK$4Nw<^SywjU?2gC8*Zu|8uY5p6M=08{4*{p-OpXGXw#Ik%x zc0}D#&b!%b%)fyp^xvgCl&AAz%Yh zMpoQoa<_p(M)L@mgTPdk9E@n(6dfre9xEM$xQ+;0qVG+xG9+@Cai_B1lj6{^NhN=W z-`T1~+ra2_l*etpgs%~;(^R20jJ-3fh*TIL>#U{mytc{yrnE&@c;!gyiFxix@h23YoBlV`Kj z@>VdNPA|82RFDHY$*&8JzcA&NlPwFN%D)n*qiia%#MRgk>TtWss7(-i{3zz0PjAZh z+M7KMLn?T_#b@FGR!)>rV7DlfwTcPLH|+K#%Xjk0MDi%-pr$?NYLZ`)NK~~9Spa?E z8r*O-9oZiRUJMfBpe7q1s@KL15Z};mVjB~6tfPob#aD}y-qh29f|e|~Gl+0BKq&{P zuAzNR1ZWibFt0dnLK_0~DF}Io=`xp0cw&;W2hajOURXcTFcZ&@Or2(M7FsJT5!3MS z06I#TJ~)ghv5SO-7U#%db;5Ou|DxR%WYr)U!A2(nVJE3KuNT-(DFqwqG5FfnX#)25 zsNK#uGQbnY{iz-5p2l9J;r70Tw|VZn@2ko}&;WQZmy7$u&ENiZ^X}b4SJH*IimL3$ zG$H)mbd^crQKU@?Zz{|Dxo%$c^jlh&=(DTpEd|Y7PzaM4*HC;HRA)$gFiLH9m(OQ^ z{rvIrd?|HKM@PaigA4a8G&@x8T(YV7iFk}S>mFtu9jo%katTL4%qwT}j%1kuviq z8*K|HP_C|3Xe-%H;k~j79S3LGfyMGA88!>MgYn{>X(K**f`73*6Y~V8&Avn#yNX<_`A#+V~j4 z!N7KB10p~u4%P$~$lz%?s_~>~C6?HO){yz_QMR)--5aPsv}6Ns=W&2}^f-cRILHkg z<*9It31JPIhiv)_x>!dFI?+KR8fF5oTGxuV4yrP|)q9#73`_zGoWb-U-?1E*iLWM* zxk}{6iBi-X+kT)Wnk;Gwbc?RzSRt5p?nd(<8)MmXScoQicZT*l^C~OUq};yBGF_Kt zzDQ;@Q4I1|qz{%?6QwG-q^5jUMv(@!I7>c`4w?8!4Z$ON^bPoyG555^>DY^Nhov@O zS3Si%19d+fY_v}4g9KZk&zXn{!(2+Kv9Myv?3Mn;fTeRAQd5r{BrM8%2W*ge=Oa&N zGE72GCZM#=DCQ3j`MBpQ9;Ub9!Puh!zrFJ1h@0h$9JQUfnAbE-%SE^5^+Anj*q{xd zk^C@DQcXrEdH+(?w{!$5=|@4WI@&ZW!kc<@P{prSh>mCNUayz)r@y_M_3wYXo-y}E z0QS#DuyBHn^SEf}dUAOz#F7fk5&a!@S8`5St#W-vkG)-eU1@5G8s2VAb>Hn9#!Oa6 zBILPkMk#J~MmF57J{=c7e;hv%s9~}0V(y~_p)?T%{2|7NT)F4dd3=Z=e>sHpD{D7; z?>WL45FNj&XiB9I6zp8brP2w#goL#@cl)Gs7;G8`Sgn+A&M&#sr@maq78bnVtX3zB zd^e~gP(COZRE0uvDCsO=yJ&3K$b#HegpsP(BFHmPZh2qMax6zHU)aB4~B zn(>r3fR~1J%3ULjLs3qtvW{L@Qb5+Xup9_NV)AR=!QHAADo-@aSoIs&t1~x&A!(6r zswCg3Vl(_WKM$-_s1fB9-Buoi42?lVLAnMIif1{`$2xzBX$DT$H3r#ufg{kHlNGIA zJM{IQ%_y$x4IpXmAn^H(Q88|zY!K6&jRpfc%_jv%62s3LuhaLV*$H#lNCzOjjGAc; zLyA3w9j=+5uP!Ass9tn0aBfhtrvP2T!N{$Bz$y&5|Dzyo7SKnAX$jH2$88c^F#i4e(fu zj;(ncsUrsoDDSNXm0~Peo>vGE$qBXv(&psr2cPF88?;-CrQ>}mS$ChqU%*YtvIl=yBr@u!4%HqSANZ-Tk!>Ude5ls5=KGs{6K zDWlQJg_|_Wx;zoXcg@|-k}WF;G^>VX)k5GajUe*}G&-MMvR=)I*F_!Ehc#AWtFlF=82bBgBtSNh^){g1)8#yUxYxQ$?EP`UypU9piIN@%X4 zCpps8;8L~|)@y-j5zP;Wy`LBAU0bww>Lu0K~oeUsiWQBqB|7 zi|lOP8s1Vf<$Qu2wqvlB`2oA4dQl2ZFpmypb1M9t`*^bo6gI;r0J<#`Z&_kE_|Z{| z4oV|zrqO)opCJ)5avHtC2{k{KLEcWFiyQMYQRj{l(2h2fg-8&_^jJ2>I2O0P0R(VG zt}}tvn-odf*kscL92Fz1nkky>L3-P80%}m8CA}pBk)4`|8zUafvVAB~ei9?lgT|Ru zrdBu_4YW8w4PVfN*GjvT^Z{Q)C5OS4aCotbI3xfm$tk#Obg0Io7pX^y)3lmOn_Ip@ zhS*@OC8MOv)sUXELdUqN;p8JazCq+4aZa1xXRfjjNYIJ-fWU15PPBFSc>6II^<3Ed z-=_neVq_3@o6ng!#=;-kO#-Lg)b*I#1?fX*$$^%t?IG^j%EBmcOPXq!22=yYN`P+^ zgrf3|s|92eNG|7VB<;*&GyB_3v%6b0o#EN^up()sGt=(I#5ye3ck+8Zu1df>3i>|s zJCRb1);-ta?kxsW{6d(=$`55{k67L9X&%c@bo@KHgJsf*zvY@ez|Lww0q^GMyz!%L z zr%sW*nN_CZEl&?@K}+!-$7B@jTAoqjZWH7v`txG7CKSbqo2H~zU_Z)Ks5$P04Knda z4(;1Pg8Wg*$6DVk7L)Q&a2Ja(Ol@iy$?F>`27j=Hr; z{Jp=vdc(aB2WTzHIf+S4S;>{LSEJl|1UsS%Qu7mOF*q=9xCI0|(!&lQI0=KTWQa7A zAZ?3s3T4?P3s)OR0*^}C0C*25-M2KW8ePE}N@Aq`!~{y#2|al?wsT4rj8Ix}C&v`U zY!bxaTI%FaTXVI`_dM}BdktK#u(ryhiY(;`i?+9HI2za@^Np%~CoZ!WM-xj?y&=6S zN?8kx8TxQU2>3AqnI7AcHl2#m2|cP9B&|@-*c&$s`Hq`hhjRno|A`8ITif_O)lw8~ z6sIE_aGT`jpRnGTcsgtgnp@ezj^2+e1@aUM*2U4uT!s zyDKZk^F7cH>#OBLmA|rQx6TIKepB^cS&uDitF5*6g=8XQT2$_RVV-nPghpCWS}?4H zt28nvIk(JzbX!2!@VP>j&)@nw>%xp(I9Y{VxL!WZnWK|`-*-qP-l6Z_M;bCno)cq3 zN8k+=UZ9fVVlG~%Wmc(cl&X8b=`ve$Jmp4NZBdP#+`XBDaw;0N^LZf^-d*vgr1o_LHj3F_QPdXYZeob%n94|mJ1{fsrW$B6(t?S2eLIpW zA_o+ZJjv`=l#7F7HS7)OcpPQhGZ2K$Zz8w3BgyI%T8(dma%A#qb(O`LHb?X%^XiE` zb&W_g>y74$;4nCO;EGh-PMO|XdQ5@zQZCj!jZ{vOaNoN+ae;{7sScA4Z-RlAo@%Mw zfydZOpG5K(4R?!U{$M^1SU9dxyom<_i;6Ty#`Z2B0iZ-=@fpTX72QS-Tbv;vmJ`Il z8!T_syN{3wfoE`gb9_OL?DVG9bi)8eZdwJL}U<$qe#{QhN2hQgJiL!{I#Bmo(W)h;N}I$KDYU8(XMEk zDWM4M`5f^nae!&#g|~s~-N+jD0Kp|LjakE>AqG@$fXitMo;P;_~)eS?9hK~2;MAC;_NzkS2TeHtgVJstYzSOAH zM_Rvf*;00xcut!hSb&vpN9ht6C&=uL;~?X6Gy~-DJ2pMof-uff^?L}t8%lz-rY;E) zs8JrMl%kq{0}J?u!kQ$1VSKt|O7kqxI}n>j92X|!gnsb1o*BS{QR!tHDB6Y;VRGmJ zca_fdx}gEYFjO8Bpbfxnm+y8u@c`j#;m4JW1d%%-M_5mUZiEf}Wx>Ix_HhE1)wJh$ zdy-$}Xw=DRK;?dT_;@o7YSonw8^Ub@N0HQV`TUZBsx`~9H<(kr31s(p2WI6hj!53k zA#t=^ah!SZ$g(xVg)`LL%~!LF^_SO0v${Vl+WGvKru4+7pI<3kxU%Zqu_~*O%i~qO z^!84Hm9l`fUuc+6)W85Wb{;p}Q{RVRLFq`GN98thIv?Ry8 z1<4x*g}HaGw%x-lcig$_?(iqK`Z$jlv&9pN_iWw>E5YRz3SCI0r8YyjliQR!bK%~OesxmglsFyM zJJb|`r52{+NjN!$^B9#@K3VdZ8pjl^jyWkaYf-p@WdsKb#arh}ki7_dt~PXjYU16+~8naK=TgKacn>tHyz8%<*+ z=1DEvE|kQP$Sq^w%_uR+0-o+E#yg_>2DUGHemY<9_7`ZaqMs&czddEE8`EO}L26rZ z**OZGw8m*tS~N#@BPh)gPANzXLdlMR1O_PkmPMXf% zwSw>E_adbN17|iOnkfB?jsJ}rK*{u4&t$}>g}Mpp#C!NtI6Ads}d`!HuNPfBJ!T0P+t z<1cz{7jp@(rw{#2$W?qGZEGN83CLuU@~^>Udt}7QUC=bQi2KM(lUcAMmWN=9pN!1; znoMjWw%Mp|ON(sle!d(kM5`Z|)IBuaygT`q9897!2U4N{VPV!($g9e3tIoU!q0>>% zUFMgk{=Kp^;%;xYuwS27D;dq=D`t8k_=JYBEZqWK@|SX9j${hvkGW}bx)xt1@f-Fi zhi%8goxl6x^?{z>2+SGcY|a4U*-XjtL)S+1-njf4)a?dD+<}4Y26u-t95f0=Ds(7s z>C@UXQaC=!@FSYxE9d*(m+Z7~GN_iBek$5RJwu6rjCQeehZ_Uu&C#?thJ~Q1A6>Da zj08<6Pj}4U9SuQAZ@-xjhMI9NuqRp`mAyhbZNNGLaspCy6#(aITVVj$wn5aJ(5v@} zBRxtWYOtj&$WF?5>XFz}!POm5m?WC{$wrlALB$`RHn&&M-8V3~t7Yk{q zKDkahX*uY(3M=T|;DgaOg!jmTgD!|F>AqCZZ3M+#ZX#h22IZZj1|w zq)O}|gtWBzD{~$Z!u6o5km8mPO>L6;2;#A_uFBsJAG6weRZ65=1hoTTGbE>V5% zgu!Z}R}R&K%qIv=wY7kqbn?y;9s0lcu5Va3>!*k;R9NjEY9>YP^>afbRtJVrV@z+d_UYL{rmzAa47I zY5$N*!vpDr8jtYO!vJDrgrIz47S@u5-??PM;c%F8$%)5>pU;mrg~l=;$FueNtp>Csm(Gz7T>BfXIv-?rug{gcx_BnZO?_Vxr2v`)QW{$fX`q z$=D6McIXP-ggkH1!uB0fkmIV;&=LnA<96+W_0V-y;( z*3q04ln~A?REfuOM3hKej+0Ts3?^(d%vI2dx*R$VQoceuH{3O)WmX|#vqs~%-iQC6 zsdHJ8BgwXQVA#m~k4QU?dw>SsDJqRZJyLl>6L2E&!9gUYQ4LEIJ%>R3^1rQbZ3|VY zTPZ0c`Zet`Aj{r=*&)@kb}7yIKSwAvh{qH~#3|?n`wI-h zrlF^5yi_=#+keaqj)941pwxrmYGX~WN5s>FJ28SJ5r#Cvyv(A(hTnoDqQU`%Ip`zw zUH&HMWXb)weaQJka>j++04{P;0(6<31v=NLcx3?Ns*RH1;HZ;=9U?*(&Gz&`nMK%T2H3 z*^xLZH{sy7@;YgDK8vI(Ghm1BZF*hp8z>p8@-m8-i4vY%}{!`p_E!;vhrTna^O zvS0QTwvclf8OkbwduXhk&kLQ|=76ynVDWM}B2$sRg3~xOWYW5~s1=%oy;nS7X)qw?qz;?Z39Tx^ip?JaU2hnBoJ*neie^G+Ew}6yOqXMrn<0 zf~-}hLD0%%L8qwT9OeU88a#jbypS?YsDZFj?Gqbri7RD==DE8 z#1A~#2ljq{P_-WhB=<+&aEv3Jwqr5;d&n#muA{{GDCU-H@{M?+)A{WsiaVf+VlV}v zoMOtkSe3J!MIR|w!QR&uwuydP#rwYW>Mdq?ukrfd)Ad&SFNt=}{g#xy*!c=>@_haH zuIVDKW9Re^qEhE`KZjZhl*|!v?$K8dzM2EkqaQcMCu}^FZCDDzadS}*sT>j6;nM21 zJHCb`_&@XIDY8@a;B}bD)*7BFzMg9)4_B&S*x0nW>f$u$GB3&ugc{>WcQRgp27+VH ztc*6An*z#63r|B>Stu+m;In$nY{vel4_LiuJkPMoip)4xRyT!3wYI2I$^_(8EQDUw zY6bVsamv-|9CqvxyB0Pjg0Q_lZM+8LMR8(Z70#e>Qs}-dc5-gH@XubK(bN4IL##tj*4^ zDi0O+!0@1@k+S`Z!H46pldbXkzJfs9*~&`)TkN#x(C36~OwT5a++ov`w{Or7H+vYR zSmdQT636UlBNkGxDzwCXLNdIE+Rwx$0C|)twSaXaOO%TQN|@f`RZ<`7kS=Y`r{;iF z_DZ~#?OYw`6kf9ywztwZxiZPiyWVLQ21p~N+Kuj~9N5JlcD>B$5$mmK@I=T5cz;oZ zZ(o_xR^xnPB!w@{^v5$SD7M67aM38oW+wB6Ps! zZRBomX>!wIjYodC8l_?nVsEQslZEMk^sW2Bc~mi1`Ch(|)qMs9IX@gusH~nao=KZm zb^{^tFC$ubfZXp=zR!_4ywvyQ45$0ki$;$xuJz8qMB?M_`;!3{CY;NNK2{%oUT)7f z?5|Y3#UYXM=XrU%1GU_5{S_$Qkivzlh>%ibb26XjrOxly-#&U^x!`Eh&)zb>rFSu> z6kpk^M1R8hZF8vvIH3*jAU$k8*w+Vfxo%4x=m`le%}PsnxfLMACQl}Bw~)aEu0#$=@M|}+@9@&!{QXMcbt4%B|`5@ z+1ZKqvN?>X6mXP!n3xLB(XR;bR|)GPe!~;+1JQ}w??btby3W~h5L#-cr@)&Ofxqq( zY?_zzL*0|S$=7aFVc($;ZeS;B9=4jt7+*k^CdAbi;l>K(3QIAeI|r%iJKN7Usr!C9HLuE#8fui)R7@Q+qJ&JCqd6 zY7#o;smx^^%7iToHK}m7q4?|+^azz-TN*y^ic>nA(b+GL)Bk-$w)4Z*u1MM)A#d8>h+{bY=j}fjn;?LH zBrrrFUq%#h{{aV83Q{>ep2^R{W8U7dvpW5Bq`khL??aoTe_1dP1UnH|(8J2=e^9%< zFaup~3zN-z@40*N?p3_^-YWF{ufJVC{{HmBIVZ+-pkLkEs>_kPPL3>d2TD0KKpp4dgjqJ-oDol=b zP*l{CBFi?5Yo$!4gP9yn>w;qBksemPNc&1_tUH7EJURWr22{Sw457KLXaPh+lF1<0 zwBD>*;vVo^5=(24>Pf3^FfL1HLDX1>R(H3~#;K3&*U_!0J6KI@b9>9fpxvmXViz=F zYFl7~O*Z%U5norumk7I2^@ipR`c3aG#^6|gatszS&*osk63G|+Zn{7{VJNrRKCoE8 zk7@7sou5M~qUnyHex6dWR#~js-c+*)byh;!MiB2ajQOa(;h*JJ2^EcuBHc?FDO&ksYQL%7G6R zWozNM((<=Q^;X#qmnz}jY;cmD220+*tqvy2Es~8UuwCtSb*Is8CfjzCXQ4Z{1&W+O zj>?8x-Rihmo1A(8?VQpe?HF^y)P<}!g+ai%C@pZ;4X8NT2d8bGUngLXA`9)>W}g&v zn!Q+N<8HXj6nlh*e_vRUfmRez0ZsfLMrQ|;bE4pdH6Ye>+|W#6CsF=*b2S|i*u}V< zu5bDAZNg5-9qOOu&)fDVvo^_((iR@N!ow4tn&p$-KSVPu+lbLzzE|?HTo63rxWIfwn|XJ6x*-2z&eNuc9k)>W=?Zm!$4i# z8=-hHh3Ee4zh9Er!B_xI=L`u_fomcAF}hZxf$omc^c z!<^otI{*D*#}rF8;fM#L8>r;(PbUlLWf=R{-+%oS*+d+YUYikEJ{M+{XSoNeP^)^s z$=+nS2LoIZoi9}H-hE3UFORD4xh$#^%UPzdZ!!}+$>(INRBy+d1W|&1(s^JtAc!?T z=qO0Pw_dYsmbwM?tgJ&Z)2v!#%N-=#=(ntt91+?fxX*2PhPqL8X=f&8s|g|?Ok0we zQM5HD%^UKtJGQM0YZ&c2Wet4HU95<2)gIFpX#T@uHW=;F&$tBu!lzn-69Eq4VvBcc zVKG~s%DL6?LnPb^?ky2{@6JBvRVnZGh-txh5o5-wa_V9GvuZxc(Vl{MNd@($rVQ(u z=~dA>G~MSPo>)2=jm(4M7y!MtR;(65b*Y#OArB_2W>jKpF`mKh+%Db;7{ul?%D@@o z9~@dBcNxVn7$cq_TQ4KPa6AxdKRo&HypT=Cy7TADTT0+ zEwYt0l$;Y0K9>B|u4ujc+}9jyww9`1(jlb}>Dz9+z+}KNP?pM|UnQUEv{b4e(l<*P zs(M#WD9iSyLEwck%Q5xZzpwrHDKVn203Z4#3&^gn=%OHtBvNPJ107_SAZnOP0Nus@ znbizfT~F1vkOu$y$M~080xTPad>%OE$Ia09ol^9Q(TZ7GqyL^5J8RR2$}$8Yq76>M z!`v8*Y~5oE^_Sx+LtlCS*nf?*%hN+#De{QveP_uhMGq&A`20^+2}V>VgG&qfpSSZc zrNZ9iE|)=n{|;yOi*OUCIP?|b)6ZVKe;OvIdN1$?g`eE|11j8aW|!wcy=lQK4_N-Z zy6${%@rI~E-+k`odY;dkQohaSbKht7+HZu}^U2j{07$EQZ3>nB^K5ovS7Rd=R$?Mm zVE7P@IwqzJZ>o_zX&dkqX}?n*F3;XsX1WV&)SN25GSDR=&9zpu78MjDwy_`aAsy^M7>>=m z#S$R?&>8(Y08a5%VWp9Ws-cnJTm#OSJb6ft#>$=(=O@`6m21Bh2uAzpqU|1B$jNUe zZ8SDa(+K&DsxsSKll^=m8~HG~fYkF1`&nWdHrG!NbOE@$_`t@n&>}tsZN7Hd19Q

L%2a<6JeA-G`p$kqIuU{I7rl>cmcBm9ZeH&%dv|zw+W#;( z6JMcN>}A)~WPdJz1o6F@=3%4Qck_7Q9wsMQqMK^i4p-&YM|__MOrinK_X`YV)-{lI zOjmqddh^J|tr#>fK3fc00Cyga1H;z}j9Vl2BM%Q-YPg2&QzMwY!0cn^qsi>PzP`S$ zjz{I4^;Sf7*AwpDAaKP@6ZsV|fW6=bzLoxCIEkybCkAN!%nn+yA!Miaw}6JRvBNSS z30f&G{gByf-M{YZhh5oex+o_sHTq(8$O=h#j>tC-jOsg(wO)vukak!3^_M!WrlQ@F zf{Xvv`)*|uL8-ziIoEKVQ3eKn-w>kAWx?vosfANw%xe+UOoQ0ZtlEpiqXp5AStzW;`m#!cSO-zubFceSHuMDP*QL=uEA8PrU&K-9=6}0 z-Rk0EH3I^+MP7%|$uJ`v2^;pr3Nwq1oBU57 z-t1+9d;vCNdraUwV571Z>v6#B$A6Ig1S=`|Td6YMd&Wkj#*zR^9S$G17j5JIWZgON zXaF>hF_z?^W-ui37(@Wsyl80f>O<<9T4R1JtMTZ)&o0|P7AIT&rdabS><0>}H6fgl zGH;q@@X=$=mFz^u#K@+v-u2FyfXLiyNDvcDKDw!)al*#KR#>qLKs0yG8tN9aB2&Gq z%b)$DT5+?5f>I7$D%LWIGOnD{MyZ6wS*U@c)AfplBdW%O*`;+pP-fB_Od;XOkyuPx zeICYT%{Etpj2)oZ%iHA`{jV;8Re1)ElJAXVHdL;|*n99p`3b<@vJvxgByGQ~N!@Fw z@KTgpYZ)95xlrxs6RaKsG=o_YMkXLocE#Mn!D_;Eye!HjYb+_ErKo(fKNMi~xrm+8AY8?$ybetP33mgm2G z`s*je5|K%I4ZarMnyNUAmA;_VNRHU>tHrcxC^CN)Z*B0;aJ3hhg6~2X`%zm!ybA*N zVEyGN7E=xsp#-L4d;kZl6oirZmyzYm_3iRoQ{?elPcw2C{P5~|sN2gnQWi21zIF%q zy9sWuCS=Xwk;YF#|A3ca3K@s<4phTy3X0-{Si-vb8fm>|ewQ&t6-=({*eXKwG&Fsy zQ6#E2LipYX%5#Vu*oyQahoIhLeA+*haxE-}MwUwsL(w+nG*}49-h;`m8wF(89QQOrjra+mZvwpN08E@)qiJS$~B)lCVJs@bq zTOyK6v38lgb!k`$C+iVpi{infP>}nGk?((hKK~;f{(gF7!`}xLWqE&4Pn4|CTj!yI zHx=b{`VYph=6^e*L4V%7TAU)E=YB_m35@dBU%jr=bU&@vtC0~I4PKq=^LCow)!uKx zAFsE6RPVBW5Yf9AZ*+S)u!2q`u+-`3x7hmz*+fOd#;7itQK%o>KFEMM*jcLFINuE7 z$Yk`yk3jKKop71LJIOJc%}u3t(+idsKKJR7 zrIKR?SR4xxZ95K=B^;_$6LT;bM02P)bZyz`EMpdF3x@uoJ~%@VfwsXE(*!F{_QinB zYN>V_t(ZHjq&bTPBv#GHCOX+0iWQDX$&1+^#SO4@YtrP0R7#h6Ld6D{weG6kFis4A z8$J1Wm1T99${0PuxHSh^twkFu2WU1LL?-Z@qIdvxSm7v}a_IB1u1>>5orj~SAYC_1 zJ`<=4Pidu(8FuJ1;e)|(ar5UPE|6RyV(f^w)VKR;+cpd9^n^-SfpIz!iIgJ^0gW9t z{xA|FK!*NS&UHf5*-e16sXaRwl4>DL;mED_9EnM`LZ&bZ7ywQrqCnIKF-W4+0C@v4xkXE!pTlB4;o$M#ng?^268?L6m} zSx5gEm;OyDfFwfAienS^T*piH83Anz{hsez(Tcq8ux&*6JMjCKFT{$!%c^Z!f2JzW z0&QaCo1Zr*Tbsi?XTUmNZ(^M46WBwAz6d2Y`ygeX^;`2*xeU77FDcv0;m9WIA7K&E zrekuFXWJNC+TJzvIlYPgP^7z&iMRP8=P`OTP=1#)3DoTu<0JMkxl@nB4E%28=7VlB zn?ruLM&5nI*>BIMkBWC7U zHO<`4GOz0|E4G#xtaUzZ+`}^U7LPj*+m2$(n@TXHO__3e2rfbAMy-ojN32IThRx2q z9btlbxOSJw{sm13j*03G3zm*E+cD5%m9PpWv7O%AEDeW^>qJFrz+`Lw;aid(P4Dm% zt#-(&p4b>tX_5Yr+2AToA>b2{1+)a{$`y?i7d&?=D%REE%!)2t!%J#qZ1zC;kv0T5 z)n$vh+l1F<@?Z`IOe!uG)m#{@f+PXsO!x#5K?`Cd`Sqq-F6_PCd;jp)rT5ERVh_Y3s|vNf%ll)G2um&QTI$^u%UD=9IyT%+jihUL{yZLI3^2)e*oTlmkBnw* zYb@T@Y!gn20v+au)gZbZv76bd>8CzqQs=TPSOW*DOe%5hQz~i+qG}G?#Y4VLmy>0P zDf0MC#&Ar9uD2}%``8&#?{y!RtQxwcDTnOQ96!tGbx3v;qq{4(i#c9w=`v>h3S`xa zQCK!Ck!|i3)}8qtzCAV@=})dUpx4tmTel%p17PSP2gD}P4-P?F-nGHdZ814tO32kr zn}h;#UEhlNB2{Fyz}%WVYy_`Kv8#2z|4Zd9Y!W)N8&>L@{0g!DCRpvJ{-D`| z5lyiVCgC{Tl|^yXeGm59OY((JvgS$WN%`_Rz)~(Kvu_i%{er(>zn|vOnal{YROxk- z+3xQSyV|Yx%a}y!51wL1z{0~L(Ac=G0|8Z*G5cJctmcaQUdhyf)9t{uUQfjm1Tc{z z{`B(qOaH;YKK1%-z#GI{ZT0p0Rh_qfSbh9kn1@rntK)Y1zt2l5AHEAV`S0~QGK5{c zFXtM%Hv+>?;tfjby_UtyWdqnHr0NwX@9-%aXaf2XC+t**qd7;|);~no5`7Vfh-E7e zSk}y_VKV63GrM}XN5DfKrKTAy)>=bY?N&msP2_t3>7hzvlxiq3SPu^RwF=Q&Z0k1} zeq|f`$he`=sj7i0R%jLzDcY}0WFg=xw#6?aImy>`%s0I+hy|_MzvVHlwcJnl;Un?J zBf6Q0NJk(Sb(siQ3lYWe{ffhUZfW}ybAa;NtG6XO(SncO`=a`?+2F~ehgC?C1EB@? zUMOcwdcv2s4z?F4ZtJ$fCea zO7fa5vTj@G_Zu~J1@{%pq~Ovb5zc|X`Qa3~%T|X;#F_yjdiBw7V(RF5b1WBTku(wO z=2>vAMhHxP31$TR&cXEVYs~7yiBq;AdVMafP;E=Y0iGRU;y-V)(=Co&v0hDDkRfF& z&z*%}tJaBQjV{EOj#Qd|p?s>^o5r7?v&rbIbv9BWsZ&XK(XvIDIpg{4#G!?O9(vp9s@w%>=anq#B|%(Hx>D9g)0 zz|WNG|6pDMY<)iuuWw80f1b|uc{z>TG;u`2#3X`vMrNAa1K)q?=RLuc4pU&uiTEBZ z0H6Nqzx{OeF4rd^B43v4dR_dw5yzu-L3I~)x0vK)_^9)~Dvja#Ttm)HA1yV5^u7oM zO(0z6Wn1i>$2`&&f)5y_dMi`HS1_<}2Mb#@Sf){qM^=;VxJO839vAV$z-d`P)Di+i za*YFFaR4d}a&w}tO+s~Vx#5k160N#(Rm_UA1$DAzp%Y?Lq#4SXnYWh%a2#GN$& zHUz|(Of@JUG}q{5cCYdj!K&|7!sO6xmA9PaYDvjs&qDLQp?=>3;{L_Y?sd0U;5$m5yFE^* zxb+-S@rW$1&r5Hi@1mj@idoz#_j3Eb;CJ=%>C?-guAIZn%JFByy;a)3T!onk^nQj5 z2x!7k^Nl83*~as`oCt06tpct_{Q6tKCW~&+{*7>=-nONm4qM})x=Hm62?|F-?)frW z?+Q1hMs^6s)wzzvfW$MGS_|s4_4P2D4WD`3h zx(;v&&PcQ9+h=u6k)sLQv7pid_coNmF3#(lS1wYLE~M00l>viVIan!sGqNca$EO$u zF#rQlyW^*c4h8}L_Ei-;=aIe%C9-b{4pmUfH|c#T+Wcm{uI$N$=bAu83Xfb3w+nn3 z%`f#(Ln244R=R$8*QMAN%Fa+>(E>3r97G6#ak^(QBiXu#X_%F1Gm&yw4qE2(DsITd z4&Eu27?Ket@HHd?96dAm<@@>iy32cTVnP~t%$96Am7Or$KjDX5`{pozfE5W^Vxn$6 zCbV#e9Vg*V$~+9S{uRE7m+qo5r-^0rMUtx0_ozN`S`7-vNN#4ARV)|w9f~_X3}Q~} zoRGCPB>aq$XH8?bU7}y#!dtEvVx)0$C|7lZs|h;U0i}va6OB}IiWOFbY+bTR;7Po9 zW&>0LJKm6M47zM=c}}<+dJ`C4h8 zi0sU=CY?v}9Fk$Wm?Zls+XhHnUM;F`b}Rt}XgR_s%ZTEtxI25OrvA|^!D))vv&o8g zKKVvMGcL~%KHP43zkT4s97sfVh!vX*elIzI46k#ysZ6gs4s=gzIG&Wx|M#nUqqXFJ zy?W!TO(?wN&FXp_Ix|7p(VXjIb8W%1s`B+=D30^f6a-0-l@f!9W~FO^7#wcZ;Wc4# zQZFXHH94JJr4`P zsC%((es5<3ad#=8?FG zX#WmOU_fuT$i^84@*uZ*Z5exSHdPua+ws5>gUMn?)BgLU$RfJkqRZ5BeVZ1b!_m<4 zRj*Ua>tt@L^LP+ru@%95R#X-1X^dRs-I(|5Yv~_kFTsG-rMfETuV~Gh2*%E+H}jk) z#hMiDJyxQJ%6iNd99gSp{t5wMO>b#Uj&MyZw_+;g?UNYV%-pqEfzhw&3*zUsnICpJ zR=FU7pvw3U;ID5$skZ#Sp>dJ|pa#y3VD z+eTl?GzxfYh<-P5qlA{zKeGa5mtMnQ~)aD#!K0|^IEX)@EtGfXp@DNz-@}!{5V};dkb6bS1>mLk?X$Z9_X+r7j=$1F@t0FSeRU!v19)E=i zW+$^y?5@0JQa8@Hi=I@OW(~hDb+Ov`&-7Hy#AuVBnK5o~H(}ao>l6OnIjqG2jKA(t z!o!z`CABZ?2iAHsIJMe4Eei+KbeNBo^_SD+B|%Y9p9!8OQXQt7_9+KsLtvvZ zT``e|SWUI4+MmIg5np|xco$4ioD&Zv3#ew|NCTs3Y5;j8Z)nHH9pJTUm#{#q#H?^9 z)U8euwrEp3KJ7;)<@f+d1t6o%25EY$02E!5Ou*G>_r7{n!?xPBS!d$|`wt!A{8`=l zp}Rs375JE zhfmwvCR%PkFMYK+Og2gqz&C4~)l{Rp?eBEcm|jL!p#jkLr++!xtPdZu3E#5PDyiAn zZ5Eo^#q?OnM)?#3Zw8q6bM)T5+P;m1;$EPy*Jq0_hZo`927%`Yt(4=S4Nrn2zKO^E zmufrRdq5~gLw^4CQ)Pc)5ZPPrFTHp_egD@V&oVh#*X!;6CaC0ef1~SOg2ghw)%Ulh z47p`lJ+O4~c5)?D!CtNVPmwcT2|=??P~GbA4>anHBab15G}k~iY}NcALZiLy%gXK6 zLiWYluP58=$5$SC#FSwS|I9c64*;e>3~kHUh~AAloF8^}^u%g>sNQOYoE_8r=u~kv z!kw;Yif-07L5m4oEIZ;cnv3vxR#!;ct^2R_y^&!cEFiY*EUmb-3R5k0=t#zkl`K1NWBG z$#2Ek0cKdIh^F&~X)_?xRHM-2NKgTbIf_vt!~#zL<^*LcI$-A~Z|FRTEC~}yI1+euFpWH!)NHRwt?#|i=`zHKWzHUoYceD(*cq4* zXOp)C?%Tm!Rfg-4Rp}*7)`9OACf2Yk+->z0)A~A819dH9>=9kNBsd9lVj8!~#$=M@ z1Tp%iS2Pz9_sGU#b!WoUn8Q}$8IE`5!YE%S6e3kfbo8SUFQ1}#=lb4af`|SNnaV?n*k9pR!!aZc z3E|N~rS1JqdQ|Y1hh`JeOVEJnN=lwasAXvBW6Fi)Yr?yuIsN0oD5N<!oN-`S4lYpzRL5+c9=;HihfUz2l6`}4TP9{>tk~hmZjbu+gRvc7}9t>UX9!X` ztw-)RQr$7|zF@xUv!E<_enO0pZEd1?9%+?dva)bDcjig%;6RUheu*YG8;Wh-9tB*+ z4rHc`D_x#ux%QhFIY9$rQS1W?mLP4QvHpS?pE?8Yn;op0#>ck9`^j@}1*XOjH~sl%FR@S4`oEt)-hTv9 z(75+``6$i_r5kcq7;FGNsNqdc;MCf-IfP9iv)9kW-WwS0OIvSdAjNHQ;MVZ7OIU8O zt5QP@;cdc0T)Pul9CA8 z2Z#$NW(&)&kyK2lx!YMm6o~??;HxCs&@{!nhPFZS^A?YYLxJp=MVJH7AUUNu=H1V+--b=7io1PLh+@gO&? zp4|xk6NUNP%C17AyETVnjlJTg=0!}WrbUDSIS^{y4^g96X~|2uY;+~NW+hi$m{*}B z*i5Q&&-0$OQXR8)y_gA^p0Jx7c8JEER}~4{)d-Keh#@Fa=WNG=zB+%J6UJ_!MdUPR z=W0lHI|0#2$v*YZK3#0mC0zXNBBZ1D(uc;82X@WOsQWEoDMbHg^3u2nyn0sUsT}R{ ziAR$R)22CwO5&vmkIX3P3Fw1|lyUe0vQuy=KCsM;}dK?!y+q$ zTT4Hu7uQ@btVYP>FXYU(iubeTNVwmEdxLo@!WmvpFJG3@(Ky5uP}`ql*+; z**P^cQC+w6fz*3WlM_^NdDOMYb)CZMM%vNMeedR22#XS822zkBsC{R0pw&i^HLN&V z@Q8R@(aR{&ayudkIA)nB+IjvGOAABR{gwHmM&s7he$wO7~n~}^< zZiOa^Hrx7*GOs7K#kZ!K2*sseX?x^_Z`e`kU^(PXjdNSG&96T6=B=rn*AlQ!1SrhA z>>wBIg4bO$u;E@PEV`~pgURUo@*bgbs{ehGB zwc#EUOQb$8KmYz|HRkztyIy~P`kjg8h|amI%YF;XD|DchbcRI(%SGp+T(K4W@ADNC zs*M?CarAqWwS3j#tL^XV8FqrO}f>Dw2cz35%_}Y z4Ap`RDO6yyj5Rr`y|3*8K)kONIwIRZ_2VSGX$Lpk*$RO*0(B0NQtz7Ch${FGv@J%( zZHm>fzth+J4_8Vl{k+$42%b7r6#bMI`Hj4~?whlUy+ zW+ejotztqd7lmjihG}FNC?YNG3*#zuUQYvNtzX~1^{!t1@2&{oy&(5ghFKd~v20)A z1?Vkprg|1oiw6Bqq`95#`%^4Fg!F zI@k?30gXM0rY;xuO0&H<4~-d+Enyxe;x|SPb4C=!?jmthso6f72iPFz@a2WIUvx^Q z-e(_bRTNf?U!&H>i*M6IvYW-a_lM8--R34sw9n{vz_L$D<2il$J7UgWBH>Jrd^4u< z*QXbh_UBQwqZPm3uOH=Xatgpjrh>Pp?@zz~e!a#}R8OHW`t$O3ew+JCgQSqnAWy+F z{@p6x7*j2aTJ3FqV@`2an}9Z+80?(S^OB2vPKaH&4)O^e_0`?B?<@1b5nkb@y-p9% z8_xD1W&H{-_6+o~Lwp#dKH@Uhh~kl36}Q~rR~fnV+>l$#ih%o^QrO4xVpxQ1L7TSj z-T~;26$BrNTw>Fbdn2^sV-mwkE(*o8?B=r$!2`1VG@QA~Z)_+!HfPreEwqqQeM#o3 zr&z3d0pa0_8#4fEsfFVl7V)NvPXh$X7(yi~p z|L2d8$>S{;xcB+XRe^VptoPQ!ngB-EPy%I2DRR}#Qb>E*39Hd{)+5woA5B8v_$gGda!U zv#3u784(0hbjnsUpw*wRVL~tgQmoRlOeo3t2wQ|QuHlFnoj5^YB|Nf#yx`WTMRZ0S zF=L{}Gcbd(s_h{RqIn=N5pKqmb57owmVev@R=DGNBDyDDEs-D0fV!Xi4`LKawWfQD z6D~)Ge%ki*Fd6Q9F`b^Tds)9tUd38?G8}H^FTS*PbBw%)1#fCTNhOWc@3mKFZ94Y& z>#9MoSVxxhN+K*DTbYxqY_G`aWgtc=FBo;sCskn;=TEIzx?5Y+1BN zC^H%a44vn>DKrC}t{Qjn>HSsj{m|V+e5&B7zWX)p-)rr5Of7uPCXFUFw>JG$XCsl@ zz)l>@L~2gjE8ofLqu*@)2aV4zC$!(x=4iNs@ppbPa&nH=`Vqu)KELz0Pd^2rpTcT( zHtV~W>gyK;5}yp3D4+87MRf1)*W39Vw&6IKD2InQ9Yfvc-iU7xSHa@q{YBayJWaOq z8FKPw%!GO_N{~&gxAg8p9r44Vjjwj2>KBv9{BwHHy;Vnyn~;zGb?0Y z8-Rlamd7z9rv)m6Zd1DI5nWU*o*JVEFEqW~)*MI*$fRpnQ1^leu zoBXL7j;_32Iu#EX8l(!$LJwO&R&zUMg%UJxRZKo}K$hm)#UTpO;?ne~`5S3;=wp@L zJRurvEyR|3r?vtJb(W)-=^3DHVCeQmm0mujYb1*;gE(*d`02GuH5=F_V!clVCP@;o5zRF*o&7pk*xV zy$F5FyYq6LeoVqDa*2!Qd@6!JpQqfStU5W)3Qw187nrrZxu3CDGg? zKGIGN)hS3))>XZ6lc)@Axm+$aFI7_x?cc=1mN1G!Adc(?`)u8XyG*MNqQo{61w88~ zsI=_MS!kT0BCf-ML*2?qU$&0faa!8E=|{6r@+61FcEt8qyE_y*TK_BR;fp9oxS}XW eR=nZ=FTeoM#=s~a2(do^00002sQ{JDj*`#lok+aQl$5ebdcT&O#!0_hK}?Sg7n^dlYmH- z5<>4Sp%c2?9X;nO_x|t0eY_7@$uHU2bM3v?8gtAs<_9GOX{w7iFM>cIDw!7&Dj?7W z7zjl6;7@Yk8_)b#5a8{Gi=>u|s=c|3yRnlQNX*p!mDz0>TVo3|6*FT~PsdI(Vc;MB zO7d!w!x7I?<>G&KA@O*;Y1#78;Ue&N;y!V$z$RPiQd3itvZB&hoVtC-=|+Fj;_)$s z{ueA3D;w1n4g!rI9zKrkn=KDGJ8O)b|5@syk~6yL=31!(0v#T9RviC)$o?=PHSYWO z@A4kSEyqVS_U_%0Ht)Jmtuh8G5k?@8^UKsBt>B9JxgW|_p^-nfP8MsAh!e#t$7aZ{ za%!(%YbbyMJ9>Qoh_+FA)3St{n;*>f=pJ27pFjRSzn}wB=T9BHi^$3SKAoYg)=oJ7 z+%w|J#d*BZd^(#mjNe{QTM3+2P^ghkidd5a_XijD(n)2M(VUDt;4F(@tTmjrYHP z?tzT|)vLK5$j(P=sp#6aU6*;RuDFZEsgAXeaXJ?gEg{m2hK(CSrIepA^Jjm%h{!KdI-5*#Xpe86V7?GAo5f~V-r1kRa2fcT&@7rHMpgxIj zi~U@IyH;|q;h){9L7>#^aRC*^7b(QH3h5j6=Rv8XQOFYTz?XW$7Te@S(6iFRT~_#Q zAJRGfVZTQZo{V(T{}`VgkIjkN6l*OW^FXtNZgtIX`kn*z*dx~$Tx$s44O&!L2c;i{ zC;aZe;=0V=1x1R|6fa0C_Ny$FN-yoC1z^tH+n*exnRofe%?R`QKd(({gPODnTeF8( zC+r^i*%V&i5JbWZl-{j8WQLq9FuWUy7{xj%Xu6QELe__GGOi&*>n~#P zKObPWTdk{C&Z?QMFFoC!02e!oDC88bP( z`=G<+iMFBnxpkU^LtcJWu^z z-<3ZZ=%Zp9)qiHTZFob^K28mW6;NWT-E)M9%Z21}&>Ii5^WOG%i5q4dzsx1}C5(de z2!8+zh#K7sJg}81ogNq19F0<~XmG56iq_+WlpL5&9)-eP+)G#Z>A+SRESVt#3r&>g zOhyh3bbP8@jif&r;Ow|gq|uUw9awqJWb@rdwS*D9#>2I%Mp0{wam8z%4F|IVvG2Rq za?T&AQ0Y>)knCi zQI$+NmPdoopP~-a$RU1CzjMdjozIa`Gi2LfUm-L*pYbez>01trKh8jyaXO)Oi&&MJ z9-t}8fy9#TR&o&BG|%)0oS`oMJqKqK)UOm=|AVcfkzl`o53o;0vYB1m6?o%SrTa2M zX#=Khj9;0uh7eqEz#LqE&4J&?KzJ(kAglKVEfX5sq}p?)$zXk8;(VAwq&ARsP={w7 zy^y)@CnmV?PqtySl)jBXE6*3~H24Z$1g;kCKyOl#aVC91#R_DNTZ_bBZFO%LYG>zV0ZmtNnn( zeg;bWZUB3LpqYLpoU#Oy0<-8Iv*#>?-VfLntz3Gp6fMJtS`R#0;K8l*-)&qdbG=3z zxn*H$<8@F9Ox369%kR0)Btww0KaUbuyrIY2el5idZ&KcQ#5pZy3}*X=G| z+c(MVdh8&O10UY;VbYy1OJ-ywfQ2V|xx3zr>|8pix&8|idm=bHKu`j!TI1N+oOBe?As(vkm%&Lw{vTjcoG z`sZ(>aGwq9cOr?;-@8{k#Hd$Alv|S?MpOx1$AQx!E@Ja#%!{oRz|Kz)$`3mhxO?do8BL@Cit0B z=mVcaWR@8+xwbY&DqaVERZ4E$AjxLdrv>{x*xzdRqq|}hOvU(eN*YH^>BlmaO9yC+ zHySYZU}J8DrNHY{ZstJ_E0Qandlp_>apzNEcrN#rFwCn{--7!gK1Hw$W;RutJCQuW z&+C4^%L&iuPwG~ZoIMph@p^j>?I8N1K`V-TBDT`G1N|10_}%GwJ=G6`t<+EKJ!SPW z;hyP`=j?3V8FOoo5iyu(YTblw9p86T_V?~oPMQid<;|7l!a}GGF$EQfel86wf7p|6 z-nzaA%5aY*<}on=ITny^$yG>v=I$RvRZf&CggG$^?XRtM3;QM77quJ#wSLp>?zuv- z_2@ny+Zn`&!)r2sj)wACEp{$rU@rIQw88rMR`X0aF7x0_k1pnll%c^shrpcJl^~Z( zOJ-KzR_$H|T_wJCqpmLVG$15U$L`jc8Vgx|rM0h(iA>UtmBGj(oVoX$Bm^gWJG%X4 zj<>8FT{&Rn6G(aR$x2bLpu*TNRLDuLo@>{%`JB&Xzwb(=fs3L?}ZotSk#p4O?NsF4QG$5#mpbQe5v}HHB>E2yNzZ$> z>l0%K8eIqFw#z`znEKN<ez*UW?EcOF!LEAu^)jMj2B`ZpTZ^D-pUz6m#2a3s64QiA%`-@4P=i#WM*$`XZ zz3gWKQXkWLpnEo>P;WJ4m!LxJFtnXFApjvX9+3XT+xM~-BbOXh8rzER%{>aBl*oZC zjzV*l)uX~-YB#cQ&-wD)8f=jRulD>vHkXN@>6@eCzDCG**BCW|r8PE`@oF{@RF<@2 zG%S&fT|;HxaD0DcAxzMg3ZJX6OHp8yS0(rwnN*)zz#W0GLE>|Aquw6w2yu|9jkksBjlhTU-=SdNxS*Q)emJ0nfzME zk>uED#nA!;ry+caQ_^l`Sgo)(viN;0G>9=pC;uFPJd~A^}t_qfpt(qy~ z^ul-jD`&!11(pj{vu|HAT)z zcYk?~knX+~-{*WUu;bF_Olec6Q_q#}4T^n-XLVe0w5|JPund;xE5 zC*4^O^Rj1X7&H+!5QFSRJ#_*T?9O_jE-iJk zcWqxER63R1zVOq!d!)O*A+kd0OJz?zrDBZrpreingl|HYmO=I=%pHvK8XPCIM$3Xg zq2-tlUop>ZD}#daW3T}h-pOjsZ2<$=OL_+je5?GiuOWI%7eNjyME;+$_f#_=@M&-3 zX*YHiK8Bve@kmoUb4hcT^%lk9tT_Pd{cY@#bA=K7v=`4e`00c@8=j}5u5d___?3UK z-}7rf4M{I|aW-Chc;b3%yXq~msZg8@q+^bpJ9he>KL&0ij2(Q)Vz-2xaC3mBgK^@A z0scY-8L;^z#Yd11AOp;WJY&!t2J)3d5aD-rdb9fm2IQ^3^Ukk&f(Ys^m%af4-RxK) zyxGqQeMTSy0k1yi^Z#2tU<4sej5Ll^p97UmLSLj*RDcVLDM6N@urLvVE##yD3`*rA zK07L_hHZ|$1^EyEN|dRmq{;>FSWQ^!oF9^dCp|j`vX`F0k%XP(%J7Z-wc4QL=DDBT zUtZ*Nlo>@l?SjJGG0Vfto8?W=TOVD7go<7AV2K4LP~IaWCO^gz7sk|=iOtm9z zo9}s_bWXn|=sV`1p#Kl@cC#XGbDGCcEf;Z$|6$wg78oI;q;yj|YS2 z`lN_Pj*r`S+X`%v(al-t@cWra9;0s^tM8K@?)#}KJFy}{e7Dv+5i+jw>tV2vSA{C! zCdO|We_VFUCopB5Pk4n4<(`UR^c{p2%nECtxLZeRimgy6Gu@C!ETIE#_R%~(G%!rA zNO$`P4((>r*6Nb67&ar}K0lir8PD@$osU7~Z+yHh$t>C7f9x@%3$6%=%b?o6lwPaE zP^{2shsrK7Hv)4BpudN3?x4Xc)`vh9a^{=>%ow<8&%v-IP)cV!G76=1cQ1!!>14bc zJA5Us8NyzZA?&wPZ8GR@HbY8Y{N&uOXG^*i`oc$tgr&+!^a&wJbAQ<|5~t8JDI3P8 zhCuhna^erIxSI1VIp|{gKAe9BABN7=!rXmiZwf)Yqc33R+IF`VGe$ID(se=i1Wb2B zmF(_AScV*{TWh=RSg_aVjdwrOlI9{(A~F_`fDCR=0-Mm%JXOsLrnQk>!#%8K@u;=HU?V zHgjpJK02B!rhUV`8l0Psfn9(n#ESGB^yV_VcBa2Yiy(ISJ+>WG7-EI2$6FIja~%RD z?M{s(vE>zDnYV=InpF5}pYjMD$EDuo^Sh3Sn|*c-DAGiHl3bkV)8x zO&g^k5Rd~h6m`eQ8>uM%4RMcP|AII`XW=9M!q6rtNtpp4o%ru@`XUwuuym^VU1Ae_ zNGcWh33x37(D~oT0mw-93m@OGcLOo)f5+6U{sUCj4nQmsfY>6)@A$TMkdvBgzvDMS zEk%D7AbNJko`HY0PNmxd*Y)VB&z;J2m$i`Ny@{67>4kc}m7=1Q{njXjWENaxDF3%Z ze82NZ_ko91h-SzRp(mjDTa}klQKcu*L1wi2Dr{&?F?5!kqKU5*6a4M-qqBvST0sC* zT|47pM^~<$>87k+@9{q?yTe}(0J18B8PAjv{2&h@YxtAddK9&^UVskI9ER>*dvdg0 z0)Kf4`9iTk^oPwZCD(Lp^7(bjh-^aq6NQqbx@C>)Ud zc8@{1CM(q>qlIWkKR1uAOrhXftsIbZtNkykBRbRq67w@xV1+`ax7JmMcJr2`^$lzEOKVOY*fF=g7af|X z&DH$zOFv_b1C&t#RPYg&H+I4K`B8=@YTQvhn1uG9n9R;INYeApcwR)E4$6rrhSnv9 zSMIZYFkNy>w}!A6%Kr#v9b$~R9W-ycy6_?i#=n$|TlqSBap>(QNK4_Ov&hAbO`@~5 zmaIf3WB9~;Fo(lLtaQg_^XO(das$3m_Aj*N+3`JyDLDo`em2|Au}oP+M?ed|}uzyHH$ zw_pRGZD!FiUpXm|q2oX0xKZa7N&m?E30W1C_@_>#6k-f^okMxs;bOjC)zshlz=DoV z)!hExYxpv&%GNqJe~22Vl9y{zL@lr6m!DrvhoBD%wZIw@+Qig@2&W(F7DyFu1&tqa zVVWl}9mni{ZRm~?sgONWXx19UsN(jba(*ds)@2kw;8;V9O z;Z+Bm-1hbHl(+ymG+> z_*HS_wh(ktQj_LF5D1h{sMeWzgw&V4ZKAV#lcC`w4!9b}c0U6KWviRnxYpo1`T!UU z*sEddl1^Nk3R{MiOA$$$1Hr6a&_rF0$GXI@B%0QJ{O-VtA)|}@gS_Nmx8=m?PaMaN z2OX=R#)85-^flDGAp_;^k2nB|Ai3k?tLzJ zpW#;-Yd33nRwF%owK;MiouG@t>Jnc50n#If52mC=NWQoQlQWp=N$HnGcLMythh{&Q zW?zS3EEzttp!~kWdSW?e#v%H7Ij%L0kVcLT&ax(4&MSl^%CZNc8S{2aY>+yATm7v9 zKmKGcD*bdZ!-4qjoRlTAFzm zxi2-_G2@l1X`IJMv&}GAlzVgP(pUj@2WNh)F?$H_yD(7KtsiCn;pUxs2pr@PYK@GD zAC@`fVRg&?gDu2|bMad{z_Q&ZdgaoldldC_wn+ax$`_{tYk1>)W69B)(aoe9F2%Cn1&uhLCHbOW zv`H~d!^YMl%=wYcjWL~8qFP`)tSYK2E9bkJyt!xMA3$wagJpj4)TPJT1)p=~HVMx@ zy1vi%YW(D2H@s)$>ei5erdTlQfKf15?OLC|Xg5ugN8OtZ#m%=lR?G;GV>mz z0n%-iBP4mY^DKJ2HcC8wZAV$Ib0+fQxXTn@%4nx*41jqy1N8q<2u+0jAXyOD zxelDT6>8oM>A1_gTDNy@1$AH8^--wa8c_zJIOQ0$rU$UHcvyk?kxPMkqpXAemP6x> zUs76_$V=c}0ckLm>;Jz*i(Jfb{~0)9P{k-gehviZz57qXRix$2F8T}J+3W7|Ex@=vV`U(XH61p`#n0usyng#3PGpQS6h|4Tyq%3BzyYLd8o_!QIClcG#3 zq3^2z-PbDZ)n^c>*{ZSLdWGn@eEn-8FXW^MBmF-JW=hB1ld}8~N!m<$Qtlcd7k-!? z@pq<6xXMI4P0f5To^thuwFAnq4*s_H9%!TusH+a=U6z`S%3itPoo1Ejw^W=7Ga0JG zKpCSzUxKlJ;8FurM}H>us%)EX59M(kZCj`G@NJ1~5qX#{oV-RRL`$-awJvXFo1^aY z3bsF>D#A#`*>^#ZrP9_y%P(Xt-g{q$+)NNxFWw2LfDJo25zP#|&K+mRDtkXBtD+-f zJ&T@|OIvLU<-oiKRie7WXbZ&Rt&knoYJ!Z1`E6-9@t~gE)ZM@g9tDe{9arr+A71gw zL{VMt(`p&Yy1nji>5&96LS}qu23JA+MmiDefO)}4DqI}l86U+}##$ftK0^j~ z^vh$pZ^5|>nRL#3fUFge$T*ToqPjZiBEgb*3nO#c7!0=xjCwY zC>iBJ1xYZi8>YzUg6VtM)*EM@u5AkRUC?ply;(7RIDJoikD;`%byT2q-}$jQAjXGs z1XuUs^bGZWY8F+BVW3b3L>J1qR;|LVNo2i`%!6fZ7Fk0Io|1vGV2>=3yQ>LRQ=}92 z9MHS#-Z0=RbL6+7?;N;#Y8>cnE|`aREG=1<_}{R%c?iLQq`_a_*Tldy_E@7?QW4LO z3|TJPJQ~_qraD*{77_Uj(i4K~Emk3-CK;WF!Zj+uK??s=9M*3w_-sN-*i<>CRfN~W zGp*48emb_2;y8?^trzji2GmoxE=_RhK}Xt-wAQ6FU&EJ28MCN(KJOF@O;4H5%v5#B41mV-NJb>;k{-gSS+a|1x@oxws5q3bS(4&A)?`s2j zz8K*B`Ghx9@BYoZePf}ZzMFtgiW>(s6yVb@>-8TQ1O!O`fa3pabU2S!z5w#S;N%6L zuD51Z0=@)Zy8r_IbHwlCu;c*l0cRmLMVkXLD}Tq#)jJ2&8c3m($p&E&$s=AIw5mmf z#PSd3iDqwit*T&~YX<-J2Z&V^#LYjMW_d6T_?GzV%eS%(=Pspjk@>>_bGD=Gueknc ztDiTMC2P2XcZmAe@XGdpzHZ`T<8q*51hEcYuR6oV5{@0H@MKMV#fVmd+lohJO#4KD z;-hA031Tm_^Usy1(<*IcF*->d+ z@ZzmhqsM+*>cWA&&tXUYQ*E)Oi)9O&cSljqZ#O)hPU8%`<;g5n;T{*xMi0Lp5pWTx zwHqAz!LS2fH5NtX_ajqE%XdT9U*Bgz@2_pH$*6qnm)78FxyprRlkse0T5xm)ME?CzB$RUQ3~c#I*`@e;X${ZIAueP_ zqr+UNvpHbPt>;ohZIF)Km;)?fb%2rKksM1mpT=|@t2{Y_eQlro^HSHTAK+a)C9y}s6+H_5+*+X2q2vl{Scw3pC6@HQyTeV(w z6|NNaIhje7MG;pb9lt>ld-2Z7rHsAT49vnCaRYACJQ}tTlqkEzi`6`*ZM#DIJlKmX zuOY+dC&mubH4Del*7JanvUj<3e(N$kbGtl(X;| zSoKdbfch58F=DPOj+lkffRe?hNy2Uf_uTUN#LYj5XqLOK z8Ulsxg#fj|dWJE>^IQ%A^5#-S0aX?ib$?|CAnGkX&aJE}yk0IYpceh7eG_LT5i%z3 zg&3@oUNtj_uQY~$a5(6v;xT0T!@PSD9cH2M&yjD+6rdum_ZVN4UWI(yZKy!(zSjBy zQ>EDtIH?k~4TZOzE@sL#P^~?3SqJNW;jhV_gEn0JFt?1GOOFB=;-Vh96>#t`dE^jT z^C;-NY7Bj@%@@HY-+kS5M_Ko%x1R^}nqeY8@NtEEQO~jQU^1jE0u$$xlFI#R^7HrL z8F&orVxx{B4^J@u{c0ln`m_`Jz62m~mz4yskD^$g4nWl`2Y(AF%j@U&9EUgJuW9Y} z)ZZ5I1?f4%wWhYG?Q-Q#8!%S$Cf!a!W9Gq!{{SG%XaJFv zNM9t5LJ!PzK+kOOZwxbS?cvkzD`da1v>T9-NuU04I7zDW-+J>e=mlvuLCruQ%iCWn z!IQa9&XogrTn>KL3v|Ey*Kz;!rx-!>tS*pDPs&m95$t(@Jx=2R_6Q(tK?zKrW@DbV z9PF$67pRXL{ym@b=e|~EW+vT8%1n14?3X#pH+&5li<#AQj{Y_d)1*HCCw|Lah30vi z1$BP#xGa6mhGVv9qIU6SGc(BlNrm*fhr9d&zP`boPn=PKsjYVWUITMD^SSTAl@)-Z zJi%4NC+Hn(k8CNNiZ{2a&4HjcOzaCUCyQ=(gF$6qV8e>+kO66)9Einx1w+F{LTy6X ze4SE^{o<|Cm+(=OqDo2PW==a!FDf~x=sHvek$vSbj$Z6uXKfweL+YpFFUQf{X(IxK zBH>6XW5-o3vm)Ri>|9?A@w1R|he@&Tx6oV)6UNt&l^0GpQzxlkD9RVXTT^-?=S7_% z!ccK{;KsTS^$lMvTEUPFd61S>lg59OY9J@wV_$;dO|LxzCCzLLfHnB|DC)gC@g&)JTTHm4 zTl@^&Do}lIA=jsMro;wW zb#F&yN>_`@^PtNJss*L^7=~6)?VBaXA^^Nv;fT|SL8`CeD{0P#fh;F(&`jQhsvOU|))C)wOv{A6Eiwsgmm}`hfOV*? zerofTaKBLR8Fc;n3hLoF1X&@i(>P)3uJ~f26fY*2%~xbsUseG=Zh3fLPSt#?mTcwa zEYHPfa9pcv%YT`fuTn4?gqfs~;MA|9guotFAKh}W^pz=oM9zv?LbF$3;`13Zx)rU` z$}4wS3Y_w6tJWlvxSa{D#J*bRaMZW7C#8r&-s@)YJ{2>w$2B`fA;Pn{eYkH2Sb#VH zhUN=saik3-w#H&qyb&QKs_vB5T8^lhdy%<*=Dmg>OjQB9f?$cHnZGPpH#exEYK^R% zxx4@FBhWA+^*Q5?-Z)zFz6{-9TprXZAIF?sTbF@&8VVMOUL}N=1%D3HG5L^Y4spF6 z^Qo%@F=rWIU5&0)3q83}?=P|*Ci2?T+j~5~rjgkiqG*&d!dN2BmSGJn z?u0P>S%FSEu-VFC&vmIdMG}w3MN7OCr8IV|#-Lv(bI3DzjNE-futbN!QB+yhlk!>7 zQ+N2)$Qoi6jyc~N>Ae?K-2=s^_vZ?R!2yChc>6yAyHRP+xN8pOTp$>0p0Tv|r~9cg z^Y-!eI0e}s<1YPiV#^(lkm@*@Zv*cr8G!{g2xYkh52W7LqvFFr?OPj02{%ShZ6^P8 zUIyP?3X|Wkk<2)L;&S%xX_0-rFjQA7w-nrq<+dN&D*WWo0UdHg>JXa8USBv_N#{$~ zEk!s+*Q$If2mi+K@ef}Wc6=bcpx)|PmA+)>J>NjPS$io6622^;IrzBH3RQ04EkPnQ z^rF@xw1UFc4Sj*h>`W5oP4-?A_eWA)AWyj8N01c#lDS z3&QE=KvPM4K9z}4JMP9VRM*^dpGeF#$h}={i5bc+R67Sq zDy4YGS6jtOW46Y|x%Y@z?O=mp)f-{Jce?^Lj|4RVAb$EC%A%JYxNEG==tOcV z=Zyn-6d!GjR$WVJBs&M625`R#daYV^R*m)Qfv}85C zgBtFhqx2JlYW719TvFX(22n#P^;Q=cHjbzvoB2wyLB@*t5nIXR2UmV60`%8XiRVBBF8c6i@%dfOW4 z463>WFXF#$;`M5z0`tviaNq@v4RUbcJ#~AAtPe>a&$T19xP%AQujgIgjLnLFQNsS* zr|hr?)gV0da8zC)2TZaSKZLw))TWH90NMm}Tn>cEQ$85uBpInl7qo~)4XWR> zx>#NHcO%MWIKTLI7;G|MuJh?Ho?2S8$ZcV`h{oi=p4Uz5v%vZ1nq5+Sn|@JcsZ7T6 zHs#XsygYFB875c2Y+AD<85L0dMjEROlsoRMd8ECvP!u-k9l+SR=xqKx89VQsnA6xn90&v@(nGl)-ZmGHK zp43*BaJLT}oIct&Qs1q@O#i#RBdQ#%`_?{Dc=uE=O+v{Yg8J0avAK$BC2Ah`4-fZ~TCXf+d(}U5Z&^g4nO5KRa-LgbHt(Fvazqm1a$t#Dg780b z#IGapOmgCmfzej`hD2}gtT^86<+CqvDI}36RKjcI%Dx%!v^56#YrAMdHAj|cda@i zn*vZ;Dq!X;ZFLn0?fLLebvXNjWUt#3oD$xP;_&YZI~^U*w0f&mqyvC;n|cHA%Z?1d zkhoG_Hz@vzdAnWpy(vCLTQGWJE{MdAp6yrzoeaUph3)?sV+4wNTNm_|)>>A8|AH)Y zUoAoCsbe8B`V(VBa{p-`hug@^F6JUl_RQO|Jhi zyei{gD-i?-+%15n{bNr7#{lURbqNOswva!LoMeOj-~2BkIjO6ls)zRPctC3bX_Jlu zRrx+?GSl?LCVNT}@cfSAFhMYOEBx?1>&(TE=F8?5W3v3u&!K?FCp41A7q0tZ%>qJm zW}x!3^ZsV{P^cQ+?NO{>kq z)VNTH{ldvTCW#3B%d4nvcj(>%8fZD2&+uwmzP6Fv(Lqco56k}aD)#mUjlC#Mnb4TH zy^9at*w@Q{l^oRf{oCBM>JBgQapu#Sx6xY@7qd;4db0{7;_V?8FQ6ruT35Ei_CHz7 z*o^3g^%n76b-P;S((kX;t(ihBgg>wUfOwFUw*HP?W^`!B?z#PdEdxL}6WHh>_TAEF zgsc72DlYwP&Yq}sgW2#pL&HUNhI`!L=-c^4;Hia#mgE$n#EWtids;)#vX`dE;DLAU z2HQGEBhy}O;URfC6WaF2U!N((JRhoiIq)Vgv>=?c1n+qpA(QIHr6$|*2(CnhUu=2~KXH8X(sVW?Z zz%iG@RLc=O1{O&F)uFQln5k8kXfN^aow|$=pDWXge--*$^D4es4~2yT5H&43I#-ae zylr??g;??7W$qqx;weg@9vNlku2;zI&VijH?WS3=62!x=0sq>bQx%vo0V_AmDI0Wu zIy}6GPd#Qi^cRX`!5(2Q<(#%D)pWyV+G{+jd6z81(X{2tsJ%^&4QxgJdKXBnqAzz5QPw CU}Lxd literal 0 HcmV?d00001 diff --git a/docs/SITL/assets/SITL-SBUS-FT232.png b/docs/SITL/assets/SITL-SBUS-FT232.png new file mode 100644 index 0000000000000000000000000000000000000000..cf7cc80e60ee2eeb561f5cb28760c48a9ff1c1c8 GIT binary patch literal 12444 zcma*N2UJtR*Dnf)f=X42bSa_;h!{!$Ly)d?5HLZS0*6R1A~h5n9RWcDA@mL+1W-_# z3Q|G>1i=8(dzBKTa}WRTd+*(M-@13btd(=l%$%9oXV0F!e|yi4GB(s0&CKcU3B1$$5-otubGFF?=yREN18hh9*-O^-*vMG98DeV9Rj>M z9BnLv!5Zo1vq#xw$!p)p2le@b&w(vAKPG+(ehM93CD%JUEz~l%$(Jy8HL< z)8^wp*;&_>5m>Bl(^y7H!@6$sZpr!c$7H8}>l?H-b(4$Rp~~+XdRDf_BO;U?>c0_a zeVP_ZZkQMu{oUNrrSbJKprg^jY;A0rhc%CmVZGD4uPLYb`TC9?jrMPD?k_GNOXeF6 z3CqN8iN{~u+}z3?0aYEB{QQE5clj}8Q_}iX!yo-N`;*@0e#JIr_|o`}%&iaY*89@v zss>Jnx$1<)tYViAwssCWUO5>%lzbaI80?NO%ZplGS@G4;nOHyGUBc`5pH~t zx=}fKJa@dbu|?f}74fh&%Ye|?IWW8czH67A_?w32M%7)-JNNyEmNTM4$rkmmGA=!4 zsDc_YG1rkVbIH9w9x+u|sp#~A(!l_kc(`mzrd@_jt%#m^z9=Fo<$2 z&)cOPn(4aS?LjmQ{oVK}Bye_<1ka>2@_6;A9{Q>gKL~O_!W6Cn^!SR^5aQ$6(juRM z%<9tT&;59^PGTt^3aE^B4yKX1) zmXU&r1rYkPtXM8M<}KLNoMU#i576C;DH6ck>pZJ z87)%5AW_7_J>dW)7%3MfK4}^wWA*MUf5vQ9{uPfT{ITot&0J6M({2?6u9S19v-Knv zw><|O&)22gSV}=-6OX&g7+}Lo=phH+l(X(!L{)jHWG2k2BXt1@3#skn$dboD?WEYu zEdFxedr}|pOQz>lQjH#rb?>=TYwRM$fD=!Gk5tdNN?HGFMtoWg$5%S#%K(3rcbn#- zAn}%%b|i&Ot`m{}t$1;UAnHo9av5vV7I-rk8{#;*T-|_+OZoTJb3iO9)qpJWG=aM@ z#YqO((yfyG0zV|@+MOi(w-`lqwjPecD zaXdC z#gI;2UPiR=6sM&;C1SUhle6cRJv+PIPUA7M3`AYp-%TU@X3$~2;U%}+Tg1hM%Cd)7 ze$Hd_vG24C$;cSxVYbk;7pLUwy%Ynvh0&yO4r>0Ow?K=xvl*QD{ar~D^61($m_stHeH zE!Gh&6i)0@NA^x=t`6Q$?VTb+Cx={b=)m-Y#L2JdRP357{s#0*U`nIM&uwwF^L3f2 zVSZ`Pvb!Brsb4~yOnE$SXMKIvEc`U%>Qy2QvS`Zi@nc1gQU3kKt?ljC>5U1>DfmBk zl)9=SHfRQz@0hLm)2ONN6L+Yvpn+%7kMpySPhlgfX*2lt>6jawRlT^%BWa!Oq-n7M z_iON{_*{9MEoFZzm0@2pq*)?PIY&*q##&HCPxF?kM@f{nK+s^Xv3QYODj;tl~lbi z+K6*dYLv}zo1VW@v%Y@dJXI8hPmM~r0X+p=cN81APDNDW(!SawZl~Su98eHX;1ajF z9lE8gh$}G?6fiQdg7Ot#@(qTo&=H$4h6qIsSu3kjT`kf32ri#=GgmkF&26UMs&(}^ zS9DsCjlT+NHdgmR6#Vne;kQ^>32dlb!1HoWaqr;aZ+lY1ZO<4Ruo;elcL!bYmQgmN zG{D{QWrMom?l;Dq(ybFFT$(>G0es1Wsi6hKsiB4j?u3M~{h@CNMTnJ0%B>ew=keuh zkO&A%()jY|pWT6Fp|NRXLTadmQf{cCxCe)LYCL-bHstr})J3&@`NAi}y^uyH?|*hf=4w&IG9tRWV=u_YauQW~AWZ zMK(!Dn`{L=s(0%A6{sE^fT_AHZH>HUzWA7h3aQ)~)Tj1taF8LU@#p}r$1{m9AtKTF zzLJo1l=WxN77LQ#%JkWLyS={>EQ6GW-ygW|0`=D9~) z=z#~5I_wR>a=QY(U2DyVTZ=%xe*MFOx4-nJs#+*k@Z^}f?##PEJ_jm8qhbceCCUSS zG!wC@>0)VBbw!H^^!>1>)J5&7S6ZYad7q`kY{1qgxNegXdnK=-?#;y8!}^;?g~i9N zHc}i!oSFQ^Lm(J$PGY>6gwJ$xgYHlFvJ|6xmEW^TUj*`O+WuAUQQ{sooFiT!S0rY? zJw)-c_#ZvAe()WQAGI8q#Flptc_~<7oAi%4LchummjWEHzR?4RDS1?!;piJ?Q_s{$ z^w8-NM|8Z0DX~ABCja@ej<{ul__0@lMO)wy?fq_tV+`HZlU10amZ~P?K6BHdyJ5RM z+5J8P<`>|{G(~%Mdf8}4o=w>Ej4c}-HXP!~mE^(4KKM5iLZ73^2=LOe`-Va2p&Hb;w`X_+*Ca4$*RBQ6sY4;*p2%kBjGh zEpUIxyOgGm^{H6y^!ABwOs9c^=p}5(l;@v?__~EOXqK^P=#Y6Q;z^nv201-!*5&X$ zM-u4l>S=1#X0SYi#UzMc;B=V~~kQ`#AD&afZqJ-ZVTIWZHf*20+s z4ufL=#tFq}3;ACptmK2Y5VV>Xjw3x5-w}@%tjf4QP?BawjUQ;+@w%p%4Y&s?h;HfX z8K9MtmwrL&f%-)R37e&zg>GYQCj}e4C@Vy3=RO!Vs*9ol8dkbX&}xZKz29s*371wY zhIS+-`3Qo{0*L-PY4hUva=YHf8v$yIPvd>G&)sV{j)gVMjxEHxJt;1-kXyo^?4rshDJ~TM)%9huv*g4X?@uEu@%};Q zUAh@u;3=LG7dZ7|mP(g8W8WYkK=ArbS zaQh`zN!C=GhQOMBA-N-Lo4^%6-p@HEu?aCTb2n^NKOOnsbw^RW{qCM#nRym^uzvWD zuKJ5gG!8b!inB$3w)=@tvR)-2_U=$yH!Y3arG~<4hqCO^#6&ZzLjRGyWedl`s2E-? zLcDZ2$)jAR0ogF!NjcpA$4R{AG;K$&<*w>#KSV) z^F4URf$r4QS{y2d#FgMCeM8l6VmY9zlczMtON(rx(&%eySL@qgNvi+DlwY1AQITS; z)P<6XZxBhUb-&~E^su#WvSgqOVNG77myPo}1B=PRHXz4_kYmal`oqWok6Wr>d*b3n_tB{Sy@&hHlY{h1-eBhY@L~Y5t%3da>*7_HE&5h)V0-8kCG-_-+PhqUxw)V{O4j!o9jJ0!`aebjckK7Xf zjd~7o>n^aJqDQq0l5tx!NKa}ya)S0=dQQWA1RbB4cD zc4mBpy0Ngp-Hfc|wH3*>?c|uB2~Du|?UksDD#@(U*h-OG8q=|pwX;K^wHC)w{8now z_+QjtoauA(REW594_>$S6xUktdh5U*H!EMvJ3$q%wkHq8i3&wnlg^`2bje%yt5InU z-8X`RdxN1$0b{SS^d*xOmN3@Gh=mUp*QvfZc?%1{AytNz?n{hAO5c9h5BPuH)7&oI z_SDwvz5)Sc6o+o(YRxJ3SZO)9>h8kC^ivgLU!H*4_c*+7K+9^z>Ieey>#HZY&^cM< zjmVLDAHZ?FgZOxA5(5pAQlBW>8ng|Cg&-@|65C6#upqw>;gE&C{5|T@Hnu#P> zlQ!F|73Xlc`C%H z(Q~8`DN(}l31Wtq>6kO{6P!RpR(d=i4%{>2ifeQ+(p>tDjbcMVh zJq#M$z#hPy4(rKxd4Yq?F>iSNzkSAd`~fUbc67y8J!EEFDOX4=v~uVe<#p741G`Q- zR=tHq@qL=k{NdGxR`ucL{;<}^&@{TA<|I#E+$=+KJestWO>&KC9iJwGM{E z!KP;&mKBHIh2IrQu!q`jjs9!EXH5<7gkpnd>tde8AF1DvI1ct@P@3niTC%tnxGnjG z-Zn|{n{YC=b@gPxV1?+RkzH$%-+Z5b6iyu^#+?JE6Mh%1#snRfb#hMK-uLv$=- zFPzd+#H0;@=lDaPTCYPGC^2YnzsR+7|C0!5ka%W)34eQU$v|X#-=q{gZEf;QQqaeBCe_Z;-gEpp6mV+Lni> zU%F1E9STol3LuL{CPb^tU-&W(oNJX`vE}ASktw3?m5hf(4hc!jjl+@ZcX~LX@+Yml zQ)RO+L}v7ra@RTH=jbWsd7(ou8vXuamA>lLz5ZyJyKcK@Y>rJc;+?tOi5M@HxSgp@o*oVPU; zuC$J?3w=31@Z;^C%6<~s^H7n2cxHld;T*7af$e7G0ms<~o8rh>g_q*S>Sfs842Sd& ze0vayk8Nhrlz`nwryDLYN8wR>dUlr#qB9MmbyE?f>PJ2{huz_jV<>)}!e5TnpZ+bA z-l6vTT{ObxvhqBSHCvu9^T$DmG*$U(g2J?j7%>&m+l_`#0-_4VSd%R|DmNW*`zONX zwYJ^_;R9OR7jREDx`WwGGr#YUqVFX){ENg-jpa_*kXUgtXngRS3ZdoPKWrZ}Wd)Ya zG)QMAVs*5t6&>}+1q~f8$g)Vi^*x@7mL<-TgZW^OAaYS=r8Eo_apTIx1pmr6!|8O_ zwUdhIw!F1fje~5=LWRd&L$Psxi!NpGrTV=aP31PwM*hgxU+Ko)un9ay7~HOK8XSEK zZ~(HOE^Hm)-*g$+XiYao3ld)}=QJ!_1+KV_3)AM_fa|{K;wcs3g{L1B^^WG1==s)q zN&h{D`=S#>QPblgg-Qm+x0MJ6<`CW2!R$v+jz$VnwK z=pr%^FB}Pk;Tb*sxUs@4MkHc5M3XV_3@GYL2nl8)TgwunIPckq^$!OD6Guz!%omk5 zy=~kJVHsMzyKsYj_u-3XpdwbHdi!1hIz2ycnhGh(^i3Eq9$>_$8wvs%j_a6+Baa%k zPbUmLiBQ7x@Q-6tw70(_(AC%Z!$)pPzIuk6t-gN|Ti3eCtzCBY9powmS#bZ!%5!|b ziw5a)U3lU@YxCh9xoCSDAlO1!R_H)`_Z~V`#-=A!sTQit0x93MGUgsnTSfyCX)nh3n)}F3o zPbbEn3qFaZl$+kEcP)e_Rc9G4UF1^72sf8F8CfKcvUtwJ^;|TXF^B)xz-v9a!9nCJ z#49++@GfoOt`LzaTzCP_r%DvzS~>@mYII=E5Whv5hXngr^NA2wBOpH}7AQ)duNd!; zz}2;b>4nvCVO!Nm`Wdw%?5~m{?y;7JxBU*7&!roeVhMC&QeTJ)S^ik*=bR=?4~*+; z+xnE_ill0SUj`71g0@372ViyCGDMra05z;UvB@*bM?T!-TwL%yWx;EJxqVt?L5+N$O0?*6y=X?_WE*Ak zw53mZl8=SiygjNbuy3f3svs>n^JcOdH@MBFw5beN8`aIyfD`FSTY@jnyE(7E&hc&| z)DUM1OyOoqW>kW%i{uaDwEFp*w1pm69yBu7QNyy>)ML-4i9cyS`@ND&4f4GEEYd8< zEHz#JPJ(=S`F&Xh&gejw1^yIW&si^Y*aongJ{E`RYt;5$dp-G$(%#;Fc=ZO@N-4SgK_F^-7F;hz$uzr|`-U-_M@=<9W(%Lrxi-xXX_WmD!a^!G zPifkd*50YHuwD*Xz3J`8=HnKtw4?}E6X^99xL>Cfi>=f2Zc}U^v5vC_*s{2|oate@ zge0!AumT~o3`Np>X@yQz7k@a|&m)rd*jR7D)z;XtPE@>I8f_0g&zq~}(;1kaQyovG z?&_iOtFLIT%1a;ivp=6cs19%Q{KML+Me28`35?Nax*;iu91iwXcpeq9Ie-cN+%YF5 z`_xY8uv**QSoX72veJ_VKcr>s*BN#ipktcwxC%J{`RF1Bw^-q=&qz%$4Rxz`DO|Ym zPoVDZZ&!+a@xG-vQ8)R6eOLbXk>^Zt5qMp%Sy_bimztYGVH1H0D5f)uenYqU@*CUM z)E_!WPAra2$=Ty)URzInr;Ox%={hqOptxukaK9Nb4fUatuft}8J?nrT%13gQ$&;xM zi@~|wUXQ}=-yJMY_kBsRYM>}XK}ZmCP#x{lrdwr@-`-}Zr&COEmd`hKtyVJp?aFK- zr(YjoYRC`OV*_vp)%0hTJ`*aM9t|rjSG&F)>VY)&&O+lVFx1#|-)!LQOj$){tu^^~ z`FCoIqZfpue9*8b%aK7E~P+&)ZG^4jqdMS7DnT2xFRuu9t};vmRVe1|m2%6;0rLFCedX(~|{UzSC?fe(%A**hTGkk5vzlZiYg{ zV4L%WzkEF2i^9`FmQq^>DxbBG9_H?2noz@|KMuOtwg~B&7ImuIzppI`52OCchnnp+ zypRp`xiqK3JY6W?$=7Svtjs$9*uKQ=fZXQC7oEYinUT{|PZE$I>8s|+r5T)US-Sf)j{wWQQXWgutGT7_Rl8XCh3oZ3NA z_b}YB^Mi)xi6U*3%ix#|s6~m7<(V&C3r_>=Q?6|A@?Igk2X@TF_FADjoIped7gj3) zKYma>YQGNSmVm}+9Aj8l+@A1mp%cz|rn(Xz((Oh>L6w7!L>CximX>EvQZ$mm;DG&?=x_G zWLVbW(u-Ha-sypuHMRXEu=X(QT>PLHnccid|7znX{rL_m#URI2n!iTXAJrO;_Hhagy?W)>KviH< zp`AD*)6_v&_(Aoac0_K6obIu9|vJYUVfhN@~RF3M#yHUe@pe%#N$?qCz171 zvr(z5_aOdMAnN?7>aFp?NG{+%GdK~0|Mo?nYC)(&`Pz*n6%vQGcpv~cK(Wa@sM|6B=!kO;4fK(#e^j1$z^PZrh%Rpz6rmaJyS5a zOPfa7=jf-WC9qzyAUXh5l=+j=4oUxzR|5)Hi+@V50&*Xj0a1aME4@whecj_>^H@@J zK&=w0gb^w)zc@7j#Pw8 zH!yvJcDZs=u5&U(aC0*{a(`;+ycPMyvG50reV+B`%pk79PkpM4bU>5*PvYZQIt>!0 zoRr8Zte&fh`o8R#TW!&BSRkHu=*=yY{M#&mM{K0(o_)SVht?@c7^@t-c{=2rYXl9{ z=O6i2VLbZj(674g;dCI?!=vO&o}0zMH=DT^Ru)_qeY!4UmCPx4)y-3R|0H_Ad6eK; ztq0Z8tTP4gQIF;^1L%)QnE_^G{gZB~cfLtW`te8Ow4`2nqt#+`@;y}4if9LKS-?e) z1DLz(W6VE0oRIS9wR@iYBGB^j)h=!CB%x)_nOtE)=+iDJs_%LIwdU@5LC1H!VH}Qc zJi9st{)>jjhNws>fM;w}|MCrO&(zo>h!B+@bb$uJg{CDoBTS(uknraJ10!Z_nHCOc zWI#N4aGt>WG0s2Dg;fEx%$E!(lgISo_8CGwI;3Sn4GiH}m)r*9bn{grCwI5=!Fa9c zJkPWkxl{ljW|1!;PjDIOxCAj^be3UW@k5GLBh$BeMk4wc@r{)8i zAQ(PYrSgTZ-1Dg=etFtnd#B3C>;J_>hpppy+SJTjvkd;5)>P`^C+3~-6M8u;#UG|mV21p>LnT?Kb6or*B-+eDB}`` zS&q|sp|k{ttIZ=W7pu2ma&byNZ7*W^y5GaiZ8b3vaJz5#(Gs*2g{nc3L4h{+v=jYw zZ8NV65UsVPuaX-s9B5f@?lf3x)54vHOwPzjk91odZpC~tjBmxdK5 zyYJ@XQhtF>-BXja?4NvVPME(zuA==mnb0p)q;lpe@up}t7HW6zwZ*u*dRK-bCERB= zSw9?aPlj;YvQbeZqa&P3J$aAc%oRIcWbhBv!F))i(_zVp5u9PolvUfU&HC+uD_{Lt7xRA)D{zXWejYin@W!iqcUNI)ya^z z>5(_LV%rkGp9Kk`LO|yt7k%O(E@D@~<1C`i@Is zu#VSn-?AX?K$X876yl~M#WMoc*><;~CReWCn?rM5FCe!G=?lQM#+6MQ#Cl{0whn!j z@(<_crVhTEZp`~-hmT8nVa?kD?#tn2ihhLL!KM&jixwW?wJxd1SD7EGIWFG6`X?6{ zyN;A^<%nIxRElqtuf9pf_Ql6+dUrg=8hSC)1K)oj?#?Y=D>V<%X54Rnk4Z}3+T+oP zEJ|#PRNh!&Xw*TF|DDH0%JE)JESy%0z-Q0Ka$w7T=T%?BR!**dw&}=8C{Qh`DyUdL z+|n1d5+{~ae|B&YFuV@c;|IzGc%=uu&Hnyf33Q3Mo0!#gO%a}Ju3({?RB}n$OsmMn zJG264V0~-xnT}zcTR2|KyDfKefQ9XLZ~?nxj(KUi6&Eo+c>k1#QD2}c!xD$|J*qrq zlw*a)1b$JugG+y|-RJjaGh!0TH(}znF!;teO5MbwDn1xI z1ljGESYgm0waXswDs}H@1o^Z>$@{41=jPB#o(i`Qfj%QXHixlAX){j+erz3mn<9Io z_Ze{Cu~GF;0g=sHQf(biS`e;O!u`kyh-S}!#|>PQensFPEMXGqg=JRn@7ksrRlq97 zI$1zVBeX@(T@)cR)RfA7!k}FY!T9Y#4+I9%mE)E4$M50o)i8*sLRd6a{12I&&6&Pg zU{&}W;^}u2hBpu?@oBqtY4hhU57>+41K^IW42stvHB&AJ&L)*vcv}?p5;7;fPJt3S zYi7_r!jgrGbv)+=0(FeXih)m)Hu~)-qVV_US4ZFrg}7ER1c*~V;aabp+-q=^%{$_t z!wh~`&({B#!>e8143eXh$8bvrva~ih!v61@?{j3%iyFr z1y{F&;<3~UoZGyn46=1(IK9A64P6bkmJ=yo#<+Axyy1I)nx2Il{1{4~MaT7T1&ayP zoB=qp4_g0?OW6c+fuKiYelY0QGZmwXHKO&y&yA%sq^5@tE|0IvS3PGOr8bpJn=t&< z)FeHcD|Ey*?5`Yt8H?<9AL~Qck-_usxp|ovH>+wZ^LquRvuxWxSlL|_32YOwKr`FG zA74ZH%soS~D?h8e$FT~N*6-k|e}0guLZP5p{X}vA*=haz4fKW=Zn}NB7j1B1tu@|u z?GU|j?RQiX4&^l?MWV)fYkR3QmC}7)zZl)^ynt|30@FMWTBYmRK>ca@`jm1}=I%Eh z4|}4uRL8bB;%4?29fdKCu``PR!z@93Ify)39)@k7M~G~YhrDaO1X`VZw+L-Uk{5sZ z%@$x96!x&fITe5(8rgkmNJ{&PEGIOk4oBHR&1C*zyfSnOknP8#(MbD0&YI5tY}i&~ z(%v2_AZLiKI8#f~I$&cyTlI$i1!B|Mrh>GN8? zu%{mzEC!QVD+5&dXm8&lM`X%5&2K+4xafjBwsH2H4aLTA0>vE)y<%wz!ti9#5>2gz zBhKtc%5GnycMaleoctfZa=kS$jjk8FiaLP&BuQRLsA&|HTjlbB#fSoVXAsUGnJy=1 zY~N0iP!1i<0iMXwH36k0$X)$|N`W&DQ;Kc(m za|Lsp2=d?$v|mAd6kb9424%?CcWAgMQ{Vz1b(S$jpmlu*guZhix_WPO@&vZf~s)oLwkeiFoZ4|NvXL1GLs9tTkxo%@p69WdAKxm zQ-kCh68|!-rq=WXurcQWwdkP^LyvOkBQ)|O8)&N6$;c(p6^ekshtsPB?1o1*RcNrg z{iFT+@|wq(Gbdx%k|t9#x!Cn!G1j0F1>?x4SFgr0KKL)}r%@Nh2r4Tcx)TGscXDQh z6Jg&)u_q4VK`>=*u!pKxke~+-v-s|lqyir994f?3XD7;nO62_#MjpQ6@bd@ae(dJB z)GJWiWv24T<&*+d`nI^fWi&nEm%|H}0q#LtLFyCL({-WvvZ4)uUk!$^(_4iRrL zlB5_~=io^vWn&lc9yDh4zT>87Sn>iuGFk}_y>HqT>wwD4k!?w+e$yxa%I?vR@SzWdBtWGF^< z?T>#+RSVSdUWG(-G6uK&roVl48vOpKcdQ~L6Od1ZR4mPtAhYg@i+6~zd8)Sujm!(! zau!}_-nwk_DRtBi!=igTbFwBNXp^w9VzAk<_4UR^ap1Sphzni!wc6Ip{Fbg1C$4lf zTv5K)ai6tuPAMXD;3WhxuoT$l7?XeT))t}X7EIuc$ek4i$z6=%!@9T}(lv4B7DXGA zyXMnnK>Xb}SEE&l-bDZ1%NzVHMoR=tQvc7Q%wA@>4CClQQoDMwN{6r7y_AwSGxBm% z4)+=_9Tszls7KreS>#{|UrO#Tnw!S`_ZP7r@ZJb?5~Fq`EUt9(%LJMhY>Ug>+wxTl z1W}*W`!`ywaBkEELy4VRkS`S~xz^2b5-!bB8Bk0`(pUAH3Wvru-TYXurNvPn2_p zMB=Tia8QUrFW*AEAnt887>_n4jT}}lO4nuqrw@)$IxvV)N6Lai5BK)X>4 z82f%;7krWZBMv;wa1MOseUbeY_(*@^ae=$<4DmJ?G6f+mVZcbz<6)sIEimqS8HVoy zOFxPo*yzCGP1q8Zyr{@!acdv~gddkV!TrCeq(+FB1G{e*1FPsEbpz?UT81(wWzfq- zBO9__;KK2z7EdV7M_V{&ffzZss5maGA&RlF0hOG|bqJ>Nc)*^6Dk1{c^8cUAvY$pl zS$wr&ka>g<48Mbl`&tb;FT2Hn1$;%-gNX&q#Y>M?+Km92DP;#Q*Vj1@)))oOP8T{Z zIJf*qq3rFVVw^o9@N5Uwastwz?s>j|d3^#PZiCN9OFSSu*#5W3A9Mof`tUyBF=)gI zLz@G+_|AhXRf8+$LMr4HPxoB={YUNhZB_yw{DWs+{HOXhDgsn!!#WQC zf%I>)H|x43y0IoQ@OvKAPVsa4wNd@OKY>+S%=-&`#UYX1qBOvGtd=8IN6V*{Ze1$y zt+afuO%U!wkJVSM_e}~~$yqfsypH$>;Nd@E96VrX!91@q5zBRh5XDqD#Jr}SsM?09 z-ck_M7B}(aLJ@H?u|X5DOBe}RH+0)KOubjy=pZi$LR%;-%!A(KTJ(SpNlyBptY%#5 z8@2{netM&6vX8~ijey%Ou;Da=LKIBfK>Eo_d^|jL#|{p8lLHkkdjv2TpiNFXASD=L zCwLNP+7yP;#|Z=;W=Q}8MKg>`RbiF3GV|pi_^|8}ga)hK!`*L;F!!F;2`$2Q8Cmu3ZnIV}0@h z!p-QGhSJa9BHs^#md^waUUU^lTq#rt$rTmlge095RNeG|c5Q=d*dXRbN6hl$he(|vhMR{~=ARX% zXi{U@$q<-l!Y};J!#+b$9$~37V}V_f7H|9# zxZQti&rJnY;?|Nlegl6FZW_<>%|H`+`9341IE^mr$MEfQvvp}G?JvcpFiH-cKz?Qu z_A&0ltTj>wkSny;b{?1= zscz!WIL5-pf?}2Gvj@K&_<%b|VJoHitD`C-9$3HcrY{hPV|J&KM{3Zs&~EnJ@i~>2 zGqX2`4oIuZMuxqFUrE!RW{-n^osE#LNgB5=F3S6ff`brLe!4;t(jxstTzCxWAGor3 zioc^k6xzv2;OA(O-#K`LK{F&4R1)>IJ196I*J|I~_zldfe2!a@D{uKVR(kA7M&xkz zqFN#RR>nbs?bxwG!(v+8mz#xUPJ$QM^a-^{9o?s;P&<27F=5VrAyP%?t3S(kXVxh< z$aPKD4Rl#XsN-{mn@(V@so_ZU!Sa-1Swuf1^k8keL-N=6D0mbSQywuJi!zXDGHSG% z;vGc@M)q72b{_G)3P?Yu4210AY!e<6>srxodz3X)2rbbnhk8cdr7uV?ShmRY3c|G- zfxS_J^erl+frU!ax;n`9$YqH?cg%Ec3P||huDNVF7=b?prdxgp^3clds#2?#Do4S&U|(HiT(W9 zSmgS*(TN?ky)(G96nE~3$jChdJ`IRyIP5GstF;BfhjNWtd3Grpp=8ha7V?H$5j$1V zBy{IPJ!B8@k&zFpCM~v?aH(mo1 z!@hb13O-ht?(E)G<+`!bUQ4rZaB;1hq+?-5m1UweIdU*DwfRY0f_ar$fn{mINLgj8 z93tl(RF;bxFjmc$){#N&Z~S)nf$aEDoVhZrBUZfEJtGoR{Ufw4*Jyr@>tts>KmIhp z0a^7o>P=ef^s1aorWLtsn`cFqRhNVzk#{4r1!80fP`HuUAMQJ%(07vv|Mq^A1~XPKl|~^-{rY+pUM&A&P``JB=1I zERCM=ZO&}_tR}oO4Ldw-1}YbGxrUOM$y%xXSQT7CVmK5nL!N_I+2J1tx8 z9c!eVa%anG)uz)HLCWx_BC$R%GE|>1dW61R?ajpb4_qOfVL>tOfe?O-G?|&grN8P6 zKQ;MTq^qA)2j0q|b4S57hHsm1!8>O3yj2&)MLWWls}y~%6>B9cMBDtkDl82~s~qCG z>l;rn9Zaaayh=m%Lo}%Tatr_ZCN|8&6BeE_p|;k`--^+Ssrw)3rcmm(5#ggaYI*98 zlr{-^e3zu1>%`{_Goeeu0~`OeOiwosyCXq9=4-5u%4J1}M^w6QZPHhSZw^5xqdim8 z)VZ=xiY&n?iJj#>jZUGz8P5OJj-9ex}n(ZZ(cT4#KyO zt}iFR$^Mm=RqU4<4p%sPq!6~=8%%1QDbLpZ?rA1}oGg!*RnAVtTQ)*DS&JOTi3Lz) z_v>Mmk;x3u^kB`0WnI^~ah$ZJt=vqOjCq5_0Lvx6#XjoF(V)K|^%PcM{64GHGWVv( zo7?GII+HV&Llp#RCjo6w_7|xHuVan8_n%vxM(`|KMWNT-0B3QoUz>uq z7#o)=aTa{CFnvA)PTOpF0BB`&OBLgl2*Cz@Seiy?V)K7J5l;QVj)LbbbtcL$X0vH? zV<4{ni0{0HZu6>vbgmYr=C~4dd6P#|(20FTm-CCC4DpFl2^R7oBi4V;TyHN8NXZ<7B90{%P1l!i|n`^~DgSUUYyi{QY$~(kW zbP-%us|k(%@{{Mam?;nLNGgbBPP#OcXr9xQ8|^9j&5iv{+h;H}V*ufG*om$$tIMi> zwWcfQYDhGnX-Z^!h(7$bfQeXq@m2% literal 0 HcmV?d00001 diff --git a/src/main/CMakeLists.txt b/src/main/CMakeLists.txt index 9f78997cad..ab86b0cd65 100644 --- a/src/main/CMakeLists.txt +++ b/src/main/CMakeLists.txt @@ -210,6 +210,8 @@ main_sources(COMMON_SRC drivers/pitotmeter/pitotmeter_msp.h drivers/pitotmeter/pitotmeter_virtual.c drivers/pitotmeter/pitotmeter_virtual.h + drivers/pitotmeter/pitotmeter_fake.h + drivers/pitotmeter/pitotmeter_fake.c drivers/pwm_esc_detect.c drivers/pwm_esc_detect.h drivers/pwm_mapping.c @@ -491,6 +493,7 @@ main_sources(COMMON_SRC io/gps_ublox.c io/gps_nmea.c io/gps_msp.c + io/gps_fake.c io/gps_private.h io/ledstrip.c io/ledstrip.h @@ -542,6 +545,8 @@ main_sources(COMMON_SRC sensors/rangefinder.h sensors/opflow.c sensors/opflow.h + sensors/battery_sensor_fake.c + sensors/battery_sensor_fake.h telemetry/crsf.c telemetry/crsf.h diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index e4b8dc1d67..b49455f008 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -1558,11 +1558,13 @@ static void loadMainState(timeUs_t currentTimeUs) blackboxCurrent->accADC[i] = lrintf(acc.accADCf[i] * acc.dev.acc_1G); blackboxCurrent->gyroRaw[i] = lrintf(gyro.gyroRaw[i]); +#ifdef USE_DYNAMIC_FILTERS for (uint8_t i = 0; i < DYN_NOTCH_PEAK_COUNT ; i++) { blackboxCurrent->gyroPeaksRoll[i] = dynamicGyroNotchState.frequency[FD_ROLL][i]; blackboxCurrent->gyroPeaksPitch[i] = dynamicGyroNotchState.frequency[FD_PITCH][i]; blackboxCurrent->gyroPeaksYaw[i] = dynamicGyroNotchState.frequency[FD_YAW][i]; } +#endif #ifdef USE_MAG blackboxCurrent->magADC[i] = mag.magADC[i]; diff --git a/src/main/build/atomic.h b/src/main/build/atomic.h index 53c165d3c6..80ec70f55d 100644 --- a/src/main/build/atomic.h +++ b/src/main/build/atomic.h @@ -17,7 +17,7 @@ #pragma once -#ifdef UNIT_TEST +#if defined(UNIT_TEST) || defined(SITL_BUILD) static inline void __set_BASEPRI(uint32_t basePri) {(void)basePri;} static inline void __set_BASEPRI_MAX(uint32_t basePri) {(void)basePri;} #endif // UNIT_TEST diff --git a/src/main/cms/cms.c b/src/main/cms/cms.c index 8341cda584..c4bae3a1f2 100644 --- a/src/main/cms/cms.c +++ b/src/main/cms/cms.c @@ -839,7 +839,11 @@ static void cmsTraverseGlobalExit(const CMS_Menu *pMenu) long cmsMenuExit(displayPort_t *pDisplay, const void *ptr) { - int exitType = (int)ptr; +#if defined(SITL_BUILD) + unsigned long exitType = (uintptr_t)ptr; +#else + int exitType = (int)ptr; +#endif switch (exitType) { case CMS_EXIT_SAVE: case CMS_EXIT_SAVEREBOOT: diff --git a/src/main/common/bitarray.c b/src/main/common/bitarray.c index a46a536e3d..07d175d515 100755 --- a/src/main/common/bitarray.c +++ b/src/main/common/bitarray.c @@ -55,7 +55,7 @@ __attribute__((always_inline)) static inline uint8_t __CTZ(uint32_t val) // rbit and then a clz, making it return 32 for zero on ARM. // For other architectures, explicitely implement the same // semantics. -#ifdef __arm__ +#if defined(__arm__) && !defined(SITL_BUILD) uint8_t zc; __asm__ volatile ("rbit %1, %1\n\t" "clz %0, %1" diff --git a/src/main/common/printf.c b/src/main/common/printf.c index 340847f568..5e72f726b0 100644 --- a/src/main/common/printf.c +++ b/src/main/common/printf.c @@ -48,6 +48,9 @@ #ifdef REQUIRE_PRINTF_LONG_SUPPORT #include "typeconversion.h" +#define MAX UINT64_MAX +#else +#define MAX UINT32_MAX #endif static serialPort_t *printfSerialPort; @@ -110,7 +113,7 @@ int tfp_nformat(void *putp, int size, void (*putf) (void *, char), const char *f int written = 0; char ch; - const void *end = size < 0 ? (void*)UINT32_MAX : ((char *)putp + size - 1); + const void *end = size < 0 ? (void*)MAX : ((char *)putp + size - 1); while ((ch = *(fmt++))) { if (ch != '%') { diff --git a/src/main/config/config_eeprom.c b/src/main/config/config_eeprom.c index 645398e8da..6d11c1804d 100755 --- a/src/main/config/config_eeprom.c +++ b/src/main/config/config_eeprom.c @@ -36,6 +36,10 @@ #include "fc/config.h" +#if defined(CONFIG_IN_FILE) + void config_streamer_impl_unlock(void); +#endif + static uint16_t eepromConfigSize; typedef enum { @@ -120,6 +124,8 @@ void initEEPROM(void) // Flash read failed - just die now failureMode(FAILURE_FLASH_READ_FAILED); } +#elif defined(CONFIG_IN_FILE) + config_streamer_impl_unlock(); #endif } diff --git a/src/main/config/config_streamer_file.c b/src/main/config/config_streamer_file.c new file mode 100644 index 0000000000..8fec837ce4 --- /dev/null +++ b/src/main/config/config_streamer_file.c @@ -0,0 +1,105 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include +#include "platform.h" +#include "drivers/system.h" +#include "config/config_streamer.h" +#include "common/utils.h" + +#if defined(CONFIG_IN_FILE) + +#include +#include + +#define FLASH_PAGE_SIZE (0x400) + +static FILE *eepromFd = NULL; + +static bool streamerLocked = true; + +void config_streamer_impl_unlock(void) +{ + if (eepromFd != NULL) { + fprintf(stderr, "[EEPROM] Unable to load %s\n", EEPROM_FILENAME); + return; + } + + // open or create + eepromFd = fopen(EEPROM_FILENAME,"r+"); + if (eepromFd != NULL) { + // obtain file size: + fseek(eepromFd , 0 , SEEK_END); + size_t size = ftell(eepromFd); + rewind(eepromFd); + + size_t n = fread(eepromData, 1, sizeof(eepromData), eepromFd); + if (n == size) { + printf("[EEPROM] Loaded '%s' (%ld of %ld bytes)\n", EEPROM_FILENAME, size, sizeof(eepromData)); + streamerLocked = false; + } else { + fprintf(stderr, "[EEPROM] Failed to load '%s'\n", EEPROM_FILENAME); + } + } else { + printf("[EEPROM] Created '%s', size = %ld\n", EEPROM_FILENAME, sizeof(eepromData)); + streamerLocked = false; + if ((eepromFd = fopen(EEPROM_FILENAME, "w+")) == NULL) { + fprintf(stderr, "[EEPROM] Failed to create '%s'\n", EEPROM_FILENAME); + streamerLocked = true; + } + if (fwrite(eepromData, sizeof(eepromData), 1, eepromFd) != 1) { + fprintf(stderr, "[EEPROM] Write failed: %s\n", strerror(errno)); + streamerLocked = true; + } + } + + +} + +void config_streamer_impl_lock(void) +{ + // flush & close + if (eepromFd != NULL) { + fseek(eepromFd, 0, SEEK_SET); + fwrite(eepromData, 1, sizeof(eepromData), eepromFd); + fclose(eepromFd); + eepromFd = NULL; + printf("[EEPROM] Saved '%s'\n", EEPROM_FILENAME); + streamerLocked = false; + } else { + fprintf(stderr, "[EEPROM] Unlock error\n"); + } +} + +int config_streamer_impl_write_word(config_streamer_t *c, config_streamer_buffer_align_type_t *buffer) +{ + if (streamerLocked) { + return -1; + } + + if ((c->address >= (uintptr_t)eepromData) && (c->address < (uintptr_t)ARRAYEND(eepromData))) { + *((uint32_t*)c->address) = *buffer; + printf("[EEPROM] Program word %p = %08x\n", (void*)c->address, *((uint32_t*)c->address)); + } else { + printf("[EEPROM] Program word %p out of range!\n", (void*)c->address); + } + + c->address += CONFIG_STREAMER_BUFFER_SIZE; + return 0; +} + +#endif \ No newline at end of file diff --git a/src/main/drivers/accgyro/accgyro.c b/src/main/drivers/accgyro/accgyro.c index 6ed99cba2f..4182e760b5 100644 --- a/src/main/drivers/accgyro/accgyro.c +++ b/src/main/drivers/accgyro/accgyro.c @@ -22,7 +22,10 @@ #include "platform.h" +#if !defined(SITL_BUILD) #include "build/atomic.h" +#endif + #include "build/build_config.h" #include "common/log.h" diff --git a/src/main/drivers/accgyro/accgyro_fake.c b/src/main/drivers/accgyro/accgyro_fake.c index 0cd9addfae..92be492f74 100644 --- a/src/main/drivers/accgyro/accgyro_fake.c +++ b/src/main/drivers/accgyro/accgyro_fake.c @@ -17,37 +17,74 @@ #include #include +#include #include "platform.h" #include "common/axis.h" #include "common/utils.h" +#include "fc/runtime_config.h" + #include "drivers/accgyro/accgyro.h" #include "drivers/accgyro/accgyro_fake.h" #ifdef USE_IMU_FAKE -static int16_t fakeGyroADC[XYZ_AXIS_COUNT]; +#if defined(SITL_BUILD) + +#define VOLATILE volatile + +static pthread_mutex_t gyroMutex; +static pthread_mutex_t accMutex; + +#define LOCK(mutex) (pthread_mutex_lock(mutex)) +#define UNLOCK(mutex) (pthread_mutex_unlock(mutex)) + +#define GYROLOCK (pthread_mutex_lock(&gyroMutex)) +#define GYROUNLOCK (pthread_mutex_unlock(&gyroMutex)) +#define ACCLOCK (pthread_mutex_lock(&accMutex)) +#define ACCUNLOCK (pthread_mutex_unlock(&accMutex)) + +#else +#define VOLATILE +#define GYROLOCK +#define GYROUNLOCK +#define ACCLOCK +#define ACCUNLOCK + +#endif + +static VOLATILE int16_t fakeGyroADC[XYZ_AXIS_COUNT]; static void fakeGyroInit(gyroDev_t *gyro) { UNUSED(gyro); + +#if defined(SITL_BUILD) + pthread_mutex_init(&gyroMutex, NULL); +#endif + + //ENABLE_STATE(ACCELEROMETER_CALIBRATED); } void fakeGyroSet(int16_t x, int16_t y, int16_t z) { + GYROLOCK; fakeGyroADC[X] = x; fakeGyroADC[Y] = y; fakeGyroADC[Z] = z; + GYROUNLOCK; } static bool fakeGyroRead(gyroDev_t *gyro) { + GYROLOCK; gyro->gyroADCRaw[X] = fakeGyroADC[X]; gyro->gyroADCRaw[Y] = fakeGyroADC[Y]; gyro->gyroADCRaw[Z] = fakeGyroADC[Z]; + GYROUNLOCK; return true; } @@ -70,34 +107,38 @@ bool fakeGyroDetect(gyroDev_t *gyro) gyro->intStatusFn = fakeGyroInitStatus; gyro->readFn = fakeGyroRead; gyro->temperatureFn = fakeGyroReadTemperature; - gyro->scale = 1.0f / 16.4f; + gyro->scale = 0.0625f; gyro->gyroAlign = 0; return true; } -#endif // USE_FAKE_GYRO - -#ifdef USE_FAKE_ACC - -static int16_t fakeAccData[XYZ_AXIS_COUNT]; +static VOLATILE int16_t fakeAccData[XYZ_AXIS_COUNT]; static void fakeAccInit(accDev_t *acc) { - UNUSED(acc); +#if defined(SITL_BUILD) + pthread_mutex_init(&accMutex, NULL); +#endif + + acc->acc_1G = 9806; } void fakeAccSet(int16_t x, int16_t y, int16_t z) -{ +{ + ACCLOCK; fakeAccData[X] = x; fakeAccData[Y] = y; fakeAccData[Z] = z; + ACCUNLOCK; } static bool fakeAccRead(accDev_t *acc) { + ACCLOCK; acc->ADCRaw[X] = fakeAccData[X]; acc->ADCRaw[Y] = fakeAccData[Y]; acc->ADCRaw[Z] = fakeAccData[Z]; + ACCUNLOCK; return true; } @@ -108,5 +149,5 @@ bool fakeAccDetect(accDev_t *acc) acc->accAlign = 0; return true; } -#endif // USE_FAKE_ACC +#endif diff --git a/src/main/drivers/accgyro/accgyro_mpu6500.c b/src/main/drivers/accgyro/accgyro_mpu6500.c old mode 100755 new mode 100644 diff --git a/src/main/drivers/accgyro/accgyro_mpu6500.h b/src/main/drivers/accgyro/accgyro_mpu6500.h old mode 100755 new mode 100644 diff --git a/src/main/drivers/accgyro/accgyro_mpu9250.c b/src/main/drivers/accgyro/accgyro_mpu9250.c old mode 100755 new mode 100644 diff --git a/src/main/drivers/accgyro/accgyro_mpu9250.h b/src/main/drivers/accgyro/accgyro_mpu9250.h old mode 100755 new mode 100644 diff --git a/src/main/drivers/adc.c b/src/main/drivers/adc.c index 573c1e69b7..eeb65acfab 100644 --- a/src/main/drivers/adc.c +++ b/src/main/drivers/adc.c @@ -25,9 +25,10 @@ #include "drivers/time.h" #include "common/utils.h" -#ifdef USE_ADC -#include "drivers/io.h" #include "drivers/adc.h" +#if defined(USE_ADC) && !defined(SITL_BUILD) +#include "drivers/io.h" + #include "drivers/adc_impl.h" #ifndef ADC_INSTANCE @@ -206,6 +207,18 @@ uint16_t adcGetChannel(uint8_t channel) #endif #else // USE_ADC + +bool adcIsFunctionAssigned(uint8_t function) +{ + UNUSED(function); + return false; +} + +void adcInit(drv_adc_config_t *init) +{ + UNUSED(init); +} + uint16_t adcGetChannel(uint8_t channel) { UNUSED(channel); diff --git a/src/main/drivers/barometer/barometer_fake.c b/src/main/drivers/barometer/barometer_fake.c index 939089c132..bcab0ce992 100644 --- a/src/main/drivers/barometer/barometer_fake.c +++ b/src/main/drivers/barometer/barometer_fake.c @@ -55,16 +55,16 @@ void fakeBaroSet(int32_t pressure, int32_t temperature) bool fakeBaroDetect(baroDev_t *baro) { - fakePressure = 101325; // pressure in Pa (0m MSL) - fakeTemperature = 2500; // temperature in 0.01 C = 25 deg + fakePressure = 0; // pressure in Pa (0m MSL) + fakeTemperature = 0; // temperature in 0.01 C = 25 deg // these are dummy as temperature is measured as part of pressure - baro->ut_delay = 10000; + baro->ut_delay = 0; baro->get_ut = fakeBaroStartGet; baro->start_ut = fakeBaroStartGet; // only _up part is executed, and gets both temperature and pressure - baro->up_delay = 10000; + baro->up_delay = 1000; baro->start_up = fakeBaroStartGet; baro->get_up = fakeBaroStartGet; baro->calculate = fakeBaroCalculate; diff --git a/src/main/drivers/bus.c b/src/main/drivers/bus.c old mode 100755 new mode 100644 index f06e847d57..3b003b8caf --- a/src/main/drivers/bus.c +++ b/src/main/drivers/bus.c @@ -66,10 +66,12 @@ static void busDevPreInit(const busDeviceDescriptor_t * descriptor) void busInit(void) { +#if !defined(SITL_BUILD) /* Pre-initialize bus devices */ for (const busDeviceDescriptor_t * descriptor = __busdev_registry_start; (descriptor) < __busdev_registry_end; descriptor++) { busDevPreInit(descriptor); } +#endif } #ifdef USE_I2C @@ -113,6 +115,11 @@ void busDeviceDeInit(busDevice_t * dev) busDevice_t * busDeviceInit(busType_e bus, devHardwareType_e hw, uint8_t tag, resourceOwner_e owner) { UNUSED(owner); +#if defined(SITL_BUILD) + UNUSED(bus); + UNUSED(hw); + UNUSED(tag); +#else for (const busDeviceDescriptor_t * descriptor = __busdev_registry_start; (descriptor) < __busdev_registry_end; descriptor++) { if (hw == descriptor->devHwType && (bus == descriptor->busType || bus == BUSTYPE_ANY) && (tag == descriptor->tag)) { @@ -163,12 +170,17 @@ busDevice_t * busDeviceInit(busType_e bus, devHardwareType_e hw, uint8_t tag, re } } } - +#endif return NULL; } busDevice_t * busDeviceOpen(busType_e bus, devHardwareType_e hw, uint8_t tag) { +#if defined(SITL_BUILD) + UNUSED(bus); + UNUSED(hw); + UNUSED(tag); +#else for (const busDeviceDescriptor_t * descriptor = __busdev_registry_start; (descriptor) < __busdev_registry_end; descriptor++) { if (hw == descriptor->devHwType && (bus == descriptor->busType || bus == BUSTYPE_ANY) && (tag == descriptor->tag)) { // Found a hardware descriptor. Now check if device context is valid @@ -178,7 +190,7 @@ busDevice_t * busDeviceOpen(busType_e bus, devHardwareType_e hw, uint8_t tag) } } } - +#endif return NULL; } @@ -258,6 +270,12 @@ bool busTransferMultiple(const busDevice_t * dev, busTransferDescriptor_t * dsc, bool busWriteBuf(const busDevice_t * dev, uint8_t reg, const uint8_t * data, uint8_t length) { +#if !defined(USE_SPI) && !defined(USE_I2C) + UNUSED(reg); + UNUSED(data); + UNUSED(length); +#endif + switch (dev->busType) { case BUSTYPE_SPI: #ifdef USE_SPI @@ -285,6 +303,11 @@ bool busWriteBuf(const busDevice_t * dev, uint8_t reg, const uint8_t * data, uin bool busWrite(const busDevice_t * dev, uint8_t reg, uint8_t data) { +#if !defined(USE_SPI) && !defined(USE_I2C) + UNUSED(reg); + UNUSED(data); +#endif + switch (dev->busType) { case BUSTYPE_SPI: #ifdef USE_SPI @@ -312,6 +335,11 @@ bool busWrite(const busDevice_t * dev, uint8_t reg, uint8_t data) bool busReadBuf(const busDevice_t * dev, uint8_t reg, uint8_t * data, uint8_t length) { +#if !defined(USE_SPI) && !defined(USE_I2C) + UNUSED(reg); + UNUSED(data); + UNUSED(length); +#endif switch (dev->busType) { case BUSTYPE_SPI: #ifdef USE_SPI @@ -339,6 +367,11 @@ bool busReadBuf(const busDevice_t * dev, uint8_t reg, uint8_t * data, uint8_t le bool busRead(const busDevice_t * dev, uint8_t reg, uint8_t * data) { +#if !defined(USE_SPI) && !defined(USE_I2C) + UNUSED(reg); + UNUSED(data); +#endif + switch (dev->busType) { case BUSTYPE_SPI: #ifdef USE_SPI diff --git a/src/main/drivers/bus.h b/src/main/drivers/bus.h old mode 100755 new mode 100644 diff --git a/src/main/drivers/bus_busdev_i2c.c b/src/main/drivers/bus_busdev_i2c.c old mode 100755 new mode 100644 diff --git a/src/main/drivers/bus_busdev_spi.c b/src/main/drivers/bus_busdev_spi.c old mode 100755 new mode 100644 diff --git a/src/main/drivers/compass/compass_ak8963.c b/src/main/drivers/compass/compass_ak8963.c old mode 100755 new mode 100644 diff --git a/src/main/drivers/compass/compass_ak8963.h b/src/main/drivers/compass/compass_ak8963.h old mode 100755 new mode 100644 diff --git a/src/main/drivers/compass/compass_mag3110.c b/src/main/drivers/compass/compass_mag3110.c old mode 100755 new mode 100644 diff --git a/src/main/drivers/compass/compass_mag3110.h b/src/main/drivers/compass/compass_mag3110.h old mode 100755 new mode 100644 diff --git a/src/main/drivers/compass/compass_mpu9250.c b/src/main/drivers/compass/compass_mpu9250.c old mode 100755 new mode 100644 diff --git a/src/main/drivers/compass/compass_mpu9250.h b/src/main/drivers/compass/compass_mpu9250.h old mode 100755 new mode 100644 diff --git a/src/main/drivers/compass/compass_qmc5883l.c b/src/main/drivers/compass/compass_qmc5883l.c old mode 100755 new mode 100644 diff --git a/src/main/drivers/compass/compass_qmc5883l.h b/src/main/drivers/compass/compass_qmc5883l.h old mode 100755 new mode 100644 diff --git a/src/main/drivers/display.c b/src/main/drivers/display.c index 28bbd88133..55e15ff043 100644 --- a/src/main/drivers/display.c +++ b/src/main/drivers/display.c @@ -179,7 +179,7 @@ int displayWriteChar(displayPort_t *instance, uint8_t x, uint8_t y, uint16_t c) } #ifdef USE_SIMULATOR - if (ARMING_FLAG(SIMULATOR_MODE)) { + if (ARMING_FLAG(SIMULATOR_MODE_HITL)) { //some FCs do not power max7456 from USB power //driver can not read font metadata //chip assumed to not support second bank of font diff --git a/src/main/drivers/exti.c b/src/main/drivers/exti.c index bc7b3400f6..27f2294065 100644 --- a/src/main/drivers/exti.c +++ b/src/main/drivers/exti.c @@ -4,6 +4,8 @@ #include "platform.h" +#if !defined(SITL_BUILD) + #include "build/assert.h" #include "drivers/exti.h" @@ -197,4 +199,6 @@ _EXTI_IRQ_HANDLER(EXTI2_TS_IRQHandler); _EXTI_IRQ_HANDLER(EXTI3_IRQHandler); _EXTI_IRQ_HANDLER(EXTI4_IRQHandler); _EXTI_IRQ_HANDLER(EXTI9_5_IRQHandler); -_EXTI_IRQ_HANDLER(EXTI15_10_IRQHandler); \ No newline at end of file +_EXTI_IRQ_HANDLER(EXTI15_10_IRQHandler); + +#endif diff --git a/src/main/drivers/io.c b/src/main/drivers/io.c index fe89596317..4a77d3a9f3 100644 --- a/src/main/drivers/io.c +++ b/src/main/drivers/io.c @@ -128,6 +128,8 @@ uint32_t IO_EXTI_Line(IO_t io) } #if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) return 1 << IO_GPIOPinIdx(io); +#elif defined (SITL_BUILD) + return 0; #else # error "Unknown target type" #endif @@ -334,8 +336,14 @@ void IOConfigGPIOAF(IO_t io, ioConfig_t cfg, uint8_t af) } #endif +#if DEFIO_PORT_USED_COUNT > 0 static const uint16_t ioDefUsedMask[DEFIO_PORT_USED_COUNT] = { DEFIO_PORT_USED_LIST }; static const uint8_t ioDefUsedOffset[DEFIO_PORT_USED_COUNT] = { DEFIO_PORT_OFFSET_LIST }; +#else +// Avoid -Wpedantic warning +static const uint16_t ioDefUsedMask[1] = {0}; +static const uint8_t ioDefUsedOffset[1] = {0}; +#endif ioRec_t ioRecs[DEFIO_IO_USED_COUNT]; // initialize all ioRec_t structures from ROM diff --git a/src/main/drivers/io.h b/src/main/drivers/io.h index 27c0b3827b..5b7025414a 100644 --- a/src/main/drivers/io.h +++ b/src/main/drivers/io.h @@ -70,7 +70,7 @@ #define IOCFG_IN_FLOATING IO_CONFIG(GPIO_Mode_IN, 0, 0, GPIO_PuPd_NOPULL) #define IOCFG_IPU_25 IO_CONFIG(GPIO_Mode_IN, GPIO_Speed_25MHz, 0, GPIO_PuPd_UP) -#elif defined(UNIT_TEST) +#elif defined(UNIT_TEST) || defined(SITL_BUILD) # define IOCFG_OUT_PP 0 # define IOCFG_OUT_OD 0 diff --git a/src/main/drivers/io_def_generated.h b/src/main/drivers/io_def_generated.h index a1f0fc3114..580837d73f 100644 --- a/src/main/drivers/io_def_generated.h +++ b/src/main/drivers/io_def_generated.h @@ -1134,7 +1134,9 @@ #endif #if !defined DEFIO_PORT_USED_LIST -# warning "No pins are defined. Maybe you forgot to define TARGET_IO_PORTx in target_io.h" +# if !defined DEFIO_NO_PORTS +# warning "No pins are defined. Maybe you forgot to define TARGET_IO_PORTx in target_io.h" +# endif # define DEFIO_PORT_USED_COUNT 0 # define DEFIO_PORT_USED_LIST /* empty */ # define DEFIO_PORT_OFFSET_LIST /* empty */ diff --git a/src/main/drivers/logging_codes.h b/src/main/drivers/logging_codes.h old mode 100755 new mode 100644 diff --git a/src/main/drivers/opflow/opflow.h b/src/main/drivers/opflow/opflow.h old mode 100755 new mode 100644 diff --git a/src/main/drivers/opflow/opflow_fake.c b/src/main/drivers/opflow/opflow_fake.c old mode 100755 new mode 100644 diff --git a/src/main/drivers/opflow/opflow_fake.h b/src/main/drivers/opflow/opflow_fake.h old mode 100755 new mode 100644 diff --git a/src/main/drivers/opflow/opflow_virtual.c b/src/main/drivers/opflow/opflow_virtual.c old mode 100755 new mode 100644 diff --git a/src/main/drivers/opflow/opflow_virtual.h b/src/main/drivers/opflow/opflow_virtual.h old mode 100755 new mode 100644 diff --git a/src/main/drivers/pitotmeter/pitotmeter_fake.c b/src/main/drivers/pitotmeter/pitotmeter_fake.c index 5d3c56c4e6..f913b76d09 100644 --- a/src/main/drivers/pitotmeter/pitotmeter_fake.c +++ b/src/main/drivers/pitotmeter/pitotmeter_fake.c @@ -24,21 +24,40 @@ #include "common/utils.h" -#include "pitotmeter.h" -#include "pitotmeter_fake.h" +#include "drivers/pitotmeter/pitotmeter.h" +#include "drivers/pitotmeter/pitotmeter_fake.h" #ifdef USE_PITOT_FAKE -static int32_t fakePressure; -static int32_t fakeTemperature; +static float fakePressure; +static float fakeTemperature; +static float fakeAirspeed; -static void fakePitotStart(pitotDev_t *pitot) +static bool fakePitotStart(pitotDev_t *pitot) { UNUSED(pitot); + return true; } -static void fakePitotRead(pitotDev_t *pitot) +void fakePitotSet(float pressure, float temperature) { - UNUSED(pitot); + fakePressure = pressure; + fakeTemperature = temperature; +} + +void fakePitotSetAirspeed(float airSpeed) +{ + fakeAirspeed = airSpeed; +} + +float fakePitotGetAirspeed(void) +{ + return fakeAirspeed; +} + +bool fakePitotRead(pitotDev_t *pitot) +{ + pitot->calculate(pitot, &fakePressure, &fakeTemperature); + return true; } static void fakePitotCalculate(pitotDev_t *pitot, float *pressure, float *temperature) diff --git a/src/main/drivers/pitotmeter/pitotmeter_fake.h b/src/main/drivers/pitotmeter/pitotmeter_fake.h index 3eeb4828c3..f9fa78fcd2 100644 --- a/src/main/drivers/pitotmeter/pitotmeter_fake.h +++ b/src/main/drivers/pitotmeter/pitotmeter_fake.h @@ -17,4 +17,10 @@ #pragma once +#include "drivers/pitotmeter/pitotmeter.h" + bool fakePitotDetect(pitotDev_t *pitot); +void fakePitotSetAirspeed(float airSpeed); +float fakePitotGetAirspeed(void); +void fakePitotSet(float pressure, float temperature); +bool fakePitotRead(pitotDev_t *pitot); diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index 1d3ab1b584..eb14d6772b 100644 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -21,6 +21,8 @@ #include "platform.h" +#if !defined(SITL_BUILD) + #include "build/debug.h" #include "common/log.h" #include "common/memory.h" @@ -396,3 +398,5 @@ bool pwmMotorAndServoInit(void) return (pwmInitError == PWM_INIT_ERROR_NONE); } + +#endif diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index 658c3f5cb5..beb7b8d178 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -22,6 +22,8 @@ #include "platform.h" +#if !defined(SITL_BUILD) + FILE_COMPILE_FOR_SPEED #include "build/debug.h" @@ -635,3 +637,5 @@ void beeperPwmInit(ioTag_t tag, uint16_t frequency) pwmOutConfigTimer(beeperPwm, tch, PWM_TIMER_HZ, 1000000 / beeperFrequency, (1000000 / beeperFrequency) / 2); } } + +#endif diff --git a/src/main/drivers/rangefinder/rangefinder_vl53l0x.c b/src/main/drivers/rangefinder/rangefinder_vl53l0x.c old mode 100755 new mode 100644 diff --git a/src/main/drivers/rangefinder/rangefinder_vl53l0x.h b/src/main/drivers/rangefinder/rangefinder_vl53l0x.h old mode 100755 new mode 100644 diff --git a/src/main/drivers/serial_tcp.c b/src/main/drivers/serial_tcp.c new file mode 100644 index 0000000000..88480748d4 --- /dev/null +++ b/src/main/drivers/serial_tcp.c @@ -0,0 +1,307 @@ +/* + * This file is part of INAV. + * + * INAV is free software. You can redistribute this software + * and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * INAV is distributed in the hope that they will be + * useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "platform.h" + +#if defined(SITL_BUILD) + +#include +#include + +#include "common/utils.h" + +#include "drivers/serial.h" +#include "drivers/serial_tcp.h" + +static const struct serialPortVTable tcpVTable[]; +static tcpPort_t tcpPorts[SERIAL_PORT_COUNT]; +static bool tcpThreadRunning = false; + +static void *tcpReceiveThread(void* arg) +{ + tcpPort_t *port = (tcpPort_t*)arg; + + while(tcpThreadRunning) { + if (tcpReceive(port) < 0) { + break; + } + } + + return NULL; +} + +static tcpPort_t *tcpReConfigure(tcpPort_t *port, uint32_t id) +{ + if (port->isInitalized){ + return port; + } + + if (pthread_mutex_init(&port->receiveMutex, NULL) != 0){ + return NULL; + } + + port->socketFd = socket(AF_INET, SOCK_STREAM, IPPROTO_TCP); + if (port->socketFd < 0) { + fprintf(stderr, "[SOCKET] Unable to create tcp socket\n"); + return NULL; + } + + int one = 1; + int err = 0; + err = setsockopt(port->socketFd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one)); + err = fcntl(port->socketFd, F_SETFL, fcntl(port->socketFd, F_GETFL, 0) | O_NONBLOCK); + + if (err < 0){ + fprintf(stderr, "[SOCKET] Unable to set socket options\n"); + return NULL; + } + + uint16_t tcpPort = BASE_IP_ADDRESS + id - 1; + port->sockAddress.sin_family = AF_INET; + port->sockAddress.sin_port = htons(tcpPort); + port->sockAddress.sin_addr.s_addr = INADDR_ANY; + port->isClientConnected = false; + port->id = id; + + if (bind(port->socketFd, (struct sockaddr*)&port->sockAddress, sizeof(port->sockAddress)) < 0) { + fprintf(stderr, "[SOCKET] Unable to bind socket\n"); + return NULL; + } + + if (listen(port->socketFd, 100) < 0) { + fprintf(stderr, "[SOCKET] Unable to listen.\n"); + return NULL; + } + + fprintf(stderr, "[SOCKET] Bind TCP port %d to UART%d\n", tcpPort, id); + + return port; +} + +static char *tcpGetAddressString(struct sockaddr *addr) +{ + return inet_ntoa(((struct sockaddr_in *)addr)->sin_addr); +} + +int tcpReceive(tcpPort_t *port) +{ + if (!port->isClientConnected) { + + fd_set fds; + + FD_ZERO(&fds); + FD_SET(port->socketFd, &fds); + + if (select(port->socketFd + 1, &fds, NULL, NULL, NULL) < 0) { + fprintf(stderr, "[SOCKET] Unable to wait for connection.\n"); + return -1; + } + + socklen_t addrLen = sizeof(port->sockAddress); + port->clientSocketFd = accept(port->socketFd, &port->clientAddress, &addrLen); + if (port->clientSocketFd < 1) { + fprintf(stderr, "[SOCKET] Can't accept connection.\n"); + return -1; + } + + fprintf(stderr, "[SOCKET] %s connected to UART%d\n", tcpGetAddressString(&port->clientAddress), port->id); + port->isClientConnected = true; + } + + uint8_t buffer[TCP_BUFFER_SIZE]; + ssize_t recvSize = recv(port->clientSocketFd, buffer, TCP_BUFFER_SIZE, 0); + + // Disconnect + if (port->isClientConnected && recvSize == 0) + { + fprintf(stderr, "[SOCKET] %s disconnected from UART%d\n", tcpGetAddressString(&port->clientAddress), port->id); + close(port->clientSocketFd); + memset(&port->clientAddress, 0, sizeof(port->clientAddress)); + port->isClientConnected = false; + + return 0; + } + + for (ssize_t i = 0; i < recvSize; i++) { + + if (port->serialPort.rxCallback) { + port->serialPort.rxCallback((uint16_t)buffer[i], port->serialPort.rxCallbackData); + } else { + pthread_mutex_lock(&port->receiveMutex); + port->serialPort.rxBuffer[port->serialPort.rxBufferHead] = buffer[i]; + port->serialPort.rxBufferHead = (port->serialPort.rxBufferHead + 1) % port->serialPort.rxBufferSize; + pthread_mutex_unlock(&port->receiveMutex); + } + } + + if (recvSize < 0) { + recvSize = 0; + } + + return (int)recvSize; +} + +serialPort_t *tcpOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, void *rxCallbackData, uint32_t baudRate, portMode_t mode, portOptions_t options) +{ + tcpPort_t *port = NULL; + +#if defined(USE_UART1) || defined(USE_UART2) || defined(USE_UART3) || defined(USE_UART4) || defined(USE_UART5) || defined(USE_UART6) || defined(USE_UART7) || defined(USE_UART8) + uint32_t id = (uintptr_t)USARTx; + if (id < SERIAL_PORT_COUNT) { + port = tcpReConfigure(&tcpPorts[id], id); + } +#endif + + if (port == NULL) { + return NULL; + + } + + port->serialPort.vTable = tcpVTable; + port->serialPort.rxCallback = callback; + port->serialPort.rxCallbackData = rxCallbackData; + port->serialPort.rxBufferHead = port->serialPort.rxBufferTail = 0; + port->serialPort.rxBufferSize = TCP_BUFFER_SIZE; + port->serialPort.rxBuffer = port->rxBuffer; + port->serialPort.mode = mode; + port->serialPort.baudRate = baudRate; + port->serialPort.options = options; + + int err = pthread_create(&port->receiveThread, NULL, tcpReceiveThread, (void*)port); + if (err < 0){ + fprintf(stderr, "[SOCKET] Unable to create receive thread for UART%d\n", id); + return NULL; + } + tcpThreadRunning = true; + + return (serialPort_t*)port; +} + +uint8_t tcpRead(serialPort_t *instance) +{ + uint8_t ch; + tcpPort_t *port = (tcpPort_t*)instance; + pthread_mutex_lock(&port->receiveMutex); + + ch = port->serialPort.rxBuffer[port->serialPort.rxBufferTail]; + port->serialPort.rxBufferTail = (port->serialPort.rxBufferTail + 1) % port->serialPort.rxBufferSize; + + pthread_mutex_unlock(&port->receiveMutex); + + return ch; +} + +void tcpWritBuf(serialPort_t *instance, const void *data, int count) +{ + tcpPort_t *port = (tcpPort_t*)instance; + + if (!port->isClientConnected) { + return; + } + + send(port->clientSocketFd, data, count, 0); +} + +void tcpWrite(serialPort_t *instance, uint8_t ch) +{ + tcpWritBuf(instance, (void*)&ch, 1); +} + +uint32_t tcpTotalRxBytesWaiting(const serialPort_t *instance) +{ + tcpPort_t *port = (tcpPort_t*)instance; + uint32_t count; + + pthread_mutex_lock(&port->receiveMutex); + + if (port->serialPort.rxBufferHead >= port->serialPort.rxBufferTail) { + count = port->serialPort.rxBufferHead - port->serialPort.rxBufferTail; + } else { + count = port->serialPort.rxBufferSize + port->serialPort.rxBufferHead - port->serialPort.rxBufferTail; + } + + pthread_mutex_unlock(&port->receiveMutex); + + return count; +} + +uint32_t tcpTotalTxBytesFree(const serialPort_t *instance) +{ + tcpPort_t *port = (tcpPort_t*)instance; + + if (port->isClientConnected) { + return TCP_MAX_PACKET_SIZE; + } else { + return 0; + } +} + +bool isTcpTransmitBufferEmpty(const serialPort_t *instance) +{ + UNUSED(instance); + + return true; +} + +bool tcpIsConnected(const serialPort_t *instance) +{ + return ((tcpPort_t*)instance)->isClientConnected; +} + +void tcpSetBaudRate(serialPort_t *instance, uint32_t baudRate) +{ + UNUSED(instance); + UNUSED(baudRate); +} + + +void tcpSetMode(serialPort_t *instance, portMode_t mode) +{ + UNUSED(instance); + UNUSED(mode); +} + +static const struct serialPortVTable tcpVTable[] = { + { + .serialWrite = tcpWrite, + .serialTotalRxWaiting = tcpTotalRxBytesWaiting, + .serialTotalTxFree = tcpTotalTxBytesFree, + .serialRead = tcpRead, + .serialSetBaudRate = tcpSetBaudRate, + .isSerialTransmitBufferEmpty = isTcpTransmitBufferEmpty, + .setMode = tcpSetMode, + .isConnected = tcpIsConnected, + .writeBuf = tcpWritBuf, + .beginWrite = NULL, + .endWrite = NULL, + .isIdle = NULL, + } +}; + +#endif diff --git a/src/main/drivers/serial_tcp.h b/src/main/drivers/serial_tcp.h new file mode 100644 index 0000000000..a73e797379 --- /dev/null +++ b/src/main/drivers/serial_tcp.h @@ -0,0 +1,51 @@ +/* + * This file is part of INAV. + * + * INAV is free software. You can redistribute this software + * and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * INAV is distributed in the hope that they will be + * useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#pragma once + +#include +#include + +#define BASE_IP_ADDRESS 5760 +#define TCP_BUFFER_SIZE 2048 +#define TCP_MAX_PACKET_SIZE 65535 + +typedef struct +{ + serialPort_t serialPort; + + uint8_t rxBuffer[TCP_BUFFER_SIZE]; + + uint8_t id; + bool isInitalized; + pthread_mutex_t receiveMutex; + pthread_t receiveThread; + int socketFd; + int clientSocketFd; + struct sockaddr_in sockAddress; + struct sockaddr clientAddress; + bool isClientConnected; +} tcpPort_t; + + +serialPort_t *tcpOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, void *rxCallbackData, uint32_t baudRate, portMode_t mode, portOptions_t options); + +void tcpSend(tcpPort_t *port); +int tcpReceive(tcpPort_t *port); diff --git a/src/main/drivers/sound_beeper.c b/src/main/drivers/sound_beeper.c index bb089b4cb9..6577b26d5a 100644 --- a/src/main/drivers/sound_beeper.c +++ b/src/main/drivers/sound_beeper.c @@ -47,7 +47,7 @@ void systemBeep(bool onoff) #else #ifdef USE_SIMULATOR - if (ARMING_FLAG(SIMULATOR_MODE)) { + if (ARMING_FLAG(SIMULATOR_MODE_HITL)) { if (SIMULATOR_HAS_OPTION(HITL_MUTE_BEEPER)) { onoff = false; } diff --git a/src/main/drivers/stack_check.c b/src/main/drivers/stack_check.c index bf4a561ddc..f86d82d38e 100644 --- a/src/main/drivers/stack_check.c +++ b/src/main/drivers/stack_check.c @@ -77,6 +77,8 @@ uint32_t stackUsedSize(void) } #endif +#if !defined(SITL_BUILD) + uint32_t stackTotalSize(void) { return (uint32_t)&_Min_Stack_Size; @@ -86,3 +88,5 @@ uint32_t stackHighMem(void) { return (uint32_t)&_estack; } + +#endif diff --git a/src/main/drivers/stack_check.h b/src/main/drivers/stack_check.h old mode 100755 new mode 100644 diff --git a/src/main/drivers/timer.c b/src/main/drivers/timer.c old mode 100755 new mode 100644 diff --git a/src/main/drivers/timer.h b/src/main/drivers/timer.h index d1cc3cc16e..9f2612e72a 100644 --- a/src/main/drivers/timer.h +++ b/src/main/drivers/timer.h @@ -39,6 +39,11 @@ typedef uint32_t timCCR_t; typedef uint32_t timCCER_t; typedef uint32_t timSR_t; typedef uint32_t timCNT_t; +#elif defined(SITL_BUILD) +typedef uint32_t timCCR_t; +typedef uint32_t timCCER_t; +typedef uint32_t timSR_t; +typedef uint32_t timCNT_t; #else #error "Unknown CPU defined" #endif @@ -49,6 +54,8 @@ typedef uint32_t timCNT_t; #define HARDWARE_TIMER_DEFINITION_COUNT 14 #elif defined(STM32H7) #define HARDWARE_TIMER_DEFINITION_COUNT 14 +#elif defined(SITL_BUILD) +#define HARDWARE_TIMER_DEFINITION_COUNT 0 #else #error "Unknown CPU defined" #endif diff --git a/src/main/drivers/timer_def.h b/src/main/drivers/timer_def.h index e8c8afad27..7fcb152610 100644 --- a/src/main/drivers/timer_def.h +++ b/src/main/drivers/timer_def.h @@ -82,6 +82,7 @@ #include "timer_def_stm32f7xx.h" #elif defined(STM32H7) #include "timer_def_stm32h7xx.h" +#elif defined(SITL_BUILD) #else #error "Unknown CPU defined" #endif diff --git a/src/main/drivers/usb_msc.c b/src/main/drivers/usb_msc.c index 3b3904dd91..7004e7efde 100644 --- a/src/main/drivers/usb_msc.c +++ b/src/main/drivers/usb_msc.c @@ -21,7 +21,11 @@ #include "drivers/persistent.h" #include +#ifdef USE_USB_MSC + bool mscCheckBoot(void) { return (persistentObjectRead(PERSISTENT_OBJECT_RESET_REASON) == RESET_MSC_REQUEST); } + +#endif \ No newline at end of file diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index 6dd129b5c3..3133a8e87f 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -3296,6 +3296,7 @@ static void cliStatus(char *cmdline) } cliPrintLinefeed(); +#if !defined(SITL_BUILD) cliPrintLine("STM32 system clocks:"); #if defined(USE_HAL_DRIVER) cliPrintLinef(" SYSCLK = %d MHz", HAL_RCC_GetSysClockFreq() / 1000000); @@ -3309,6 +3310,7 @@ static void cliStatus(char *cmdline) cliPrintLinef(" HCLK = %d MHz", clocks.HCLK_Frequency / 1000000); cliPrintLinef(" PCLK1 = %d MHz", clocks.PCLK1_Frequency / 1000000); cliPrintLinef(" PCLK2 = %d MHz", clocks.PCLK2_Frequency / 1000000); +#endif #endif cliPrintLinef("Sensor status: GYRO=%s, ACC=%s, MAG=%s, BARO=%s, RANGEFINDER=%s, OPFLOW=%s, GPS=%s", @@ -3338,18 +3340,19 @@ static void cliStatus(char *cmdline) #endif #ifdef USE_I2C const uint16_t i2cErrorCounter = i2cGetErrorCounter(); -#else +#elif !defined(SITL_BUILD) const uint16_t i2cErrorCounter = 0; #endif #ifdef STACK_CHECK cliPrintf("Stack used: %d, ", stackUsedSize()); #endif +#if !defined(SITL_BUILD) cliPrintLinef("Stack size: %d, Stack address: 0x%x, Heap available: %d", stackTotalSize(), stackHighMem(), memGetAvailableBytes()); cliPrintLinef("I2C Errors: %d, config size: %d, max available config: %d", i2cErrorCounter, getEEPROMConfigSize(), &__config_end - &__config_start); - -#ifdef USE_ADC +#endif +#if defined(USE_ADC) && !defined(SITL_BUILD) static char * adcFunctions[] = { "BATTERY", "RSSI", "CURRENT", "AIRSPEED" }; cliPrintLine("ADC channel usage:"); for (int i = 0; i < ADC_FUNCTION_COUNT; i++) { @@ -3492,7 +3495,7 @@ static void cliResource(char *cmdline) { UNUSED(cmdline); cliPrintLinef("IO:\r\n----------------------"); - for (unsigned i = 0; i < DEFIO_IO_USED_COUNT; i++) { + for (int i = 0; i < DEFIO_IO_USED_COUNT; i++) { const char* owner; owner = ownerNames[ioRecs[i].owner]; diff --git a/src/main/fc/config.c b/src/main/fc/config.c index b8f665598d..3d6157f4f4 100755 --- a/src/main/fc/config.c +++ b/src/main/fc/config.c @@ -152,12 +152,16 @@ void validateNavConfig(void) // Stubs to handle target-specific configs __attribute__((weak)) void validateAndFixTargetConfig(void) { +#if !defined(SITL_BUILD) __NOP(); +#endif } __attribute__((weak)) void targetConfiguration(void) { +#if !defined(SITL_BUILD) __NOP(); +#endif } diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index b79e97c396..f0dc83bdf6 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -860,6 +860,7 @@ static float calculateThrottleTiltCompensationFactor(uint8_t throttleTiltCompens void taskMainPidLoop(timeUs_t currentTimeUs) { + cycleTime = getTaskDeltaTime(TASK_SELF); dT = (float)cycleTime * 0.000001f; @@ -872,11 +873,19 @@ void taskMainPidLoop(timeUs_t currentTimeUs) armTime = 0; } +#if defined(SITL_BUILD) + if (lockMainPID()) { +#endif + gyroFilter(); imuUpdateAccelerometer(); imuUpdateAttitude(currentTimeUs); +#if defined(SITL_BUILD) + } +#endif + processPilotAndFailSafeActions(dT); updateArmingStatus(); @@ -932,8 +941,8 @@ void taskMainPidLoop(timeUs_t currentTimeUs) //Servos should be filtered or written only when mixer is using servos or special feaures are enabled -#ifdef USE_SMULATOR - if (!ARMING_FLAG(SIMULATOR_MODE)) { +#ifdef USE_SIMULATOR + if (!ARMING_FLAG(SIMULATOR_MODE_HITL)) { if (isServoOutputEnabled()) { writeServos(); } diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c index a8ab8146d2..8153a9ff9c 100644 --- a/src/main/fc/fc_init.c +++ b/src/main/fc/fc_init.c @@ -199,7 +199,9 @@ void init(void) // Initialize system and CPU clocks to their initial values systemInit(); +#if !defined(SITL_BUILD) __enable_irq(); +#endif // initialize IO (needed for all IO operations) IOInitGlobal(); @@ -246,8 +248,9 @@ void init(void) latchActiveFeatures(); ledInit(false); - +#if !defined(SITL_BUILD) EXTIInit(); +#endif #ifdef USE_SPEKTRUM_BIND if (rxConfig()->receiverType == RX_TYPE_SERIAL) { @@ -309,7 +312,7 @@ void init(void) if (!STATE(ALTITUDE_CONTROL)) { featureClear(FEATURE_AIRMODE); } - +#if !defined(SITL_BUILD) // Initialize motor and servo outpus if (pwmMotorAndServoInit()) { DISABLE_ARMING_FLAG(ARMING_DISABLED_PWM_OUTPUT_ERROR); @@ -317,7 +320,9 @@ void init(void) else { ENABLE_ARMING_FLAG(ARMING_DISABLED_PWM_OUTPUT_ERROR); } - +#else + DISABLE_ARMING_FLAG(ARMING_DISABLED_PWM_OUTPUT_ERROR); +#endif systemState |= SYSTEM_STATE_MOTORS_READY; #ifdef USE_ESC_SENSOR @@ -700,8 +705,10 @@ void init(void) powerLimiterInit(); #endif +#if !defined(SITL_BUILD) // Considering that the persistent reset reason is only used during init persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_NONE); +#endif systemState |= SYSTEM_STATE_READY; } diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 524fc6319b..a29cfa6016 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -46,6 +46,11 @@ #include "drivers/compass/compass_msp.h" #include "drivers/barometer/barometer_msp.h" #include "drivers/pitotmeter/pitotmeter_msp.h" +#include "drivers/accgyro/accgyro_fake.h" +#include "drivers/barometer/barometer_fake.h" +#include "drivers/compass/compass_fake.h" +#include "sensors/battery_sensor_fake.h" +#include "drivers/pitotmeter/pitotmeter_fake.h" #include "drivers/bus_i2c.h" #include "drivers/display.h" #include "drivers/flash.h" @@ -1368,6 +1373,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF break; case MSP_VTX_CONFIG: +#ifdef USE_VTX_CONTROL { vtxDevice_t *vtxDevice = vtxCommonDevice(); if (vtxDevice) { @@ -1394,6 +1400,9 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU8(dst, VTXDEV_UNKNOWN); // no VTX configured } } +#else + sbufWriteU8(dst, VTXDEV_UNKNOWN); // no VTX configured +#endif break; case MSP_NAME: @@ -2419,6 +2428,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) break; #endif // USE_OSD +#ifdef USE_VTX_CONTROL case MSP_SET_VTX_CONFIG: if (dataSize >= 2) { vtxDevice_t *vtxDevice = vtxCommonDevice(); @@ -2452,6 +2462,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) return MSP_RESULT_ERROR; } break; +#endif #ifdef USE_FLASHFS case MSP_DATAFLASH_ERASE: @@ -3394,8 +3405,8 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu if (!SIMULATOR_HAS_OPTION(HITL_ENABLE)) { - if (ARMING_FLAG(SIMULATOR_MODE)) { // Just once - DISABLE_ARMING_FLAG(SIMULATOR_MODE); + if (ARMING_FLAG(SIMULATOR_MODE_HITL)) { // Just once + DISABLE_ARMING_FLAG(SIMULATOR_MODE_HITL); #ifdef USE_BARO baroStartCalibration(); @@ -3408,9 +3419,9 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu // Review: Many states were affected. Reboot? disarm(DISARM_SWITCH); // Disarm to prevent motor output!!! - } + } } else if (!areSensorsCalibrating()) { - if (!ARMING_FLAG(SIMULATOR_MODE)) { // Just once + if (!ARMING_FLAG(SIMULATOR_MODE_HITL)) { // Just once #ifdef USE_BARO baroStartCalibration(); #endif @@ -3425,7 +3436,7 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu mag.magADC[Z] = 0; } #endif - ENABLE_ARMING_FLAG(SIMULATOR_MODE); + ENABLE_ARMING_FLAG(SIMULATOR_MODE_HITL); LOG_DEBUG(SYSTEM, "Simulator enabled"); } @@ -3502,9 +3513,9 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu } if (SIMULATOR_HAS_OPTION(HITL_EXT_BATTERY_VOLTAGE)) { - simulatorData.vbat = sbufReadU8(src); + fakeBattSensorSetVbat(sbufReadU8(src) * 10); } else { - simulatorData.vbat = (uint8_t)(SIMULATOR_FULL_BATTERY * 10.0f); + fakeBattSensorSetVbat((uint16_t)(SIMULATOR_FULL_BATTERY * 10.0f)); } if (SIMULATOR_HAS_OPTION(HITL_AIRSPEED)) { diff --git a/src/main/fc/fc_tasks.c b/src/main/fc/fc_tasks.c index 0e0b8c5432..1830c49e79 100755 --- a/src/main/fc/fc_tasks.c +++ b/src/main/fc/fc_tasks.c @@ -306,7 +306,7 @@ void taskUpdateAux(timeUs_t currentTimeUs) updatePIDCoefficients(); dynamicLpfGyroTask(); #ifdef USE_SIMULATOR - if (!ARMING_FLAG(SIMULATOR_MODE)) { + if (!ARMING_FLAG(SIMULATOR_MODE_HITL)) { updateFixedWingLevelTrim(currentTimeUs); } #else diff --git a/src/main/fc/runtime_config.h b/src/main/fc/runtime_config.h index 9333fd62c1..a4e613ed72 100644 --- a/src/main/fc/runtime_config.h +++ b/src/main/fc/runtime_config.h @@ -21,7 +21,8 @@ typedef enum { ARMED = (1 << 2), WAS_EVER_ARMED = (1 << 3), - SIMULATOR_MODE = (1 << 4), + SIMULATOR_MODE_HITL = (1 << 4), + SIMULATOR_MODE_SITL = (1 << 5), ARMING_DISABLED_FAILSAFE_SYSTEM = (1 << 7), ARMING_DISABLED_NOT_LEVEL = (1 << 8), diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index b3c5c1f7bc..74c30e2da1 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -35,16 +35,16 @@ tables: - name: failsafe_procedure values: ["LAND", "DROP", "RTH", "NONE"] - name: current_sensor - values: ["NONE", "ADC", "VIRTUAL", "ESC"] + values: ["NONE", "ADC", "VIRTUAL", "FAKE", "ESC"] enum: currentSensor_e - name: voltage_sensor - values: ["NONE", "ADC", "ESC"] + values: ["NONE", "ADC", "ESC", "FAKE"] enum: voltageSensor_e - name: imu_inertia_comp_method values: ["VELNED", "TURNRATE","ADAPTIVE"] enum: imu_inertia_comp_method_e - name: gps_provider - values: ["NMEA", "UBLOX", "UBLOX7", "MSP"] + values: ["NMEA", "UBLOX", "UBLOX7", "MSP", "FAKE"] enum: gpsProvider_e - name: gps_sbas_mode values: ["AUTO", "EGNOS", "WAAS", "MSAS", "GAGAN", "NONE"] diff --git a/src/main/fc/settings_generated.c b/src/main/fc/settings_generated.c new file mode 100644 index 0000000000..da2700a955 --- /dev/null +++ b/src/main/fc/settings_generated.c @@ -0,0 +1,1697 @@ +// This file has been automatically generated by utils/settings.rb +// Don't make any modifications to it. They will be lost. + +#include "platform.h" +#include "config/parameter_group_ids.h" +#include "fc/settings.h" +#include "sensors/gyro.h" +#include "fc/config.h" +#include "sensors/acceleration.h" +#include "sensors/rangefinder.h" +#include "sensors/opflow.h" +#include "sensors/compass.h" +#include "sensors/barometer.h" +#include "sensors/pitotmeter.h" +#include "rx/rx.h" +#include "rx/spektrum.h" +#include "blackbox/blackbox.h" +#include "flight/mixer.h" +#include "flight/failsafe.h" +#include "sensors/boardalignment.h" +#include "sensors/battery_config_structs.h" +#include "sensors/battery_config_structs.h" +#include "flight/servos.h" +#include "fc/controlrate_profile_config_struct.h" +#include "io/serial.h" +#include "flight/imu.h" +#include "config/general_settings.h" +#include "fc/rc_controls.h" +#include "flight/pid.h" +#include "navigation/navigation.h" +#include "io/osd.h" +#include "drivers/osd.h" +#include "io/osd_common.h" +#include "fc/config.h" +#include "fc/rc_modes.h" +#include "fc/stats.h" +#include "common/time.h" +#include "drivers/display.h" +#include "common/log.h" +#include "io/smartport_master.h" +#include "io/osd_dji_hd.h" +#include "fc/config.h" +#include "flight/power_limits.h" +#pragma GCC diagnostic ignored "-Wunused-const-variable" +const pgn_t settingsPgn[] = { + PG_GYRO_CONFIG, + PG_ADC_CHANNEL_CONFIG, + PG_ACCELEROMETER_CONFIG, + PG_RANGEFINDER_CONFIG, + PG_OPFLOW_CONFIG, + PG_COMPASS_CONFIG, + PG_BAROMETER_CONFIG, + PG_PITOTMETER_CONFIG, + PG_RX_CONFIG, + PG_BLACKBOX_CONFIG, + PG_MOTOR_CONFIG, + PG_FAILSAFE_CONFIG, + PG_BOARD_ALIGNMENT, + PG_BATTERY_METERS_CONFIG, + PG_BATTERY_PROFILES, + PG_MIXER_CONFIG, + PG_REVERSIBLE_MOTORS_CONFIG, + PG_SERVO_CONFIG, + PG_CONTROL_RATE_PROFILES, + PG_SERIAL_CONFIG, + PG_IMU_CONFIG, + PG_ARMING_CONFIG, + PG_GENERAL_SETTINGS, + PG_GPS_CONFIG, + PG_RC_CONTROLS_CONFIG, + PG_PID_PROFILE, + PG_PID_AUTOTUNE_CONFIG, + PG_POSITION_ESTIMATION_CONFIG, + PG_NAV_CONFIG, + PG_OSD_CONFIG, + PG_OSD_COMMON_CONFIG, + PG_SYSTEM_CONFIG, + PG_MODE_ACTIVATION_OPERATOR_CONFIG, + PG_STATS_CONFIG, + PG_TIME_CONFIG, + PG_DISPLAY_CONFIG, + PG_LOG_CONFIG, + PG_SMARTPORT_MASTER_CONFIG, + PG_DJI_OSD_CONFIG, + PG_BEEPER_CONFIG, + PG_POWER_LIMITS_CONFIG, +}; +const uint8_t settingsPgnCounts[] = { + 16, + 4, + 11, + 2, + 3, + 13, + 2, + 3, + 18, + 3, + 5, + 12, + 3, + 10, + 28, + 5, + 3, + 7, + 22, + 1, + 9, + 4, + 1, + 7, + 8, + 90, + 3, + 23, + 89, + 84, + 1, + 3, + 1, + 4, + 2, + 1, + 2, + 2, + 7, + 3, + 3, +}; +static const uint8_t settingNamesWords[] = { + 0x70,0x6c, /* "nav" */ + 0x3,0x5c, /* "fw" */ + 0xf,0x99, /* "osd" */ + 0x0,0xd1, /* "mc" */ + 0x82,0x41,0xa1, /* "rate" */ + 0x40,0xd0,0xe0, /* "max" */ + 0x10, /* "p" */ + 0x6,0x43,0x70, /* "yaw" */ + 0x25,0xc1,0xb0, /* "inav" */ + 0x1a,0x97, /* "min" */ + 0x2,0x9,0xa0,0xd0, /* "pitch" */ + 0x0,0xb0,0x32,0x68, /* "alarm" */ + 0x18,0x96,0xa6,0x80, /* "limit" */ + 0x64,0xc, /* "lpf" */ + 0xd, /* "z" */ + 0x1,0x81,0xab,0x86,0x80, /* "launch" */ + 0x10, /* "d" */ + 0x12,0x7b,0x18, /* "roll" */ + 0x3,0x5,0x2c,0x98,0x4c,0x50, /* "failsafe" */ + 0x1e,0x13, /* "gps" */ + 0x2,0x34, /* "hz" */ + 0x4, /* "i" */ + 0x82,0xf,0x98, /* "pos" */ + 0x2,0xe3,0xb0,0xa0, /* "angle" */ + 0xa2,0x5a,0x50, /* "time" */ + 0x5c, /* "w" */ + 0x18,0xc8, /* "xy" */ + 0x25,0x44, /* "rth" */ + 0x0,0x85,0x9,0x4,0x17,0x10, /* "deadband" */ + 0x7,0xcc,0x9e, /* "gyro" */ + 0x9,0xdd,0x34,0x1a, /* "switch" */ + 0x1,0x4c,0xc0,0xa0, /* "type" */ + 0x21,0x58,0x1c, /* "delay" */ + 0x81,0x2d,0xa8, /* "imu" */ + 0x1a,0x13, /* "mag" */ + 0x82,0x53,0x9a, /* "rssi" */ + 0x41,0x38,0x14,0xa4, /* "speed" */ + 0x5,0x11,0x27,0xd2,0x8c,0x28, /* "throttle" */ + 0x2,0x31, /* "acc" */ + 0x80,0x28,0x48, /* "ahi" */ + 0x2,0xc4,0x9d,0xc0, /* "align" */ + 0x1a,0x2,0xe7,0x15,0x80, /* "channel" */ + 0x1d,0x65,0x22,0xba,0x80, /* "current" */ + 0x61,0x6c,0x56, /* "level" */ + 0x2,0x88,0x90, /* "thr" */ + 0x3,0x5a,0x3c, /* "auto" */ + 0x9,0x71,0x12,0x30,0xd1,0xf2, /* "indicator" */ + 0x3,0x42,0xea,0x85,0x80, /* "manual" */ + 0x6b,0xc8,0x50, /* "mode" */ + 0x4c,0xb2,0xb3, /* "servo" */ + 0xc1,0x42,0xb6,0x0, /* "temp" */ + 0xb0, /* "v" */ + 0x2,0xca,0x26,0x95,0x21, /* "altitude" */ + 0x40,0x20,0xc9,0xe0, /* "baro" */ + 0x14,0x82,0xb4,0xb8,0xe0, /* "braking" */ + 0x2e,0x20,0xf0, /* "expo" */ + 0x20,0x32,0x25,0xc3,0x22, /* "hardware" */ + 0x81,0xaf,0xa3,0xe4, /* "motor" */ + 0x9,0xc, /* "rc" */ + 0x14,0x44,0x8b,0x34,0x3d,0x84, /* "threshold" */ + 0x5,0x84,0x1a, /* "vbat" */ + 0x2,0xc5,0x60, /* "vel" */ + 0x2c,0xf6,0x50,0x27,0x28, /* "voltage" */ + 0x5,0x59,0x4e,0x80, /* "burst" */ + 0x22,0x67,0x40,0xb8,0x65, /* "distance" */ + 0x1,0x32,0xe0,0xb5,0x23,0x98, /* "dynamics" */ + 0x11,0x52, /* "hud" */ + 0x1,0x81,0x71, /* "land" */ + 0x0,0xf3,0x1a,0x65,0xa0, /* "offset" */ + 0x20,0xfb,0x96,0x40, /* "power" */ + 0x9d,0x3,0x49, /* "stats" */ + 0x82,0xb3,0x28, /* "use" */ + 0x2f,0x0, /* "wp" */ + 0x5,0x94, /* "alt" */ + 0x0,0x9e,0xf9,0xd0, /* "boost" */ + 0x3,0x62,0x5a,0x20, /* "climb" */ + 0xd,0xee,0xa4,0x9e,0xc0, /* "control" */ + 0x11,0x49, /* "dji" */ + 0x1,0x32,0xe0, /* "dyn" */ + 0x19,0x2c,0xa1,0x64, /* "filter" */ + 0x7,0x5,0xa5, /* "name" */ + 0x4,0xc6,0x16,0x14, /* "scale" */ + 0x13,0x49,0xa,0x20,0xc8, /* "sidebar" */ + 0x13,0x7d,0x64,0x32, /* "source" */ + 0x82,0x89,0x69,0x5f,0x5a, /* "timeout" */ + 0x3,0x0, /* "x" */ + 0xc8, /* "y" */ + 0x34,0x59,0x3c, /* "zero" */ + 0x1b,0x20, /* "3d" */ + 0x2,0x41, /* "adc" */ + 0x80,0x29,0x94,0xe0,0x52,0x90, /* "airspeed" */ + 0x2,0xd,0x28,0x59,0x64, /* "battery" */ + 0x3,0xb,0x4b,0x20, /* "camera" */ + 0x80,0x61,0x80,0x46,0x9a,0x64, /* "capacity" */ + 0x3,0x20, /* "cd" */ + 0x6,0x56,0x30, /* "cell" */ + 0x3,0x2b,0xa8,0x59, /* "center" */ + 0x0,0x6f,0x6c, /* "comp" */ + 0x0,0x39,0x55,0x33,0x28, /* "cruise" */ + 0x7,0x5a,0x3c,0xc6, /* "cutoff" */ + 0x1,0x6,0xd0, /* "dcm" */ + 0x11,0x33,0xc,0x9a, /* "disarm" */ + 0x2,0x50,0xb2,0x68, /* "dterm" */ + 0xa,0xe2, /* "end" */ + 0x0,0xb3,0x18, /* "esc" */ + 0xc,0x60, /* "ff" */ + 0x24,0x8c,0x28, /* "idle" */ + 0x13,0x42,0xc9,0xa0, /* "iterm" */ + 0x69,0x68,0x59, /* "meter" */ + 0x2,0x17,0x68, /* "pwm" */ + 0x2a,0xe4,0xd0, /* "unit" */ + 0x1,0x18,0xca,0xc0, /* "accel" */ + 0x4,0x63,0x38,0x52,0xe0, /* "accgain" */ + 0x4,0x63,0xd1,0x64,0xf0, /* "acczero" */ + 0x5,0xd4,0x49,0xe4,0x1b,0x26,0x99, /* "antigravity" */ + 0x0,0x6b,0x47,0xd2,0xae,0x28, /* "autotune" */ + 0x4,0x17,0x2c, /* "bank" */ + 0x2,0x29,0x60,0x59, /* "beeper" */ + 0x0,0x4c,0x8,0xd6,0x27,0xe0, /* "blackbox" */ + 0x2,0x78,0x64,0x40, /* "board" */ + 0xc,0x2c, /* "cal" */ + 0x1,0x4,0xd0, /* "dbm" */ + 0x10,0xb4,0x28,0xe8, /* "detect" */ + 0x2,0xb8,0xb2,0x3e, /* "energy" */ + 0x40,0x82,0x1c, /* "hdg" */ + 0x8,0x28,0x48,0x97,0x1c, /* "heading" */ + 0x8,0x7b,0x8, /* "hold" */ + 0x4,0xba,0xc5,0x95,0xa,0x40, /* "inverted" */ + 0x30,0x2e,0x22,0x5c,0x70, /* "landing" */ + 0x34,0x27,0x38,0x52,0xe0, /* "maggain" */ + 0x34,0x27,0xd1,0x64,0xf0, /* "magzero" */ + 0x34,0x29,0x70, /* "main" */ + 0x1a,0x19,0x1d,0x2e, /* "margin" */ + 0x3,0xe0,0x66,0x3e,0xe0, /* "opflow" */ + 0x82,0x68,0x34,0x72,0x88,0x90, /* "pitch2thr" */ + 0x20,0x9a,0x3e,0x80, /* "pitot" */ + 0x84,0x8a,0x44,0x8e,0x8f,0x90, /* "predictor" */ + 0x26,0x39,0x3d,0x8c, /* "scroll" */ + 0x4,0xca,0xe9,0xa6,0x89,0xb2,0x69,0x90, /* "sensitivity" */ + 0x4c,0xb2,0x48,0x59,0x2c, /* "serialrx" */ + 0x2,0x6c,0x7d,0xc8,0xfb,0xb8, /* "slowdown" */ + 0x13,0x6a,0x68,0x80, /* "smith" */ + 0x4e,0xb2,0x30,0x46,0x50, /* "surface" */ + 0x51,0xf4,0xb, /* "total" */ + 0x1,0x48,0x4, /* "tpa" */ + 0x17,0x2a,0x4e,0x8a, /* "weight" */ + 0x0,0x22,0x7c,0xa8, /* "abort" */ + 0x0,0xa6,0x4d,0x79,0xa, /* "airmode" */ + 0x1,0x6,0x80, /* "bat" */ + 0x10,0x6a,0x40, /* "baud" */ + 0xd,0x5,0x1a, /* "check" */ + 0xc0,0x37,0xba,0x80, /* "cont" */ + 0x1b,0xe5,0x22,0x8e,0x89,0x7b, /* "correction" */ + 0x80,0x44,0xc8,0xa3,0xa2,0x5e,0xe0, /* "direction" */ + 0x11,0x33,0x80, /* "disp" */ + 0x8,0x99,0xd0, /* "dist" */ + 0x4,0x4d,0x8a, /* "dive" */ + 0x2,0x4d,0xf,0xa0, /* "dshot" */ + 0xb,0xb, /* "epv" */ + 0x0,0xc1,0x1d,0x1f,0x20, /* "factor" */ + 0x18,0x2c,0x61,0x1f,0x77, /* "falldown" */ + 0x0,0xc9,0x94,0xe8, /* "first" */ + 0x3,0x31,0xf7, /* "flow" */ + 0x1,0x9f,0x60, /* "fov" */ + 0x1c,0x29,0x70, /* "gain" */ + 0xf,0x20,0xd9,0x34,0xc8, /* "gravity" */ + 0x10, /* "h" */ + 0x4,0x5,0x86,0x25,0x60,0xc2,0xe0, /* "halfduplex" */ + 0x8,0x2a,0x4e,0x8a, /* "height" */ + 0x1,0xf,0x69, /* "home" */ + 0x40,0x93,0xb9,0xf2,0x28, /* "ignore" */ + 0x12,0xe1,0xb1,0x2e,0xd,0x12,0xf7, /* "inclination" */ + 0x1,0x2e,0xa1,0x65,0x60,0xb0, /* "interval" */ + 0xb,0x48, /* "ki" */ + 0x17,0x0, /* "kp" */ + 0x31,0xe7, /* "log" */ + 0x3,0x1e,0x9a,0x16,0x40, /* "loiter" */ + 0x63,0xee, /* "low" */ + 0x6,0x40,0xdc, /* "lpf2" */ + 0x3,0x43,0x3a,0x16,0x40, /* "master" */ + 0x68,0x70,0x16,0x50, /* "maxalt" */ + 0xd,0x4b,0x82,0xca, /* "minalt" */ + 0x1,0xa9,0x9c,0xd2,0xf7, /* "mission" */ + 0x1,0xaf,0x21,0x58, /* "model" */ + 0x7,0x3e,0x83,0x40, /* "notch" */ + 0x1e,0xe2, /* "one" */ + 0x82,0x1,0x70, /* "pan" */ + 0x20,0x90, /* "pi" */ + 0x41,0x24,0x9d,0x5a, /* "pidsum" */ + 0x8,0x49,0xe3,0x29,0x2b,0x22, /* "procedure" */ + 0x82,0x12,0x7d,0x1e,0x37,0xb0, /* "protocol" */ + 0x10,0x93,0xec,0x92,0x16,0x40, /* "provider" */ + 0x90,0x48,0x9a,0xcc, /* "radius" */ + 0x12,0xb,0x8e,0x53,0x25,0xc4,0x2c, /* "rangefinder" */ + 0x81,0x22,0xb0,0x38, /* "relax" */ + 0x4,0x8b,0x30, /* "res" */ + 0x48,0xb3,0x2d, /* "reset" */ + 0x1,0x2c, /* "rx" */ + 0x2,0x61,0x31,0x50,0xf6,0x94, /* "safehome" */ + 0x13,0x68,0x65,0x48,0x3e,0x54, /* "smartport" */ + 0x4,0xda,0xf7,0xd1,0x9,0x71, /* "smoothing" */ + 0xc1,0x39,0x61,0x9c, /* "srxl2" */ + 0x4,0xe8,0x91,0xac, /* "stick" */ + 0x13,0xa6,0x58,0x50, /* "style" */ + 0x51,0x12,0x29, /* "three" */ + 0x41,0x44,0x49,0xf7, /* "throw" */ + 0x5,0x1e,0xc2,0xc8,0x2e,0x19, /* "tolerance" */ + 0x41,0x49,0x4,0x6b,0x10,0x46,0xb0, /* "trackback" */ + 0x52,0xef, /* "two" */ + 0x5,0x34, /* "tz" */ + 0xa,0xc2,0x89,0x65, /* "uptilt" */ + 0x1,0x59,0x94,0x60, /* "usec" */ + 0xb4,0xe0,0x40, /* "vspd" */ + 0x5c,0x32,0x72,0x5c,0x70, /* "warning" */ + 0x4,0x63,0x2b,0xb,0x20,0xd1,0xf2, /* "accelerator" */ + 0x0,0x48,0xaa,0xce,0x8d,0x2b,0xa8, /* "adjustment" */ + 0x0,0x91,0x55,0x9d,0x1a,0x57,0x52,0x60, /* "adjustments" */ + 0xb,0x18,0xfb, /* "allow" */ + 0x80,0x30,0x83,0x12,0x52, /* "applied" */ + 0x0,0x32,0x93,0xef,0x30, /* "arrows" */ + 0x6,0x94,0x70, /* "attn" */ + 0x3,0x5a,0x3d,0xa1,0xa2,0x46, /* "automatic" */ + 0x0,0xd6,0x8f,0xa4,0x92,0xd0, /* "autotrim" */ + 0x9,0x21,0x98, /* "bias" */ + 0x4,0xf9,0x10,0xb2,0x29, /* "bordered" */ + 0x0,0x29,0x14,0x2b,0x83,0xd2,0xea, /* "breakpoint" */ + 0x0,0x61,0x62,0x45,0x20,0xd1,0x2f,0x70, /* "calibration" */ + 0x6,0x56,0x32,0x60, /* "cells" */ + 0x1a,0x3,0x20,0x8e,0x85,0x90, /* "character" */ + 0x6,0xd9,0xcc, /* "cmss" */ + 0x3,0x7b,0x5a,0x17,0x10, /* "command" */ + 0x3,0x7b,0x8c,0x93, /* "config" */ + 0x80,0x6f,0x74,0xe8,0x17,0x50, /* "constant" */ + 0x3,0x7b,0xa9,0x27,0xb2,0x41,0xa1, /* "controlrate" */ + 0x40,0x37,0xbe,0x44,0x4b,0x83,0x42, /* "coordinate" */ + 0x80,0x72,0x4d,0x12,0x30,0xb0, /* "critical" */ + 0x3,0x93,0xe7,0x34,0x5,0x32,0x98, /* "crosshairs" */ + 0x7,0x59,0x58,0xa0, /* "curve" */ + 0x27,0x44,0xf7,0xce,0x9d,0x3e,0x64,0xfe,0x90,0xac,0xa0,0x7a,0xc8,0x1b,0xa8,0xd0, /* "d_boost_gyro_delta_lpf_hz" */ + 0x9,0xd1,0x3d,0xf3,0xa7,0x5a,0x1c,0x74,0x34,0xe8,0x46,0x32,0xb0,0xb2,0xd,0x12,0xf7, /* "d_boost_max_at_acceleration" */ + 0x0,0x85,0x15,0x4e, /* "debug" */ + 0x2,0x14,0x65,0x61,0x64,0x1a,0x25,0xee, /* "deceleration" */ + 0x1,0xa,0x34,0xb4,0x2c,0x98, /* "decimals" */ + 0x8,0x51,0xb0, /* "decl" */ + 0x4,0x28,0xd8,0x97,0x6,0x89,0x7b, /* "declination" */ + 0x80,0x42,0x98,0x35,0x65,0x26, /* "defaults" */ + 0x2,0x14,0xcc,0x28,0xe8,0x97,0xb8, /* "deflection" */ + 0x4,0x29,0xe4,0x52,0xcc, /* "degrees" */ + 0x4,0x2b,0x9e,0xd0, /* "denom" */ + 0x10,0xb6,0x48,0xca, /* "device" */ + 0x2,0x24,0xe9,0xa4, /* "digits" */ + 0xc0,0x44,0xcc,0xae,0x38,0x4e,0x50, /* "disengage" */ + 0x11,0x33,0x83,0x3,0x9e,0x99,0xf2,0x19,0x7b,0x3b,0xf4,0x4c,0x4b,0x96, /* "display_force_sw_blink" */ + 0x2,0x29,0x3d,0x1b,0xba,0x16,0x50,0xb2,0x70,0x68,0x97,0x1f,0xa4,0xac,0x83,0x44,0xbd,0xc0, /* "dji_cn_alternating_duration" */ + 0x22,0x93,0xda,0xcc,0xbd,0x70,0x5a,0x5e,0x99,0xf2,0xeb,0x4b,0x39,0x84,0xe5,0x98, /* "dji_use_name_for_messages" */ + 0x8,0xfb,0xb8, /* "down" */ + 0x4,0x9d, /* "dst" */ + 0x0,0x56,0x96,0x47, /* "emerg" */ + 0x1,0x5c,0x11,0x30,0xa4, /* "enabled" */ + 0x1,0x5c,0x67,0xc8,0x65, /* "enforce" */ + 0x1,0x60,0x80, /* "eph" */ + 0x18,0x33,0xa0, /* "fast" */ + 0xc,0x9c,0x14,0x9d,0xba,0x5c,0x7e,0x86,0xb4,0x7f,0x43,0x26, /* "fixed_wing_auto_arm" */ + 0x80,0xcc,0xc,0xb,0x27,0xb8, /* "flaperon" */ + 0x6,0x60,0x61,0x30, /* "flaps" */ + 0x19,0xf2,0x19, /* "force" */ + 0x40,0x68,0x58, /* "fpv" */ + 0x6,0xbf,0x53,0x42,0xc9,0xbd,0x62,0x5a,0x9a,0x76,0x74,0x48,0xd7,0xd8,0x3e,0x69,0xa2,0x5e,0xe0, /* "fw_iterm_limit_stick_position" */ + 0x1a,0xfd,0xa5,0x64,0xee,0x86,0x73,0x4c,0xe9,0xd8,0x26,0x83,0x47,0x4e,0x14,0xb8, /* "fw_turn_assist_pitch_gain" */ + 0x6,0xbf,0x69,0x59,0x3b,0xa1,0x9c,0xd3,0x3a,0x77,0x21,0xbf,0x4e,0x14,0xb8, /* "fw_turn_assist_yaw_gain" */ + 0x6,0xbf,0x72,0x1b,0xf5,0x34,0x2c,0x9b,0xd3,0x48,0xa5,0xd1,0x7a,0x20,0xb9,0x7d,0xb,0x8e,0xc2, /* "fw_yaw_iterm_freeze_bank_angle" */ + 0x80,0xe1,0x62,0x58,0x57, /* "galileo" */ + 0x80,0xe6,0x7c,0x86,0x50, /* "gforce" */ + 0x1e,0x49,0x20, /* "grid" */ + 0xf,0x99,0x3f,0xa1,0x75,0x13,0xd0,0xb1,0x21,0x9a,0x5c,0x7e,0xb2,0x6,0xea,0x34, /* "gyro_anti_aliasing_lpf_hz" */ + 0x3,0xe6,0x4f,0xe8,0x5d,0x44,0xf4,0x2c,0x48,0x66,0x97,0x1f,0xac,0x81,0xbb,0x4c,0xc0,0xa0, /* "gyro_anti_aliasing_lpf_type" */ + 0x40,0x66, /* "has" */ + 0x4,0x24,0xe8, /* "high" */ + 0x2,0x1e,0xd2,0xc1,0xe9,0x75, /* "homepoint" */ + 0x0,0x87,0xb5,0x2e,0x38, /* "homing" */ + 0x10,0xf9,0x27,0x4f,0x70, /* "horizon" */ + 0x10,0xf9,0x27,0x4f,0x75,0x2,0xc0, /* "horizontal" */ + 0x21,0xf6,0x2c, /* "hover" */ + 0x80,0x92, /* "id" */ + 0x1,0x2e,0xd,0xba,0x16,0x31,0xf7,0xe9,0xa,0x12,0x76,0x45,0x1a,0xde,0xe4,0xb8,0xe0, /* "inav_allow_dead_reckoning" */ + 0x4b,0x88,0x5c, /* "index" */ + 0x1,0x2e,0x2c,0xa8,0x90, /* "inertia" */ + 0x81,0x2e,0x4d, /* "init" */ + 0x0,0x97,0x4c, /* "ins" */ + 0xb,0x4b,0x18, /* "kill" */ + 0x6,0x4,0x45,0x60, /* "label" */ + 0x18,0x1c,0xbe,0xb4, /* "layout" */ + 0x3,0xa,0x6a, /* "left" */ + 0x1,0x89,0x72, /* "link" */ + 0xc0,0xc7,0xbe,0x14,0x4b,0x4a, /* "looptime" */ + 0x6,0x94,0x89,0xb, /* "median" */ + 0x80,0xd2,0xce,0x61,0x39, /* "message" */ + 0x40,0xd2,0xd1,0xf,0x20, /* "method" */ + 0x1a,0x92, /* "mid" */ + 0x1,0xa9,0x63,0x12, /* "milli" */ + 0x6,0xa7,0x0, /* "mix" */ + 0x6b,0xc8,0x5e,0xc8,0x2e,0x39,0x7a,0xc7,0x9d,0x23,0xeb,0xe0,0x59,0x6,0x8f,0x90, /* "mode_range_logic_operator" */ + 0x1a,0xf9,0x3d,0xc0, /* "moron" */ + 0x70,0x6d,0xd2,0xe2,0x92,0xf,0x43,0x26,0xa5,0xc7,0xec,0xc2,0x62,0xd3,0x20, /* "nav_extra_arming_safety" */ + 0x70,0x6d,0xd3,0x5f,0xa1,0x63,0x1f,0x7e,0xb4,0x2e,0xa8,0x59,0xda,0x22,0x5d,0x4b,0x87,0x22,0x86,0x65, /* "nav_fw_allow_manual_thr_increase" */ + 0x3,0x83,0x6e,0x9a,0xfd,0x83,0xe7,0xd4,0x10,0xfd,0x82,0x49,0x3a,0xb7,0xac,0x4b,0x53,0x40, /* "nav_fw_pos_hdg_pidsum_limit" */ + 0x38,0x36,0xe9,0xaf,0xd9,0xbc,0x32,0x4b,0x8f,0xd6,0xbe,0x8f,0x97,0x67,0x47,0xc0, /* "nav_fw_soaring_motor_stop" */ + 0xe,0xd,0xba,0x6b,0xf6,0xf0,0xed,0x24,0x11,0xad,0x2e,0x3f,0x42,0x31,0xd6,0x41,0x1e, /* "nav_fw_wp_tracking_accuracy" */ + 0x40,0xe0,0xdb,0xa6,0xbf,0x6f,0xe,0xd2,0x41,0x1a,0xd2,0xe3,0xf5,0xa1,0xc7,0x42,0xe3,0xb0,0xa0, /* "nav_fw_wp_tracking_max_angle" */ + 0x70,0x6d,0xd3,0x5f,0xb7,0x87,0x69,0x59,0x3b,0xb3,0x6b,0xdf,0x44,0x25,0xc7, /* "nav_fw_wp_turn_smoothing" */ + 0x3,0x83,0x6e,0xb4,0x38,0xed,0xb,0x29,0x5,0x2e,0xe9,0x9e,0xc6,0x3e,0xfd,0xb,0x28, /* "nav_max_terrain_follow_alt" */ + 0x7,0x6,0xdd,0x68,0xfa,0x29,0x5,0x69,0x71,0xfa,0x27,0xbe,0x74,0xe9,0x13,0x32,0xb8,0xe1,0x39,0x7b,0x38,0x14,0xa4, /* "nav_mc_braking_boost_disengage_speed" */ + 0x3,0x83,0x6e,0xb4,0x7d,0xb1,0x59,0xdc,0x67,0xa4,0xa1,0x64,0xde,0x86,0x94,0x2b,0xaa,0x1a,0x25,0xee, /* "nav_mc_vel_xy_dterm_attenuation" */ + 0x3,0x83,0x6e,0xb4,0x7d,0xb1,0x59,0xdc,0x67,0xa4,0xa1,0x64,0xde,0x86,0x94,0x2b,0xaa,0x1a,0x25,0xee,0xe9,0x5c,0x40, /* "nav_mc_vel_xy_dterm_attenuation_end" */ + 0x38,0x36,0xeb,0x47,0xdb,0x15,0x9d,0xc6,0x7a,0x4a,0x16,0x4d,0xe8,0x69,0x42,0xba,0xa1,0xa2,0x5e,0xee,0xce,0x81,0x95, /* "nav_mc_vel_xy_dterm_attenuation_start" */ + 0x0,0xe0,0xdb,0xad,0x1f,0x6c,0x56,0x77,0x19,0xe9,0x28,0x59,0x37,0xac,0x81,0xba,0x8d, /* "nav_mc_vel_xy_dterm_lpf_hz" */ + 0x1,0xc1,0xb7,0x5a,0x99,0xcd,0x2f,0x77,0x60,0xc0,0xb9,0xc5,0x97,0x64,0x59,0x96,0x80, /* "nav_mission_planner_reset" */ + 0x70,0x6d,0xd9,0x51,0x1d,0x1b,0x12,0xd1,0x74,0xc9,0x94,0xe9,0xd9,0xd0,0x27,0x2f,0x42,0xca,0x26,0x95,0x21, /* "nav_rth_climb_first_stage_altitude" */ + 0x40,0xe0,0xdb,0xb2,0xa2,0x3a,0x36,0x25,0xa2,0xe9,0x93,0x29,0xd3,0xb3,0xa0,0x4e,0x5e,0xb5,0xe4,0x28, /* "nav_rth_climb_first_stage_mode" */ + 0x1c,0x1b,0x76,0x54,0x47,0x46,0xc4,0xb4,0x5d,0x49,0xdc,0xf9,0x17,0xa5,0x69,0x64,0x70, /* "nav_rth_climb_ignore_emerg" */ + 0x38,0x36,0xed,0x66,0x5e,0xb5,0x24,0xa2,0x25,0xd3,0x3e,0x5d,0xb,0x28,0x87,0xb0,0x80, /* "nav_use_midthr_for_althold" */ + 0x70,0x6d,0xdb,0xc3,0xac,0x78,0x49,0xd7,0xbb,0xa2,0x7b,0xe8, /* "nav_wp_load_on_boot" */ + 0x7,0x6,0xdd,0xbc,0x3a,0xda,0xb2,0x89,0xeb,0x53,0x39,0xa5,0xee,0xea,0x5c,0x42,0xe0, /* "nav_wp_multi_mission_index" */ + 0xe,0x29, /* "neg" */ + 0xc0,0xe2,0xd6,0x92,0xb, /* "neutral" */ + 0x0,0xe7, /* "no" */ + 0x81,0xd5,0x68, /* "num" */ + 0x1e,0x63, /* "off" */ + 0x1,0xee, /* "on" */ + 0x3,0xe6,0x4e,0x8e,0x53,0x37,0x59,0x1e,0x99,0xf2,0x68,0x68, /* "osd_crsf_lq_format" */ + 0x7,0xcc,0x9d,0x2c,0xe8,0x96,0x86,0x89,0x7b,0xa7,0xdb,0xa5,0xc4,0xe8,0xde,0xd8,0x15,0xd3,0xd,0x12,0xf7, /* "osd_estimations_wind_compensation" */ + 0x1,0xf3,0x27,0x4e,0x67,0xc8,0x65,0xe8,0x70,0x99,0xf4,0x2c,0xc,0x9b,0xd6,0x87,0x0, /* "osd_gforce_axis_alarm_max" */ + 0x7c,0xc9,0xd3,0x99,0xf2,0x19,0x7a,0x1c,0x26,0x7d,0xb,0x3,0x26,0xf5,0xa9,0x70, /* "osd_gforce_axis_alarm_min" */ + 0x1f,0x32,0x75,0xf,0x69,0x7b,0x7,0xcd,0x34,0x4b,0xdd,0xd0,0xc9,0xbd,0x98,0xe4,0x52,0xb8, /* "osd_home_position_arm_screen" */ + 0xf,0x99,0x3a,0x8a,0x93,0xb2,0x9,0x3,0x2e,0x85,0x94,0xe9,0x12,0x63,0x16,0x45,0x70,0xcb,0xd2,0x26,0x70,0x60,0x73,0xda,0x25,0xa5, /* "osd_hud_radar_alt_difference_display_time" */ + 0x3,0xe6,0x4e,0xa2,0xa4,0xec,0x82,0x40,0xcb,0xa4,0x4c,0xe8,0x17,0xc,0xbd,0x22,0x67,0x6,0x7,0x3d,0xa2,0x5a,0x50, /* "osd_hud_radar_distance_display_time" */ + 0x3e,0x64,0xea,0x2a,0x4e,0xc8,0x24,0xc,0xbb,0x20,0xb8,0xe5,0xeb,0x43,0x80, /* "osd_hud_radar_range_max" */ + 0x3e,0x64,0xea,0x2a,0x4e,0xc8,0x24,0xc,0xbb,0x20,0xb8,0xe5,0xeb,0x52,0xe0, /* "osd_hud_radar_range_min" */ + 0x3e,0x64,0xeb,0xa,0x6a,0x76,0x69,0x21,0x44,0x19,0x76,0x63,0x93,0xd8,0xce,0xce,0x85,0x80, /* "osd_left_sidebar_scroll_step" */ + 0x1f,0x32,0x75,0xa1,0x47,0x6b,0x32,0x93,0xb0,0x91,0x46,0x99,0xa5,0xee, /* "osd_mah_used_precision" */ + 0x3,0xe6,0x4e,0xc1,0x95,0x9f,0x46,0xf2,0x17,0xa4,0x49,0xd3,0x49, /* "osd_plus_code_digits" */ + 0x81,0xf3,0x27,0x60,0xca,0xcf,0xa3,0x79,0xb,0xd9,0xa1,0xf2,0xa0, /* "osd_plus_code_short" */ + 0x1f,0x32,0x76,0x49,0x3a,0x29,0xd9,0xa4,0x85,0x10,0x65,0xd9,0x8e,0x4f,0x63,0x3b,0x3a,0x16,0x0, /* "osd_right_sidebar_scroll_step" */ + 0x7c,0xc9,0xd9,0xd0,0x34,0x9f,0x60,0x13,0x97,0xa1,0xad,0x1f,0xd9,0xdc,0x30,0xed,0x12,0xd2, /* "osd_stats_page_auto_swap_time" */ + 0x81,0xf3,0x27,0x67,0x74,0xd0,0x68,0xea,0x5c,0x44,0x8c,0x34,0x7c,0xa7,0xd0,0xb1,0x27,0x77,0x58,0x53,0x50, /* "osd_switch_indicators_align_left" */ + 0xf,0x99,0x3b,0x3c,0xce,0x85,0x6f,0x5b,0x33,0xf4,0x89,0x9c,0x18,0x1c,0xf6,0x89,0x69, /* "osd_system_msg_display_time" */ + 0x40,0xfa,0xd2,0x15,0xa0, /* "output" */ + 0x1f,0x62,0xca,0x49,0x21, /* "override" */ + 0x40,0xfb,0x16,0x52,0x49,0xb,0x30, /* "overrides" */ + 0x41,0x24, /* "pid" */ + 0x4,0x13,0x40, /* "pit" */ + 0x41,0x81,0xa1,0x9f,0x26, /* "platform" */ + 0x82,0xf,0x61,0x66, /* "poles" */ + 0x8,0x3e,0x69,0xa2,0x5e,0xe0, /* "position" */ + 0x42,0x45,0xc,0x9a, /* "prearm" */ + 0x8,0x48,0xa3,0x4c,0xd2,0xf7, /* "precision" */ + 0x2,0x12,0x2d,0x92,0x5b, /* "preview" */ + 0x82,0x12,0x79,0x92,0xc2, /* "profile" */ + 0x82,0x15,0x64,0xca, /* "pulse" */ + 0x8,0x5d,0xbc,0x19,0x5d,0x44,0x90,0xa7, /* "pwm2centideg" */ + 0x4,0x6a,0x16,0x26,0x99, /* "quality" */ + 0x4,0x82,0x40,0xc8, /* "radar" */ + 0x12,0x28,0x9e,0xfa, /* "reboot" */ + 0x2,0x45,0x19,0x53,0x62,0xc8, /* "receiver" */ + 0x12,0x28,0xdf,0x62,0xcb,0x20, /* "recovery" */ + 0x91,0x4c,0x59,0x15,0xc3,0x28, /* "reference" */ + 0x24,0x59,0xd0,0x32,0xa0, /* "restart" */ + 0x24,0x5b,0x16,0x53,0x28, /* "reverse" */ + 0x24,0x93,0xa2,0x80, /* "right" */ + 0x93,0x18, /* "rll" */ + 0x9,0x3e,0x81,0xa2,0x5e,0xe0, /* "rotation" */ + 0x49,0xf7, /* "row" */ + 0x4,0xa0,0xd0, /* "rpm" */ + 0x4c,0x26,0x28, /* "safe" */ + 0x26,0x1a,0x4c, /* "sats" */ + 0x13,0x10,0x66, /* "sbas" */ + 0x9,0x8a,0xb3, /* "sbus" */ + 0x4,0xd0,0x93,0x50,0x8f,0xbb, /* "shiftdown" */ + 0x81,0x36,0x3e,0x5, /* "slope" */ + 0x4,0xda,0x16,0x30, /* "small" */ + 0x13,0x6b,0xdf,0x44,0x38,0xb3,0x98, /* "smoothness" */ + 0x26,0xe9, /* "snr" */ + 0x2,0x6f,0xc,0x92,0xe3, /* "soaring" */ + 0x82,0x70,0x4b,0xab,0x0, /* "spinup" */ + 0x4e,0x43, /* "src" */ + 0x4,0xe8,0xf8, /* "stop" */ + 0x2,0x74,0x90, /* "str" */ + 0x27,0x49,0x15,0xc7,0xa2, /* "strength" */ + 0x1,0x3c,0xb8,0x60, /* "sync" */ + 0x9e,0x67,0x42,0xb4, /* "system" */ + 0x14,0xa,0x58, /* "tail" */ + 0xa,0x15,0x85,0x69,0x69,0x2c, /* "telemetry" */ + 0x82,0x89,0x65, /* "tilt" */ + 0x1,0x47,0xb8,0xa0, /* "tone" */ + 0xa3,0xe0,0x91,0xcc, /* "topics" */ + 0x14,0x92, /* "tri" */ + 0x41,0x49,0x25,0xa0, /* "trim" */ + 0xa8,0x98,0xfc, /* "ublox" */ + 0x2,0xae,0xc,0x9a,0x52, /* "unarmed" */ + 0x2,0xae,0x4d,0x26, /* "units" */ + 0xa,0xcc,0x27,0x28, /* "usage" */ + 0x2b,0x32,0xc8, /* "user" */ + 0x16,0x2b,0x1c,0x52, /* "velned" */ + 0x2,0xc5,0x63,0xc6,0x9a,0x64, /* "velocity" */ + 0x16,0x2c,0xa8,0x91,0x85,0x80, /* "vertical" */ + 0xb2,0x48,0x57, /* "video" */ + 0x82,0xe9,0x25,0x10, /* "width" */ + 0xb,0xa5,0xc4,0x1b,0xdb,0x0, /* "windcomp" */ + 0x5d,0x2e,0x25,0x60, /* "windup" */ + 0xb,0xbe,0x4b,0xc,0x9f,0x57,0x12,0x60, /* "workarounds" */ + 0xc6,0x74, /* "xyz" */ + 0x0,0x00 +}; +static const char wordSymbols[] = {'3','2','_',}; +const char * const table_acc_hardware[] = { + "NONE", + "AUTO", + "MPU6000", + "MPU6500", + "MPU9250", + "BMI160", + "ICM20689", + "BMI088", + "ICM42605", + "BMI270", + "FAKE", +}; +const char * const table_airmodeHandlingType[] = { + "STICK_CENTER", + "THROTTLE_THRESHOLD", + "STICK_CENTER_ONCE", +}; +const char * const table_alignment[] = { + "DEFAULT", + "CW0", + "CW90", + "CW180", + "CW270", + "CW0FLIP", + "CW90FLIP", + "CW180FLIP", + "CW270FLIP", +}; +const char * const table_autotune_rate_adjustment[] = { + "FIXED", + "LIMIT", + "AUTO", +}; +const char * const table_aux_operator[] = { + "OR", + "AND", +}; +const char * const table_baro_hardware[] = { + "NONE", + "AUTO", + "BMP085", + "MS5611", + "BMP280", + "MS5607", + "LPS25H", + "SPL06", + "BMP388", + "DPS310", + "B2SMPB", + "MSP", + "FAKE", +}; +const char * const table_bat_capacity_unit[] = { + "MAH", + "MWH", +}; +const char * const table_bat_voltage_source[] = { + "RAW", + "SAG_COMP", +}; +const char * const table_blackbox_device[] = { + "SERIAL", + "SPIFLASH", + "SDCARD", +}; +const char * const table_current_sensor[] = { + "NONE", + "ADC", + "VIRTUAL", + "FAKE", + "ESC", +}; +const char * const table_debug_modes[] = { + "NONE", + "AGL", + "FLOW_RAW", + "FLOW", + "ALWAYS", + "SAG_COMP_VOLTAGE", + "VIBE", + "CRUISE", + "REM_FLIGHT_TIME", + "SMARTAUDIO", + "ACC", + "NAV_YAW", + "PCF8574", + "DYN_GYRO_LPF", + "AUTOLEVEL", + "ALTITUDE", + "AUTOTRIM", + "AUTOTUNE", + "RATE_DYNAMICS", + "LANDING", +}; +const char * const table_direction[] = { + "RIGHT", + "LEFT", + "YAW", +}; +const char * const table_djiOsdTempSource[] = { + "ESC", + "IMU", + "BARO", +}; +const char * const table_djiRssiSource[] = { + "RSSI", + "CRSF_LQ", +}; +const char * const table_failsafe_procedure[] = { + "LAND", + "DROP", + "RTH", + "NONE", +}; +const char * const table_filter_type[] = { + "PT1", + "BIQUAD", +}; +const char * const table_filter_type_full[] = { + "PT1", + "BIQUAD", + "PT2", + "PT3", +}; +const char * const table_gps_dyn_model[] = { + "PEDESTRIAN", + "AIR_1G", + "AIR_4G", +}; +const char * const table_gps_provider[] = { + "NMEA", + "UBLOX", + "UBLOX7", + "MSP", + "FAKE", +}; +const char * const table_gps_sbas_mode[] = { + "AUTO", + "EGNOS", + "WAAS", + "MSAS", + "GAGAN", + "NONE", +}; +const char * const table_gyro_lpf[] = { + "256HZ", + "188HZ", + "98HZ", + "42HZ", + "20HZ", + "10HZ", +}; +const char * const table_imu_inertia_comp_method[] = { + "VELNED", + "TURNRATE", + "ADAPTIVE", +}; +const char * const table_iterm_relax[] = { + "OFF", + "RP", + "RPY", +}; +const char * const table_log_level[] = { + "ERROR", + "WARNING", + "INFO", + "VERBOSE", + "DEBUG", +}; +const char * const table_mag_hardware[] = { + "NONE", + "AUTO", + "HMC5883", + "AK8975", + "MAG3110", + "AK8963", + "IST8310", + "QMC5883", + "MPU9250", + "IST8308", + "LIS3MDL", + "MSP", + "RM3100", + "VCM5883", + "MLX90393", + "FAKE", +}; +const char * const table_motor_pwm_protocol[] = { + "STANDARD", + "ONESHOT125", + "MULTISHOT", + "BRUSHED", + "DSHOT150", + "DSHOT300", + "DSHOT600", +}; +const char * const table_nav_extra_arming_safety[] = { + "ON", + "ALLOW_BYPASS", +}; +const char * const table_nav_fw_wp_turn_smoothing[] = { + "OFF", + "ON", + "ON-CUT", +}; +const char * const table_nav_overrides_motor_stop[] = { + "OFF_ALWAYS", + "OFF", + "AUTO_ONLY", + "ALL_NAV", +}; +const char * const table_nav_rth_allow_landing[] = { + "NEVER", + "ALWAYS", + "FS_ONLY", +}; +const char * const table_nav_rth_alt_mode[] = { + "CURRENT", + "EXTRA", + "FIXED", + "MAX", + "AT_LEAST", + "AT_LEAST_LINEAR_DESCENT", +}; +const char * const table_nav_rth_climb_first[] = { + "OFF", + "ON", + "ON_FW_SPIRAL", +}; +const char * const table_nav_rth_climb_first_stage_modes[] = { + "AT_LEAST", + "EXTRA", +}; +const char * const table_nav_user_control_mode[] = { + "ATTI", + "CRUISE", +}; +const char * const table_nav_wp_mission_restart[] = { + "START", + "RESUME", + "SWITCH", +}; +const char * const table_off_on[] = { + "OFF", + "ON", +}; +const char * const table_opflow_hardware[] = { + "NONE", + "CXOF", + "MSP", + "FAKE", +}; +const char * const table_osdSpeedSource[] = { + "GROUND", + "3D", + "AIR", +}; +const char * const table_osd_ahi_style[] = { + "DEFAULT", + "LINE", +}; +const char * const table_osd_alignment[] = { + "LEFT", + "RIGHT", +}; +const char * const table_osd_crosshairs_style[] = { + "DEFAULT", + "AIRCRAFT", + "TYPE3", + "TYPE4", + "TYPE5", + "TYPE6", + "TYPE7", + "TYPE8", +}; +const char * const table_osd_crsf_lq_format[] = { + "TYPE1", + "TYPE2", + "TYPE3", +}; +const char * const table_osd_plus_code_short[] = { + "0", + "2", + "4", + "6", +}; +const char * const table_osd_sidebar_scroll[] = { + "NONE", + "ALTITUDE", + "SPEED", + "HOME_DISTANCE", +}; +const char * const table_osd_stats_energy_unit[] = { + "MAH", + "WH", +}; +const char * const table_osd_stats_min_voltage_unit[] = { + "BATTERY", + "CELL", +}; +const char * const table_osd_telemetry[] = { + "OFF", + "ON", + "TEST", +}; +const char * const table_osd_unit[] = { + "IMPERIAL", + "METRIC", + "METRIC_MPH", + "UK", + "GA", +}; +const char * const table_osd_video_system[] = { + "AUTO", + "PAL", + "NTSC", + "HDZERO", + "DJIWTF", +}; +const char * const table_output_mode[] = { + "AUTO", + "MOTORS", + "SERVOS", +}; +const char * const table_pidTypeTable[] = { + "NONE", + "PID", + "PIFF", + "AUTO", +}; +const char * const table_pitot_hardware[] = { + "NONE", + "AUTO", + "MS4525", + "ADC", + "VIRTUAL", + "FAKE", + "MSP", +}; +const char * const table_platform_type[] = { + "MULTIROTOR", + "AIRPLANE", + "HELICOPTER", + "TRICOPTER", + "ROVER", + "BOAT", +}; +const char * const table_rangefinder_hardware[] = { + "NONE", + "SRF10", + "VL53L0X", + "MSP", + "BENEWAKE", + "VL53L1X", + "US42", + "TOF10120_I2C", +}; +const char * const table_receiver_type[] = { + "NONE", + "SERIAL", + "MSP", +}; +const char * const table_reset_type[] = { + "NEVER", + "FIRST_ARM", + "EACH_ARM", +}; +const char * const table_rssi_source[] = { + "NONE", + "AUTO", + "ADC", + "CHANNEL", + "PROTOCOL", + "MSP", +}; +const char * const table_rth_trackback_mode[] = { + "OFF", + "ON", + "FS", +}; +const char * const table_safehome_usage_mode[] = { + "OFF", + "RTH", + "RTH_FS", +}; +const char * const table_serial_rx[] = { + "SPEK1024", + "SPEK2048", + "SBUS", + "SUMD", + "IBUS", + "JETIEXBUS", + "CRSF", + "FPORT", + "SBUS_FAST", + "FPORT2", + "SRXL2", + "GHST", + "MAVLINK", +}; +const char * const table_servo_protocol[] = { + "PWM", + "SBUS", + "SBUS_PWM", +}; +const char * const table_tristate[] = { + "AUTO", + "ON", + "OFF", +}; +const char * const table_tz_automatic_dst[] = { + "OFF", + "EU", + "USA", +}; +const char * const table_voltage_sensor[] = { + "NONE", + "ADC", + "ESC", + "FAKE", +}; +static const lookupTableEntry_t settingLookupTables[] = { + { table_acc_hardware, sizeof(table_acc_hardware) / sizeof(char*) }, + { table_airmodeHandlingType, sizeof(table_airmodeHandlingType) / sizeof(char*) }, + { table_alignment, sizeof(table_alignment) / sizeof(char*) }, + { table_autotune_rate_adjustment, sizeof(table_autotune_rate_adjustment) / sizeof(char*) }, + { table_aux_operator, sizeof(table_aux_operator) / sizeof(char*) }, + { table_baro_hardware, sizeof(table_baro_hardware) / sizeof(char*) }, + { table_bat_capacity_unit, sizeof(table_bat_capacity_unit) / sizeof(char*) }, + { table_bat_voltage_source, sizeof(table_bat_voltage_source) / sizeof(char*) }, + { table_blackbox_device, sizeof(table_blackbox_device) / sizeof(char*) }, + { table_current_sensor, sizeof(table_current_sensor) / sizeof(char*) }, + { table_debug_modes, sizeof(table_debug_modes) / sizeof(char*) }, + { table_direction, sizeof(table_direction) / sizeof(char*) }, + { table_djiOsdTempSource, sizeof(table_djiOsdTempSource) / sizeof(char*) }, + { table_djiRssiSource, sizeof(table_djiRssiSource) / sizeof(char*) }, + { table_failsafe_procedure, sizeof(table_failsafe_procedure) / sizeof(char*) }, + { table_filter_type, sizeof(table_filter_type) / sizeof(char*) }, + { table_filter_type_full, sizeof(table_filter_type_full) / sizeof(char*) }, + { table_gps_dyn_model, sizeof(table_gps_dyn_model) / sizeof(char*) }, + { table_gps_provider, sizeof(table_gps_provider) / sizeof(char*) }, + { table_gps_sbas_mode, sizeof(table_gps_sbas_mode) / sizeof(char*) }, + { table_gyro_lpf, sizeof(table_gyro_lpf) / sizeof(char*) }, + { table_imu_inertia_comp_method, sizeof(table_imu_inertia_comp_method) / sizeof(char*) }, + { table_iterm_relax, sizeof(table_iterm_relax) / sizeof(char*) }, + { table_log_level, sizeof(table_log_level) / sizeof(char*) }, + { table_mag_hardware, sizeof(table_mag_hardware) / sizeof(char*) }, + { table_motor_pwm_protocol, sizeof(table_motor_pwm_protocol) / sizeof(char*) }, + { table_nav_extra_arming_safety, sizeof(table_nav_extra_arming_safety) / sizeof(char*) }, + { table_nav_fw_wp_turn_smoothing, sizeof(table_nav_fw_wp_turn_smoothing) / sizeof(char*) }, + { table_nav_overrides_motor_stop, sizeof(table_nav_overrides_motor_stop) / sizeof(char*) }, + { table_nav_rth_allow_landing, sizeof(table_nav_rth_allow_landing) / sizeof(char*) }, + { table_nav_rth_alt_mode, sizeof(table_nav_rth_alt_mode) / sizeof(char*) }, + { table_nav_rth_climb_first, sizeof(table_nav_rth_climb_first) / sizeof(char*) }, + { table_nav_rth_climb_first_stage_modes, sizeof(table_nav_rth_climb_first_stage_modes) / sizeof(char*) }, + { table_nav_user_control_mode, sizeof(table_nav_user_control_mode) / sizeof(char*) }, + { table_nav_wp_mission_restart, sizeof(table_nav_wp_mission_restart) / sizeof(char*) }, + { table_off_on, sizeof(table_off_on) / sizeof(char*) }, + { table_opflow_hardware, sizeof(table_opflow_hardware) / sizeof(char*) }, + { table_osdSpeedSource, sizeof(table_osdSpeedSource) / sizeof(char*) }, + { table_osd_ahi_style, sizeof(table_osd_ahi_style) / sizeof(char*) }, + { table_osd_alignment, sizeof(table_osd_alignment) / sizeof(char*) }, + { table_osd_crosshairs_style, sizeof(table_osd_crosshairs_style) / sizeof(char*) }, + { table_osd_crsf_lq_format, sizeof(table_osd_crsf_lq_format) / sizeof(char*) }, + { table_osd_plus_code_short, sizeof(table_osd_plus_code_short) / sizeof(char*) }, + { table_osd_sidebar_scroll, sizeof(table_osd_sidebar_scroll) / sizeof(char*) }, + { table_osd_stats_energy_unit, sizeof(table_osd_stats_energy_unit) / sizeof(char*) }, + { table_osd_stats_min_voltage_unit, sizeof(table_osd_stats_min_voltage_unit) / sizeof(char*) }, + { table_osd_telemetry, sizeof(table_osd_telemetry) / sizeof(char*) }, + { table_osd_unit, sizeof(table_osd_unit) / sizeof(char*) }, + { table_osd_video_system, sizeof(table_osd_video_system) / sizeof(char*) }, + { table_output_mode, sizeof(table_output_mode) / sizeof(char*) }, + { table_pidTypeTable, sizeof(table_pidTypeTable) / sizeof(char*) }, + { table_pitot_hardware, sizeof(table_pitot_hardware) / sizeof(char*) }, + { table_platform_type, sizeof(table_platform_type) / sizeof(char*) }, + { table_rangefinder_hardware, sizeof(table_rangefinder_hardware) / sizeof(char*) }, + { table_receiver_type, sizeof(table_receiver_type) / sizeof(char*) }, + { table_reset_type, sizeof(table_reset_type) / sizeof(char*) }, + { table_rssi_source, sizeof(table_rssi_source) / sizeof(char*) }, + { table_rth_trackback_mode, sizeof(table_rth_trackback_mode) / sizeof(char*) }, + { table_safehome_usage_mode, sizeof(table_safehome_usage_mode) / sizeof(char*) }, + { table_serial_rx, sizeof(table_serial_rx) / sizeof(char*) }, + { table_servo_protocol, sizeof(table_servo_protocol) / sizeof(char*) }, + { table_tristate, sizeof(table_tristate) / sizeof(char*) }, + { table_tz_automatic_dst, sizeof(table_tz_automatic_dst) / sizeof(char*) }, + { table_voltage_sensor, sizeof(table_voltage_sensor) / sizeof(char*) }, +}; +static const uint32_t settingMinMaxTable[] = { + 0, + 255, + 100, + 1000, + 10, + 1, + 2000, + 5, + 500, + 32767, + -32768, + 10000, + 4, + 65535, + 2, + 20, + 50, + 200, + 30, + 250, + 5000, + 65000, + -1800, + -550, + 15, + 3600, + 3, + 18, + 80, + 180, + 4294967295, + -20, + 60, + 90, + 95, + 1250, + 3000, + 60000, + 9, + 900, + 1500, + 4000, + 8192, + 2147483647, + -800, + -130, + -128, + -1, + 6, + 8, + 25, + 40, + 45, + 120, + 127, + 150, + 175, + 300, + 400, + 450, + 600, + 750, + 800, + 2250, + 9999, + 27000, + 40000, + 500000, + -18000, + -10000, + -1440, + -1000, + -50, + -40, + -36, + -10, + -2, + 11, + 12, + 13, + 16, + 32, + 36, + 48, + 99, + 126, + 128, + 498, + 1440, + 6000, + 9000, + 9990, + 16000, + 18000, + 20000, + 30000, + 32000, + 50000, +}; +typedef uint8_t setting_min_max_idx_t; +#define SETTING_INDEXES_GET_MIN(val) (val->config.minmax.indexes[0]) +#define SETTING_INDEXES_GET_MAX(val) (val->config.minmax.indexes[1]) +static const setting_t settingsTable[] = { + // PG_GYRO_CONFIG + { {167, 2, 0, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 90}, offsetof(gyroConfig_t, looptime) }, + { {30, 57, 14, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GYRO_LPF }, offsetof(gyroConfig_t, gyro_lpf) }, + { {147, 2, 0, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 3}, offsetof(gyroConfig_t, gyro_anti_aliasing_lpf_hz) }, + { {148, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_FILTER_TYPE }, offsetof(gyroConfig_t, gyro_anti_aliasing_lpf_type) }, + { {175, 2, 60, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 86}, offsetof(gyroConfig_t, gyroMovementCalibrationThreshold) }, + { {30, 132, 1, 14, 21, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 8}, offsetof(gyroConfig_t, gyro_main_lpf_hz) }, + { {30, 132, 1, 14, 32, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_FILTER_TYPE }, offsetof(gyroConfig_t, gyro_main_lpf_type) }, + { {30, 72, 79, 14, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(gyroConfig_t, useDynamicLpf) }, + { {30, 79, 14, 10, 21, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {51, 58}, offsetof(gyroConfig_t, gyroDynamicLpfMinHz) }, + { {30, 79, 14, 6, 21, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {51, 3}, offsetof(gyroConfig_t, gyroDynamicLpfMaxHz) }, + { {30, 79, 14, 238, 1, 56}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {5, 4}, offsetof(gyroConfig_t, gyroDynamicLpfCurveExpo) }, + { {160, 2, 30, 121, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(gyroConfig_t, init_gyro_cal_enabled) }, + { {30, 88, 86, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(gyroConfig_t, gyro_zero_cal[X]) }, + { {30, 88, 87, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(gyroConfig_t, gyro_zero_cal[Y]) }, + { {30, 88, 15, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(gyroConfig_t, gyro_zero_cal[Z]) }, + { {161, 2, 166, 1, 230, 1}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 6}, offsetof(gyroConfig_t, gravity_cmss_cal) }, + // PG_ADC_CHANNEL_CONFIG + { {61, 90, 42, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 12}, offsetof(adcChannelConfig_t, adcFunctionChannel[ADC_BATTERY]) }, + { {36, 90, 42, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 12}, offsetof(adcChannelConfig_t, adcFunctionChannel[ADC_RSSI]) }, + { {43, 90, 42, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 12}, offsetof(adcChannelConfig_t, adcFunctionChannel[ADC_CURRENT]) }, + { {91, 90, 42, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 12}, offsetof(adcChannelConfig_t, adcFunctionChannel[ADC_AIRSPEED]) }, + // PG_ACCELEROMETER_CONFIG + { {39, 185, 1, 21, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 1}, offsetof(accelerometerConfig_t, acc_notch_hz) }, + { {39, 185, 1, 100, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {5, 1}, offsetof(accelerometerConfig_t, acc_notch_cutoff) }, + { {39, 57, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_ACC_HARDWARE }, offsetof(accelerometerConfig_t, acc_hardware) }, + { {39, 14, 21, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 17}, offsetof(accelerometerConfig_t, acc_lpf_hz) }, + { {39, 14, 32, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_FILTER_TYPE }, offsetof(accelerometerConfig_t, acc_soft_lpf_type) }, + { {114, 86, 0, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(accelerometerConfig_t, accZero.raw[X]) }, + { {114, 87, 0, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(accelerometerConfig_t, accZero.raw[Y]) }, + { {114, 15, 0, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(accelerometerConfig_t, accZero.raw[Z]) }, + { {113, 86, 0, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {5, 42}, offsetof(accelerometerConfig_t, accGain.raw[X]) }, + { {113, 87, 0, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {5, 42}, offsetof(accelerometerConfig_t, accGain.raw[Y]) }, + { {113, 15, 0, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {5, 42}, offsetof(accelerometerConfig_t, accGain.raw[Z]) }, + // PG_RANGEFINDER_CONFIG + { {194, 1, 57, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_RANGEFINDER_HARDWARE }, offsetof(rangefinderConfig_t, rangefinder_hardware) }, + { {194, 1, 168, 2, 80, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(rangefinderConfig_t, use_median_filtering) }, + // PG_OPFLOW_CONFIG + { {134, 1, 57, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OPFLOW_HARDWARE }, offsetof(opticalFlowConfig_t, opflow_hardware) }, + { {134, 1, 82, 0, 0, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 11}, offsetof(opticalFlowConfig_t, opflow_scale) }, + { {41, 134, 1, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_ALIGNMENT }, offsetof(opticalFlowConfig_t, opflow_align) }, + // PG_COMPASS_CONFIG + { {41, 35, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_ALIGNMENT }, offsetof(compassConfig_t, mag_align) }, + { {35, 57, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_MAG_HARDWARE }, offsetof(compassConfig_t, mag_hardware) }, + { {35, 245, 1, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {68, 93}, offsetof(compassConfig_t, mag_declination) }, + { {131, 1, 86, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(compassConfig_t, magZero.raw[X]) }, + { {131, 1, 87, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(compassConfig_t, magZero.raw[Y]) }, + { {131, 1, 15, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(compassConfig_t, magZero.raw[Z]) }, + { {130, 1, 86, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(compassConfig_t, magGain[X]) }, + { {130, 1, 87, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(compassConfig_t, magGain[Y]) }, + { {130, 1, 15, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(compassConfig_t, magGain[Z]) }, + { {35, 227, 1, 25, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {15, 53}, offsetof(compassConfig_t, magCalibrationTimeLimit) }, + { {41, 35, 18, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {22, 25}, offsetof(compassConfig_t, rollDeciDegrees) }, + { {41, 35, 11, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {22, 25}, offsetof(compassConfig_t, pitchDeciDegrees) }, + { {41, 35, 8, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {22, 25}, offsetof(compassConfig_t, yawDeciDegrees) }, + // PG_BAROMETER_CONFIG + { {54, 57, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BARO_HARDWARE }, offsetof(barometerConfig_t, baro_hardware) }, + { {54, 121, 207, 1, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 3}, offsetof(barometerConfig_t, baro_calibration_tolerance) }, + // PG_PITOTMETER_CONFIG + { {136, 1, 57, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_PITOT_HARDWARE }, offsetof(pitotmeterConfig_t, pitot_hardware) }, + { {136, 1, 14, 172, 2, 21}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 11}, offsetof(pitotmeterConfig_t, pitot_lpf_milli_hz) }, + { {136, 1, 82, 0, 0, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(pitotmeterConfig_t, pitot_scale) }, + // PG_RX_CONFIG + { {236, 2, 32, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_RECEIVER_TYPE }, offsetof(rxConfig_t, receiverType) }, + { {10, 151, 1, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {3, 6}, offsetof(rxConfig_t, mincheck) }, + { {6, 151, 1, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {3, 6}, offsetof(rxConfig_t, maxcheck) }, + { {36, 84, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_RSSI_SOURCE }, offsetof(rxConfig_t, rssi_source) }, + { {36, 42, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 27}, offsetof(rxConfig_t, rssi_channel) }, + { {36, 10, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(rxConfig_t, rssiMin) }, + { {36, 6, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(rxConfig_t, rssiMax) }, + { {249, 2, 133, 3, 173, 1}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {8, 11}, offsetof(rxConfig_t, sbusSyncInterval) }, + { {59, 80, 14, 21, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {24, 19}, offsetof(rxConfig_t, rcFilterFrequency) }, + { {59, 80, 46, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(rxConfig_t, autoSmooth) }, + { {59, 80, 201, 1, 160, 1}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {5, 2}, offsetof(rxConfig_t, autoSmoothFactor) }, + { {140, 1, 192, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_SERIAL_RX }, offsetof(rxConfig_t, serialrx_provider) }, + { {140, 1, 128, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(rxConfig_t, serialrx_inverted) }, + { {202, 1, 111, 156, 2, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 24}, offsetof(rxConfig_t, srxl2_unit_id) }, + { {202, 1, 150, 1, 134, 2}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(rxConfig_t, srxl2_baud_fast) }, + { {198, 1, 10, 212, 1, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {61, 63}, offsetof(rxConfig_t, rx_min_usec) }, + { {198, 1, 6, 212, 1, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {61, 63}, offsetof(rxConfig_t, rx_max_usec) }, + { {140, 1, 168, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_TRISTATE }, offsetof(rxConfig_t, halfDuplex) }, + // PG_BLACKBOX_CONFIG + { {119, 5, 199, 2, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {5, 13}, offsetof(blackboxConfig_t, rate_num) }, + { {119, 5, 249, 1, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {5, 13}, offsetof(blackboxConfig_t, rate_denom) }, + { {119, 250, 1, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BLACKBOX_DEVICE }, offsetof(blackboxConfig_t, device) }, + // PG_MOTOR_CONFIG + { {6, 38, 0, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {3, 6}, offsetof(motorConfig_t, maxthrottle) }, + { {10, 231, 1, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 6}, offsetof(motorConfig_t, mincommand) }, + { {58, 110, 5, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {16, 96}, offsetof(motorConfig_t, motorPwmRate) }, + { {58, 110, 191, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_MOTOR_PWM_PROTOCOL }, offsetof(motorConfig_t, motorPwmProtocol) }, + { {58, 225, 2, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {12, 1}, offsetof(motorConfig_t, motorPoleCount) }, + // PG_FAILSAFE_CONFIG + { {19, 33, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 17}, offsetof(failsafeConfig_t, failsafe_delay) }, + { {19, 237, 2, 33, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 17}, offsetof(failsafeConfig_t, failsafe_recovery_delay) }, + { {19, 200, 2, 33, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 17}, offsetof(failsafeConfig_t, failsafe_off_delay) }, + { {19, 38, 178, 1, 33, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 57}, offsetof(failsafeConfig_t, failsafe_throttle_low_delay) }, + { {19, 190, 1, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_FAILSAFE_PROCEDURE }, offsetof(failsafeConfig_t, failsafe_procedure) }, + { {19, 203, 1, 60, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 8}, offsetof(failsafeConfig_t, failsafe_stick_motion_threshold) }, + { {19, 2, 18, 24, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {44, 62}, offsetof(failsafeConfig_t, failsafe_fw_roll_angle) }, + { {19, 2, 11, 24, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {44, 62}, offsetof(failsafeConfig_t, failsafe_fw_pitch_angle) }, + { {19, 2, 8, 5, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {71, 3}, offsetof(failsafeConfig_t, failsafe_fw_yaw_rate) }, + { {19, 10, 65, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 21}, offsetof(failsafeConfig_t, failsafe_min_distance) }, + { {19, 10, 65, 190, 1, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_FAILSAFE_PROCEDURE }, offsetof(failsafeConfig_t, failsafe_min_distance_procedure) }, + { {19, 183, 1, 33, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {47, 60}, offsetof(failsafeConfig_t, failsafe_mission_delay) }, + // PG_BOARD_ALIGNMENT + { {41, 120, 18, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {22, 25}, offsetof(boardAlignment_t, rollDeciDegrees) }, + { {41, 120, 11, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {22, 25}, offsetof(boardAlignment_t, pitchDeciDegrees) }, + { {41, 120, 8, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {22, 25}, offsetof(boardAlignment_t, yawDeciDegrees) }, + // PG_BATTERY_METERS_CONFIG + { {61, 109, 32, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_VOLTAGE_SENSOR }, offsetof(batteryMetersConfig_t, voltage.type) }, + { {61, 82, 0, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 13}, offsetof(batteryMetersConfig_t, voltage.scale) }, + { {43, 109, 82, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {69, 11}, offsetof(batteryMetersConfig_t, current.scale) }, + { {43, 109, 69, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(batteryMetersConfig_t, current.offset) }, + { {43, 109, 32, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_CURRENT_SENSOR }, offsetof(batteryMetersConfig_t, current.type) }, + { {149, 1, 63, 129, 3, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BAT_VOLTAGE_SOURCE }, offsetof(batteryMetersConfig_t, voltageSource) }, + { {99, 70, 0, 0, 0, 0}, VAR_UINT32 | MASTER_VALUE, .config.minmax.indexes = {0, 30}, offsetof(batteryMetersConfig_t, cruise_power) }, + { {107, 70, 0, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 13}, offsetof(batteryMetersConfig_t, idle_power) }, + { {28, 124, 133, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(batteryMetersConfig_t, rth_energy_margin) }, + { {45, 98, 146, 1, 0, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 14}, offsetof(batteryMetersConfig_t, throttle_compensation_weight) }, + // PG_BATTERY_PROFILES + { {149, 1, 228, 1, 0, 0}, VAR_UINT8 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 78}, offsetof(batteryProfile_t, cells) }, + { {61, 96, 123, 63, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {2, 8}, offsetof(batteryProfile_t, voltage.cellDetect) }, + { {61, 6, 96, 63, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {2, 8}, offsetof(batteryProfile_t, voltage.cellMax) }, + { {61, 10, 96, 63, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {2, 8}, offsetof(batteryProfile_t, voltage.cellMin) }, + { {61, 214, 1, 96, 63, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {2, 8}, offsetof(batteryProfile_t, voltage.cellWarning) }, + { {92, 94, 0, 0, 0, 0}, VAR_UINT32 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 30}, offsetof(batteryProfile_t, capacity.value) }, + { {92, 94, 214, 1, 0, 0}, VAR_UINT32 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 30}, offsetof(batteryProfile_t, capacity.warning) }, + { {92, 94, 236, 1, 0, 0}, VAR_UINT32 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 30}, offsetof(batteryProfile_t, capacity.critical) }, + { {92, 94, 111, 0, 0, 0}, VAR_UINT8 | BATTERY_CONFIG_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BAT_CAPACITY_UNIT }, offsetof(batteryProfile_t, capacity.unit) }, + { {234, 1, 230, 2, 0, 0}, VAR_UINT8 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 26}, offsetof(batteryProfile_t, controlRateProfile) }, + { {38, 82, 0, 0, 0, 0}, VAR_FLOAT | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 5}, offsetof(batteryProfile_t, motor.throttleScale) }, + { {38, 107, 0, 0, 0, 0}, VAR_FLOAT | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 18}, offsetof(batteryProfile_t, motor.throttleIdle) }, + { {19, 38, 0, 0, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {3, 6}, offsetof(batteryProfile_t, failsafe_throttle) }, + { {1, 4, 155, 2, 45, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {3, 6}, offsetof(batteryProfile_t, nav.mc.hover_throttle) }, + { {1, 2, 99, 45, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {3, 6}, offsetof(batteryProfile_t, nav.fw.cruise_throttle) }, + { {1, 2, 10, 45, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {3, 6}, offsetof(batteryProfile_t, nav.fw.min_throttle) }, + { {1, 2, 6, 45, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {3, 6}, offsetof(batteryProfile_t, nav.fw.max_throttle) }, + { {1, 2, 135, 1, 0, 0}, VAR_UINT8 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 2}, offsetof(batteryProfile_t, nav.fw.pitch_to_throttle) }, + { {1, 2, 16, 45, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {3, 6}, offsetof(batteryProfile_t, nav.fw.launch_throttle) }, + { {1, 2, 16, 107, 45, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {3, 6}, offsetof(batteryProfile_t, nav.fw.launch_idle_throttle) }, + { {13, 152, 1, 43, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 41}, offsetof(batteryProfile_t, powerLimits.continuousCurrent) }, + { {13, 64, 43, 0, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 41}, offsetof(batteryProfile_t, powerLimits.burstCurrent) }, + { {13, 64, 43, 25, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 36}, offsetof(batteryProfile_t, powerLimits.burstCurrentTime) }, + { {13, 64, 43, 161, 1, 25}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 36}, offsetof(batteryProfile_t, powerLimits.burstCurrentFalldownTime) }, + { {13, 152, 1, 70, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 66}, offsetof(batteryProfile_t, powerLimits.continuousPower) }, + { {13, 64, 70, 0, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 66}, offsetof(batteryProfile_t, powerLimits.burstPower) }, + { {13, 64, 70, 25, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 36}, offsetof(batteryProfile_t, powerLimits.burstPowerTime) }, + { {13, 64, 70, 161, 1, 25}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 36}, offsetof(batteryProfile_t, powerLimits.burstPowerFalldownTime) }, + // PG_MIXER_CONFIG + { {58, 154, 1, 128, 1, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(mixerConfig_t, motorDirectionInverted) }, + { {224, 2, 32, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_PLATFORM_TYPE }, offsetof(mixerConfig_t, platformType) }, + { {149, 2, 137, 2, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(mixerConfig_t, hasFlaps) }, + { {184, 1, 229, 2, 32, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {47, 9}, offsetof(mixerConfig_t, appliedMixerPreset) }, + { {219, 2, 49, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OUTPUT_MODE }, offsetof(mixerConfig_t, outputMode) }, + // PG_REVERSIBLE_MOTORS_CONFIG + { {89, 29, 178, 1, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {3, 6}, offsetof(reversibleMotorsConfig_t, deadband_low) }, + { {89, 29, 150, 2, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {3, 6}, offsetof(reversibleMotorsConfig_t, deadband_high) }, + { {89, 197, 2, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {3, 6}, offsetof(reversibleMotorsConfig_t, neutral) }, + // PG_SERVO_CONFIG + { {50, 191, 1, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_SERVO_PROTOCOL }, offsetof(servoConfig_t, servo_protocol) }, + { {50, 97, 231, 2, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {3, 6}, offsetof(servoConfig_t, servoCenterPulse) }, + { {50, 110, 5, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {16, 87}, offsetof(servoConfig_t, servoPwmRate) }, + { {50, 14, 21, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {0, 58}, offsetof(servoConfig_t, servo_lowpass_freq) }, + { {136, 2, 206, 1, 69, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {16, 59}, offsetof(servoConfig_t, flaperon_throw_offset) }, + { {140, 3, 143, 3, 50, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(servoConfig_t, tri_unarmed_servo) }, + { {50, 223, 1, 243, 2, 13}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {5, 32}, offsetof(servoConfig_t, servo_autotrim_rotation_limit) }, + // PG_CONTROL_RATE_PROFILES + { {45, 171, 2, 0, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(controlRateConfig_t, throttle.rcMid8) }, + { {45, 56, 0, 0, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(controlRateConfig_t, throttle.rcExpo8) }, + { {145, 1, 5, 0, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(controlRateConfig_t, throttle.dynPID) }, + { {145, 1, 226, 1, 0, 0}, VAR_UINT16 | CONTROL_RATE_VALUE, .config.minmax.indexes = {3, 6}, offsetof(controlRateConfig_t, throttle.pa_breakpoint) }, + { {2, 145, 1, 25, 233, 1}, VAR_UINT16 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 20}, offsetof(controlRateConfig_t, throttle.fixedWingTauMs) }, + { {59, 56, 0, 0, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(controlRateConfig_t, stabilized.rcExpo8) }, + { {59, 8, 56, 0, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(controlRateConfig_t, stabilized.rcYawExpo8) }, + { {18, 5, 0, 0, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {12, 29}, offsetof(controlRateConfig_t, stabilized.rates[FD_ROLL]) }, + { {11, 5, 0, 0, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {12, 29}, offsetof(controlRateConfig_t, stabilized.rates[FD_PITCH]) }, + { {8, 5, 0, 0, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {5, 29}, offsetof(controlRateConfig_t, stabilized.rates[FD_YAW]) }, + { {48, 59, 56, 0, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(controlRateConfig_t, manual.rcExpo8) }, + { {48, 59, 8, 56, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(controlRateConfig_t, manual.rcYawExpo8) }, + { {48, 18, 5, 0, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(controlRateConfig_t, manual.rates[FD_ROLL]) }, + { {48, 11, 5, 0, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(controlRateConfig_t, manual.rates[FD_PITCH]) }, + { {48, 8, 5, 0, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(controlRateConfig_t, manual.rates[FD_YAW]) }, + { {139, 2, 173, 2, 248, 1}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 16}, offsetof(controlRateConfig_t, misc.fpvCamAngleDegrees) }, + { {5, 66, 97, 139, 1, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {50, 56}, offsetof(controlRateConfig_t, rateDynamics.sensitivityCenter) }, + { {5, 66, 104, 139, 1, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {50, 56}, offsetof(controlRateConfig_t, rateDynamics.sensitivityEnd) }, + { {5, 66, 97, 153, 1, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {4, 34}, offsetof(controlRateConfig_t, rateDynamics.correctionCenter) }, + { {5, 66, 104, 153, 1, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {4, 34}, offsetof(controlRateConfig_t, rateDynamics.correctionEnd) }, + { {5, 66, 97, 146, 1, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 34}, offsetof(controlRateConfig_t, rateDynamics.weightCenter) }, + { {5, 66, 104, 146, 1, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 34}, offsetof(controlRateConfig_t, rateDynamics.weightEnd) }, + // PG_SERIAL_CONFIG + { {235, 2, 229, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {83, 85}, offsetof(serialConfig_t, reboot_character) }, + // PG_IMU_CONFIG + { {34, 101, 175, 1, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 13}, offsetof(imuConfig_t, dcm_kp_acc) }, + { {34, 101, 174, 1, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 13}, offsetof(imuConfig_t, dcm_ki_acc) }, + { {34, 101, 175, 1, 35, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 13}, offsetof(imuConfig_t, dcm_kp_mag) }, + { {34, 101, 174, 1, 35, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 13}, offsetof(imuConfig_t, dcm_ki_mag) }, + { {252, 2, 24, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 29}, offsetof(imuConfig_t, small_angle) }, + { {34, 39, 171, 1, 5, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 18}, offsetof(imuConfig_t, acc_ignore_rate) }, + { {34, 39, 171, 1, 251, 2}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(imuConfig_t, acc_ignore_slope) }, + { {34, 20, 8, 152, 3, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(imuConfig_t, gps_yaw_windcomp) }, + { {34, 159, 2, 98, 170, 2}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_IMU_INERTIA_COMP_METHOD }, offsetof(imuConfig_t, inertia_comp_method) }, + // PG_ARMING_CONFIG + { {135, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(armingConfig_t, fixed_wing_auto_arm) }, + { {102, 162, 2, 31, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(armingConfig_t, disarm_kill_switch) }, + { {31, 102, 33, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 3}, offsetof(armingConfig_t, switchDisarmDelayMs) }, + { {227, 2, 85, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 11}, offsetof(armingConfig_t, prearmTimeoutMs) }, + // PG_GENERAL_SETTINGS + { {219, 1, 246, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 84}, offsetof(generalSettings_t, appliedDefaults) }, + // PG_GPS_CONFIG + { {20, 192, 1, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GPS_PROVIDER }, offsetof(gpsConfig_t, provider) }, + { {20, 248, 2, 49, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GPS_SBAS_MODE }, offsetof(gpsConfig_t, sbasMode) }, + { {20, 79, 184, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GPS_DYN_MODEL }, offsetof(gpsConfig_t, dynModel) }, + { {20, 46, 232, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(gpsConfig_t, autoConfig) }, + { {20, 46, 150, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(gpsConfig_t, autoBaud) }, + { {20, 142, 3, 72, 144, 2}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(gpsConfig_t, ubloxUseGalileo) }, + { {20, 10, 247, 2, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {7, 4}, offsetof(gpsConfig_t, gpsMinSats) }, + // PG_RC_CONTROLS_CONFIG + { {29, 0, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 81}, offsetof(rcControlsConfig_t, deadband) }, + { {8, 29, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(rcControlsConfig_t, yaw_deadband) }, + { {23, 127, 29, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {14, 19}, offsetof(rcControlsConfig_t, pos_hold_deadband) }, + { {77, 29, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {14, 19}, offsetof(rcControlsConfig_t, control_deadband) }, + { {74, 127, 29, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {4, 19}, offsetof(rcControlsConfig_t, alt_hold_deadband) }, + { {89, 29, 38, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 17}, offsetof(rcControlsConfig_t, mid_throttle_deadband) }, + { {148, 1, 32, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_AIRMODEHANDLINGTYPE }, offsetof(rcControlsConfig_t, airmodeHandlingType) }, + { {148, 1, 38, 60, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {3, 6}, offsetof(rcControlsConfig_t, airmodeThrottleThreshold) }, + // PG_PID_PROFILE + { {4, 7, 11, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_PITCH].P) }, + { {4, 22, 11, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_PITCH].I) }, + { {4, 17, 11, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_PITCH].D) }, + { {4, 95, 11, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_PITCH].FF) }, + { {4, 7, 18, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_ROLL].P) }, + { {4, 22, 18, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_ROLL].I) }, + { {4, 17, 18, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_ROLL].D) }, + { {4, 95, 18, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_ROLL].FF) }, + { {4, 7, 8, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_YAW].P) }, + { {4, 22, 8, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_YAW].I) }, + { {4, 17, 8, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_YAW].D) }, + { {4, 95, 8, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_YAW].FF) }, + { {4, 7, 44, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_LEVEL].P) }, + { {4, 22, 44, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_LEVEL].I) }, + { {4, 17, 44, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_LEVEL].D) }, + { {2, 7, 11, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_PITCH].P) }, + { {2, 22, 11, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_PITCH].I) }, + { {2, 17, 11, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_PITCH].D) }, + { {2, 106, 11, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_PITCH].FF) }, + { {2, 7, 18, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_ROLL].P) }, + { {2, 22, 18, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_ROLL].I) }, + { {2, 17, 18, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_ROLL].D) }, + { {2, 106, 18, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_ROLL].FF) }, + { {2, 7, 8, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_YAW].P) }, + { {2, 22, 8, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_YAW].I) }, + { {2, 17, 8, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_YAW].D) }, + { {2, 106, 8, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_YAW].FF) }, + { {2, 7, 44, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_LEVEL].P) }, + { {2, 22, 44, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_LEVEL].I) }, + { {2, 17, 44, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_LEVEL].D) }, + { {6, 24, 172, 1, 242, 2}, VAR_INT16 | PROFILE_VALUE, .config.minmax.indexes = {2, 39}, offsetof(pidProfile_t, max_angle_inclination[FD_ROLL]) }, + { {6, 24, 172, 1, 223, 2}, VAR_INT16 | PROFILE_VALUE, .config.minmax.indexes = {2, 39}, offsetof(pidProfile_t, max_angle_inclination[FD_PITCH]) }, + { {103, 14, 21, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 8}, offsetof(pidProfile_t, dterm_lpf_hz) }, + { {103, 14, 32, 0, 0, 0}, VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_FILTER_TYPE_FULL }, offsetof(pidProfile_t, dterm_lpf_type) }, + { {103, 179, 1, 21, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 8}, offsetof(pidProfile_t, dterm_lpf2_hz) }, + { {103, 179, 1, 32, 0, 0}, VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_FILTER_TYPE_FULL }, offsetof(pidProfile_t, dterm_lpf2_type) }, + { {8, 14, 21, 0, 0, 0}, VAR_UINT8 | PROFILE_VALUE, .config.minmax.indexes = {0, 17}, offsetof(pidProfile_t, yaw_lpf_hz) }, + { {2, 108, 206, 1, 13, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 8}, offsetof(pidProfile_t, fixedWingItermThrowLimit) }, + { {2, 238, 2, 91, 0, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {57, 89}, offsetof(pidProfile_t, fixedWingReferenceAirspeed) }, + { {142, 2, 0, 0, 0, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {0, 14}, offsetof(pidProfile_t, fixedWingCoordinatedYawGain) }, + { {141, 2, 0, 0, 0, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {0, 14}, offsetof(pidProfile_t, fixedWingCoordinatedPitchGain) }, + { {140, 2, 0, 0, 0, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {0, 5}, offsetof(pidProfile_t, fixedWingItermLimitOnStickPosition) }, + { {143, 2, 0, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 33}, offsetof(pidProfile_t, fixedWingYawItermBankFreeze) }, + { {189, 1, 13, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {2, 3}, offsetof(pidProfile_t, pidSumLimit) }, + { {189, 1, 13, 8, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {2, 3}, offsetof(pidProfile_t, pidSumLimitYaw) }, + { {108, 153, 3, 0, 0, 0}, VAR_UINT8 | PROFILE_VALUE, .config.minmax.indexes = {0, 33}, offsetof(pidProfile_t, itermWindupPointPercent) }, + { {5, 112, 13, 18, 11, 0}, VAR_UINT32 | PROFILE_VALUE, .config.minmax.indexes = {0, 67}, offsetof(pidProfile_t, axisAccelerationLimitRollPitch) }, + { {5, 112, 13, 8, 0, 0}, VAR_UINT32 | PROFILE_VALUE, .config.minmax.indexes = {0, 67}, offsetof(pidProfile_t, axisAccelerationLimitYaw) }, + { {126, 127, 5, 13, 0, 0}, VAR_UINT8 | PROFILE_VALUE, .config.minmax.indexes = {4, 19}, offsetof(pidProfile_t, heading_hold_rate_limit) }, + { {1, 4, 23, 15, 7, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_POS_Z].P) }, + { {1, 4, 62, 15, 7, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_VEL_Z].P) }, + { {1, 4, 62, 15, 22, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_VEL_Z].I) }, + { {1, 4, 62, 15, 17, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_VEL_Z].D) }, + { {1, 4, 23, 27, 7, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_POS_XY].P) }, + { {1, 4, 62, 27, 7, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_VEL_XY].P) }, + { {1, 4, 62, 27, 22, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_VEL_XY].I) }, + { {1, 4, 62, 27, 17, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_VEL_XY].D) }, + { {1, 4, 62, 27, 106, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_VEL_XY].FF) }, + { {1, 4, 126, 7, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_HEADING].P) }, + { {188, 2, 0, 0, 0, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(pidProfile_t, navVelXyDTermLpfHz) }, + { {185, 2, 0, 0, 0, 0}, VAR_UINT8 | PROFILE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(pidProfile_t, navVelXyDtermAttenuation) }, + { {187, 2, 0, 0, 0, 0}, VAR_UINT8 | PROFILE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(pidProfile_t, navVelXyDtermAttenuationStart) }, + { {186, 2, 0, 0, 0, 0}, VAR_UINT8 | PROFILE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(pidProfile_t, navVelXyDtermAttenuationEnd) }, + { {1, 2, 23, 15, 7, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_POS_Z].P) }, + { {1, 2, 23, 15, 22, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_POS_Z].I) }, + { {1, 2, 23, 15, 17, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_POS_Z].D) }, + { {1, 2, 23, 27, 7, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_POS_XY].P) }, + { {1, 2, 23, 27, 22, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_POS_XY].I) }, + { {1, 2, 23, 27, 17, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_POS_XY].D) }, + { {1, 2, 126, 7, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_HEADING].P) }, + { {1, 2, 23, 125, 7, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_POS_HEADING].P) }, + { {1, 2, 23, 125, 22, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_POS_HEADING].I) }, + { {1, 2, 23, 125, 17, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_POS_HEADING].D) }, + { {178, 2, 0, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {2, 3}, offsetof(pidProfile_t, navFwPosHdgPidsumLimit) }, + { {4, 108, 195, 1, 0, 0}, VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_ITERM_RELAX }, offsetof(pidProfile_t, iterm_relax) }, + { {4, 108, 195, 1, 100, 0}, VAR_UINT8 | PROFILE_VALUE, .config.minmax.indexes = {5, 2}, offsetof(pidProfile_t, iterm_relax_cutoff) }, + { {17, 75, 10, 0, 0, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {0, 5}, offsetof(pidProfile_t, dBoostMin) }, + { {17, 75, 6, 0, 0, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {5, 26}, offsetof(pidProfile_t, dBoostMax) }, + { {240, 1, 0, 0, 0, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {3, 92}, offsetof(pidProfile_t, dBoostMaxAtAlleceleration) }, + { {239, 1, 0, 0, 0, 0}, VAR_UINT8 | PROFILE_VALUE, .config.minmax.indexes = {4, 19}, offsetof(pidProfile_t, dBoostGyroDeltaLpfHz) }, + { {115, 165, 1, 0, 0, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {5, 15}, offsetof(pidProfile_t, antigravityGain) }, + { {115, 215, 1, 0, 0, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {5, 15}, offsetof(pidProfile_t, antigravityAccelerator) }, + { {115, 100, 14, 21, 0, 0}, VAR_UINT8 | PROFILE_VALUE, .config.minmax.indexes = {5, 18}, offsetof(pidProfile_t, antigravityCutoff) }, + { {222, 2, 32, 0, 0, 0}, VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_PIDTYPETABLE }, offsetof(pidProfile_t, pidControllerType) }, + { {4, 95, 14, 21, 0, 0}, VAR_UINT8 | PROFILE_VALUE, .config.minmax.indexes = {0, 17}, offsetof(pidProfile_t, controlDerivativeLpfHz) }, + { {2, 44, 11, 141, 3, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {75, 4}, offsetof(pidProfile_t, fixedWingLevelTrim) }, + { {142, 1, 137, 1, 132, 3}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {0, 5}, offsetof(pidProfile_t, smithPredictorStrength) }, + { {142, 1, 137, 1, 33, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {0, 49}, offsetof(pidProfile_t, smithPredictorDelay) }, + { {142, 1, 137, 1, 14, 21}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {5, 8}, offsetof(pidProfile_t, smithPredictorFilterHz) }, + { {2, 44, 11, 165, 1, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {0, 15}, offsetof(pidProfile_t, fixedWingLevelTrimGain) }, + // PG_PID_AUTOTUNE_CONFIG + { {2, 116, 10, 203, 1, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(pidAutotuneConfig_t, fw_min_stick) }, + { {2, 116, 5, 216, 1, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_AUTOTUNE_RATE_ADJUSTMENT }, offsetof(pidAutotuneConfig_t, fw_rate_adjustment) }, + { {2, 116, 6, 5, 247, 1}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {16, 2}, offsetof(pidAutotuneConfig_t, fw_max_rate_deflection) }, + // PG_POSITION_ESTIMATION_CONFIG + { {9, 46, 35, 244, 1, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(positionEstimationConfig_t, automatic_mag_declination) }, + { {9, 166, 1, 121, 207, 1}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 1}, offsetof(positionEstimationConfig_t, gravity_calibration_tolerance) }, + { {9, 72, 20, 147, 3, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(positionEstimationConfig_t, use_gps_velned) }, + { {9, 72, 20, 198, 2, 54}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(positionEstimationConfig_t, use_gps_no_baro) }, + { {157, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(positionEstimationConfig_t, allow_dead_reckoning) }, + { {9, 197, 1, 53, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_RESET_TYPE }, offsetof(positionEstimationConfig_t, reset_altitude_type) }, + { {9, 197, 1, 170, 1, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_RESET_TYPE }, offsetof(positionEstimationConfig_t, reset_home_type) }, + { {9, 6, 143, 1, 53, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 3}, offsetof(positionEstimationConfig_t, max_surface_altitude) }, + { {9, 26, 15, 143, 1, 7}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(positionEstimationConfig_t, w_z_surface_p) }, + { {9, 26, 15, 143, 1, 52}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(positionEstimationConfig_t, w_z_surface_v) }, + { {9, 26, 27, 163, 1, 7}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(positionEstimationConfig_t, w_xy_flow_p) }, + { {9, 26, 27, 163, 1, 52}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(positionEstimationConfig_t, w_xy_flow_v) }, + { {9, 26, 15, 54, 7, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(positionEstimationConfig_t, w_z_baro_p) }, + { {9, 26, 15, 20, 7, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(positionEstimationConfig_t, w_z_gps_p) }, + { {9, 26, 15, 20, 52, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(positionEstimationConfig_t, w_z_gps_v) }, + { {9, 26, 27, 20, 7, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(positionEstimationConfig_t, w_xy_gps_p) }, + { {9, 26, 27, 20, 52, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(positionEstimationConfig_t, w_xy_gps_v) }, + { {9, 26, 15, 196, 1, 52}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(positionEstimationConfig_t, w_z_res_v) }, + { {9, 26, 27, 196, 1, 52}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(positionEstimationConfig_t, w_xy_res_v) }, + { {9, 26, 155, 3, 39, 7}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 5}, offsetof(positionEstimationConfig_t, w_xyz_acc_p) }, + { {9, 26, 39, 224, 1, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 5}, offsetof(positionEstimationConfig_t, w_acc_bias) }, + { {9, 6, 133, 2, 159, 1}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 64}, offsetof(positionEstimationConfig_t, max_eph_epv) }, + { {9, 54, 159, 1, 0, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 64}, offsetof(positionEstimationConfig_t, baro_epv) }, + // PG_NAV_CONFIG + { {1, 102, 201, 2, 129, 1}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(navConfig_t, general.flags.disarm_on_landing) }, + { {1, 68, 123, 139, 1, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {5, 24}, offsetof(navConfig_t, general.land_detect_sensitivity) }, + { {193, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(navConfig_t, general.flags.use_thr_mid_for_althold) }, + { {176, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_NAV_EXTRA_ARMING_SAFETY }, offsetof(navConfig_t, general.flags.extra_arming_safety) }, + { {1, 146, 3, 77, 49, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_NAV_USER_CONTROL_MODE }, offsetof(navConfig_t, general.flags.user_control_mode) }, + { {1, 226, 2, 85, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(navConfig_t, general.pos_failure_timeout) }, + { {194, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(navConfig_t, general.waypoint_load_on_boot) }, + { {1, 73, 193, 1, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {4, 11}, offsetof(navConfig_t, general.waypoint_radius) }, + { {1, 73, 132, 2, 53, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 6}, offsetof(navConfig_t, general.waypoint_enforce_altitude) }, + { {1, 73, 6, 246, 2, 65}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 40}, offsetof(navConfig_t, general.waypoint_safe_distance) }, + { {1, 73, 183, 1, 239, 2}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_NAV_WP_MISSION_RESTART }, offsetof(navConfig_t, general.flags.waypoint_mission_restart) }, + { {195, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {5, 38}, offsetof(navConfig_t, general.waypoint_multi_mission_index) }, + { {180, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(navConfig_t, fw.wp_tracking_accuracy) }, + { {181, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {18, 28}, offsetof(navConfig_t, fw.wp_tracking_max_angle) }, + { {182, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_NAV_FW_WP_TURN_SMOOTHING }, offsetof(navConfig_t, fw.wp_turn_smoothing) }, + { {1, 46, 37, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {4, 6}, offsetof(navConfig_t, general.auto_speed) }, + { {1, 6, 46, 37, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {4, 6}, offsetof(navConfig_t, general.max_auto_speed) }, + { {1, 46, 76, 5, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {4, 6}, offsetof(navConfig_t, general.max_auto_climb_rate) }, + { {1, 48, 37, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {4, 6}, offsetof(navConfig_t, general.max_manual_speed) }, + { {1, 48, 76, 5, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {4, 6}, offsetof(navConfig_t, general.max_manual_climb_rate) }, + { {1, 68, 182, 1, 213, 1}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {16, 8}, offsetof(navConfig_t, general.land_minalt_vspd) }, + { {1, 68, 181, 1, 213, 1}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {2, 6}, offsetof(navConfig_t, general.land_maxalt_vspd) }, + { {1, 68, 141, 1, 182, 1}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {16, 3}, offsetof(navConfig_t, general.land_slowdown_minalt) }, + { {1, 68, 141, 1, 181, 1}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {8, 41}, offsetof(navConfig_t, general.land_slowdown_maxalt) }, + { {1, 130, 2, 129, 1, 37}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {2, 6}, offsetof(navConfig_t, general.emerg_descent_rate) }, + { {1, 10, 28, 65, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 20}, offsetof(navConfig_t, general.min_rth_distance) }, + { {1, 221, 2, 58, 130, 3}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_NAV_OVERRIDES_MOTOR_STOP }, offsetof(navConfig_t, general.flags.nav_overrides_motor_stop) }, + { {179, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(navConfig_t, general.flags.soaring_motor_stop) }, + { {1, 2, 255, 2, 11, 29}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 24}, offsetof(navConfig_t, fw.soaring_pitch_deadband) }, + { {1, 28, 76, 162, 1, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_NAV_RTH_CLIMB_FIRST }, offsetof(navConfig_t, general.flags.rth_climb_first) }, + { {191, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_NAV_RTH_CLIMB_FIRST_STAGE_MODES }, offsetof(navConfig_t, general.flags.rth_climb_first_stage_mode) }, + { {190, 2, 0, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 21}, offsetof(navConfig_t, general.rth_climb_first_stage_altitude) }, + { {192, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(navConfig_t, general.flags.rth_climb_ignore_emerg) }, + { {1, 28, 135, 3, 162, 1}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(navConfig_t, general.flags.rth_tail_first) }, + { {1, 28, 218, 1, 129, 1}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_NAV_RTH_ALLOW_LANDING }, offsetof(navConfig_t, general.flags.rth_allow_landing) }, + { {1, 28, 74, 49, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_NAV_RTH_ALT_MODE }, offsetof(navConfig_t, general.flags.rth_alt_control_mode) }, + { {1, 28, 74, 77, 220, 2}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(navConfig_t, general.flags.rth_alt_control_override) }, + { {1, 28, 147, 1, 60, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 21}, offsetof(navConfig_t, general.rth_abort_threshold) }, + { {183, 2, 0, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 3}, offsetof(navConfig_t, general.max_terrain_follow_altitude) }, + { {1, 6, 53, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 21}, offsetof(navConfig_t, general.max_altitude) }, + { {1, 28, 53, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 21}, offsetof(navConfig_t, general.rth_altitude) }, + { {1, 28, 170, 1, 53, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 21}, offsetof(navConfig_t, general.rth_home_altitude) }, + { {1, 28, 208, 1, 49, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_RTH_TRACKBACK_MODE }, offsetof(navConfig_t, general.flags.rth_trackback_mode) }, + { {1, 28, 208, 1, 65, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {16, 6}, offsetof(navConfig_t, general.rth_trackback_distance) }, + { {199, 1, 6, 65, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 21}, offsetof(navConfig_t, general.safehome_max_distance) }, + { {199, 1, 145, 3, 49, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_SAFEHOME_USAGE_MODE }, offsetof(navConfig_t, general.flags.safehome_usage_mode) }, + { {189, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(navConfig_t, general.flags.mission_planner_reset) }, + { {1, 4, 117, 24, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {24, 52}, offsetof(navConfig_t, mc.max_bank_angle) }, + { {1, 46, 102, 33, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {2, 11}, offsetof(navConfig_t, general.auto_disarm_delay) }, + { {1, 4, 55, 37, 60, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 3}, offsetof(navConfig_t, mc.braking_speed_threshold) }, + { {1, 4, 55, 252, 1, 37}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 3}, offsetof(navConfig_t, mc.braking_disengage_speed) }, + { {1, 4, 55, 85, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {2, 20}, offsetof(navConfig_t, mc.braking_timeout) }, + { {1, 4, 55, 75, 160, 1}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 17}, offsetof(navConfig_t, mc.braking_boost_factor) }, + { {1, 4, 55, 75, 85, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 20}, offsetof(navConfig_t, mc.braking_boost_timeout) }, + { {1, 4, 55, 75, 37, 60}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {2, 3}, offsetof(navConfig_t, mc.braking_boost_speed_threshold) }, + { {184, 2, 0, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 3}, offsetof(navConfig_t, mc.braking_boost_disengage_speed) }, + { {1, 4, 55, 117, 24, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {24, 32}, offsetof(navConfig_t, mc.braking_bank_angle) }, + { {1, 4, 23, 242, 1, 25}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 1}, offsetof(navConfig_t, mc.posDecelerationTime) }, + { {1, 4, 23, 56, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 1}, offsetof(navConfig_t, mc.posResponseExpo) }, + { {1, 4, 73, 141, 1, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(navConfig_t, mc.slowDownForTurning) }, + { {1, 2, 117, 24, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {7, 28}, offsetof(navConfig_t, fw.max_bank_angle) }, + { {1, 2, 76, 24, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {7, 28}, offsetof(navConfig_t, fw.max_climb_angle) }, + { {1, 2, 157, 1, 24, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {7, 28}, offsetof(navConfig_t, fw.max_dive_angle) }, + { {1, 2, 135, 1, 201, 1}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 38}, offsetof(navConfig_t, fw.pitch_to_throttle_smooth) }, + { {2, 10, 38, 128, 2, 11}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 59}, offsetof(navConfig_t, fw.minThrottleDownPitchAngle) }, + { {1, 2, 135, 1, 60, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 39}, offsetof(navConfig_t, fw.pitch_to_throttle_thresh) }, + { {1, 2, 177, 1, 193, 1}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 95}, offsetof(navConfig_t, fw.loiter_radius) }, + { {2, 177, 1, 154, 1, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_DIRECTION }, offsetof(navConfig_t, fw.loiter_direction) }, + { {1, 2, 99, 37, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 13}, offsetof(navConfig_t, fw.cruise_speed) }, + { {1, 2, 77, 253, 2, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 38}, offsetof(navConfig_t, fw.control_smoothness) }, + { {1, 2, 68, 157, 1, 24}, VAR_INT8 | MASTER_VALUE, .config.minmax.indexes = {31, 15}, offsetof(navConfig_t, fw.land_dive_angle) }, + { {1, 2, 16, 148, 3, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {2, 11}, offsetof(navConfig_t, fw.launch_velocity_thresh) }, + { {1, 2, 16, 112, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {3, 94}, offsetof(navConfig_t, fw.launch_accel_thresh) }, + { {1, 2, 16, 6, 24, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {7, 29}, offsetof(navConfig_t, fw.launch_max_angle) }, + { {1, 2, 16, 123, 25, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {4, 3}, offsetof(navConfig_t, fw.launch_time_thresh) }, + { {1, 2, 16, 107, 58, 33}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 37}, offsetof(navConfig_t, fw.launch_idle_motor_timer) }, + { {1, 2, 16, 58, 33, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 20}, offsetof(navConfig_t, fw.launch_motor_timer) }, + { {1, 2, 16, 128, 3, 25}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 3}, offsetof(navConfig_t, fw.launch_motor_spinup_time) }, + { {1, 2, 16, 104, 25, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 20}, offsetof(navConfig_t, fw.launch_end_time) }, + { {1, 2, 16, 10, 25, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 37}, offsetof(navConfig_t, fw.launch_min_time) }, + { {1, 2, 16, 85, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 37}, offsetof(navConfig_t, fw.launch_timeout) }, + { {1, 2, 16, 6, 53, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 37}, offsetof(navConfig_t, fw.launch_max_altitude) }, + { {1, 2, 16, 76, 24, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {7, 52}, offsetof(navConfig_t, fw.launch_climb_angle) }, + { {1, 2, 16, 48, 38, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(navConfig_t, fw.launch_manual_throttle) }, + { {1, 2, 16, 147, 1, 29}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {14, 19}, offsetof(navConfig_t, fw.launch_abort_deadband) }, + { {1, 2, 99, 8, 5, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 32}, offsetof(navConfig_t, fw.cruise_yaw_rate) }, + { {177, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(navConfig_t, fw.allow_manual_thr_increase) }, + { {1, 72, 2, 8, 77, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(navConfig_t, fw.useFwNavYawControl) }, + { {1, 2, 8, 29, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 33}, offsetof(navConfig_t, fw.yawControlDeadband) }, + // PG_OSD_CONFIG + { {3, 136, 3, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSD_TELEMETRY }, offsetof(osdConfig_t, telemetry) }, + { {3, 150, 3, 134, 3, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSD_VIDEO_SYSTEM }, offsetof(osdConfig_t, video_system) }, + { {3, 244, 2, 250, 2, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 5}, offsetof(osdConfig_t, row_shiftdown) }, + { {3, 144, 3, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSD_UNIT }, offsetof(osdConfig_t, units) }, + { {3, 71, 124, 111, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSD_STATS_ENERGY_UNIT }, offsetof(osdConfig_t, stats_energy_unit) }, + { {3, 71, 10, 63, 111, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSD_STATS_MIN_VOLTAGE_UNIT }, offsetof(osdConfig_t, stats_min_voltage_unit) }, + { {216, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(osdConfig_t, stats_page_auto_swap_time) }, + { {3, 36, 12, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(osdConfig_t, rssi_alarm) }, + { {3, 25, 12, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 60}, offsetof(osdConfig_t, time_alarm) }, + { {3, 74, 12, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 11}, offsetof(osdConfig_t, alt_alarm) }, + { {3, 156, 1, 12, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 97}, offsetof(osdConfig_t, dist_alarm) }, + { {3, 196, 2, 74, 12, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 11}, offsetof(osdConfig_t, neg_alt_alarm) }, + { {3, 43, 12, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 1}, offsetof(osdConfig_t, current_alarm) }, + { {3, 145, 2, 12, 0, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 15}, offsetof(osdConfig_t, gforce_alarm) }, + { {205, 2, 0, 0, 0, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {31, 15}, offsetof(osdConfig_t, gforce_axis_alarm_min) }, + { {204, 2, 0, 0, 0, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {31, 15}, offsetof(osdConfig_t, gforce_axis_alarm_max) }, + { {3, 34, 51, 12, 10, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {23, 35}, offsetof(osdConfig_t, imu_temp_alarm_min) }, + { {3, 34, 51, 12, 6, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {23, 35}, offsetof(osdConfig_t, imu_temp_alarm_max) }, + { {3, 105, 51, 12, 6, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {23, 40}, offsetof(osdConfig_t, esc_temp_alarm_max) }, + { {3, 105, 51, 12, 10, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {23, 40}, offsetof(osdConfig_t, esc_temp_alarm_min) }, + { {3, 54, 51, 12, 10, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {23, 35}, offsetof(osdConfig_t, baro_temp_alarm_min) }, + { {3, 54, 51, 12, 6, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {23, 35}, offsetof(osdConfig_t, baro_temp_alarm_max) }, + { {3, 254, 2, 12, 0, 0}, VAR_INT8 | MASTER_VALUE, .config.minmax.indexes = {31, 4}, offsetof(osdConfig_t, snr_alarm) }, + { {3, 166, 2, 233, 2, 12}, VAR_INT8 | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(osdConfig_t, link_quality_alarm) }, + { {3, 36, 122, 12, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {45, 0}, offsetof(osdConfig_t, rssi_dbm_alarm) }, + { {3, 36, 122, 6, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {72, 0}, offsetof(osdConfig_t, rssi_dbm_max) }, + { {3, 36, 122, 10, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {45, 0}, offsetof(osdConfig_t, rssi_dbm_min) }, + { {3, 51, 163, 2, 41, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSD_ALIGNMENT }, offsetof(osdConfig_t, temp_label_align) }, + { {3, 91, 12, 10, 0, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 65}, offsetof(osdConfig_t, airspeed_alarm_min) }, + { {3, 91, 12, 6, 0, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 65}, offsetof(osdConfig_t, airspeed_alarm_max) }, + { {3, 40, 240, 2, 18, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(osdConfig_t, ahi_reverse_roll) }, + { {3, 40, 6, 11, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {4, 33}, offsetof(osdConfig_t, ahi_max_pitch) }, + { {3, 237, 1, 204, 1, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSD_CROSSHAIRS_STYLE }, offsetof(osdConfig_t, crosshairs_style) }, + { {202, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSD_CRSF_LQ_FORMAT }, offsetof(osdConfig_t, crsf_lq_format) }, + { {3, 153, 2, 69, 0, 0}, VAR_INT8 | MASTER_VALUE, .config.minmax.indexes = {76, 14}, offsetof(osdConfig_t, horizon_offset) }, + { {3, 93, 211, 1, 0, 0}, VAR_INT8 | MASTER_VALUE, .config.minmax.indexes = {73, 28}, offsetof(osdConfig_t, camera_uptilt) }, + { {3, 40, 93, 211, 1, 98}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(osdConfig_t, ahi_camera_uptilt_comp) }, + { {3, 93, 164, 1, 167, 1}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {32, 55}, offsetof(osdConfig_t, camera_fov_h) }, + { {3, 93, 164, 1, 52, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {18, 53}, offsetof(osdConfig_t, camera_fov_v) }, + { {3, 67, 133, 1, 167, 1}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 12}, offsetof(osdConfig_t, hud_margin_h) }, + { {3, 67, 133, 1, 52, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {5, 26}, offsetof(osdConfig_t, hud_margin_v) }, + { {3, 67, 152, 2, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(osdConfig_t, hud_homing) }, + { {3, 67, 151, 2, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(osdConfig_t, hud_homepoint) }, + { {3, 67, 234, 2, 155, 1}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 12}, offsetof(osdConfig_t, hud_radar_disp) }, + { {210, 2, 0, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {5, 18}, offsetof(osdConfig_t, hud_radar_range_min) }, + { {209, 2, 0, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {2, 91}, offsetof(osdConfig_t, hud_radar_range_max) }, + { {207, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(osdConfig_t, hud_radar_alt_difference_display_time) }, + { {208, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {5, 4}, offsetof(osdConfig_t, hud_radar_distance_display_time) }, + { {3, 67, 73, 155, 1, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 26}, offsetof(osdConfig_t, hud_wp_disp) }, + { {3, 165, 2, 83, 138, 1}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSD_SIDEBAR_SCROLL }, offsetof(osdConfig_t, left_sidebar_scroll) }, + { {3, 241, 2, 83, 138, 1}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSD_SIDEBAR_SCROLL }, offsetof(osdConfig_t, right_sidebar_scroll) }, + { {3, 83, 138, 1, 220, 1}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(osdConfig_t, sidebar_scroll_arrows) }, + { {3, 132, 1, 63, 243, 1}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {5, 14}, offsetof(osdConfig_t, main_voltage_decimals) }, + { {3, 235, 1, 251, 1, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {49, 77}, offsetof(osdConfig_t, coordinate_digits) }, + { {203, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(osdConfig_t, estimations_wind_compensation) }, + { {3, 19, 31, 164, 2, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(osdConfig_t, osd_failsafe_switch_layout) }, + { {213, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {4, 79}, offsetof(osdConfig_t, plus_code_digits) }, + { {214, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSD_PLUS_CODE_SHORT }, offsetof(osdConfig_t, plus_code_short) }, + { {3, 40, 204, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSD_AHI_STYLE }, offsetof(osdConfig_t, ahi_style) }, + { {3, 138, 2, 146, 2, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(osdConfig_t, force_grid) }, + { {3, 40, 225, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(osdConfig_t, ahi_bordered) }, + { {3, 40, 151, 3, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 1}, offsetof(osdConfig_t, ahi_width) }, + { {3, 40, 169, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 1}, offsetof(osdConfig_t, ahi_height) }, + { {3, 40, 149, 3, 69, 0}, VAR_INT8 | MASTER_VALUE, .config.minmax.indexes = {46, 54}, offsetof(osdConfig_t, ahi_vertical_offset) }, + { {3, 83, 154, 2, 69, 0}, VAR_INT8 | MASTER_VALUE, .config.minmax.indexes = {46, 54}, offsetof(osdConfig_t, sidebar_horizontal_offset) }, + { {211, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 1}, offsetof(osdConfig_t, left_sidebar_scroll_step) }, + { {215, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 1}, offsetof(osdConfig_t, right_sidebar_scroll_step) }, + { {3, 83, 169, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 7}, offsetof(osdConfig_t, sidebar_height) }, + { {3, 40, 11, 173, 1, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 18}, offsetof(osdConfig_t, ahi_pitch_interval) }, + { {206, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(osdConfig_t, osd_home_position_arm_screen) }, + { {3, 187, 1, 50, 158, 2}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(osdConfig_t, pan_servo_index) }, + { {3, 187, 1, 50, 232, 2}, VAR_INT8 | MASTER_VALUE, .config.minmax.indexes = {74, 82}, offsetof(osdConfig_t, pan_servo_pwm2centideg) }, + { {3, 105, 245, 2, 228, 2}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {26, 48}, offsetof(osdConfig_t, esc_rpm_precision) }, + { {212, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {12, 48}, offsetof(osdConfig_t, mAh_used_precision) }, + { {3, 31, 47, 88, 81, 0}, VAR_STRING | MASTER_VALUE, .config.minmax.indexes = {0, 7}, offsetof(osdConfig_t, osd_switch_indicator0_name) }, + { {3, 31, 47, 186, 1, 81}, VAR_STRING | MASTER_VALUE, .config.minmax.indexes = {0, 7}, offsetof(osdConfig_t, osd_switch_indicator1_name) }, + { {3, 31, 47, 209, 1, 81}, VAR_STRING | MASTER_VALUE, .config.minmax.indexes = {0, 7}, offsetof(osdConfig_t, osd_switch_indicator2_name) }, + { {3, 31, 47, 205, 1, 81}, VAR_STRING | MASTER_VALUE, .config.minmax.indexes = {0, 7}, offsetof(osdConfig_t, osd_switch_indicator3_name) }, + { {3, 31, 47, 88, 42, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {7, 27}, offsetof(osdConfig_t, osd_switch_indicator0_channel) }, + { {3, 31, 47, 186, 1, 42}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {7, 27}, offsetof(osdConfig_t, osd_switch_indicator1_channel) }, + { {3, 31, 47, 209, 1, 42}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {7, 27}, offsetof(osdConfig_t, osd_switch_indicator2_channel) }, + { {3, 31, 47, 205, 1, 42}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {7, 27}, offsetof(osdConfig_t, osd_switch_indicator3_channel) }, + { {217, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(osdConfig_t, osd_switch_indicators_align_left) }, + { {218, 2, 0, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {8, 20}, offsetof(osdConfig_t, system_msg_display_time) }, + // PG_OSD_COMMON_CONFIG + { {3, 37, 84, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSDSPEEDSOURCE }, offsetof(osdCommonConfig_t, speedSource) }, + // PG_SYSTEM_CONFIG + { {241, 1, 49, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_DEBUG_MODES }, offsetof(systemConfig_t, debug_mode) }, + { {38, 137, 3, 98, 131, 3}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(systemConfig_t, throttle_tilt_compensation_strength) }, + { {81, 0, 0, 0, 0, 0}, VAR_STRING | MASTER_VALUE, .config.minmax.indexes = {0, 80}, offsetof(systemConfig_t, name) }, + // PG_MODE_ACTIVATION_OPERATOR_CONFIG + { {174, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_AUX_OPERATOR }, offsetof(modeActivationOperatorConfig_t, modeActivationOperator) }, + // PG_STATS_CONFIG + { {71, 0, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(statsConfig_t, stats_enabled) }, + { {71, 144, 1, 25, 0, 0}, VAR_UINT32 | MASTER_VALUE, .config.minmax.indexes = {0, 43}, offsetof(statsConfig_t, stats_total_time) }, + { {71, 144, 1, 156, 1, 0}, VAR_UINT32 | MASTER_VALUE, .config.minmax.indexes = {0, 43}, offsetof(statsConfig_t, stats_total_dist) }, + { {71, 144, 1, 124, 0, 0}, VAR_UINT32 | MASTER_VALUE, .config.minmax.indexes = {0, 43}, offsetof(statsConfig_t, stats_total_energy) }, + // PG_TIME_CONFIG + { {210, 1, 69, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {70, 88}, offsetof(timeConfig_t, tz_offset) }, + { {210, 1, 222, 1, 129, 2}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_TZ_AUTOMATIC_DST }, offsetof(timeConfig_t, tz_automatic_dst) }, + // PG_DISPLAY_CONFIG + { {253, 1, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(displayConfig_t, force_sw_blink) }, + // PG_LOG_CONFIG + { {176, 1, 44, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_LOG_LEVEL }, offsetof(logConfig_t, level) }, + { {176, 1, 139, 3, 0, 0}, VAR_UINT32 | MASTER_VALUE, .config.minmax.indexes = {0, 30}, offsetof(logConfig_t, topics) }, + // PG_SMARTPORT_MASTER_CONFIG + { {200, 1, 180, 1, 168, 1}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(smartportMasterConfig_t, halfDuplex) }, + { {200, 1, 180, 1, 128, 1}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(smartportMasterConfig_t, inverted) }, + // PG_DJI_OSD_CONFIG + { {78, 154, 3, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 1}, offsetof(djiOsdConfig_t, proto_workarounds) }, + { {255, 1, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(djiOsdConfig_t, use_name_for_messages) }, + { {78, 105, 51, 84, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_DJIOSDTEMPSOURCE }, offsetof(djiOsdConfig_t, esc_temperature_source) }, + { {78, 169, 2, 37, 84, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSDSPEEDSOURCE }, offsetof(djiOsdConfig_t, messageSpeedSource) }, + { {78, 36, 84, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_DJIRSSISOURCE }, offsetof(djiOsdConfig_t, rssi_source) }, + { {78, 72, 217, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(djiOsdConfig_t, useAdjustments) }, + { {254, 1, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {5, 55}, offsetof(djiOsdConfig_t, craftNameAlternatingDuration) }, + // PG_BEEPER_CONFIG + { {158, 1, 118, 131, 2, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(beeperConfig_t, dshot_beeper_enabled) }, + { {158, 1, 118, 138, 3, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {5, 7}, offsetof(beeperConfig_t, dshot_beeper_tone) }, + { {118, 110, 49, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(beeperConfig_t, pwmMode) }, + // PG_POWER_LIMITS_CONFIG + { {13, 188, 1, 7, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 11}, offsetof(powerLimitsConfig_t, piP) }, + { {13, 188, 1, 22, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 11}, offsetof(powerLimitsConfig_t, piI) }, + { {13, 221, 1, 80, 100, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(powerLimitsConfig_t, attnFilterCutoff) }, +}; diff --git a/src/main/fc/settings_generated.h b/src/main/fc/settings_generated.h new file mode 100644 index 0000000000..2ad7c90104 --- /dev/null +++ b/src/main/fc/settings_generated.h @@ -0,0 +1,2209 @@ +// This file has been automatically generated by utils/settings.rb +// Don't make any modifications to it. They will be lost. + +#pragma once +#define SETTING_MAX_NAME_LENGTH 42 +#define SETTING_MAX_WORD_LENGTH 42 +#define SETTING_ENCODED_NAME_MAX_BYTES 6 +#define SETTINGS_WORDS_BITS_PER_CHAR 5 +#define SETTINGS_TABLE_COUNT 518 +typedef uint16_t setting_offset_t; +#define SETTINGS_PGN_COUNT 41 +typedef int16_t setting_min_t; +typedef uint32_t setting_max_t; +#define SETTING_MIN_MAX_INDEX_BYTES 2 +enum { + TABLE_ACC_HARDWARE, + TABLE_AIRMODEHANDLINGTYPE, + TABLE_ALIGNMENT, + TABLE_AUTOTUNE_RATE_ADJUSTMENT, + TABLE_AUX_OPERATOR, + TABLE_BARO_HARDWARE, + TABLE_BAT_CAPACITY_UNIT, + TABLE_BAT_VOLTAGE_SOURCE, + TABLE_BLACKBOX_DEVICE, + TABLE_CURRENT_SENSOR, + TABLE_DEBUG_MODES, + TABLE_DIRECTION, + TABLE_DJIOSDTEMPSOURCE, + TABLE_DJIRSSISOURCE, + TABLE_FAILSAFE_PROCEDURE, + TABLE_FILTER_TYPE, + TABLE_FILTER_TYPE_FULL, + TABLE_GPS_DYN_MODEL, + TABLE_GPS_PROVIDER, + TABLE_GPS_SBAS_MODE, + TABLE_GYRO_LPF, + TABLE_IMU_INERTIA_COMP_METHOD, + TABLE_ITERM_RELAX, + TABLE_LOG_LEVEL, + TABLE_MAG_HARDWARE, + TABLE_MOTOR_PWM_PROTOCOL, + TABLE_NAV_EXTRA_ARMING_SAFETY, + TABLE_NAV_FW_WP_TURN_SMOOTHING, + TABLE_NAV_OVERRIDES_MOTOR_STOP, + TABLE_NAV_RTH_ALLOW_LANDING, + TABLE_NAV_RTH_ALT_MODE, + TABLE_NAV_RTH_CLIMB_FIRST, + TABLE_NAV_RTH_CLIMB_FIRST_STAGE_MODES, + TABLE_NAV_USER_CONTROL_MODE, + TABLE_NAV_WP_MISSION_RESTART, + TABLE_OFF_ON, + TABLE_OPFLOW_HARDWARE, + TABLE_OSDSPEEDSOURCE, + TABLE_OSD_AHI_STYLE, + TABLE_OSD_ALIGNMENT, + TABLE_OSD_CROSSHAIRS_STYLE, + TABLE_OSD_CRSF_LQ_FORMAT, + TABLE_OSD_PLUS_CODE_SHORT, + TABLE_OSD_SIDEBAR_SCROLL, + TABLE_OSD_STATS_ENERGY_UNIT, + TABLE_OSD_STATS_MIN_VOLTAGE_UNIT, + TABLE_OSD_TELEMETRY, + TABLE_OSD_UNIT, + TABLE_OSD_VIDEO_SYSTEM, + TABLE_OUTPUT_MODE, + TABLE_PIDTYPETABLE, + TABLE_PITOT_HARDWARE, + TABLE_PLATFORM_TYPE, + TABLE_RANGEFINDER_HARDWARE, + TABLE_RECEIVER_TYPE, + TABLE_RESET_TYPE, + TABLE_RSSI_SOURCE, + TABLE_RTH_TRACKBACK_MODE, + TABLE_SAFEHOME_USAGE_MODE, + TABLE_SERIAL_RX, + TABLE_SERVO_PROTOCOL, + TABLE_TRISTATE, + TABLE_TZ_AUTOMATIC_DST, + TABLE_VOLTAGE_SENSOR, + LOOKUP_TABLE_COUNT, +}; +extern const char * const table_acc_hardware[]; +extern const char * const table_airmodeHandlingType[]; +extern const char * const table_alignment[]; +extern const char * const table_autotune_rate_adjustment[]; +extern const char * const table_aux_operator[]; +extern const char * const table_baro_hardware[]; +extern const char * const table_bat_capacity_unit[]; +extern const char * const table_bat_voltage_source[]; +extern const char * const table_blackbox_device[]; +extern const char * const table_current_sensor[]; +extern const char * const table_debug_modes[]; +extern const char * const table_direction[]; +extern const char * const table_djiOsdTempSource[]; +extern const char * const table_djiRssiSource[]; +extern const char * const table_failsafe_procedure[]; +extern const char * const table_filter_type[]; +extern const char * const table_filter_type_full[]; +extern const char * const table_gps_dyn_model[]; +extern const char * const table_gps_provider[]; +extern const char * const table_gps_sbas_mode[]; +extern const char * const table_gyro_lpf[]; +extern const char * const table_imu_inertia_comp_method[]; +extern const char * const table_iterm_relax[]; +extern const char * const table_log_level[]; +extern const char * const table_mag_hardware[]; +extern const char * const table_motor_pwm_protocol[]; +extern const char * const table_nav_extra_arming_safety[]; +extern const char * const table_nav_fw_wp_turn_smoothing[]; +extern const char * const table_nav_overrides_motor_stop[]; +extern const char * const table_nav_rth_allow_landing[]; +extern const char * const table_nav_rth_alt_mode[]; +extern const char * const table_nav_rth_climb_first[]; +extern const char * const table_nav_rth_climb_first_stage_modes[]; +extern const char * const table_nav_user_control_mode[]; +extern const char * const table_nav_wp_mission_restart[]; +extern const char * const table_off_on[]; +extern const char * const table_opflow_hardware[]; +extern const char * const table_osdSpeedSource[]; +extern const char * const table_osd_ahi_style[]; +extern const char * const table_osd_alignment[]; +extern const char * const table_osd_crosshairs_style[]; +extern const char * const table_osd_crsf_lq_format[]; +extern const char * const table_osd_plus_code_short[]; +extern const char * const table_osd_sidebar_scroll[]; +extern const char * const table_osd_stats_energy_unit[]; +extern const char * const table_osd_stats_min_voltage_unit[]; +extern const char * const table_osd_telemetry[]; +extern const char * const table_osd_unit[]; +extern const char * const table_osd_video_system[]; +extern const char * const table_output_mode[]; +extern const char * const table_pidTypeTable[]; +extern const char * const table_pitot_hardware[]; +extern const char * const table_platform_type[]; +extern const char * const table_rangefinder_hardware[]; +extern const char * const table_receiver_type[]; +extern const char * const table_reset_type[]; +extern const char * const table_rssi_source[]; +extern const char * const table_rth_trackback_mode[]; +extern const char * const table_safehome_usage_mode[]; +extern const char * const table_serial_rx[]; +extern const char * const table_servo_protocol[]; +extern const char * const table_tristate[]; +extern const char * const table_tz_automatic_dst[]; +extern const char * const table_voltage_sensor[]; +#define SETTING_CONSTANT_RPYL_PID_MIN 0 +#define SETTING_CONSTANT_RPYL_PID_MAX 255 +#define SETTING_CONSTANT_MANUAL_RATE_MIN 0 +#define SETTING_CONSTANT_MANUAL_RATE_MAX 100 +#define SETTING_CONSTANT_ROLL_PITCH_RATE_MIN 4 +#define SETTING_CONSTANT_ROLL_PITCH_RATE_MAX 180 +#define SETTING_CONSTANT_MAX_CONTROL_RATE_PROFILE_COUNT 3 +#define SETTING_CONSTANT_MAX_BATTERY_PROFILE_COUNT 3 +#define SETTING_LOOPTIME_DEFAULT 1000 +#define SETTING_LOOPTIME 0 +#define SETTING_LOOPTIME_MIN 0 +#define SETTING_LOOPTIME_MAX 9000 +#define SETTING_GYRO_HARDWARE_LPF_DEFAULT 0 +#define SETTING_GYRO_HARDWARE_LPF 1 +#define SETTING_GYRO_HARDWARE_LPF_MIN 0 +#define SETTING_GYRO_HARDWARE_LPF_MAX 0 +#define SETTING_GYRO_ANTI_ALIASING_LPF_HZ_DEFAULT 250 +#define SETTING_GYRO_ANTI_ALIASING_LPF_HZ 2 +#define SETTING_GYRO_ANTI_ALIASING_LPF_HZ_MIN 0 +#define SETTING_GYRO_ANTI_ALIASING_LPF_HZ_MAX 1000 +#define SETTING_GYRO_ANTI_ALIASING_LPF_TYPE_DEFAULT 0 +#define SETTING_GYRO_ANTI_ALIASING_LPF_TYPE 3 +#define SETTING_GYRO_ANTI_ALIASING_LPF_TYPE_MIN 0 +#define SETTING_GYRO_ANTI_ALIASING_LPF_TYPE_MAX 0 +#define SETTING_MORON_THRESHOLD_DEFAULT 32 +#define SETTING_MORON_THRESHOLD 4 +#define SETTING_MORON_THRESHOLD_MIN 0 +#define SETTING_MORON_THRESHOLD_MAX 128 +#define SETTING_GYRO_MAIN_LPF_HZ_DEFAULT 60 +#define SETTING_GYRO_MAIN_LPF_HZ 5 +#define SETTING_GYRO_MAIN_LPF_HZ_MIN 0 +#define SETTING_GYRO_MAIN_LPF_HZ_MAX 500 +#define SETTING_GYRO_MAIN_LPF_TYPE_DEFAULT 1 +#define SETTING_GYRO_MAIN_LPF_TYPE 6 +#define SETTING_GYRO_MAIN_LPF_TYPE_MIN 0 +#define SETTING_GYRO_MAIN_LPF_TYPE_MAX 0 +#define SETTING_GYRO_USE_DYN_LPF_DEFAULT 0 +#define SETTING_GYRO_USE_DYN_LPF 7 +#define SETTING_GYRO_USE_DYN_LPF_MIN 0 +#define SETTING_GYRO_USE_DYN_LPF_MAX 0 +#define SETTING_GYRO_DYN_LPF_MIN_HZ_DEFAULT 200 +#define SETTING_GYRO_DYN_LPF_MIN_HZ 8 +#define SETTING_GYRO_DYN_LPF_MIN_HZ_MIN 40 +#define SETTING_GYRO_DYN_LPF_MIN_HZ_MAX 400 +#define SETTING_GYRO_DYN_LPF_MAX_HZ_DEFAULT 500 +#define SETTING_GYRO_DYN_LPF_MAX_HZ 9 +#define SETTING_GYRO_DYN_LPF_MAX_HZ_MIN 40 +#define SETTING_GYRO_DYN_LPF_MAX_HZ_MAX 1000 +#define SETTING_GYRO_DYN_LPF_CURVE_EXPO_DEFAULT 5 +#define SETTING_GYRO_DYN_LPF_CURVE_EXPO 10 +#define SETTING_GYRO_DYN_LPF_CURVE_EXPO_MIN 1 +#define SETTING_GYRO_DYN_LPF_CURVE_EXPO_MAX 10 +#define SETTING_INIT_GYRO_CAL_DEFAULT 1 +#define SETTING_INIT_GYRO_CAL 11 +#define SETTING_INIT_GYRO_CAL_MIN 0 +#define SETTING_INIT_GYRO_CAL_MAX 0 +#define SETTING_GYRO_ZERO_X_DEFAULT 0 +#define SETTING_GYRO_ZERO_X 12 +#define SETTING_GYRO_ZERO_X_MIN -32768 +#define SETTING_GYRO_ZERO_X_MAX 32767 +#define SETTING_GYRO_ZERO_Y_DEFAULT 0 +#define SETTING_GYRO_ZERO_Y 13 +#define SETTING_GYRO_ZERO_Y_MIN -32768 +#define SETTING_GYRO_ZERO_Y_MAX 32767 +#define SETTING_GYRO_ZERO_Z_DEFAULT 0 +#define SETTING_GYRO_ZERO_Z 14 +#define SETTING_GYRO_ZERO_Z_MIN -32768 +#define SETTING_GYRO_ZERO_Z_MAX 32767 +#define SETTING_INS_GRAVITY_CMSS_DEFAULT 0.0f +#define SETTING_INS_GRAVITY_CMSS 15 +#define SETTING_INS_GRAVITY_CMSS_MIN 0 +#define SETTING_INS_GRAVITY_CMSS_MAX 2000 +#define SETTING_VBAT_ADC_CHANNEL 16 +#define SETTING_VBAT_ADC_CHANNEL_MIN 0 +#define SETTING_VBAT_ADC_CHANNEL_MAX 4 +#define SETTING_RSSI_ADC_CHANNEL 17 +#define SETTING_RSSI_ADC_CHANNEL_MIN 0 +#define SETTING_RSSI_ADC_CHANNEL_MAX 4 +#define SETTING_CURRENT_ADC_CHANNEL 18 +#define SETTING_CURRENT_ADC_CHANNEL_MIN 0 +#define SETTING_CURRENT_ADC_CHANNEL_MAX 4 +#define SETTING_AIRSPEED_ADC_CHANNEL 19 +#define SETTING_AIRSPEED_ADC_CHANNEL_MIN 0 +#define SETTING_AIRSPEED_ADC_CHANNEL_MAX 4 +#define SETTING_ACC_NOTCH_HZ_DEFAULT 0 +#define SETTING_ACC_NOTCH_HZ 20 +#define SETTING_ACC_NOTCH_HZ_MIN 0 +#define SETTING_ACC_NOTCH_HZ_MAX 255 +#define SETTING_ACC_NOTCH_CUTOFF_DEFAULT 1 +#define SETTING_ACC_NOTCH_CUTOFF 21 +#define SETTING_ACC_NOTCH_CUTOFF_MIN 1 +#define SETTING_ACC_NOTCH_CUTOFF_MAX 255 +#define SETTING_ACC_HARDWARE_DEFAULT 1 +#define SETTING_ACC_HARDWARE 22 +#define SETTING_ACC_HARDWARE_MIN 0 +#define SETTING_ACC_HARDWARE_MAX 0 +#define SETTING_ACC_LPF_HZ_DEFAULT 15 +#define SETTING_ACC_LPF_HZ 23 +#define SETTING_ACC_LPF_HZ_MIN 0 +#define SETTING_ACC_LPF_HZ_MAX 200 +#define SETTING_ACC_LPF_TYPE_DEFAULT 1 +#define SETTING_ACC_LPF_TYPE 24 +#define SETTING_ACC_LPF_TYPE_MIN 0 +#define SETTING_ACC_LPF_TYPE_MAX 0 +#define SETTING_ACCZERO_X_DEFAULT 0 +#define SETTING_ACCZERO_X 25 +#define SETTING_ACCZERO_X_MIN -32768 +#define SETTING_ACCZERO_X_MAX 32767 +#define SETTING_ACCZERO_Y_DEFAULT 0 +#define SETTING_ACCZERO_Y 26 +#define SETTING_ACCZERO_Y_MIN -32768 +#define SETTING_ACCZERO_Y_MAX 32767 +#define SETTING_ACCZERO_Z_DEFAULT 0 +#define SETTING_ACCZERO_Z 27 +#define SETTING_ACCZERO_Z_MIN -32768 +#define SETTING_ACCZERO_Z_MAX 32767 +#define SETTING_ACCGAIN_X_DEFAULT 4096 +#define SETTING_ACCGAIN_X 28 +#define SETTING_ACCGAIN_X_MIN 1 +#define SETTING_ACCGAIN_X_MAX 8192 +#define SETTING_ACCGAIN_Y_DEFAULT 4096 +#define SETTING_ACCGAIN_Y 29 +#define SETTING_ACCGAIN_Y_MIN 1 +#define SETTING_ACCGAIN_Y_MAX 8192 +#define SETTING_ACCGAIN_Z_DEFAULT 4096 +#define SETTING_ACCGAIN_Z 30 +#define SETTING_ACCGAIN_Z_MIN 1 +#define SETTING_ACCGAIN_Z_MAX 8192 +#define SETTING_RANGEFINDER_HARDWARE_DEFAULT 0 +#define SETTING_RANGEFINDER_HARDWARE 31 +#define SETTING_RANGEFINDER_HARDWARE_MIN 0 +#define SETTING_RANGEFINDER_HARDWARE_MAX 0 +#define SETTING_RANGEFINDER_MEDIAN_FILTER_DEFAULT 0 +#define SETTING_RANGEFINDER_MEDIAN_FILTER 32 +#define SETTING_RANGEFINDER_MEDIAN_FILTER_MIN 0 +#define SETTING_RANGEFINDER_MEDIAN_FILTER_MAX 0 +#define SETTING_OPFLOW_HARDWARE_DEFAULT 0 +#define SETTING_OPFLOW_HARDWARE 33 +#define SETTING_OPFLOW_HARDWARE_MIN 0 +#define SETTING_OPFLOW_HARDWARE_MAX 0 +#define SETTING_OPFLOW_SCALE_DEFAULT 10.5f +#define SETTING_OPFLOW_SCALE 34 +#define SETTING_OPFLOW_SCALE_MIN 0 +#define SETTING_OPFLOW_SCALE_MAX 10000 +#define SETTING_ALIGN_OPFLOW_DEFAULT 5 +#define SETTING_ALIGN_OPFLOW 35 +#define SETTING_ALIGN_OPFLOW_MIN 0 +#define SETTING_ALIGN_OPFLOW_MAX 0 +#define SETTING_ALIGN_MAG_DEFAULT 0 +#define SETTING_ALIGN_MAG 36 +#define SETTING_ALIGN_MAG_MIN 0 +#define SETTING_ALIGN_MAG_MAX 0 +#define SETTING_MAG_HARDWARE_DEFAULT 1 +#define SETTING_MAG_HARDWARE 37 +#define SETTING_MAG_HARDWARE_MIN 0 +#define SETTING_MAG_HARDWARE_MAX 0 +#define SETTING_MAG_DECLINATION_DEFAULT 0 +#define SETTING_MAG_DECLINATION 38 +#define SETTING_MAG_DECLINATION_MIN -18000 +#define SETTING_MAG_DECLINATION_MAX 18000 +#define SETTING_MAGZERO_X 39 +#define SETTING_MAGZERO_X_MIN -32768 +#define SETTING_MAGZERO_X_MAX 32767 +#define SETTING_MAGZERO_Y 40 +#define SETTING_MAGZERO_Y_MIN -32768 +#define SETTING_MAGZERO_Y_MAX 32767 +#define SETTING_MAGZERO_Z 41 +#define SETTING_MAGZERO_Z_MIN -32768 +#define SETTING_MAGZERO_Z_MAX 32767 +#define SETTING_MAGGAIN_X_DEFAULT 1024 +#define SETTING_MAGGAIN_X 42 +#define SETTING_MAGGAIN_X_MIN -32768 +#define SETTING_MAGGAIN_X_MAX 32767 +#define SETTING_MAGGAIN_Y_DEFAULT 1024 +#define SETTING_MAGGAIN_Y 43 +#define SETTING_MAGGAIN_Y_MIN -32768 +#define SETTING_MAGGAIN_Y_MAX 32767 +#define SETTING_MAGGAIN_Z_DEFAULT 1024 +#define SETTING_MAGGAIN_Z 44 +#define SETTING_MAGGAIN_Z_MIN -32768 +#define SETTING_MAGGAIN_Z_MAX 32767 +#define SETTING_MAG_CALIBRATION_TIME_DEFAULT 30 +#define SETTING_MAG_CALIBRATION_TIME 45 +#define SETTING_MAG_CALIBRATION_TIME_MIN 20 +#define SETTING_MAG_CALIBRATION_TIME_MAX 120 +#define SETTING_ALIGN_MAG_ROLL_DEFAULT 0 +#define SETTING_ALIGN_MAG_ROLL 46 +#define SETTING_ALIGN_MAG_ROLL_MIN -1800 +#define SETTING_ALIGN_MAG_ROLL_MAX 3600 +#define SETTING_ALIGN_MAG_PITCH_DEFAULT 0 +#define SETTING_ALIGN_MAG_PITCH 47 +#define SETTING_ALIGN_MAG_PITCH_MIN -1800 +#define SETTING_ALIGN_MAG_PITCH_MAX 3600 +#define SETTING_ALIGN_MAG_YAW_DEFAULT 0 +#define SETTING_ALIGN_MAG_YAW 48 +#define SETTING_ALIGN_MAG_YAW_MIN -1800 +#define SETTING_ALIGN_MAG_YAW_MAX 3600 +#define SETTING_BARO_HARDWARE_DEFAULT 1 +#define SETTING_BARO_HARDWARE 49 +#define SETTING_BARO_HARDWARE_MIN 0 +#define SETTING_BARO_HARDWARE_MAX 0 +#define SETTING_BARO_CAL_TOLERANCE_DEFAULT 150 +#define SETTING_BARO_CAL_TOLERANCE 50 +#define SETTING_BARO_CAL_TOLERANCE_MIN 0 +#define SETTING_BARO_CAL_TOLERANCE_MAX 1000 +#define SETTING_PITOT_HARDWARE_DEFAULT 0 +#define SETTING_PITOT_HARDWARE 51 +#define SETTING_PITOT_HARDWARE_MIN 0 +#define SETTING_PITOT_HARDWARE_MAX 0 +#define SETTING_PITOT_LPF_MILLI_HZ_DEFAULT 350 +#define SETTING_PITOT_LPF_MILLI_HZ 52 +#define SETTING_PITOT_LPF_MILLI_HZ_MIN 0 +#define SETTING_PITOT_LPF_MILLI_HZ_MAX 10000 +#define SETTING_PITOT_SCALE_DEFAULT 1.0f +#define SETTING_PITOT_SCALE 53 +#define SETTING_PITOT_SCALE_MIN 0 +#define SETTING_PITOT_SCALE_MAX 100 +#define SETTING_RECEIVER_TYPE 54 +#define SETTING_RECEIVER_TYPE_MIN 0 +#define SETTING_RECEIVER_TYPE_MAX 0 +#define SETTING_MIN_CHECK_DEFAULT 1100 +#define SETTING_MIN_CHECK 55 +#define SETTING_MIN_CHECK_MIN 1000 +#define SETTING_MIN_CHECK_MAX 2000 +#define SETTING_MAX_CHECK_DEFAULT 1900 +#define SETTING_MAX_CHECK 56 +#define SETTING_MAX_CHECK_MIN 1000 +#define SETTING_MAX_CHECK_MAX 2000 +#define SETTING_RSSI_SOURCE_DEFAULT 1 +#define SETTING_RSSI_SOURCE 57 +#define SETTING_RSSI_SOURCE_MIN 0 +#define SETTING_RSSI_SOURCE_MAX 0 +#define SETTING_RSSI_CHANNEL_DEFAULT 0 +#define SETTING_RSSI_CHANNEL 58 +#define SETTING_RSSI_CHANNEL_MIN 0 +#define SETTING_RSSI_CHANNEL_MAX 18 +#define SETTING_RSSI_MIN_DEFAULT 0 +#define SETTING_RSSI_MIN 59 +#define SETTING_RSSI_MIN_MIN 0 +#define SETTING_RSSI_MIN_MAX 100 +#define SETTING_RSSI_MAX_DEFAULT 100 +#define SETTING_RSSI_MAX 60 +#define SETTING_RSSI_MAX_MIN 0 +#define SETTING_RSSI_MAX_MAX 100 +#define SETTING_SBUS_SYNC_INTERVAL_DEFAULT 3000 +#define SETTING_SBUS_SYNC_INTERVAL 61 +#define SETTING_SBUS_SYNC_INTERVAL_MIN 500 +#define SETTING_SBUS_SYNC_INTERVAL_MAX 10000 +#define SETTING_RC_FILTER_LPF_HZ_DEFAULT 50 +#define SETTING_RC_FILTER_LPF_HZ 62 +#define SETTING_RC_FILTER_LPF_HZ_MIN 15 +#define SETTING_RC_FILTER_LPF_HZ_MAX 250 +#define SETTING_RC_FILTER_AUTO_DEFAULT 0 +#define SETTING_RC_FILTER_AUTO 63 +#define SETTING_RC_FILTER_AUTO_MIN 0 +#define SETTING_RC_FILTER_AUTO_MAX 0 +#define SETTING_RC_FILTER_SMOOTHING_FACTOR_DEFAULT 30 +#define SETTING_RC_FILTER_SMOOTHING_FACTOR 64 +#define SETTING_RC_FILTER_SMOOTHING_FACTOR_MIN 1 +#define SETTING_RC_FILTER_SMOOTHING_FACTOR_MAX 100 +#define SETTING_SERIALRX_PROVIDER 65 +#define SETTING_SERIALRX_PROVIDER_MIN 0 +#define SETTING_SERIALRX_PROVIDER_MAX 0 +#define SETTING_SERIALRX_INVERTED_DEFAULT 0 +#define SETTING_SERIALRX_INVERTED 66 +#define SETTING_SERIALRX_INVERTED_MIN 0 +#define SETTING_SERIALRX_INVERTED_MAX 0 +#define SETTING_SRXL2_UNIT_ID_DEFAULT 1 +#define SETTING_SRXL2_UNIT_ID 67 +#define SETTING_SRXL2_UNIT_ID_MIN 0 +#define SETTING_SRXL2_UNIT_ID_MAX 15 +#define SETTING_SRXL2_BAUD_FAST_DEFAULT 1 +#define SETTING_SRXL2_BAUD_FAST 68 +#define SETTING_SRXL2_BAUD_FAST_MIN 0 +#define SETTING_SRXL2_BAUD_FAST_MAX 0 +#define SETTING_RX_MIN_USEC_DEFAULT 885 +#define SETTING_RX_MIN_USEC 69 +#define SETTING_RX_MIN_USEC_MIN 750 +#define SETTING_RX_MIN_USEC_MAX 2250 +#define SETTING_RX_MAX_USEC_DEFAULT 2115 +#define SETTING_RX_MAX_USEC 70 +#define SETTING_RX_MAX_USEC_MIN 750 +#define SETTING_RX_MAX_USEC_MAX 2250 +#define SETTING_SERIALRX_HALFDUPLEX_DEFAULT 0 +#define SETTING_SERIALRX_HALFDUPLEX 71 +#define SETTING_SERIALRX_HALFDUPLEX_MIN 0 +#define SETTING_SERIALRX_HALFDUPLEX_MAX 0 +#define SETTING_BLACKBOX_RATE_NUM_DEFAULT 1 +#define SETTING_BLACKBOX_RATE_NUM 72 +#define SETTING_BLACKBOX_RATE_NUM_MIN 1 +#define SETTING_BLACKBOX_RATE_NUM_MAX 65535 +#define SETTING_BLACKBOX_RATE_DENOM_DEFAULT 1 +#define SETTING_BLACKBOX_RATE_DENOM 73 +#define SETTING_BLACKBOX_RATE_DENOM_MIN 1 +#define SETTING_BLACKBOX_RATE_DENOM_MAX 65535 +#define SETTING_BLACKBOX_DEVICE 74 +#define SETTING_BLACKBOX_DEVICE_MIN 0 +#define SETTING_BLACKBOX_DEVICE_MAX 0 +#define SETTING_MAX_THROTTLE_DEFAULT 1850 +#define SETTING_MAX_THROTTLE 75 +#define SETTING_MAX_THROTTLE_MIN 1000 +#define SETTING_MAX_THROTTLE_MAX 2000 +#define SETTING_MIN_COMMAND_DEFAULT 1000 +#define SETTING_MIN_COMMAND 76 +#define SETTING_MIN_COMMAND_MIN 0 +#define SETTING_MIN_COMMAND_MAX 2000 +#define SETTING_MOTOR_PWM_RATE_DEFAULT 16000 +#define SETTING_MOTOR_PWM_RATE 77 +#define SETTING_MOTOR_PWM_RATE_MIN 50 +#define SETTING_MOTOR_PWM_RATE_MAX 32000 +#define SETTING_MOTOR_PWM_PROTOCOL_DEFAULT 1 +#define SETTING_MOTOR_PWM_PROTOCOL 78 +#define SETTING_MOTOR_PWM_PROTOCOL_MIN 0 +#define SETTING_MOTOR_PWM_PROTOCOL_MAX 0 +#define SETTING_MOTOR_POLES_DEFAULT 14 +#define SETTING_MOTOR_POLES 79 +#define SETTING_MOTOR_POLES_MIN 4 +#define SETTING_MOTOR_POLES_MAX 255 +#define SETTING_FAILSAFE_DELAY_DEFAULT 5 +#define SETTING_FAILSAFE_DELAY 80 +#define SETTING_FAILSAFE_DELAY_MIN 0 +#define SETTING_FAILSAFE_DELAY_MAX 200 +#define SETTING_FAILSAFE_RECOVERY_DELAY_DEFAULT 5 +#define SETTING_FAILSAFE_RECOVERY_DELAY 81 +#define SETTING_FAILSAFE_RECOVERY_DELAY_MIN 0 +#define SETTING_FAILSAFE_RECOVERY_DELAY_MAX 200 +#define SETTING_FAILSAFE_OFF_DELAY_DEFAULT 200 +#define SETTING_FAILSAFE_OFF_DELAY 82 +#define SETTING_FAILSAFE_OFF_DELAY_MIN 0 +#define SETTING_FAILSAFE_OFF_DELAY_MAX 200 +#define SETTING_FAILSAFE_THROTTLE_LOW_DELAY_DEFAULT 0 +#define SETTING_FAILSAFE_THROTTLE_LOW_DELAY 83 +#define SETTING_FAILSAFE_THROTTLE_LOW_DELAY_MIN 0 +#define SETTING_FAILSAFE_THROTTLE_LOW_DELAY_MAX 300 +#define SETTING_FAILSAFE_PROCEDURE_DEFAULT 0 +#define SETTING_FAILSAFE_PROCEDURE 84 +#define SETTING_FAILSAFE_PROCEDURE_MIN 0 +#define SETTING_FAILSAFE_PROCEDURE_MAX 0 +#define SETTING_FAILSAFE_STICK_THRESHOLD_DEFAULT 50 +#define SETTING_FAILSAFE_STICK_THRESHOLD 85 +#define SETTING_FAILSAFE_STICK_THRESHOLD_MIN 0 +#define SETTING_FAILSAFE_STICK_THRESHOLD_MAX 500 +#define SETTING_FAILSAFE_FW_ROLL_ANGLE_DEFAULT -200 +#define SETTING_FAILSAFE_FW_ROLL_ANGLE 86 +#define SETTING_FAILSAFE_FW_ROLL_ANGLE_MIN -800 +#define SETTING_FAILSAFE_FW_ROLL_ANGLE_MAX 800 +#define SETTING_FAILSAFE_FW_PITCH_ANGLE_DEFAULT 100 +#define SETTING_FAILSAFE_FW_PITCH_ANGLE 87 +#define SETTING_FAILSAFE_FW_PITCH_ANGLE_MIN -800 +#define SETTING_FAILSAFE_FW_PITCH_ANGLE_MAX 800 +#define SETTING_FAILSAFE_FW_YAW_RATE_DEFAULT -45 +#define SETTING_FAILSAFE_FW_YAW_RATE 88 +#define SETTING_FAILSAFE_FW_YAW_RATE_MIN -1000 +#define SETTING_FAILSAFE_FW_YAW_RATE_MAX 1000 +#define SETTING_FAILSAFE_MIN_DISTANCE_DEFAULT 0 +#define SETTING_FAILSAFE_MIN_DISTANCE 89 +#define SETTING_FAILSAFE_MIN_DISTANCE_MIN 0 +#define SETTING_FAILSAFE_MIN_DISTANCE_MAX 65000 +#define SETTING_FAILSAFE_MIN_DISTANCE_PROCEDURE_DEFAULT 1 +#define SETTING_FAILSAFE_MIN_DISTANCE_PROCEDURE 90 +#define SETTING_FAILSAFE_MIN_DISTANCE_PROCEDURE_MIN 0 +#define SETTING_FAILSAFE_MIN_DISTANCE_PROCEDURE_MAX 0 +#define SETTING_FAILSAFE_MISSION_DELAY_DEFAULT 0 +#define SETTING_FAILSAFE_MISSION_DELAY 91 +#define SETTING_FAILSAFE_MISSION_DELAY_MIN -1 +#define SETTING_FAILSAFE_MISSION_DELAY_MAX 600 +#define SETTING_ALIGN_BOARD_ROLL 92 +#define SETTING_ALIGN_BOARD_ROLL_MIN -1800 +#define SETTING_ALIGN_BOARD_ROLL_MAX 3600 +#define SETTING_ALIGN_BOARD_PITCH 93 +#define SETTING_ALIGN_BOARD_PITCH_MIN -1800 +#define SETTING_ALIGN_BOARD_PITCH_MAX 3600 +#define SETTING_ALIGN_BOARD_YAW 94 +#define SETTING_ALIGN_BOARD_YAW_MIN -1800 +#define SETTING_ALIGN_BOARD_YAW_MAX 3600 +#define SETTING_VBAT_METER_TYPE_DEFAULT 1 +#define SETTING_VBAT_METER_TYPE 95 +#define SETTING_VBAT_METER_TYPE_MIN 0 +#define SETTING_VBAT_METER_TYPE_MAX 0 +#define SETTING_VBAT_SCALE 96 +#define SETTING_VBAT_SCALE_MIN 0 +#define SETTING_VBAT_SCALE_MAX 65535 +#define SETTING_CURRENT_METER_SCALE 97 +#define SETTING_CURRENT_METER_SCALE_MIN -10000 +#define SETTING_CURRENT_METER_SCALE_MAX 10000 +#define SETTING_CURRENT_METER_OFFSET 98 +#define SETTING_CURRENT_METER_OFFSET_MIN -32768 +#define SETTING_CURRENT_METER_OFFSET_MAX 32767 +#define SETTING_CURRENT_METER_TYPE_DEFAULT 1 +#define SETTING_CURRENT_METER_TYPE 99 +#define SETTING_CURRENT_METER_TYPE_MIN 0 +#define SETTING_CURRENT_METER_TYPE_MAX 0 +#define SETTING_BAT_VOLTAGE_SRC_DEFAULT 0 +#define SETTING_BAT_VOLTAGE_SRC 100 +#define SETTING_BAT_VOLTAGE_SRC_MIN 0 +#define SETTING_BAT_VOLTAGE_SRC_MAX 0 +#define SETTING_CRUISE_POWER_DEFAULT 0 +#define SETTING_CRUISE_POWER 101 +#define SETTING_CRUISE_POWER_MIN 0 +#define SETTING_CRUISE_POWER_MAX 4294967295 +#define SETTING_IDLE_POWER_DEFAULT 0 +#define SETTING_IDLE_POWER 102 +#define SETTING_IDLE_POWER_MIN 0 +#define SETTING_IDLE_POWER_MAX 65535 +#define SETTING_RTH_ENERGY_MARGIN_DEFAULT 5 +#define SETTING_RTH_ENERGY_MARGIN 103 +#define SETTING_RTH_ENERGY_MARGIN_MIN 0 +#define SETTING_RTH_ENERGY_MARGIN_MAX 100 +#define SETTING_THR_COMP_WEIGHT_DEFAULT 1 +#define SETTING_THR_COMP_WEIGHT 104 +#define SETTING_THR_COMP_WEIGHT_MIN 0 +#define SETTING_THR_COMP_WEIGHT_MAX 2 +#define SETTING_BAT_CELLS_DEFAULT 0 +#define SETTING_BAT_CELLS 105 +#define SETTING_BAT_CELLS_MIN 0 +#define SETTING_BAT_CELLS_MAX 12 +#define SETTING_VBAT_CELL_DETECT_VOLTAGE_DEFAULT 425 +#define SETTING_VBAT_CELL_DETECT_VOLTAGE 106 +#define SETTING_VBAT_CELL_DETECT_VOLTAGE_MIN 100 +#define SETTING_VBAT_CELL_DETECT_VOLTAGE_MAX 500 +#define SETTING_VBAT_MAX_CELL_VOLTAGE_DEFAULT 420 +#define SETTING_VBAT_MAX_CELL_VOLTAGE 107 +#define SETTING_VBAT_MAX_CELL_VOLTAGE_MIN 100 +#define SETTING_VBAT_MAX_CELL_VOLTAGE_MAX 500 +#define SETTING_VBAT_MIN_CELL_VOLTAGE_DEFAULT 330 +#define SETTING_VBAT_MIN_CELL_VOLTAGE 108 +#define SETTING_VBAT_MIN_CELL_VOLTAGE_MIN 100 +#define SETTING_VBAT_MIN_CELL_VOLTAGE_MAX 500 +#define SETTING_VBAT_WARNING_CELL_VOLTAGE_DEFAULT 350 +#define SETTING_VBAT_WARNING_CELL_VOLTAGE 109 +#define SETTING_VBAT_WARNING_CELL_VOLTAGE_MIN 100 +#define SETTING_VBAT_WARNING_CELL_VOLTAGE_MAX 500 +#define SETTING_BATTERY_CAPACITY_DEFAULT 0 +#define SETTING_BATTERY_CAPACITY 110 +#define SETTING_BATTERY_CAPACITY_MIN 0 +#define SETTING_BATTERY_CAPACITY_MAX 4294967295 +#define SETTING_BATTERY_CAPACITY_WARNING_DEFAULT 0 +#define SETTING_BATTERY_CAPACITY_WARNING 111 +#define SETTING_BATTERY_CAPACITY_WARNING_MIN 0 +#define SETTING_BATTERY_CAPACITY_WARNING_MAX 4294967295 +#define SETTING_BATTERY_CAPACITY_CRITICAL_DEFAULT 0 +#define SETTING_BATTERY_CAPACITY_CRITICAL 112 +#define SETTING_BATTERY_CAPACITY_CRITICAL_MIN 0 +#define SETTING_BATTERY_CAPACITY_CRITICAL_MAX 4294967295 +#define SETTING_BATTERY_CAPACITY_UNIT_DEFAULT 0 +#define SETTING_BATTERY_CAPACITY_UNIT 113 +#define SETTING_BATTERY_CAPACITY_UNIT_MIN 0 +#define SETTING_BATTERY_CAPACITY_UNIT_MAX 0 +#define SETTING_CONTROLRATE_PROFILE_DEFAULT 0 +#define SETTING_CONTROLRATE_PROFILE 114 +#define SETTING_CONTROLRATE_PROFILE_MIN 0 +#define SETTING_CONTROLRATE_PROFILE_MAX 3 +#define SETTING_THROTTLE_SCALE_DEFAULT 1.0f +#define SETTING_THROTTLE_SCALE 115 +#define SETTING_THROTTLE_SCALE_MIN 0 +#define SETTING_THROTTLE_SCALE_MAX 1 +#define SETTING_THROTTLE_IDLE_DEFAULT 15 +#define SETTING_THROTTLE_IDLE 116 +#define SETTING_THROTTLE_IDLE_MIN 0 +#define SETTING_THROTTLE_IDLE_MAX 30 +#define SETTING_FAILSAFE_THROTTLE_DEFAULT 1000 +#define SETTING_FAILSAFE_THROTTLE 117 +#define SETTING_FAILSAFE_THROTTLE_MIN 1000 +#define SETTING_FAILSAFE_THROTTLE_MAX 2000 +#define SETTING_NAV_MC_HOVER_THR_DEFAULT 1500 +#define SETTING_NAV_MC_HOVER_THR 118 +#define SETTING_NAV_MC_HOVER_THR_MIN 1000 +#define SETTING_NAV_MC_HOVER_THR_MAX 2000 +#define SETTING_NAV_FW_CRUISE_THR_DEFAULT 1400 +#define SETTING_NAV_FW_CRUISE_THR 119 +#define SETTING_NAV_FW_CRUISE_THR_MIN 1000 +#define SETTING_NAV_FW_CRUISE_THR_MAX 2000 +#define SETTING_NAV_FW_MIN_THR_DEFAULT 1200 +#define SETTING_NAV_FW_MIN_THR 120 +#define SETTING_NAV_FW_MIN_THR_MIN 1000 +#define SETTING_NAV_FW_MIN_THR_MAX 2000 +#define SETTING_NAV_FW_MAX_THR_DEFAULT 1700 +#define SETTING_NAV_FW_MAX_THR 121 +#define SETTING_NAV_FW_MAX_THR_MIN 1000 +#define SETTING_NAV_FW_MAX_THR_MAX 2000 +#define SETTING_NAV_FW_PITCH2THR_DEFAULT 10 +#define SETTING_NAV_FW_PITCH2THR 122 +#define SETTING_NAV_FW_PITCH2THR_MIN 0 +#define SETTING_NAV_FW_PITCH2THR_MAX 100 +#define SETTING_NAV_FW_LAUNCH_THR_DEFAULT 1700 +#define SETTING_NAV_FW_LAUNCH_THR 123 +#define SETTING_NAV_FW_LAUNCH_THR_MIN 1000 +#define SETTING_NAV_FW_LAUNCH_THR_MAX 2000 +#define SETTING_NAV_FW_LAUNCH_IDLE_THR_DEFAULT 1000 +#define SETTING_NAV_FW_LAUNCH_IDLE_THR 124 +#define SETTING_NAV_FW_LAUNCH_IDLE_THR_MIN 1000 +#define SETTING_NAV_FW_LAUNCH_IDLE_THR_MAX 2000 +#define SETTING_LIMIT_CONT_CURRENT_DEFAULT 0 +#define SETTING_LIMIT_CONT_CURRENT 125 +#define SETTING_LIMIT_CONT_CURRENT_MIN 0 +#define SETTING_LIMIT_CONT_CURRENT_MAX 4000 +#define SETTING_LIMIT_BURST_CURRENT_DEFAULT 0 +#define SETTING_LIMIT_BURST_CURRENT 126 +#define SETTING_LIMIT_BURST_CURRENT_MIN 0 +#define SETTING_LIMIT_BURST_CURRENT_MAX 4000 +#define SETTING_LIMIT_BURST_CURRENT_TIME_DEFAULT 0 +#define SETTING_LIMIT_BURST_CURRENT_TIME 127 +#define SETTING_LIMIT_BURST_CURRENT_TIME_MIN 0 +#define SETTING_LIMIT_BURST_CURRENT_TIME_MAX 3000 +#define SETTING_LIMIT_BURST_CURRENT_FALLDOWN_TIME_DEFAULT 0 +#define SETTING_LIMIT_BURST_CURRENT_FALLDOWN_TIME 128 +#define SETTING_LIMIT_BURST_CURRENT_FALLDOWN_TIME_MIN 0 +#define SETTING_LIMIT_BURST_CURRENT_FALLDOWN_TIME_MAX 3000 +#define SETTING_LIMIT_CONT_POWER_DEFAULT 0 +#define SETTING_LIMIT_CONT_POWER 129 +#define SETTING_LIMIT_CONT_POWER_MIN 0 +#define SETTING_LIMIT_CONT_POWER_MAX 40000 +#define SETTING_LIMIT_BURST_POWER_DEFAULT 0 +#define SETTING_LIMIT_BURST_POWER 130 +#define SETTING_LIMIT_BURST_POWER_MIN 0 +#define SETTING_LIMIT_BURST_POWER_MAX 40000 +#define SETTING_LIMIT_BURST_POWER_TIME_DEFAULT 0 +#define SETTING_LIMIT_BURST_POWER_TIME 131 +#define SETTING_LIMIT_BURST_POWER_TIME_MIN 0 +#define SETTING_LIMIT_BURST_POWER_TIME_MAX 3000 +#define SETTING_LIMIT_BURST_POWER_FALLDOWN_TIME_DEFAULT 0 +#define SETTING_LIMIT_BURST_POWER_FALLDOWN_TIME 132 +#define SETTING_LIMIT_BURST_POWER_FALLDOWN_TIME_MIN 0 +#define SETTING_LIMIT_BURST_POWER_FALLDOWN_TIME_MAX 3000 +#define SETTING_MOTOR_DIRECTION_INVERTED_DEFAULT 0 +#define SETTING_MOTOR_DIRECTION_INVERTED 133 +#define SETTING_MOTOR_DIRECTION_INVERTED_MIN 0 +#define SETTING_MOTOR_DIRECTION_INVERTED_MAX 0 +#define SETTING_PLATFORM_TYPE_DEFAULT 0 +#define SETTING_PLATFORM_TYPE 134 +#define SETTING_PLATFORM_TYPE_MIN 0 +#define SETTING_PLATFORM_TYPE_MAX 0 +#define SETTING_HAS_FLAPS_DEFAULT 0 +#define SETTING_HAS_FLAPS 135 +#define SETTING_HAS_FLAPS_MIN 0 +#define SETTING_HAS_FLAPS_MAX 0 +#define SETTING_MODEL_PREVIEW_TYPE_DEFAULT -1 +#define SETTING_MODEL_PREVIEW_TYPE 136 +#define SETTING_MODEL_PREVIEW_TYPE_MIN -1 +#define SETTING_MODEL_PREVIEW_TYPE_MAX 32767 +#define SETTING_OUTPUT_MODE_DEFAULT 0 +#define SETTING_OUTPUT_MODE 137 +#define SETTING_OUTPUT_MODE_MIN 0 +#define SETTING_OUTPUT_MODE_MAX 0 +#define SETTING_3D_DEADBAND_LOW_DEFAULT 1406 +#define SETTING_3D_DEADBAND_LOW 138 +#define SETTING_3D_DEADBAND_LOW_MIN 1000 +#define SETTING_3D_DEADBAND_LOW_MAX 2000 +#define SETTING_3D_DEADBAND_HIGH_DEFAULT 1514 +#define SETTING_3D_DEADBAND_HIGH 139 +#define SETTING_3D_DEADBAND_HIGH_MIN 1000 +#define SETTING_3D_DEADBAND_HIGH_MAX 2000 +#define SETTING_3D_NEUTRAL_DEFAULT 1460 +#define SETTING_3D_NEUTRAL 140 +#define SETTING_3D_NEUTRAL_MIN 1000 +#define SETTING_3D_NEUTRAL_MAX 2000 +#define SETTING_SERVO_PROTOCOL_DEFAULT 0 +#define SETTING_SERVO_PROTOCOL 141 +#define SETTING_SERVO_PROTOCOL_MIN 0 +#define SETTING_SERVO_PROTOCOL_MAX 0 +#define SETTING_SERVO_CENTER_PULSE_DEFAULT 1500 +#define SETTING_SERVO_CENTER_PULSE 142 +#define SETTING_SERVO_CENTER_PULSE_MIN 1000 +#define SETTING_SERVO_CENTER_PULSE_MAX 2000 +#define SETTING_SERVO_PWM_RATE_DEFAULT 50 +#define SETTING_SERVO_PWM_RATE 143 +#define SETTING_SERVO_PWM_RATE_MIN 50 +#define SETTING_SERVO_PWM_RATE_MAX 498 +#define SETTING_SERVO_LPF_HZ_DEFAULT 20 +#define SETTING_SERVO_LPF_HZ 144 +#define SETTING_SERVO_LPF_HZ_MIN 0 +#define SETTING_SERVO_LPF_HZ_MAX 400 +#define SETTING_FLAPERON_THROW_OFFSET_DEFAULT 200 +#define SETTING_FLAPERON_THROW_OFFSET 145 +#define SETTING_FLAPERON_THROW_OFFSET_MIN 50 +#define SETTING_FLAPERON_THROW_OFFSET_MAX 450 +#define SETTING_TRI_UNARMED_SERVO_DEFAULT 1 +#define SETTING_TRI_UNARMED_SERVO 146 +#define SETTING_TRI_UNARMED_SERVO_MIN 0 +#define SETTING_TRI_UNARMED_SERVO_MAX 0 +#define SETTING_SERVO_AUTOTRIM_ROTATION_LIMIT_DEFAULT 15 +#define SETTING_SERVO_AUTOTRIM_ROTATION_LIMIT 147 +#define SETTING_SERVO_AUTOTRIM_ROTATION_LIMIT_MIN 1 +#define SETTING_SERVO_AUTOTRIM_ROTATION_LIMIT_MAX 60 +#define SETTING_THR_MID_DEFAULT 50 +#define SETTING_THR_MID 148 +#define SETTING_THR_MID_MIN 0 +#define SETTING_THR_MID_MAX 100 +#define SETTING_THR_EXPO_DEFAULT 0 +#define SETTING_THR_EXPO 149 +#define SETTING_THR_EXPO_MIN 0 +#define SETTING_THR_EXPO_MAX 100 +#define SETTING_TPA_RATE_DEFAULT 0 +#define SETTING_TPA_RATE 150 +#define SETTING_TPA_RATE_MIN 0 +#define SETTING_TPA_RATE_MAX 100 +#define SETTING_TPA_BREAKPOINT_DEFAULT 1500 +#define SETTING_TPA_BREAKPOINT 151 +#define SETTING_TPA_BREAKPOINT_MIN 1000 +#define SETTING_TPA_BREAKPOINT_MAX 2000 +#define SETTING_FW_TPA_TIME_CONSTANT_DEFAULT 1500 +#define SETTING_FW_TPA_TIME_CONSTANT 152 +#define SETTING_FW_TPA_TIME_CONSTANT_MIN 0 +#define SETTING_FW_TPA_TIME_CONSTANT_MAX 5000 +#define SETTING_RC_EXPO_DEFAULT 70 +#define SETTING_RC_EXPO 153 +#define SETTING_RC_EXPO_MIN 0 +#define SETTING_RC_EXPO_MAX 100 +#define SETTING_RC_YAW_EXPO_DEFAULT 20 +#define SETTING_RC_YAW_EXPO 154 +#define SETTING_RC_YAW_EXPO_MIN 0 +#define SETTING_RC_YAW_EXPO_MAX 100 +#define SETTING_ROLL_RATE_DEFAULT 20 +#define SETTING_ROLL_RATE 155 +#define SETTING_ROLL_RATE_MIN 4 +#define SETTING_ROLL_RATE_MAX 180 +#define SETTING_PITCH_RATE_DEFAULT 20 +#define SETTING_PITCH_RATE 156 +#define SETTING_PITCH_RATE_MIN 4 +#define SETTING_PITCH_RATE_MAX 180 +#define SETTING_YAW_RATE_DEFAULT 20 +#define SETTING_YAW_RATE 157 +#define SETTING_YAW_RATE_MIN 1 +#define SETTING_YAW_RATE_MAX 180 +#define SETTING_MANUAL_RC_EXPO_DEFAULT 35 +#define SETTING_MANUAL_RC_EXPO 158 +#define SETTING_MANUAL_RC_EXPO_MIN 0 +#define SETTING_MANUAL_RC_EXPO_MAX 100 +#define SETTING_MANUAL_RC_YAW_EXPO_DEFAULT 20 +#define SETTING_MANUAL_RC_YAW_EXPO 159 +#define SETTING_MANUAL_RC_YAW_EXPO_MIN 0 +#define SETTING_MANUAL_RC_YAW_EXPO_MAX 100 +#define SETTING_MANUAL_ROLL_RATE_DEFAULT 100 +#define SETTING_MANUAL_ROLL_RATE 160 +#define SETTING_MANUAL_ROLL_RATE_MIN 0 +#define SETTING_MANUAL_ROLL_RATE_MAX 100 +#define SETTING_MANUAL_PITCH_RATE_DEFAULT 100 +#define SETTING_MANUAL_PITCH_RATE 161 +#define SETTING_MANUAL_PITCH_RATE_MIN 0 +#define SETTING_MANUAL_PITCH_RATE_MAX 100 +#define SETTING_MANUAL_YAW_RATE_DEFAULT 100 +#define SETTING_MANUAL_YAW_RATE 162 +#define SETTING_MANUAL_YAW_RATE_MIN 0 +#define SETTING_MANUAL_YAW_RATE_MAX 100 +#define SETTING_FPV_MIX_DEGREES_DEFAULT 0 +#define SETTING_FPV_MIX_DEGREES 163 +#define SETTING_FPV_MIX_DEGREES_MIN 0 +#define SETTING_FPV_MIX_DEGREES_MAX 50 +#define SETTING_RATE_DYNAMICS_CENTER_SENSITIVITY_DEFAULT 100 +#define SETTING_RATE_DYNAMICS_CENTER_SENSITIVITY 164 +#define SETTING_RATE_DYNAMICS_CENTER_SENSITIVITY_MIN 25 +#define SETTING_RATE_DYNAMICS_CENTER_SENSITIVITY_MAX 175 +#define SETTING_RATE_DYNAMICS_END_SENSITIVITY_DEFAULT 100 +#define SETTING_RATE_DYNAMICS_END_SENSITIVITY 165 +#define SETTING_RATE_DYNAMICS_END_SENSITIVITY_MIN 25 +#define SETTING_RATE_DYNAMICS_END_SENSITIVITY_MAX 175 +#define SETTING_RATE_DYNAMICS_CENTER_CORRECTION_DEFAULT 10 +#define SETTING_RATE_DYNAMICS_CENTER_CORRECTION 166 +#define SETTING_RATE_DYNAMICS_CENTER_CORRECTION_MIN 10 +#define SETTING_RATE_DYNAMICS_CENTER_CORRECTION_MAX 95 +#define SETTING_RATE_DYNAMICS_END_CORRECTION_DEFAULT 10 +#define SETTING_RATE_DYNAMICS_END_CORRECTION 167 +#define SETTING_RATE_DYNAMICS_END_CORRECTION_MIN 10 +#define SETTING_RATE_DYNAMICS_END_CORRECTION_MAX 95 +#define SETTING_RATE_DYNAMICS_CENTER_WEIGHT_DEFAULT 0 +#define SETTING_RATE_DYNAMICS_CENTER_WEIGHT 168 +#define SETTING_RATE_DYNAMICS_CENTER_WEIGHT_MIN 0 +#define SETTING_RATE_DYNAMICS_CENTER_WEIGHT_MAX 95 +#define SETTING_RATE_DYNAMICS_END_WEIGHT_DEFAULT 0 +#define SETTING_RATE_DYNAMICS_END_WEIGHT 169 +#define SETTING_RATE_DYNAMICS_END_WEIGHT_MIN 0 +#define SETTING_RATE_DYNAMICS_END_WEIGHT_MAX 95 +#define SETTING_REBOOT_CHARACTER_DEFAULT 82 +#define SETTING_REBOOT_CHARACTER 170 +#define SETTING_REBOOT_CHARACTER_MIN 48 +#define SETTING_REBOOT_CHARACTER_MAX 126 +#define SETTING_IMU_DCM_KP_DEFAULT 2000 +#define SETTING_IMU_DCM_KP 171 +#define SETTING_IMU_DCM_KP_MIN 0 +#define SETTING_IMU_DCM_KP_MAX 65535 +#define SETTING_IMU_DCM_KI_DEFAULT 50 +#define SETTING_IMU_DCM_KI 172 +#define SETTING_IMU_DCM_KI_MIN 0 +#define SETTING_IMU_DCM_KI_MAX 65535 +#define SETTING_IMU_DCM_KP_MAG_DEFAULT 2000 +#define SETTING_IMU_DCM_KP_MAG 173 +#define SETTING_IMU_DCM_KP_MAG_MIN 0 +#define SETTING_IMU_DCM_KP_MAG_MAX 65535 +#define SETTING_IMU_DCM_KI_MAG_DEFAULT 50 +#define SETTING_IMU_DCM_KI_MAG 174 +#define SETTING_IMU_DCM_KI_MAG_MIN 0 +#define SETTING_IMU_DCM_KI_MAG_MAX 65535 +#define SETTING_SMALL_ANGLE_DEFAULT 25 +#define SETTING_SMALL_ANGLE 175 +#define SETTING_SMALL_ANGLE_MIN 0 +#define SETTING_SMALL_ANGLE_MAX 180 +#define SETTING_IMU_ACC_IGNORE_RATE_DEFAULT 15 +#define SETTING_IMU_ACC_IGNORE_RATE 176 +#define SETTING_IMU_ACC_IGNORE_RATE_MIN 0 +#define SETTING_IMU_ACC_IGNORE_RATE_MAX 30 +#define SETTING_IMU_ACC_IGNORE_SLOPE_DEFAULT 5 +#define SETTING_IMU_ACC_IGNORE_SLOPE 177 +#define SETTING_IMU_ACC_IGNORE_SLOPE_MIN 0 +#define SETTING_IMU_ACC_IGNORE_SLOPE_MAX 10 +#define SETTING_IMU_GPS_YAW_WINDCOMP_DEFAULT 1 +#define SETTING_IMU_GPS_YAW_WINDCOMP 178 +#define SETTING_IMU_GPS_YAW_WINDCOMP_MIN 0 +#define SETTING_IMU_GPS_YAW_WINDCOMP_MAX 0 +#define SETTING_IMU_INERTIA_COMP_METHOD_DEFAULT 0 +#define SETTING_IMU_INERTIA_COMP_METHOD 179 +#define SETTING_IMU_INERTIA_COMP_METHOD_MIN 0 +#define SETTING_IMU_INERTIA_COMP_METHOD_MAX 0 +#define SETTING_FIXED_WING_AUTO_ARM_DEFAULT 0 +#define SETTING_FIXED_WING_AUTO_ARM 180 +#define SETTING_FIXED_WING_AUTO_ARM_MIN 0 +#define SETTING_FIXED_WING_AUTO_ARM_MAX 0 +#define SETTING_DISARM_KILL_SWITCH_DEFAULT 1 +#define SETTING_DISARM_KILL_SWITCH 181 +#define SETTING_DISARM_KILL_SWITCH_MIN 0 +#define SETTING_DISARM_KILL_SWITCH_MAX 0 +#define SETTING_SWITCH_DISARM_DELAY_DEFAULT 250 +#define SETTING_SWITCH_DISARM_DELAY 182 +#define SETTING_SWITCH_DISARM_DELAY_MIN 0 +#define SETTING_SWITCH_DISARM_DELAY_MAX 1000 +#define SETTING_PREARM_TIMEOUT_DEFAULT 10000 +#define SETTING_PREARM_TIMEOUT 183 +#define SETTING_PREARM_TIMEOUT_MIN 0 +#define SETTING_PREARM_TIMEOUT_MAX 10000 +#define SETTING_APPLIED_DEFAULTS_DEFAULT 0 +#define SETTING_APPLIED_DEFAULTS 184 +#define SETTING_APPLIED_DEFAULTS_MIN 0 +#define SETTING_APPLIED_DEFAULTS_MAX 99 +#define SETTING_GPS_PROVIDER_DEFAULT 1 +#define SETTING_GPS_PROVIDER 185 +#define SETTING_GPS_PROVIDER_MIN 0 +#define SETTING_GPS_PROVIDER_MAX 0 +#define SETTING_GPS_SBAS_MODE_DEFAULT 5 +#define SETTING_GPS_SBAS_MODE 186 +#define SETTING_GPS_SBAS_MODE_MIN 0 +#define SETTING_GPS_SBAS_MODE_MAX 0 +#define SETTING_GPS_DYN_MODEL_DEFAULT 1 +#define SETTING_GPS_DYN_MODEL 187 +#define SETTING_GPS_DYN_MODEL_MIN 0 +#define SETTING_GPS_DYN_MODEL_MAX 0 +#define SETTING_GPS_AUTO_CONFIG_DEFAULT 1 +#define SETTING_GPS_AUTO_CONFIG 188 +#define SETTING_GPS_AUTO_CONFIG_MIN 0 +#define SETTING_GPS_AUTO_CONFIG_MAX 0 +#define SETTING_GPS_AUTO_BAUD_DEFAULT 1 +#define SETTING_GPS_AUTO_BAUD 189 +#define SETTING_GPS_AUTO_BAUD_MIN 0 +#define SETTING_GPS_AUTO_BAUD_MAX 0 +#define SETTING_GPS_UBLOX_USE_GALILEO_DEFAULT 0 +#define SETTING_GPS_UBLOX_USE_GALILEO 190 +#define SETTING_GPS_UBLOX_USE_GALILEO_MIN 0 +#define SETTING_GPS_UBLOX_USE_GALILEO_MAX 0 +#define SETTING_GPS_MIN_SATS_DEFAULT 6 +#define SETTING_GPS_MIN_SATS 191 +#define SETTING_GPS_MIN_SATS_MIN 5 +#define SETTING_GPS_MIN_SATS_MAX 10 +#define SETTING_DEADBAND_DEFAULT 5 +#define SETTING_DEADBAND 192 +#define SETTING_DEADBAND_MIN 0 +#define SETTING_DEADBAND_MAX 32 +#define SETTING_YAW_DEADBAND_DEFAULT 5 +#define SETTING_YAW_DEADBAND 193 +#define SETTING_YAW_DEADBAND_MIN 0 +#define SETTING_YAW_DEADBAND_MAX 100 +#define SETTING_POS_HOLD_DEADBAND_DEFAULT 10 +#define SETTING_POS_HOLD_DEADBAND 194 +#define SETTING_POS_HOLD_DEADBAND_MIN 2 +#define SETTING_POS_HOLD_DEADBAND_MAX 250 +#define SETTING_CONTROL_DEADBAND_DEFAULT 10 +#define SETTING_CONTROL_DEADBAND 195 +#define SETTING_CONTROL_DEADBAND_MIN 2 +#define SETTING_CONTROL_DEADBAND_MAX 250 +#define SETTING_ALT_HOLD_DEADBAND_DEFAULT 50 +#define SETTING_ALT_HOLD_DEADBAND 196 +#define SETTING_ALT_HOLD_DEADBAND_MIN 10 +#define SETTING_ALT_HOLD_DEADBAND_MAX 250 +#define SETTING_3D_DEADBAND_THROTTLE_DEFAULT 50 +#define SETTING_3D_DEADBAND_THROTTLE 197 +#define SETTING_3D_DEADBAND_THROTTLE_MIN 0 +#define SETTING_3D_DEADBAND_THROTTLE_MAX 200 +#define SETTING_AIRMODE_TYPE_DEFAULT 0 +#define SETTING_AIRMODE_TYPE 198 +#define SETTING_AIRMODE_TYPE_MIN 0 +#define SETTING_AIRMODE_TYPE_MAX 0 +#define SETTING_AIRMODE_THROTTLE_THRESHOLD_DEFAULT 1150 +#define SETTING_AIRMODE_THROTTLE_THRESHOLD 199 +#define SETTING_AIRMODE_THROTTLE_THRESHOLD_MIN 1000 +#define SETTING_AIRMODE_THROTTLE_THRESHOLD_MAX 2000 +#define SETTING_MC_P_PITCH_DEFAULT 40 +#define SETTING_MC_P_PITCH 200 +#define SETTING_MC_P_PITCH_MIN 0 +#define SETTING_MC_P_PITCH_MAX 255 +#define SETTING_MC_I_PITCH_DEFAULT 30 +#define SETTING_MC_I_PITCH 201 +#define SETTING_MC_I_PITCH_MIN 0 +#define SETTING_MC_I_PITCH_MAX 255 +#define SETTING_MC_D_PITCH_DEFAULT 23 +#define SETTING_MC_D_PITCH 202 +#define SETTING_MC_D_PITCH_MIN 0 +#define SETTING_MC_D_PITCH_MAX 255 +#define SETTING_MC_CD_PITCH_DEFAULT 60 +#define SETTING_MC_CD_PITCH 203 +#define SETTING_MC_CD_PITCH_MIN 0 +#define SETTING_MC_CD_PITCH_MAX 255 +#define SETTING_MC_P_ROLL_DEFAULT 40 +#define SETTING_MC_P_ROLL 204 +#define SETTING_MC_P_ROLL_MIN 0 +#define SETTING_MC_P_ROLL_MAX 255 +#define SETTING_MC_I_ROLL_DEFAULT 30 +#define SETTING_MC_I_ROLL 205 +#define SETTING_MC_I_ROLL_MIN 0 +#define SETTING_MC_I_ROLL_MAX 255 +#define SETTING_MC_D_ROLL_DEFAULT 23 +#define SETTING_MC_D_ROLL 206 +#define SETTING_MC_D_ROLL_MIN 0 +#define SETTING_MC_D_ROLL_MAX 255 +#define SETTING_MC_CD_ROLL_DEFAULT 60 +#define SETTING_MC_CD_ROLL 207 +#define SETTING_MC_CD_ROLL_MIN 0 +#define SETTING_MC_CD_ROLL_MAX 255 +#define SETTING_MC_P_YAW_DEFAULT 85 +#define SETTING_MC_P_YAW 208 +#define SETTING_MC_P_YAW_MIN 0 +#define SETTING_MC_P_YAW_MAX 255 +#define SETTING_MC_I_YAW_DEFAULT 45 +#define SETTING_MC_I_YAW 209 +#define SETTING_MC_I_YAW_MIN 0 +#define SETTING_MC_I_YAW_MAX 255 +#define SETTING_MC_D_YAW_DEFAULT 0 +#define SETTING_MC_D_YAW 210 +#define SETTING_MC_D_YAW_MIN 0 +#define SETTING_MC_D_YAW_MAX 255 +#define SETTING_MC_CD_YAW_DEFAULT 60 +#define SETTING_MC_CD_YAW 211 +#define SETTING_MC_CD_YAW_MIN 0 +#define SETTING_MC_CD_YAW_MAX 255 +#define SETTING_MC_P_LEVEL_DEFAULT 20 +#define SETTING_MC_P_LEVEL 212 +#define SETTING_MC_P_LEVEL_MIN 0 +#define SETTING_MC_P_LEVEL_MAX 255 +#define SETTING_MC_I_LEVEL_DEFAULT 15 +#define SETTING_MC_I_LEVEL 213 +#define SETTING_MC_I_LEVEL_MIN 0 +#define SETTING_MC_I_LEVEL_MAX 255 +#define SETTING_MC_D_LEVEL_DEFAULT 75 +#define SETTING_MC_D_LEVEL 214 +#define SETTING_MC_D_LEVEL_MIN 0 +#define SETTING_MC_D_LEVEL_MAX 255 +#define SETTING_FW_P_PITCH_DEFAULT 5 +#define SETTING_FW_P_PITCH 215 +#define SETTING_FW_P_PITCH_MIN 0 +#define SETTING_FW_P_PITCH_MAX 255 +#define SETTING_FW_I_PITCH_DEFAULT 7 +#define SETTING_FW_I_PITCH 216 +#define SETTING_FW_I_PITCH_MIN 0 +#define SETTING_FW_I_PITCH_MAX 255 +#define SETTING_FW_D_PITCH_DEFAULT 0 +#define SETTING_FW_D_PITCH 217 +#define SETTING_FW_D_PITCH_MIN 0 +#define SETTING_FW_D_PITCH_MAX 255 +#define SETTING_FW_FF_PITCH_DEFAULT 50 +#define SETTING_FW_FF_PITCH 218 +#define SETTING_FW_FF_PITCH_MIN 0 +#define SETTING_FW_FF_PITCH_MAX 255 +#define SETTING_FW_P_ROLL_DEFAULT 5 +#define SETTING_FW_P_ROLL 219 +#define SETTING_FW_P_ROLL_MIN 0 +#define SETTING_FW_P_ROLL_MAX 255 +#define SETTING_FW_I_ROLL_DEFAULT 7 +#define SETTING_FW_I_ROLL 220 +#define SETTING_FW_I_ROLL_MIN 0 +#define SETTING_FW_I_ROLL_MAX 255 +#define SETTING_FW_D_ROLL_DEFAULT 0 +#define SETTING_FW_D_ROLL 221 +#define SETTING_FW_D_ROLL_MIN 0 +#define SETTING_FW_D_ROLL_MAX 255 +#define SETTING_FW_FF_ROLL_DEFAULT 50 +#define SETTING_FW_FF_ROLL 222 +#define SETTING_FW_FF_ROLL_MIN 0 +#define SETTING_FW_FF_ROLL_MAX 255 +#define SETTING_FW_P_YAW_DEFAULT 6 +#define SETTING_FW_P_YAW 223 +#define SETTING_FW_P_YAW_MIN 0 +#define SETTING_FW_P_YAW_MAX 255 +#define SETTING_FW_I_YAW_DEFAULT 10 +#define SETTING_FW_I_YAW 224 +#define SETTING_FW_I_YAW_MIN 0 +#define SETTING_FW_I_YAW_MAX 255 +#define SETTING_FW_D_YAW_DEFAULT 0 +#define SETTING_FW_D_YAW 225 +#define SETTING_FW_D_YAW_MIN 0 +#define SETTING_FW_D_YAW_MAX 255 +#define SETTING_FW_FF_YAW_DEFAULT 60 +#define SETTING_FW_FF_YAW 226 +#define SETTING_FW_FF_YAW_MIN 0 +#define SETTING_FW_FF_YAW_MAX 255 +#define SETTING_FW_P_LEVEL_DEFAULT 20 +#define SETTING_FW_P_LEVEL 227 +#define SETTING_FW_P_LEVEL_MIN 0 +#define SETTING_FW_P_LEVEL_MAX 255 +#define SETTING_FW_I_LEVEL_DEFAULT 5 +#define SETTING_FW_I_LEVEL 228 +#define SETTING_FW_I_LEVEL_MIN 0 +#define SETTING_FW_I_LEVEL_MAX 255 +#define SETTING_FW_D_LEVEL_DEFAULT 75 +#define SETTING_FW_D_LEVEL 229 +#define SETTING_FW_D_LEVEL_MIN 0 +#define SETTING_FW_D_LEVEL_MAX 255 +#define SETTING_MAX_ANGLE_INCLINATION_RLL_DEFAULT 300 +#define SETTING_MAX_ANGLE_INCLINATION_RLL 230 +#define SETTING_MAX_ANGLE_INCLINATION_RLL_MIN 100 +#define SETTING_MAX_ANGLE_INCLINATION_RLL_MAX 900 +#define SETTING_MAX_ANGLE_INCLINATION_PIT_DEFAULT 300 +#define SETTING_MAX_ANGLE_INCLINATION_PIT 231 +#define SETTING_MAX_ANGLE_INCLINATION_PIT_MIN 100 +#define SETTING_MAX_ANGLE_INCLINATION_PIT_MAX 900 +#define SETTING_DTERM_LPF_HZ_DEFAULT 110 +#define SETTING_DTERM_LPF_HZ 232 +#define SETTING_DTERM_LPF_HZ_MIN 0 +#define SETTING_DTERM_LPF_HZ_MAX 500 +#define SETTING_DTERM_LPF_TYPE_DEFAULT 2 +#define SETTING_DTERM_LPF_TYPE 233 +#define SETTING_DTERM_LPF_TYPE_MIN 0 +#define SETTING_DTERM_LPF_TYPE_MAX 0 +#define SETTING_DTERM_LPF2_HZ_DEFAULT 0 +#define SETTING_DTERM_LPF2_HZ 234 +#define SETTING_DTERM_LPF2_HZ_MIN 0 +#define SETTING_DTERM_LPF2_HZ_MAX 500 +#define SETTING_DTERM_LPF2_TYPE_DEFAULT 0 +#define SETTING_DTERM_LPF2_TYPE 235 +#define SETTING_DTERM_LPF2_TYPE_MIN 0 +#define SETTING_DTERM_LPF2_TYPE_MAX 0 +#define SETTING_YAW_LPF_HZ_DEFAULT 0 +#define SETTING_YAW_LPF_HZ 236 +#define SETTING_YAW_LPF_HZ_MIN 0 +#define SETTING_YAW_LPF_HZ_MAX 200 +#define SETTING_FW_ITERM_THROW_LIMIT_DEFAULT 165 +#define SETTING_FW_ITERM_THROW_LIMIT 237 +#define SETTING_FW_ITERM_THROW_LIMIT_MIN 0 +#define SETTING_FW_ITERM_THROW_LIMIT_MAX 500 +#define SETTING_FW_REFERENCE_AIRSPEED_DEFAULT 1500 +#define SETTING_FW_REFERENCE_AIRSPEED 238 +#define SETTING_FW_REFERENCE_AIRSPEED_MIN 300 +#define SETTING_FW_REFERENCE_AIRSPEED_MAX 6000 +#define SETTING_FW_TURN_ASSIST_YAW_GAIN_DEFAULT 1 +#define SETTING_FW_TURN_ASSIST_YAW_GAIN 239 +#define SETTING_FW_TURN_ASSIST_YAW_GAIN_MIN 0 +#define SETTING_FW_TURN_ASSIST_YAW_GAIN_MAX 2 +#define SETTING_FW_TURN_ASSIST_PITCH_GAIN_DEFAULT 1 +#define SETTING_FW_TURN_ASSIST_PITCH_GAIN 240 +#define SETTING_FW_TURN_ASSIST_PITCH_GAIN_MIN 0 +#define SETTING_FW_TURN_ASSIST_PITCH_GAIN_MAX 2 +#define SETTING_FW_ITERM_LIMIT_STICK_POSITION_DEFAULT 0.5f +#define SETTING_FW_ITERM_LIMIT_STICK_POSITION 241 +#define SETTING_FW_ITERM_LIMIT_STICK_POSITION_MIN 0 +#define SETTING_FW_ITERM_LIMIT_STICK_POSITION_MAX 1 +#define SETTING_FW_YAW_ITERM_FREEZE_BANK_ANGLE_DEFAULT 0 +#define SETTING_FW_YAW_ITERM_FREEZE_BANK_ANGLE 242 +#define SETTING_FW_YAW_ITERM_FREEZE_BANK_ANGLE_MIN 0 +#define SETTING_FW_YAW_ITERM_FREEZE_BANK_ANGLE_MAX 90 +#define SETTING_PIDSUM_LIMIT_DEFAULT 500 +#define SETTING_PIDSUM_LIMIT 243 +#define SETTING_PIDSUM_LIMIT_MIN 100 +#define SETTING_PIDSUM_LIMIT_MAX 1000 +#define SETTING_PIDSUM_LIMIT_YAW_DEFAULT 350 +#define SETTING_PIDSUM_LIMIT_YAW 244 +#define SETTING_PIDSUM_LIMIT_YAW_MIN 100 +#define SETTING_PIDSUM_LIMIT_YAW_MAX 1000 +#define SETTING_ITERM_WINDUP_DEFAULT 50 +#define SETTING_ITERM_WINDUP 245 +#define SETTING_ITERM_WINDUP_MIN 0 +#define SETTING_ITERM_WINDUP_MAX 90 +#define SETTING_RATE_ACCEL_LIMIT_ROLL_PITCH_DEFAULT 0 +#define SETTING_RATE_ACCEL_LIMIT_ROLL_PITCH 246 +#define SETTING_RATE_ACCEL_LIMIT_ROLL_PITCH_MIN 0 +#define SETTING_RATE_ACCEL_LIMIT_ROLL_PITCH_MAX 500000 +#define SETTING_RATE_ACCEL_LIMIT_YAW_DEFAULT 10000 +#define SETTING_RATE_ACCEL_LIMIT_YAW 247 +#define SETTING_RATE_ACCEL_LIMIT_YAW_MIN 0 +#define SETTING_RATE_ACCEL_LIMIT_YAW_MAX 500000 +#define SETTING_HEADING_HOLD_RATE_LIMIT_DEFAULT 90 +#define SETTING_HEADING_HOLD_RATE_LIMIT 248 +#define SETTING_HEADING_HOLD_RATE_LIMIT_MIN 10 +#define SETTING_HEADING_HOLD_RATE_LIMIT_MAX 250 +#define SETTING_NAV_MC_POS_Z_P_DEFAULT 50 +#define SETTING_NAV_MC_POS_Z_P 249 +#define SETTING_NAV_MC_POS_Z_P_MIN 0 +#define SETTING_NAV_MC_POS_Z_P_MAX 255 +#define SETTING_NAV_MC_VEL_Z_P_DEFAULT 100 +#define SETTING_NAV_MC_VEL_Z_P 250 +#define SETTING_NAV_MC_VEL_Z_P_MIN 0 +#define SETTING_NAV_MC_VEL_Z_P_MAX 255 +#define SETTING_NAV_MC_VEL_Z_I_DEFAULT 50 +#define SETTING_NAV_MC_VEL_Z_I 251 +#define SETTING_NAV_MC_VEL_Z_I_MIN 0 +#define SETTING_NAV_MC_VEL_Z_I_MAX 255 +#define SETTING_NAV_MC_VEL_Z_D_DEFAULT 10 +#define SETTING_NAV_MC_VEL_Z_D 252 +#define SETTING_NAV_MC_VEL_Z_D_MIN 0 +#define SETTING_NAV_MC_VEL_Z_D_MAX 255 +#define SETTING_NAV_MC_POS_XY_P_DEFAULT 65 +#define SETTING_NAV_MC_POS_XY_P 253 +#define SETTING_NAV_MC_POS_XY_P_MIN 0 +#define SETTING_NAV_MC_POS_XY_P_MAX 255 +#define SETTING_NAV_MC_VEL_XY_P_DEFAULT 40 +#define SETTING_NAV_MC_VEL_XY_P 254 +#define SETTING_NAV_MC_VEL_XY_P_MIN 0 +#define SETTING_NAV_MC_VEL_XY_P_MAX 255 +#define SETTING_NAV_MC_VEL_XY_I_DEFAULT 15 +#define SETTING_NAV_MC_VEL_XY_I 255 +#define SETTING_NAV_MC_VEL_XY_I_MIN 0 +#define SETTING_NAV_MC_VEL_XY_I_MAX 255 +#define SETTING_NAV_MC_VEL_XY_D_DEFAULT 100 +#define SETTING_NAV_MC_VEL_XY_D 256 +#define SETTING_NAV_MC_VEL_XY_D_MIN 0 +#define SETTING_NAV_MC_VEL_XY_D_MAX 255 +#define SETTING_NAV_MC_VEL_XY_FF_DEFAULT 40 +#define SETTING_NAV_MC_VEL_XY_FF 257 +#define SETTING_NAV_MC_VEL_XY_FF_MIN 0 +#define SETTING_NAV_MC_VEL_XY_FF_MAX 255 +#define SETTING_NAV_MC_HEADING_P_DEFAULT 60 +#define SETTING_NAV_MC_HEADING_P 258 +#define SETTING_NAV_MC_HEADING_P_MIN 0 +#define SETTING_NAV_MC_HEADING_P_MAX 255 +#define SETTING_NAV_MC_VEL_XY_DTERM_LPF_HZ_DEFAULT 2 +#define SETTING_NAV_MC_VEL_XY_DTERM_LPF_HZ 259 +#define SETTING_NAV_MC_VEL_XY_DTERM_LPF_HZ_MIN 0 +#define SETTING_NAV_MC_VEL_XY_DTERM_LPF_HZ_MAX 100 +#define SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_DEFAULT 90 +#define SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION 260 +#define SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_MIN 0 +#define SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_MAX 100 +#define SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_START_DEFAULT 10 +#define SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_START 261 +#define SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_START_MIN 0 +#define SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_START_MAX 100 +#define SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_END_DEFAULT 60 +#define SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_END 262 +#define SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_END_MIN 0 +#define SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_END_MAX 100 +#define SETTING_NAV_FW_POS_Z_P_DEFAULT 40 +#define SETTING_NAV_FW_POS_Z_P 263 +#define SETTING_NAV_FW_POS_Z_P_MIN 0 +#define SETTING_NAV_FW_POS_Z_P_MAX 255 +#define SETTING_NAV_FW_POS_Z_I_DEFAULT 5 +#define SETTING_NAV_FW_POS_Z_I 264 +#define SETTING_NAV_FW_POS_Z_I_MIN 0 +#define SETTING_NAV_FW_POS_Z_I_MAX 255 +#define SETTING_NAV_FW_POS_Z_D_DEFAULT 10 +#define SETTING_NAV_FW_POS_Z_D 265 +#define SETTING_NAV_FW_POS_Z_D_MIN 0 +#define SETTING_NAV_FW_POS_Z_D_MAX 255 +#define SETTING_NAV_FW_POS_XY_P_DEFAULT 75 +#define SETTING_NAV_FW_POS_XY_P 266 +#define SETTING_NAV_FW_POS_XY_P_MIN 0 +#define SETTING_NAV_FW_POS_XY_P_MAX 255 +#define SETTING_NAV_FW_POS_XY_I_DEFAULT 5 +#define SETTING_NAV_FW_POS_XY_I 267 +#define SETTING_NAV_FW_POS_XY_I_MIN 0 +#define SETTING_NAV_FW_POS_XY_I_MAX 255 +#define SETTING_NAV_FW_POS_XY_D_DEFAULT 8 +#define SETTING_NAV_FW_POS_XY_D 268 +#define SETTING_NAV_FW_POS_XY_D_MIN 0 +#define SETTING_NAV_FW_POS_XY_D_MAX 255 +#define SETTING_NAV_FW_HEADING_P_DEFAULT 60 +#define SETTING_NAV_FW_HEADING_P 269 +#define SETTING_NAV_FW_HEADING_P_MIN 0 +#define SETTING_NAV_FW_HEADING_P_MAX 255 +#define SETTING_NAV_FW_POS_HDG_P_DEFAULT 30 +#define SETTING_NAV_FW_POS_HDG_P 270 +#define SETTING_NAV_FW_POS_HDG_P_MIN 0 +#define SETTING_NAV_FW_POS_HDG_P_MAX 255 +#define SETTING_NAV_FW_POS_HDG_I_DEFAULT 2 +#define SETTING_NAV_FW_POS_HDG_I 271 +#define SETTING_NAV_FW_POS_HDG_I_MIN 0 +#define SETTING_NAV_FW_POS_HDG_I_MAX 255 +#define SETTING_NAV_FW_POS_HDG_D_DEFAULT 0 +#define SETTING_NAV_FW_POS_HDG_D 272 +#define SETTING_NAV_FW_POS_HDG_D_MIN 0 +#define SETTING_NAV_FW_POS_HDG_D_MAX 255 +#define SETTING_NAV_FW_POS_HDG_PIDSUM_LIMIT_DEFAULT 350 +#define SETTING_NAV_FW_POS_HDG_PIDSUM_LIMIT 273 +#define SETTING_NAV_FW_POS_HDG_PIDSUM_LIMIT_MIN 100 +#define SETTING_NAV_FW_POS_HDG_PIDSUM_LIMIT_MAX 1000 +#define SETTING_MC_ITERM_RELAX_DEFAULT 1 +#define SETTING_MC_ITERM_RELAX 274 +#define SETTING_MC_ITERM_RELAX_MIN 0 +#define SETTING_MC_ITERM_RELAX_MAX 0 +#define SETTING_MC_ITERM_RELAX_CUTOFF_DEFAULT 15 +#define SETTING_MC_ITERM_RELAX_CUTOFF 275 +#define SETTING_MC_ITERM_RELAX_CUTOFF_MIN 1 +#define SETTING_MC_ITERM_RELAX_CUTOFF_MAX 100 +#define SETTING_D_BOOST_MIN_DEFAULT 0.5f +#define SETTING_D_BOOST_MIN 276 +#define SETTING_D_BOOST_MIN_MIN 0 +#define SETTING_D_BOOST_MIN_MAX 1 +#define SETTING_D_BOOST_MAX_DEFAULT 1.25f +#define SETTING_D_BOOST_MAX 277 +#define SETTING_D_BOOST_MAX_MIN 1 +#define SETTING_D_BOOST_MAX_MAX 3 +#define SETTING_D_BOOST_MAX_AT_ACCELERATION_DEFAULT 7500 +#define SETTING_D_BOOST_MAX_AT_ACCELERATION 278 +#define SETTING_D_BOOST_MAX_AT_ACCELERATION_MIN 1000 +#define SETTING_D_BOOST_MAX_AT_ACCELERATION_MAX 16000 +#define SETTING_D_BOOST_GYRO_DELTA_LPF_HZ_DEFAULT 80 +#define SETTING_D_BOOST_GYRO_DELTA_LPF_HZ 279 +#define SETTING_D_BOOST_GYRO_DELTA_LPF_HZ_MIN 10 +#define SETTING_D_BOOST_GYRO_DELTA_LPF_HZ_MAX 250 +#define SETTING_ANTIGRAVITY_GAIN_DEFAULT 1 +#define SETTING_ANTIGRAVITY_GAIN 280 +#define SETTING_ANTIGRAVITY_GAIN_MIN 1 +#define SETTING_ANTIGRAVITY_GAIN_MAX 20 +#define SETTING_ANTIGRAVITY_ACCELERATOR_DEFAULT 1 +#define SETTING_ANTIGRAVITY_ACCELERATOR 281 +#define SETTING_ANTIGRAVITY_ACCELERATOR_MIN 1 +#define SETTING_ANTIGRAVITY_ACCELERATOR_MAX 20 +#define SETTING_ANTIGRAVITY_CUTOFF_LPF_HZ_DEFAULT 15 +#define SETTING_ANTIGRAVITY_CUTOFF_LPF_HZ 282 +#define SETTING_ANTIGRAVITY_CUTOFF_LPF_HZ_MIN 1 +#define SETTING_ANTIGRAVITY_CUTOFF_LPF_HZ_MAX 30 +#define SETTING_PID_TYPE_DEFAULT 3 +#define SETTING_PID_TYPE 283 +#define SETTING_PID_TYPE_MIN 0 +#define SETTING_PID_TYPE_MAX 0 +#define SETTING_MC_CD_LPF_HZ_DEFAULT 30 +#define SETTING_MC_CD_LPF_HZ 284 +#define SETTING_MC_CD_LPF_HZ_MIN 0 +#define SETTING_MC_CD_LPF_HZ_MAX 200 +#define SETTING_FW_LEVEL_PITCH_TRIM_DEFAULT 0 +#define SETTING_FW_LEVEL_PITCH_TRIM 285 +#define SETTING_FW_LEVEL_PITCH_TRIM_MIN -10 +#define SETTING_FW_LEVEL_PITCH_TRIM_MAX 10 +#define SETTING_SMITH_PREDICTOR_STRENGTH_DEFAULT 0.5f +#define SETTING_SMITH_PREDICTOR_STRENGTH 286 +#define SETTING_SMITH_PREDICTOR_STRENGTH_MIN 0 +#define SETTING_SMITH_PREDICTOR_STRENGTH_MAX 1 +#define SETTING_SMITH_PREDICTOR_DELAY_DEFAULT 0 +#define SETTING_SMITH_PREDICTOR_DELAY 287 +#define SETTING_SMITH_PREDICTOR_DELAY_MIN 0 +#define SETTING_SMITH_PREDICTOR_DELAY_MAX 8 +#define SETTING_SMITH_PREDICTOR_LPF_HZ_DEFAULT 50 +#define SETTING_SMITH_PREDICTOR_LPF_HZ 288 +#define SETTING_SMITH_PREDICTOR_LPF_HZ_MIN 1 +#define SETTING_SMITH_PREDICTOR_LPF_HZ_MAX 500 +#define SETTING_FW_LEVEL_PITCH_GAIN_DEFAULT 5 +#define SETTING_FW_LEVEL_PITCH_GAIN 289 +#define SETTING_FW_LEVEL_PITCH_GAIN_MIN 0 +#define SETTING_FW_LEVEL_PITCH_GAIN_MAX 20 +#define SETTING_FW_AUTOTUNE_MIN_STICK_DEFAULT 50 +#define SETTING_FW_AUTOTUNE_MIN_STICK 290 +#define SETTING_FW_AUTOTUNE_MIN_STICK_MIN 0 +#define SETTING_FW_AUTOTUNE_MIN_STICK_MAX 100 +#define SETTING_FW_AUTOTUNE_RATE_ADJUSTMENT_DEFAULT 2 +#define SETTING_FW_AUTOTUNE_RATE_ADJUSTMENT 291 +#define SETTING_FW_AUTOTUNE_RATE_ADJUSTMENT_MIN 0 +#define SETTING_FW_AUTOTUNE_RATE_ADJUSTMENT_MAX 0 +#define SETTING_FW_AUTOTUNE_MAX_RATE_DEFLECTION_DEFAULT 80 +#define SETTING_FW_AUTOTUNE_MAX_RATE_DEFLECTION 292 +#define SETTING_FW_AUTOTUNE_MAX_RATE_DEFLECTION_MIN 50 +#define SETTING_FW_AUTOTUNE_MAX_RATE_DEFLECTION_MAX 100 +#define SETTING_INAV_AUTO_MAG_DECL_DEFAULT 1 +#define SETTING_INAV_AUTO_MAG_DECL 293 +#define SETTING_INAV_AUTO_MAG_DECL_MIN 0 +#define SETTING_INAV_AUTO_MAG_DECL_MAX 0 +#define SETTING_INAV_GRAVITY_CAL_TOLERANCE_DEFAULT 5 +#define SETTING_INAV_GRAVITY_CAL_TOLERANCE 294 +#define SETTING_INAV_GRAVITY_CAL_TOLERANCE_MIN 0 +#define SETTING_INAV_GRAVITY_CAL_TOLERANCE_MAX 255 +#define SETTING_INAV_USE_GPS_VELNED_DEFAULT 1 +#define SETTING_INAV_USE_GPS_VELNED 295 +#define SETTING_INAV_USE_GPS_VELNED_MIN 0 +#define SETTING_INAV_USE_GPS_VELNED_MAX 0 +#define SETTING_INAV_USE_GPS_NO_BARO_DEFAULT 0 +#define SETTING_INAV_USE_GPS_NO_BARO 296 +#define SETTING_INAV_USE_GPS_NO_BARO_MIN 0 +#define SETTING_INAV_USE_GPS_NO_BARO_MAX 0 +#define SETTING_INAV_ALLOW_DEAD_RECKONING_DEFAULT 0 +#define SETTING_INAV_ALLOW_DEAD_RECKONING 297 +#define SETTING_INAV_ALLOW_DEAD_RECKONING_MIN 0 +#define SETTING_INAV_ALLOW_DEAD_RECKONING_MAX 0 +#define SETTING_INAV_RESET_ALTITUDE_DEFAULT 1 +#define SETTING_INAV_RESET_ALTITUDE 298 +#define SETTING_INAV_RESET_ALTITUDE_MIN 0 +#define SETTING_INAV_RESET_ALTITUDE_MAX 0 +#define SETTING_INAV_RESET_HOME_DEFAULT 1 +#define SETTING_INAV_RESET_HOME 299 +#define SETTING_INAV_RESET_HOME_MIN 0 +#define SETTING_INAV_RESET_HOME_MAX 0 +#define SETTING_INAV_MAX_SURFACE_ALTITUDE_DEFAULT 200 +#define SETTING_INAV_MAX_SURFACE_ALTITUDE 300 +#define SETTING_INAV_MAX_SURFACE_ALTITUDE_MIN 0 +#define SETTING_INAV_MAX_SURFACE_ALTITUDE_MAX 1000 +#define SETTING_INAV_W_Z_SURFACE_P_DEFAULT 3.5f +#define SETTING_INAV_W_Z_SURFACE_P 301 +#define SETTING_INAV_W_Z_SURFACE_P_MIN 0 +#define SETTING_INAV_W_Z_SURFACE_P_MAX 100 +#define SETTING_INAV_W_Z_SURFACE_V_DEFAULT 6.1f +#define SETTING_INAV_W_Z_SURFACE_V 302 +#define SETTING_INAV_W_Z_SURFACE_V_MIN 0 +#define SETTING_INAV_W_Z_SURFACE_V_MAX 100 +#define SETTING_INAV_W_XY_FLOW_P_DEFAULT 1.0f +#define SETTING_INAV_W_XY_FLOW_P 303 +#define SETTING_INAV_W_XY_FLOW_P_MIN 0 +#define SETTING_INAV_W_XY_FLOW_P_MAX 100 +#define SETTING_INAV_W_XY_FLOW_V_DEFAULT 2.0f +#define SETTING_INAV_W_XY_FLOW_V 304 +#define SETTING_INAV_W_XY_FLOW_V_MIN 0 +#define SETTING_INAV_W_XY_FLOW_V_MAX 100 +#define SETTING_INAV_W_Z_BARO_P_DEFAULT 0.35f +#define SETTING_INAV_W_Z_BARO_P 305 +#define SETTING_INAV_W_Z_BARO_P_MIN 0 +#define SETTING_INAV_W_Z_BARO_P_MAX 10 +#define SETTING_INAV_W_Z_GPS_P_DEFAULT 0.2f +#define SETTING_INAV_W_Z_GPS_P 306 +#define SETTING_INAV_W_Z_GPS_P_MIN 0 +#define SETTING_INAV_W_Z_GPS_P_MAX 10 +#define SETTING_INAV_W_Z_GPS_V_DEFAULT 0.1f +#define SETTING_INAV_W_Z_GPS_V 307 +#define SETTING_INAV_W_Z_GPS_V_MIN 0 +#define SETTING_INAV_W_Z_GPS_V_MAX 10 +#define SETTING_INAV_W_XY_GPS_P_DEFAULT 1.0f +#define SETTING_INAV_W_XY_GPS_P 308 +#define SETTING_INAV_W_XY_GPS_P_MIN 0 +#define SETTING_INAV_W_XY_GPS_P_MAX 10 +#define SETTING_INAV_W_XY_GPS_V_DEFAULT 2.0f +#define SETTING_INAV_W_XY_GPS_V 309 +#define SETTING_INAV_W_XY_GPS_V_MIN 0 +#define SETTING_INAV_W_XY_GPS_V_MAX 10 +#define SETTING_INAV_W_Z_RES_V_DEFAULT 0.5f +#define SETTING_INAV_W_Z_RES_V 310 +#define SETTING_INAV_W_Z_RES_V_MIN 0 +#define SETTING_INAV_W_Z_RES_V_MAX 10 +#define SETTING_INAV_W_XY_RES_V_DEFAULT 0.5f +#define SETTING_INAV_W_XY_RES_V 311 +#define SETTING_INAV_W_XY_RES_V_MIN 0 +#define SETTING_INAV_W_XY_RES_V_MAX 10 +#define SETTING_INAV_W_XYZ_ACC_P_DEFAULT 1.0f +#define SETTING_INAV_W_XYZ_ACC_P 312 +#define SETTING_INAV_W_XYZ_ACC_P_MIN 0 +#define SETTING_INAV_W_XYZ_ACC_P_MAX 1 +#define SETTING_INAV_W_ACC_BIAS_DEFAULT 0.01f +#define SETTING_INAV_W_ACC_BIAS 313 +#define SETTING_INAV_W_ACC_BIAS_MIN 0 +#define SETTING_INAV_W_ACC_BIAS_MAX 1 +#define SETTING_INAV_MAX_EPH_EPV_DEFAULT 1000 +#define SETTING_INAV_MAX_EPH_EPV 314 +#define SETTING_INAV_MAX_EPH_EPV_MIN 0 +#define SETTING_INAV_MAX_EPH_EPV_MAX 9999 +#define SETTING_INAV_BARO_EPV_DEFAULT 100 +#define SETTING_INAV_BARO_EPV 315 +#define SETTING_INAV_BARO_EPV_MIN 0 +#define SETTING_INAV_BARO_EPV_MAX 9999 +#define SETTING_NAV_DISARM_ON_LANDING_DEFAULT 0 +#define SETTING_NAV_DISARM_ON_LANDING 316 +#define SETTING_NAV_DISARM_ON_LANDING_MIN 0 +#define SETTING_NAV_DISARM_ON_LANDING_MAX 0 +#define SETTING_NAV_LAND_DETECT_SENSITIVITY_DEFAULT 5 +#define SETTING_NAV_LAND_DETECT_SENSITIVITY 317 +#define SETTING_NAV_LAND_DETECT_SENSITIVITY_MIN 1 +#define SETTING_NAV_LAND_DETECT_SENSITIVITY_MAX 15 +#define SETTING_NAV_USE_MIDTHR_FOR_ALTHOLD_DEFAULT 0 +#define SETTING_NAV_USE_MIDTHR_FOR_ALTHOLD 318 +#define SETTING_NAV_USE_MIDTHR_FOR_ALTHOLD_MIN 0 +#define SETTING_NAV_USE_MIDTHR_FOR_ALTHOLD_MAX 0 +#define SETTING_NAV_EXTRA_ARMING_SAFETY_DEFAULT 0 +#define SETTING_NAV_EXTRA_ARMING_SAFETY 319 +#define SETTING_NAV_EXTRA_ARMING_SAFETY_MIN 0 +#define SETTING_NAV_EXTRA_ARMING_SAFETY_MAX 0 +#define SETTING_NAV_USER_CONTROL_MODE_DEFAULT 0 +#define SETTING_NAV_USER_CONTROL_MODE 320 +#define SETTING_NAV_USER_CONTROL_MODE_MIN 0 +#define SETTING_NAV_USER_CONTROL_MODE_MAX 0 +#define SETTING_NAV_POSITION_TIMEOUT_DEFAULT 5 +#define SETTING_NAV_POSITION_TIMEOUT 321 +#define SETTING_NAV_POSITION_TIMEOUT_MIN 0 +#define SETTING_NAV_POSITION_TIMEOUT_MAX 10 +#define SETTING_NAV_WP_LOAD_ON_BOOT_DEFAULT 0 +#define SETTING_NAV_WP_LOAD_ON_BOOT 322 +#define SETTING_NAV_WP_LOAD_ON_BOOT_MIN 0 +#define SETTING_NAV_WP_LOAD_ON_BOOT_MAX 0 +#define SETTING_NAV_WP_RADIUS_DEFAULT 100 +#define SETTING_NAV_WP_RADIUS 323 +#define SETTING_NAV_WP_RADIUS_MIN 10 +#define SETTING_NAV_WP_RADIUS_MAX 10000 +#define SETTING_NAV_WP_ENFORCE_ALTITUDE_DEFAULT 0 +#define SETTING_NAV_WP_ENFORCE_ALTITUDE 324 +#define SETTING_NAV_WP_ENFORCE_ALTITUDE_MIN 0 +#define SETTING_NAV_WP_ENFORCE_ALTITUDE_MAX 2000 +#define SETTING_NAV_WP_MAX_SAFE_DISTANCE_DEFAULT 100 +#define SETTING_NAV_WP_MAX_SAFE_DISTANCE 325 +#define SETTING_NAV_WP_MAX_SAFE_DISTANCE_MIN 0 +#define SETTING_NAV_WP_MAX_SAFE_DISTANCE_MAX 1500 +#define SETTING_NAV_WP_MISSION_RESTART_DEFAULT 1 +#define SETTING_NAV_WP_MISSION_RESTART 326 +#define SETTING_NAV_WP_MISSION_RESTART_MIN 0 +#define SETTING_NAV_WP_MISSION_RESTART_MAX 0 +#define SETTING_NAV_WP_MULTI_MISSION_INDEX_DEFAULT 1 +#define SETTING_NAV_WP_MULTI_MISSION_INDEX 327 +#define SETTING_NAV_WP_MULTI_MISSION_INDEX_MIN 1 +#define SETTING_NAV_WP_MULTI_MISSION_INDEX_MAX 9 +#define SETTING_NAV_FW_WP_TRACKING_ACCURACY_DEFAULT 0 +#define SETTING_NAV_FW_WP_TRACKING_ACCURACY 328 +#define SETTING_NAV_FW_WP_TRACKING_ACCURACY_MIN 0 +#define SETTING_NAV_FW_WP_TRACKING_ACCURACY_MAX 10 +#define SETTING_NAV_FW_WP_TRACKING_MAX_ANGLE_DEFAULT 60 +#define SETTING_NAV_FW_WP_TRACKING_MAX_ANGLE 329 +#define SETTING_NAV_FW_WP_TRACKING_MAX_ANGLE_MIN 30 +#define SETTING_NAV_FW_WP_TRACKING_MAX_ANGLE_MAX 80 +#define SETTING_NAV_FW_WP_TURN_SMOOTHING_DEFAULT 0 +#define SETTING_NAV_FW_WP_TURN_SMOOTHING 330 +#define SETTING_NAV_FW_WP_TURN_SMOOTHING_MIN 0 +#define SETTING_NAV_FW_WP_TURN_SMOOTHING_MAX 0 +#define SETTING_NAV_AUTO_SPEED_DEFAULT 300 +#define SETTING_NAV_AUTO_SPEED 331 +#define SETTING_NAV_AUTO_SPEED_MIN 10 +#define SETTING_NAV_AUTO_SPEED_MAX 2000 +#define SETTING_NAV_MAX_AUTO_SPEED_DEFAULT 1000 +#define SETTING_NAV_MAX_AUTO_SPEED 332 +#define SETTING_NAV_MAX_AUTO_SPEED_MIN 10 +#define SETTING_NAV_MAX_AUTO_SPEED_MAX 2000 +#define SETTING_NAV_AUTO_CLIMB_RATE_DEFAULT 500 +#define SETTING_NAV_AUTO_CLIMB_RATE 333 +#define SETTING_NAV_AUTO_CLIMB_RATE_MIN 10 +#define SETTING_NAV_AUTO_CLIMB_RATE_MAX 2000 +#define SETTING_NAV_MANUAL_SPEED_DEFAULT 500 +#define SETTING_NAV_MANUAL_SPEED 334 +#define SETTING_NAV_MANUAL_SPEED_MIN 10 +#define SETTING_NAV_MANUAL_SPEED_MAX 2000 +#define SETTING_NAV_MANUAL_CLIMB_RATE_DEFAULT 200 +#define SETTING_NAV_MANUAL_CLIMB_RATE 335 +#define SETTING_NAV_MANUAL_CLIMB_RATE_MIN 10 +#define SETTING_NAV_MANUAL_CLIMB_RATE_MAX 2000 +#define SETTING_NAV_LAND_MINALT_VSPD_DEFAULT 50 +#define SETTING_NAV_LAND_MINALT_VSPD 336 +#define SETTING_NAV_LAND_MINALT_VSPD_MIN 50 +#define SETTING_NAV_LAND_MINALT_VSPD_MAX 500 +#define SETTING_NAV_LAND_MAXALT_VSPD_DEFAULT 200 +#define SETTING_NAV_LAND_MAXALT_VSPD 337 +#define SETTING_NAV_LAND_MAXALT_VSPD_MIN 100 +#define SETTING_NAV_LAND_MAXALT_VSPD_MAX 2000 +#define SETTING_NAV_LAND_SLOWDOWN_MINALT_DEFAULT 500 +#define SETTING_NAV_LAND_SLOWDOWN_MINALT 338 +#define SETTING_NAV_LAND_SLOWDOWN_MINALT_MIN 50 +#define SETTING_NAV_LAND_SLOWDOWN_MINALT_MAX 1000 +#define SETTING_NAV_LAND_SLOWDOWN_MAXALT_DEFAULT 2000 +#define SETTING_NAV_LAND_SLOWDOWN_MAXALT 339 +#define SETTING_NAV_LAND_SLOWDOWN_MAXALT_MIN 500 +#define SETTING_NAV_LAND_SLOWDOWN_MAXALT_MAX 4000 +#define SETTING_NAV_EMERG_LANDING_SPEED_DEFAULT 500 +#define SETTING_NAV_EMERG_LANDING_SPEED 340 +#define SETTING_NAV_EMERG_LANDING_SPEED_MIN 100 +#define SETTING_NAV_EMERG_LANDING_SPEED_MAX 2000 +#define SETTING_NAV_MIN_RTH_DISTANCE_DEFAULT 500 +#define SETTING_NAV_MIN_RTH_DISTANCE 341 +#define SETTING_NAV_MIN_RTH_DISTANCE_MIN 0 +#define SETTING_NAV_MIN_RTH_DISTANCE_MAX 5000 +#define SETTING_NAV_OVERRIDES_MOTOR_STOP_DEFAULT 3 +#define SETTING_NAV_OVERRIDES_MOTOR_STOP 342 +#define SETTING_NAV_OVERRIDES_MOTOR_STOP_MIN 0 +#define SETTING_NAV_OVERRIDES_MOTOR_STOP_MAX 0 +#define SETTING_NAV_FW_SOARING_MOTOR_STOP_DEFAULT 0 +#define SETTING_NAV_FW_SOARING_MOTOR_STOP 343 +#define SETTING_NAV_FW_SOARING_MOTOR_STOP_MIN 0 +#define SETTING_NAV_FW_SOARING_MOTOR_STOP_MAX 0 +#define SETTING_NAV_FW_SOARING_PITCH_DEADBAND_DEFAULT 5 +#define SETTING_NAV_FW_SOARING_PITCH_DEADBAND 344 +#define SETTING_NAV_FW_SOARING_PITCH_DEADBAND_MIN 0 +#define SETTING_NAV_FW_SOARING_PITCH_DEADBAND_MAX 15 +#define SETTING_NAV_RTH_CLIMB_FIRST_DEFAULT 1 +#define SETTING_NAV_RTH_CLIMB_FIRST 345 +#define SETTING_NAV_RTH_CLIMB_FIRST_MIN 0 +#define SETTING_NAV_RTH_CLIMB_FIRST_MAX 0 +#define SETTING_NAV_RTH_CLIMB_FIRST_STAGE_MODE_DEFAULT 0 +#define SETTING_NAV_RTH_CLIMB_FIRST_STAGE_MODE 346 +#define SETTING_NAV_RTH_CLIMB_FIRST_STAGE_MODE_MIN 0 +#define SETTING_NAV_RTH_CLIMB_FIRST_STAGE_MODE_MAX 0 +#define SETTING_NAV_RTH_CLIMB_FIRST_STAGE_ALTITUDE_DEFAULT 0 +#define SETTING_NAV_RTH_CLIMB_FIRST_STAGE_ALTITUDE 347 +#define SETTING_NAV_RTH_CLIMB_FIRST_STAGE_ALTITUDE_MIN 0 +#define SETTING_NAV_RTH_CLIMB_FIRST_STAGE_ALTITUDE_MAX 65000 +#define SETTING_NAV_RTH_CLIMB_IGNORE_EMERG_DEFAULT 0 +#define SETTING_NAV_RTH_CLIMB_IGNORE_EMERG 348 +#define SETTING_NAV_RTH_CLIMB_IGNORE_EMERG_MIN 0 +#define SETTING_NAV_RTH_CLIMB_IGNORE_EMERG_MAX 0 +#define SETTING_NAV_RTH_TAIL_FIRST_DEFAULT 0 +#define SETTING_NAV_RTH_TAIL_FIRST 349 +#define SETTING_NAV_RTH_TAIL_FIRST_MIN 0 +#define SETTING_NAV_RTH_TAIL_FIRST_MAX 0 +#define SETTING_NAV_RTH_ALLOW_LANDING_DEFAULT 1 +#define SETTING_NAV_RTH_ALLOW_LANDING 350 +#define SETTING_NAV_RTH_ALLOW_LANDING_MIN 0 +#define SETTING_NAV_RTH_ALLOW_LANDING_MAX 0 +#define SETTING_NAV_RTH_ALT_MODE_DEFAULT 4 +#define SETTING_NAV_RTH_ALT_MODE 351 +#define SETTING_NAV_RTH_ALT_MODE_MIN 0 +#define SETTING_NAV_RTH_ALT_MODE_MAX 0 +#define SETTING_NAV_RTH_ALT_CONTROL_OVERRIDE_DEFAULT 0 +#define SETTING_NAV_RTH_ALT_CONTROL_OVERRIDE 352 +#define SETTING_NAV_RTH_ALT_CONTROL_OVERRIDE_MIN 0 +#define SETTING_NAV_RTH_ALT_CONTROL_OVERRIDE_MAX 0 +#define SETTING_NAV_RTH_ABORT_THRESHOLD_DEFAULT 50000 +#define SETTING_NAV_RTH_ABORT_THRESHOLD 353 +#define SETTING_NAV_RTH_ABORT_THRESHOLD_MIN 0 +#define SETTING_NAV_RTH_ABORT_THRESHOLD_MAX 65000 +#define SETTING_NAV_MAX_TERRAIN_FOLLOW_ALT_DEFAULT 100 +#define SETTING_NAV_MAX_TERRAIN_FOLLOW_ALT 354 +#define SETTING_NAV_MAX_TERRAIN_FOLLOW_ALT_MIN 0 +#define SETTING_NAV_MAX_TERRAIN_FOLLOW_ALT_MAX 1000 +#define SETTING_NAV_MAX_ALTITUDE_DEFAULT 0 +#define SETTING_NAV_MAX_ALTITUDE 355 +#define SETTING_NAV_MAX_ALTITUDE_MIN 0 +#define SETTING_NAV_MAX_ALTITUDE_MAX 65000 +#define SETTING_NAV_RTH_ALTITUDE_DEFAULT 1000 +#define SETTING_NAV_RTH_ALTITUDE 356 +#define SETTING_NAV_RTH_ALTITUDE_MIN 0 +#define SETTING_NAV_RTH_ALTITUDE_MAX 65000 +#define SETTING_NAV_RTH_HOME_ALTITUDE_DEFAULT 0 +#define SETTING_NAV_RTH_HOME_ALTITUDE 357 +#define SETTING_NAV_RTH_HOME_ALTITUDE_MIN 0 +#define SETTING_NAV_RTH_HOME_ALTITUDE_MAX 65000 +#define SETTING_NAV_RTH_TRACKBACK_MODE_DEFAULT 0 +#define SETTING_NAV_RTH_TRACKBACK_MODE 358 +#define SETTING_NAV_RTH_TRACKBACK_MODE_MIN 0 +#define SETTING_NAV_RTH_TRACKBACK_MODE_MAX 0 +#define SETTING_NAV_RTH_TRACKBACK_DISTANCE_DEFAULT 500 +#define SETTING_NAV_RTH_TRACKBACK_DISTANCE 359 +#define SETTING_NAV_RTH_TRACKBACK_DISTANCE_MIN 50 +#define SETTING_NAV_RTH_TRACKBACK_DISTANCE_MAX 2000 +#define SETTING_SAFEHOME_MAX_DISTANCE_DEFAULT 20000 +#define SETTING_SAFEHOME_MAX_DISTANCE 360 +#define SETTING_SAFEHOME_MAX_DISTANCE_MIN 0 +#define SETTING_SAFEHOME_MAX_DISTANCE_MAX 65000 +#define SETTING_SAFEHOME_USAGE_MODE_DEFAULT 1 +#define SETTING_SAFEHOME_USAGE_MODE 361 +#define SETTING_SAFEHOME_USAGE_MODE_MIN 0 +#define SETTING_SAFEHOME_USAGE_MODE_MAX 0 +#define SETTING_NAV_MISSION_PLANNER_RESET_DEFAULT 1 +#define SETTING_NAV_MISSION_PLANNER_RESET 362 +#define SETTING_NAV_MISSION_PLANNER_RESET_MIN 0 +#define SETTING_NAV_MISSION_PLANNER_RESET_MAX 0 +#define SETTING_NAV_MC_BANK_ANGLE_DEFAULT 30 +#define SETTING_NAV_MC_BANK_ANGLE 363 +#define SETTING_NAV_MC_BANK_ANGLE_MIN 15 +#define SETTING_NAV_MC_BANK_ANGLE_MAX 45 +#define SETTING_NAV_AUTO_DISARM_DELAY_DEFAULT 2000 +#define SETTING_NAV_AUTO_DISARM_DELAY 364 +#define SETTING_NAV_AUTO_DISARM_DELAY_MIN 100 +#define SETTING_NAV_AUTO_DISARM_DELAY_MAX 10000 +#define SETTING_NAV_MC_BRAKING_SPEED_THRESHOLD_DEFAULT 100 +#define SETTING_NAV_MC_BRAKING_SPEED_THRESHOLD 365 +#define SETTING_NAV_MC_BRAKING_SPEED_THRESHOLD_MIN 0 +#define SETTING_NAV_MC_BRAKING_SPEED_THRESHOLD_MAX 1000 +#define SETTING_NAV_MC_BRAKING_DISENGAGE_SPEED_DEFAULT 75 +#define SETTING_NAV_MC_BRAKING_DISENGAGE_SPEED 366 +#define SETTING_NAV_MC_BRAKING_DISENGAGE_SPEED_MIN 0 +#define SETTING_NAV_MC_BRAKING_DISENGAGE_SPEED_MAX 1000 +#define SETTING_NAV_MC_BRAKING_TIMEOUT_DEFAULT 2000 +#define SETTING_NAV_MC_BRAKING_TIMEOUT 367 +#define SETTING_NAV_MC_BRAKING_TIMEOUT_MIN 100 +#define SETTING_NAV_MC_BRAKING_TIMEOUT_MAX 5000 +#define SETTING_NAV_MC_BRAKING_BOOST_FACTOR_DEFAULT 100 +#define SETTING_NAV_MC_BRAKING_BOOST_FACTOR 368 +#define SETTING_NAV_MC_BRAKING_BOOST_FACTOR_MIN 0 +#define SETTING_NAV_MC_BRAKING_BOOST_FACTOR_MAX 200 +#define SETTING_NAV_MC_BRAKING_BOOST_TIMEOUT_DEFAULT 750 +#define SETTING_NAV_MC_BRAKING_BOOST_TIMEOUT 369 +#define SETTING_NAV_MC_BRAKING_BOOST_TIMEOUT_MIN 0 +#define SETTING_NAV_MC_BRAKING_BOOST_TIMEOUT_MAX 5000 +#define SETTING_NAV_MC_BRAKING_BOOST_SPEED_THRESHOLD_DEFAULT 150 +#define SETTING_NAV_MC_BRAKING_BOOST_SPEED_THRESHOLD 370 +#define SETTING_NAV_MC_BRAKING_BOOST_SPEED_THRESHOLD_MIN 100 +#define SETTING_NAV_MC_BRAKING_BOOST_SPEED_THRESHOLD_MAX 1000 +#define SETTING_NAV_MC_BRAKING_BOOST_DISENGAGE_SPEED_DEFAULT 100 +#define SETTING_NAV_MC_BRAKING_BOOST_DISENGAGE_SPEED 371 +#define SETTING_NAV_MC_BRAKING_BOOST_DISENGAGE_SPEED_MIN 0 +#define SETTING_NAV_MC_BRAKING_BOOST_DISENGAGE_SPEED_MAX 1000 +#define SETTING_NAV_MC_BRAKING_BANK_ANGLE_DEFAULT 40 +#define SETTING_NAV_MC_BRAKING_BANK_ANGLE 372 +#define SETTING_NAV_MC_BRAKING_BANK_ANGLE_MIN 15 +#define SETTING_NAV_MC_BRAKING_BANK_ANGLE_MAX 60 +#define SETTING_NAV_MC_POS_DECELERATION_TIME_DEFAULT 120 +#define SETTING_NAV_MC_POS_DECELERATION_TIME 373 +#define SETTING_NAV_MC_POS_DECELERATION_TIME_MIN 0 +#define SETTING_NAV_MC_POS_DECELERATION_TIME_MAX 255 +#define SETTING_NAV_MC_POS_EXPO_DEFAULT 10 +#define SETTING_NAV_MC_POS_EXPO 374 +#define SETTING_NAV_MC_POS_EXPO_MIN 0 +#define SETTING_NAV_MC_POS_EXPO_MAX 255 +#define SETTING_NAV_MC_WP_SLOWDOWN_DEFAULT 1 +#define SETTING_NAV_MC_WP_SLOWDOWN 375 +#define SETTING_NAV_MC_WP_SLOWDOWN_MIN 0 +#define SETTING_NAV_MC_WP_SLOWDOWN_MAX 0 +#define SETTING_NAV_FW_BANK_ANGLE_DEFAULT 35 +#define SETTING_NAV_FW_BANK_ANGLE 376 +#define SETTING_NAV_FW_BANK_ANGLE_MIN 5 +#define SETTING_NAV_FW_BANK_ANGLE_MAX 80 +#define SETTING_NAV_FW_CLIMB_ANGLE_DEFAULT 20 +#define SETTING_NAV_FW_CLIMB_ANGLE 377 +#define SETTING_NAV_FW_CLIMB_ANGLE_MIN 5 +#define SETTING_NAV_FW_CLIMB_ANGLE_MAX 80 +#define SETTING_NAV_FW_DIVE_ANGLE_DEFAULT 15 +#define SETTING_NAV_FW_DIVE_ANGLE 378 +#define SETTING_NAV_FW_DIVE_ANGLE_MIN 5 +#define SETTING_NAV_FW_DIVE_ANGLE_MAX 80 +#define SETTING_NAV_FW_PITCH2THR_SMOOTHING_DEFAULT 6 +#define SETTING_NAV_FW_PITCH2THR_SMOOTHING 379 +#define SETTING_NAV_FW_PITCH2THR_SMOOTHING_MIN 0 +#define SETTING_NAV_FW_PITCH2THR_SMOOTHING_MAX 9 +#define SETTING_FW_MIN_THROTTLE_DOWN_PITCH_DEFAULT 0 +#define SETTING_FW_MIN_THROTTLE_DOWN_PITCH 380 +#define SETTING_FW_MIN_THROTTLE_DOWN_PITCH_MIN 0 +#define SETTING_FW_MIN_THROTTLE_DOWN_PITCH_MAX 450 +#define SETTING_NAV_FW_PITCH2THR_THRESHOLD_DEFAULT 50 +#define SETTING_NAV_FW_PITCH2THR_THRESHOLD 381 +#define SETTING_NAV_FW_PITCH2THR_THRESHOLD_MIN 0 +#define SETTING_NAV_FW_PITCH2THR_THRESHOLD_MAX 900 +#define SETTING_NAV_FW_LOITER_RADIUS_DEFAULT 7500 +#define SETTING_NAV_FW_LOITER_RADIUS 382 +#define SETTING_NAV_FW_LOITER_RADIUS_MIN 0 +#define SETTING_NAV_FW_LOITER_RADIUS_MAX 30000 +#define SETTING_FW_LOITER_DIRECTION_DEFAULT 0 +#define SETTING_FW_LOITER_DIRECTION 383 +#define SETTING_FW_LOITER_DIRECTION_MIN 0 +#define SETTING_FW_LOITER_DIRECTION_MAX 0 +#define SETTING_NAV_FW_CRUISE_SPEED_DEFAULT 0 +#define SETTING_NAV_FW_CRUISE_SPEED 384 +#define SETTING_NAV_FW_CRUISE_SPEED_MIN 0 +#define SETTING_NAV_FW_CRUISE_SPEED_MAX 65535 +#define SETTING_NAV_FW_CONTROL_SMOOTHNESS_DEFAULT 0 +#define SETTING_NAV_FW_CONTROL_SMOOTHNESS 385 +#define SETTING_NAV_FW_CONTROL_SMOOTHNESS_MIN 0 +#define SETTING_NAV_FW_CONTROL_SMOOTHNESS_MAX 9 +#define SETTING_NAV_FW_LAND_DIVE_ANGLE_DEFAULT 2 +#define SETTING_NAV_FW_LAND_DIVE_ANGLE 386 +#define SETTING_NAV_FW_LAND_DIVE_ANGLE_MIN -20 +#define SETTING_NAV_FW_LAND_DIVE_ANGLE_MAX 20 +#define SETTING_NAV_FW_LAUNCH_VELOCITY_DEFAULT 300 +#define SETTING_NAV_FW_LAUNCH_VELOCITY 387 +#define SETTING_NAV_FW_LAUNCH_VELOCITY_MIN 100 +#define SETTING_NAV_FW_LAUNCH_VELOCITY_MAX 10000 +#define SETTING_NAV_FW_LAUNCH_ACCEL_DEFAULT 1863 +#define SETTING_NAV_FW_LAUNCH_ACCEL 388 +#define SETTING_NAV_FW_LAUNCH_ACCEL_MIN 1000 +#define SETTING_NAV_FW_LAUNCH_ACCEL_MAX 20000 +#define SETTING_NAV_FW_LAUNCH_MAX_ANGLE_DEFAULT 45 +#define SETTING_NAV_FW_LAUNCH_MAX_ANGLE 389 +#define SETTING_NAV_FW_LAUNCH_MAX_ANGLE_MIN 5 +#define SETTING_NAV_FW_LAUNCH_MAX_ANGLE_MAX 180 +#define SETTING_NAV_FW_LAUNCH_DETECT_TIME_DEFAULT 40 +#define SETTING_NAV_FW_LAUNCH_DETECT_TIME 390 +#define SETTING_NAV_FW_LAUNCH_DETECT_TIME_MIN 10 +#define SETTING_NAV_FW_LAUNCH_DETECT_TIME_MAX 1000 +#define SETTING_NAV_FW_LAUNCH_IDLE_MOTOR_DELAY_DEFAULT 0 +#define SETTING_NAV_FW_LAUNCH_IDLE_MOTOR_DELAY 391 +#define SETTING_NAV_FW_LAUNCH_IDLE_MOTOR_DELAY_MIN 0 +#define SETTING_NAV_FW_LAUNCH_IDLE_MOTOR_DELAY_MAX 60000 +#define SETTING_NAV_FW_LAUNCH_MOTOR_DELAY_DEFAULT 500 +#define SETTING_NAV_FW_LAUNCH_MOTOR_DELAY 392 +#define SETTING_NAV_FW_LAUNCH_MOTOR_DELAY_MIN 0 +#define SETTING_NAV_FW_LAUNCH_MOTOR_DELAY_MAX 5000 +#define SETTING_NAV_FW_LAUNCH_SPINUP_TIME_DEFAULT 100 +#define SETTING_NAV_FW_LAUNCH_SPINUP_TIME 393 +#define SETTING_NAV_FW_LAUNCH_SPINUP_TIME_MIN 0 +#define SETTING_NAV_FW_LAUNCH_SPINUP_TIME_MAX 1000 +#define SETTING_NAV_FW_LAUNCH_END_TIME_DEFAULT 3000 +#define SETTING_NAV_FW_LAUNCH_END_TIME 394 +#define SETTING_NAV_FW_LAUNCH_END_TIME_MIN 0 +#define SETTING_NAV_FW_LAUNCH_END_TIME_MAX 5000 +#define SETTING_NAV_FW_LAUNCH_MIN_TIME_DEFAULT 0 +#define SETTING_NAV_FW_LAUNCH_MIN_TIME 395 +#define SETTING_NAV_FW_LAUNCH_MIN_TIME_MIN 0 +#define SETTING_NAV_FW_LAUNCH_MIN_TIME_MAX 60000 +#define SETTING_NAV_FW_LAUNCH_TIMEOUT_DEFAULT 5000 +#define SETTING_NAV_FW_LAUNCH_TIMEOUT 396 +#define SETTING_NAV_FW_LAUNCH_TIMEOUT_MIN 0 +#define SETTING_NAV_FW_LAUNCH_TIMEOUT_MAX 60000 +#define SETTING_NAV_FW_LAUNCH_MAX_ALTITUDE_DEFAULT 0 +#define SETTING_NAV_FW_LAUNCH_MAX_ALTITUDE 397 +#define SETTING_NAV_FW_LAUNCH_MAX_ALTITUDE_MIN 0 +#define SETTING_NAV_FW_LAUNCH_MAX_ALTITUDE_MAX 60000 +#define SETTING_NAV_FW_LAUNCH_CLIMB_ANGLE_DEFAULT 18 +#define SETTING_NAV_FW_LAUNCH_CLIMB_ANGLE 398 +#define SETTING_NAV_FW_LAUNCH_CLIMB_ANGLE_MIN 5 +#define SETTING_NAV_FW_LAUNCH_CLIMB_ANGLE_MAX 45 +#define SETTING_NAV_FW_LAUNCH_MANUAL_THROTTLE_DEFAULT 0 +#define SETTING_NAV_FW_LAUNCH_MANUAL_THROTTLE 399 +#define SETTING_NAV_FW_LAUNCH_MANUAL_THROTTLE_MIN 0 +#define SETTING_NAV_FW_LAUNCH_MANUAL_THROTTLE_MAX 0 +#define SETTING_NAV_FW_LAUNCH_ABORT_DEADBAND_DEFAULT 100 +#define SETTING_NAV_FW_LAUNCH_ABORT_DEADBAND 400 +#define SETTING_NAV_FW_LAUNCH_ABORT_DEADBAND_MIN 2 +#define SETTING_NAV_FW_LAUNCH_ABORT_DEADBAND_MAX 250 +#define SETTING_NAV_FW_CRUISE_YAW_RATE_DEFAULT 20 +#define SETTING_NAV_FW_CRUISE_YAW_RATE 401 +#define SETTING_NAV_FW_CRUISE_YAW_RATE_MIN 0 +#define SETTING_NAV_FW_CRUISE_YAW_RATE_MAX 60 +#define SETTING_NAV_FW_ALLOW_MANUAL_THR_INCREASE_DEFAULT 0 +#define SETTING_NAV_FW_ALLOW_MANUAL_THR_INCREASE 402 +#define SETTING_NAV_FW_ALLOW_MANUAL_THR_INCREASE_MIN 0 +#define SETTING_NAV_FW_ALLOW_MANUAL_THR_INCREASE_MAX 0 +#define SETTING_NAV_USE_FW_YAW_CONTROL_DEFAULT 0 +#define SETTING_NAV_USE_FW_YAW_CONTROL 403 +#define SETTING_NAV_USE_FW_YAW_CONTROL_MIN 0 +#define SETTING_NAV_USE_FW_YAW_CONTROL_MAX 0 +#define SETTING_NAV_FW_YAW_DEADBAND_DEFAULT 0 +#define SETTING_NAV_FW_YAW_DEADBAND 404 +#define SETTING_NAV_FW_YAW_DEADBAND_MIN 0 +#define SETTING_NAV_FW_YAW_DEADBAND_MAX 90 +#define SETTING_OSD_TELEMETRY_DEFAULT 0 +#define SETTING_OSD_TELEMETRY 405 +#define SETTING_OSD_TELEMETRY_MIN 0 +#define SETTING_OSD_TELEMETRY_MAX 0 +#define SETTING_OSD_VIDEO_SYSTEM_DEFAULT 0 +#define SETTING_OSD_VIDEO_SYSTEM 406 +#define SETTING_OSD_VIDEO_SYSTEM_MIN 0 +#define SETTING_OSD_VIDEO_SYSTEM_MAX 0 +#define SETTING_OSD_ROW_SHIFTDOWN_DEFAULT 0 +#define SETTING_OSD_ROW_SHIFTDOWN 407 +#define SETTING_OSD_ROW_SHIFTDOWN_MIN 0 +#define SETTING_OSD_ROW_SHIFTDOWN_MAX 1 +#define SETTING_OSD_UNITS_DEFAULT 1 +#define SETTING_OSD_UNITS 408 +#define SETTING_OSD_UNITS_MIN 0 +#define SETTING_OSD_UNITS_MAX 0 +#define SETTING_OSD_STATS_ENERGY_UNIT_DEFAULT 0 +#define SETTING_OSD_STATS_ENERGY_UNIT 409 +#define SETTING_OSD_STATS_ENERGY_UNIT_MIN 0 +#define SETTING_OSD_STATS_ENERGY_UNIT_MAX 0 +#define SETTING_OSD_STATS_MIN_VOLTAGE_UNIT_DEFAULT 0 +#define SETTING_OSD_STATS_MIN_VOLTAGE_UNIT 410 +#define SETTING_OSD_STATS_MIN_VOLTAGE_UNIT_MIN 0 +#define SETTING_OSD_STATS_MIN_VOLTAGE_UNIT_MAX 0 +#define SETTING_OSD_STATS_PAGE_AUTO_SWAP_TIME_DEFAULT 3 +#define SETTING_OSD_STATS_PAGE_AUTO_SWAP_TIME 411 +#define SETTING_OSD_STATS_PAGE_AUTO_SWAP_TIME_MIN 0 +#define SETTING_OSD_STATS_PAGE_AUTO_SWAP_TIME_MAX 10 +#define SETTING_OSD_RSSI_ALARM_DEFAULT 20 +#define SETTING_OSD_RSSI_ALARM 412 +#define SETTING_OSD_RSSI_ALARM_MIN 0 +#define SETTING_OSD_RSSI_ALARM_MAX 100 +#define SETTING_OSD_TIME_ALARM_DEFAULT 10 +#define SETTING_OSD_TIME_ALARM 413 +#define SETTING_OSD_TIME_ALARM_MIN 0 +#define SETTING_OSD_TIME_ALARM_MAX 600 +#define SETTING_OSD_ALT_ALARM_DEFAULT 100 +#define SETTING_OSD_ALT_ALARM 414 +#define SETTING_OSD_ALT_ALARM_MIN 0 +#define SETTING_OSD_ALT_ALARM_MAX 10000 +#define SETTING_OSD_DIST_ALARM_DEFAULT 1000 +#define SETTING_OSD_DIST_ALARM 415 +#define SETTING_OSD_DIST_ALARM_MIN 0 +#define SETTING_OSD_DIST_ALARM_MAX 50000 +#define SETTING_OSD_NEG_ALT_ALARM_DEFAULT 5 +#define SETTING_OSD_NEG_ALT_ALARM 416 +#define SETTING_OSD_NEG_ALT_ALARM_MIN 0 +#define SETTING_OSD_NEG_ALT_ALARM_MAX 10000 +#define SETTING_OSD_CURRENT_ALARM_DEFAULT 0 +#define SETTING_OSD_CURRENT_ALARM 417 +#define SETTING_OSD_CURRENT_ALARM_MIN 0 +#define SETTING_OSD_CURRENT_ALARM_MAX 255 +#define SETTING_OSD_GFORCE_ALARM_DEFAULT 5 +#define SETTING_OSD_GFORCE_ALARM 418 +#define SETTING_OSD_GFORCE_ALARM_MIN 0 +#define SETTING_OSD_GFORCE_ALARM_MAX 20 +#define SETTING_OSD_GFORCE_AXIS_ALARM_MIN_DEFAULT -5 +#define SETTING_OSD_GFORCE_AXIS_ALARM_MIN 419 +#define SETTING_OSD_GFORCE_AXIS_ALARM_MIN_MIN -20 +#define SETTING_OSD_GFORCE_AXIS_ALARM_MIN_MAX 20 +#define SETTING_OSD_GFORCE_AXIS_ALARM_MAX_DEFAULT 5 +#define SETTING_OSD_GFORCE_AXIS_ALARM_MAX 420 +#define SETTING_OSD_GFORCE_AXIS_ALARM_MAX_MIN -20 +#define SETTING_OSD_GFORCE_AXIS_ALARM_MAX_MAX 20 +#define SETTING_OSD_IMU_TEMP_ALARM_MIN_DEFAULT -200 +#define SETTING_OSD_IMU_TEMP_ALARM_MIN 421 +#define SETTING_OSD_IMU_TEMP_ALARM_MIN_MIN -550 +#define SETTING_OSD_IMU_TEMP_ALARM_MIN_MAX 1250 +#define SETTING_OSD_IMU_TEMP_ALARM_MAX_DEFAULT 600 +#define SETTING_OSD_IMU_TEMP_ALARM_MAX 422 +#define SETTING_OSD_IMU_TEMP_ALARM_MAX_MIN -550 +#define SETTING_OSD_IMU_TEMP_ALARM_MAX_MAX 1250 +#define SETTING_OSD_ESC_TEMP_ALARM_MAX_DEFAULT 900 +#define SETTING_OSD_ESC_TEMP_ALARM_MAX 423 +#define SETTING_OSD_ESC_TEMP_ALARM_MAX_MIN -550 +#define SETTING_OSD_ESC_TEMP_ALARM_MAX_MAX 1500 +#define SETTING_OSD_ESC_TEMP_ALARM_MIN_DEFAULT -200 +#define SETTING_OSD_ESC_TEMP_ALARM_MIN 424 +#define SETTING_OSD_ESC_TEMP_ALARM_MIN_MIN -550 +#define SETTING_OSD_ESC_TEMP_ALARM_MIN_MAX 1500 +#define SETTING_OSD_BARO_TEMP_ALARM_MIN_DEFAULT -200 +#define SETTING_OSD_BARO_TEMP_ALARM_MIN 425 +#define SETTING_OSD_BARO_TEMP_ALARM_MIN_MIN -550 +#define SETTING_OSD_BARO_TEMP_ALARM_MIN_MAX 1250 +#define SETTING_OSD_BARO_TEMP_ALARM_MAX_DEFAULT 600 +#define SETTING_OSD_BARO_TEMP_ALARM_MAX 426 +#define SETTING_OSD_BARO_TEMP_ALARM_MAX_MIN -550 +#define SETTING_OSD_BARO_TEMP_ALARM_MAX_MAX 1250 +#define SETTING_OSD_SNR_ALARM_DEFAULT 4 +#define SETTING_OSD_SNR_ALARM 427 +#define SETTING_OSD_SNR_ALARM_MIN -20 +#define SETTING_OSD_SNR_ALARM_MAX 10 +#define SETTING_OSD_LINK_QUALITY_ALARM_DEFAULT 70 +#define SETTING_OSD_LINK_QUALITY_ALARM 428 +#define SETTING_OSD_LINK_QUALITY_ALARM_MIN 0 +#define SETTING_OSD_LINK_QUALITY_ALARM_MAX 100 +#define SETTING_OSD_RSSI_DBM_ALARM_DEFAULT 0 +#define SETTING_OSD_RSSI_DBM_ALARM 429 +#define SETTING_OSD_RSSI_DBM_ALARM_MIN -130 +#define SETTING_OSD_RSSI_DBM_ALARM_MAX 0 +#define SETTING_OSD_RSSI_DBM_MAX_DEFAULT -30 +#define SETTING_OSD_RSSI_DBM_MAX 430 +#define SETTING_OSD_RSSI_DBM_MAX_MIN -50 +#define SETTING_OSD_RSSI_DBM_MAX_MAX 0 +#define SETTING_OSD_RSSI_DBM_MIN_DEFAULT -120 +#define SETTING_OSD_RSSI_DBM_MIN 431 +#define SETTING_OSD_RSSI_DBM_MIN_MIN -130 +#define SETTING_OSD_RSSI_DBM_MIN_MAX 0 +#define SETTING_OSD_TEMP_LABEL_ALIGN_DEFAULT 0 +#define SETTING_OSD_TEMP_LABEL_ALIGN 432 +#define SETTING_OSD_TEMP_LABEL_ALIGN_MIN 0 +#define SETTING_OSD_TEMP_LABEL_ALIGN_MAX 0 +#define SETTING_OSD_AIRSPEED_ALARM_MIN_DEFAULT 0 +#define SETTING_OSD_AIRSPEED_ALARM_MIN 433 +#define SETTING_OSD_AIRSPEED_ALARM_MIN_MIN 0 +#define SETTING_OSD_AIRSPEED_ALARM_MIN_MAX 27000 +#define SETTING_OSD_AIRSPEED_ALARM_MAX_DEFAULT 0 +#define SETTING_OSD_AIRSPEED_ALARM_MAX 434 +#define SETTING_OSD_AIRSPEED_ALARM_MAX_MIN 0 +#define SETTING_OSD_AIRSPEED_ALARM_MAX_MAX 27000 +#define SETTING_OSD_AHI_REVERSE_ROLL_DEFAULT 0 +#define SETTING_OSD_AHI_REVERSE_ROLL 435 +#define SETTING_OSD_AHI_REVERSE_ROLL_MIN 0 +#define SETTING_OSD_AHI_REVERSE_ROLL_MAX 0 +#define SETTING_OSD_AHI_MAX_PITCH_DEFAULT 20 +#define SETTING_OSD_AHI_MAX_PITCH 436 +#define SETTING_OSD_AHI_MAX_PITCH_MIN 10 +#define SETTING_OSD_AHI_MAX_PITCH_MAX 90 +#define SETTING_OSD_CROSSHAIRS_STYLE_DEFAULT 0 +#define SETTING_OSD_CROSSHAIRS_STYLE 437 +#define SETTING_OSD_CROSSHAIRS_STYLE_MIN 0 +#define SETTING_OSD_CROSSHAIRS_STYLE_MAX 0 +#define SETTING_OSD_CRSF_LQ_FORMAT_DEFAULT 0 +#define SETTING_OSD_CRSF_LQ_FORMAT 438 +#define SETTING_OSD_CRSF_LQ_FORMAT_MIN 0 +#define SETTING_OSD_CRSF_LQ_FORMAT_MAX 0 +#define SETTING_OSD_HORIZON_OFFSET_DEFAULT 0 +#define SETTING_OSD_HORIZON_OFFSET 439 +#define SETTING_OSD_HORIZON_OFFSET_MIN -2 +#define SETTING_OSD_HORIZON_OFFSET_MAX 2 +#define SETTING_OSD_CAMERA_UPTILT_DEFAULT 0 +#define SETTING_OSD_CAMERA_UPTILT 440 +#define SETTING_OSD_CAMERA_UPTILT_MIN -40 +#define SETTING_OSD_CAMERA_UPTILT_MAX 80 +#define SETTING_OSD_AHI_CAMERA_UPTILT_COMP_DEFAULT 0 +#define SETTING_OSD_AHI_CAMERA_UPTILT_COMP 441 +#define SETTING_OSD_AHI_CAMERA_UPTILT_COMP_MIN 0 +#define SETTING_OSD_AHI_CAMERA_UPTILT_COMP_MAX 0 +#define SETTING_OSD_CAMERA_FOV_H_DEFAULT 135 +#define SETTING_OSD_CAMERA_FOV_H 442 +#define SETTING_OSD_CAMERA_FOV_H_MIN 60 +#define SETTING_OSD_CAMERA_FOV_H_MAX 150 +#define SETTING_OSD_CAMERA_FOV_V_DEFAULT 85 +#define SETTING_OSD_CAMERA_FOV_V 443 +#define SETTING_OSD_CAMERA_FOV_V_MIN 30 +#define SETTING_OSD_CAMERA_FOV_V_MAX 120 +#define SETTING_OSD_HUD_MARGIN_H_DEFAULT 3 +#define SETTING_OSD_HUD_MARGIN_H 444 +#define SETTING_OSD_HUD_MARGIN_H_MIN 0 +#define SETTING_OSD_HUD_MARGIN_H_MAX 4 +#define SETTING_OSD_HUD_MARGIN_V_DEFAULT 3 +#define SETTING_OSD_HUD_MARGIN_V 445 +#define SETTING_OSD_HUD_MARGIN_V_MIN 1 +#define SETTING_OSD_HUD_MARGIN_V_MAX 3 +#define SETTING_OSD_HUD_HOMING_DEFAULT 0 +#define SETTING_OSD_HUD_HOMING 446 +#define SETTING_OSD_HUD_HOMING_MIN 0 +#define SETTING_OSD_HUD_HOMING_MAX 0 +#define SETTING_OSD_HUD_HOMEPOINT_DEFAULT 0 +#define SETTING_OSD_HUD_HOMEPOINT 447 +#define SETTING_OSD_HUD_HOMEPOINT_MIN 0 +#define SETTING_OSD_HUD_HOMEPOINT_MAX 0 +#define SETTING_OSD_HUD_RADAR_DISP_DEFAULT 0 +#define SETTING_OSD_HUD_RADAR_DISP 448 +#define SETTING_OSD_HUD_RADAR_DISP_MIN 0 +#define SETTING_OSD_HUD_RADAR_DISP_MAX 4 +#define SETTING_OSD_HUD_RADAR_RANGE_MIN_DEFAULT 3 +#define SETTING_OSD_HUD_RADAR_RANGE_MIN 449 +#define SETTING_OSD_HUD_RADAR_RANGE_MIN_MIN 1 +#define SETTING_OSD_HUD_RADAR_RANGE_MIN_MAX 30 +#define SETTING_OSD_HUD_RADAR_RANGE_MAX_DEFAULT 4000 +#define SETTING_OSD_HUD_RADAR_RANGE_MAX 450 +#define SETTING_OSD_HUD_RADAR_RANGE_MAX_MIN 100 +#define SETTING_OSD_HUD_RADAR_RANGE_MAX_MAX 9990 +#define SETTING_OSD_HUD_RADAR_ALT_DIFFERENCE_DISPLAY_TIME_DEFAULT 3 +#define SETTING_OSD_HUD_RADAR_ALT_DIFFERENCE_DISPLAY_TIME 451 +#define SETTING_OSD_HUD_RADAR_ALT_DIFFERENCE_DISPLAY_TIME_MIN 0 +#define SETTING_OSD_HUD_RADAR_ALT_DIFFERENCE_DISPLAY_TIME_MAX 10 +#define SETTING_OSD_HUD_RADAR_DISTANCE_DISPLAY_TIME_DEFAULT 3 +#define SETTING_OSD_HUD_RADAR_DISTANCE_DISPLAY_TIME 452 +#define SETTING_OSD_HUD_RADAR_DISTANCE_DISPLAY_TIME_MIN 1 +#define SETTING_OSD_HUD_RADAR_DISTANCE_DISPLAY_TIME_MAX 10 +#define SETTING_OSD_HUD_WP_DISP_DEFAULT 0 +#define SETTING_OSD_HUD_WP_DISP 453 +#define SETTING_OSD_HUD_WP_DISP_MIN 0 +#define SETTING_OSD_HUD_WP_DISP_MAX 3 +#define SETTING_OSD_LEFT_SIDEBAR_SCROLL_DEFAULT 0 +#define SETTING_OSD_LEFT_SIDEBAR_SCROLL 454 +#define SETTING_OSD_LEFT_SIDEBAR_SCROLL_MIN 0 +#define SETTING_OSD_LEFT_SIDEBAR_SCROLL_MAX 0 +#define SETTING_OSD_RIGHT_SIDEBAR_SCROLL_DEFAULT 0 +#define SETTING_OSD_RIGHT_SIDEBAR_SCROLL 455 +#define SETTING_OSD_RIGHT_SIDEBAR_SCROLL_MIN 0 +#define SETTING_OSD_RIGHT_SIDEBAR_SCROLL_MAX 0 +#define SETTING_OSD_SIDEBAR_SCROLL_ARROWS_DEFAULT 0 +#define SETTING_OSD_SIDEBAR_SCROLL_ARROWS 456 +#define SETTING_OSD_SIDEBAR_SCROLL_ARROWS_MIN 0 +#define SETTING_OSD_SIDEBAR_SCROLL_ARROWS_MAX 0 +#define SETTING_OSD_MAIN_VOLTAGE_DECIMALS_DEFAULT 1 +#define SETTING_OSD_MAIN_VOLTAGE_DECIMALS 457 +#define SETTING_OSD_MAIN_VOLTAGE_DECIMALS_MIN 1 +#define SETTING_OSD_MAIN_VOLTAGE_DECIMALS_MAX 2 +#define SETTING_OSD_COORDINATE_DIGITS_DEFAULT 9 +#define SETTING_OSD_COORDINATE_DIGITS 458 +#define SETTING_OSD_COORDINATE_DIGITS_MIN 8 +#define SETTING_OSD_COORDINATE_DIGITS_MAX 11 +#define SETTING_OSD_ESTIMATIONS_WIND_COMPENSATION_DEFAULT 1 +#define SETTING_OSD_ESTIMATIONS_WIND_COMPENSATION 459 +#define SETTING_OSD_ESTIMATIONS_WIND_COMPENSATION_MIN 0 +#define SETTING_OSD_ESTIMATIONS_WIND_COMPENSATION_MAX 0 +#define SETTING_OSD_FAILSAFE_SWITCH_LAYOUT_DEFAULT 0 +#define SETTING_OSD_FAILSAFE_SWITCH_LAYOUT 460 +#define SETTING_OSD_FAILSAFE_SWITCH_LAYOUT_MIN 0 +#define SETTING_OSD_FAILSAFE_SWITCH_LAYOUT_MAX 0 +#define SETTING_OSD_PLUS_CODE_DIGITS_DEFAULT 11 +#define SETTING_OSD_PLUS_CODE_DIGITS 461 +#define SETTING_OSD_PLUS_CODE_DIGITS_MIN 10 +#define SETTING_OSD_PLUS_CODE_DIGITS_MAX 13 +#define SETTING_OSD_PLUS_CODE_SHORT_DEFAULT 0 +#define SETTING_OSD_PLUS_CODE_SHORT 462 +#define SETTING_OSD_PLUS_CODE_SHORT_MIN 0 +#define SETTING_OSD_PLUS_CODE_SHORT_MAX 0 +#define SETTING_OSD_AHI_STYLE_DEFAULT 0 +#define SETTING_OSD_AHI_STYLE 463 +#define SETTING_OSD_AHI_STYLE_MIN 0 +#define SETTING_OSD_AHI_STYLE_MAX 0 +#define SETTING_OSD_FORCE_GRID_DEFAULT 0 +#define SETTING_OSD_FORCE_GRID 464 +#define SETTING_OSD_FORCE_GRID_MIN 0 +#define SETTING_OSD_FORCE_GRID_MAX 0 +#define SETTING_OSD_AHI_BORDERED_DEFAULT 0 +#define SETTING_OSD_AHI_BORDERED 465 +#define SETTING_OSD_AHI_BORDERED_MIN 0 +#define SETTING_OSD_AHI_BORDERED_MAX 0 +#define SETTING_OSD_AHI_WIDTH_DEFAULT 132 +#define SETTING_OSD_AHI_WIDTH 466 +#define SETTING_OSD_AHI_WIDTH_MIN 0 +#define SETTING_OSD_AHI_WIDTH_MAX 255 +#define SETTING_OSD_AHI_HEIGHT_DEFAULT 162 +#define SETTING_OSD_AHI_HEIGHT 467 +#define SETTING_OSD_AHI_HEIGHT_MIN 0 +#define SETTING_OSD_AHI_HEIGHT_MAX 255 +#define SETTING_OSD_AHI_VERTICAL_OFFSET_DEFAULT -18 +#define SETTING_OSD_AHI_VERTICAL_OFFSET 468 +#define SETTING_OSD_AHI_VERTICAL_OFFSET_MIN -128 +#define SETTING_OSD_AHI_VERTICAL_OFFSET_MAX 127 +#define SETTING_OSD_SIDEBAR_HORIZONTAL_OFFSET_DEFAULT 0 +#define SETTING_OSD_SIDEBAR_HORIZONTAL_OFFSET 469 +#define SETTING_OSD_SIDEBAR_HORIZONTAL_OFFSET_MIN -128 +#define SETTING_OSD_SIDEBAR_HORIZONTAL_OFFSET_MAX 127 +#define SETTING_OSD_LEFT_SIDEBAR_SCROLL_STEP_DEFAULT 0 +#define SETTING_OSD_LEFT_SIDEBAR_SCROLL_STEP 470 +#define SETTING_OSD_LEFT_SIDEBAR_SCROLL_STEP_MIN 0 +#define SETTING_OSD_LEFT_SIDEBAR_SCROLL_STEP_MAX 255 +#define SETTING_OSD_RIGHT_SIDEBAR_SCROLL_STEP_DEFAULT 0 +#define SETTING_OSD_RIGHT_SIDEBAR_SCROLL_STEP 471 +#define SETTING_OSD_RIGHT_SIDEBAR_SCROLL_STEP_MIN 0 +#define SETTING_OSD_RIGHT_SIDEBAR_SCROLL_STEP_MAX 255 +#define SETTING_OSD_SIDEBAR_HEIGHT_DEFAULT 3 +#define SETTING_OSD_SIDEBAR_HEIGHT 472 +#define SETTING_OSD_SIDEBAR_HEIGHT_MIN 0 +#define SETTING_OSD_SIDEBAR_HEIGHT_MAX 5 +#define SETTING_OSD_AHI_PITCH_INTERVAL_DEFAULT 0 +#define SETTING_OSD_AHI_PITCH_INTERVAL 473 +#define SETTING_OSD_AHI_PITCH_INTERVAL_MIN 0 +#define SETTING_OSD_AHI_PITCH_INTERVAL_MAX 30 +#define SETTING_OSD_HOME_POSITION_ARM_SCREEN_DEFAULT 1 +#define SETTING_OSD_HOME_POSITION_ARM_SCREEN 474 +#define SETTING_OSD_HOME_POSITION_ARM_SCREEN_MIN 0 +#define SETTING_OSD_HOME_POSITION_ARM_SCREEN_MAX 0 +#define SETTING_OSD_PAN_SERVO_INDEX_DEFAULT 0 +#define SETTING_OSD_PAN_SERVO_INDEX 475 +#define SETTING_OSD_PAN_SERVO_INDEX_MIN 0 +#define SETTING_OSD_PAN_SERVO_INDEX_MAX 10 +#define SETTING_OSD_PAN_SERVO_PWM2CENTIDEG_DEFAULT 0 +#define SETTING_OSD_PAN_SERVO_PWM2CENTIDEG 476 +#define SETTING_OSD_PAN_SERVO_PWM2CENTIDEG_MIN -36 +#define SETTING_OSD_PAN_SERVO_PWM2CENTIDEG_MAX 36 +#define SETTING_OSD_ESC_RPM_PRECISION_DEFAULT 3 +#define SETTING_OSD_ESC_RPM_PRECISION 477 +#define SETTING_OSD_ESC_RPM_PRECISION_MIN 3 +#define SETTING_OSD_ESC_RPM_PRECISION_MAX 6 +#define SETTING_OSD_MAH_USED_PRECISION_DEFAULT 4 +#define SETTING_OSD_MAH_USED_PRECISION 478 +#define SETTING_OSD_MAH_USED_PRECISION_MIN 4 +#define SETTING_OSD_MAH_USED_PRECISION_MAX 6 +#define SETTING_OSD_SWITCH_INDICATOR_ZERO_NAME_DEFAULT { 70, 76, 65, 80, 0 } +#define SETTING_OSD_SWITCH_INDICATOR_ZERO_NAME 479 +#define SETTING_OSD_SWITCH_INDICATOR_ZERO_NAME_MIN 0 +#define SETTING_OSD_SWITCH_INDICATOR_ZERO_NAME_MAX 5 +#define SETTING_OSD_SWITCH_INDICATOR_ONE_NAME_DEFAULT { 71, 69, 65, 82, 0 } +#define SETTING_OSD_SWITCH_INDICATOR_ONE_NAME 480 +#define SETTING_OSD_SWITCH_INDICATOR_ONE_NAME_MIN 0 +#define SETTING_OSD_SWITCH_INDICATOR_ONE_NAME_MAX 5 +#define SETTING_OSD_SWITCH_INDICATOR_TWO_NAME_DEFAULT { 67, 65, 77, 0 } +#define SETTING_OSD_SWITCH_INDICATOR_TWO_NAME 481 +#define SETTING_OSD_SWITCH_INDICATOR_TWO_NAME_MIN 0 +#define SETTING_OSD_SWITCH_INDICATOR_TWO_NAME_MAX 5 +#define SETTING_OSD_SWITCH_INDICATOR_THREE_NAME_DEFAULT { 76, 73, 71, 84, 0 } +#define SETTING_OSD_SWITCH_INDICATOR_THREE_NAME 482 +#define SETTING_OSD_SWITCH_INDICATOR_THREE_NAME_MIN 0 +#define SETTING_OSD_SWITCH_INDICATOR_THREE_NAME_MAX 5 +#define SETTING_OSD_SWITCH_INDICATOR_ZERO_CHANNEL_DEFAULT 5 +#define SETTING_OSD_SWITCH_INDICATOR_ZERO_CHANNEL 483 +#define SETTING_OSD_SWITCH_INDICATOR_ZERO_CHANNEL_MIN 5 +#define SETTING_OSD_SWITCH_INDICATOR_ZERO_CHANNEL_MAX 18 +#define SETTING_OSD_SWITCH_INDICATOR_ONE_CHANNEL_DEFAULT 5 +#define SETTING_OSD_SWITCH_INDICATOR_ONE_CHANNEL 484 +#define SETTING_OSD_SWITCH_INDICATOR_ONE_CHANNEL_MIN 5 +#define SETTING_OSD_SWITCH_INDICATOR_ONE_CHANNEL_MAX 18 +#define SETTING_OSD_SWITCH_INDICATOR_TWO_CHANNEL_DEFAULT 5 +#define SETTING_OSD_SWITCH_INDICATOR_TWO_CHANNEL 485 +#define SETTING_OSD_SWITCH_INDICATOR_TWO_CHANNEL_MIN 5 +#define SETTING_OSD_SWITCH_INDICATOR_TWO_CHANNEL_MAX 18 +#define SETTING_OSD_SWITCH_INDICATOR_THREE_CHANNEL_DEFAULT 5 +#define SETTING_OSD_SWITCH_INDICATOR_THREE_CHANNEL 486 +#define SETTING_OSD_SWITCH_INDICATOR_THREE_CHANNEL_MIN 5 +#define SETTING_OSD_SWITCH_INDICATOR_THREE_CHANNEL_MAX 18 +#define SETTING_OSD_SWITCH_INDICATORS_ALIGN_LEFT_DEFAULT 1 +#define SETTING_OSD_SWITCH_INDICATORS_ALIGN_LEFT 487 +#define SETTING_OSD_SWITCH_INDICATORS_ALIGN_LEFT_MIN 0 +#define SETTING_OSD_SWITCH_INDICATORS_ALIGN_LEFT_MAX 0 +#define SETTING_OSD_SYSTEM_MSG_DISPLAY_TIME_DEFAULT 1000 +#define SETTING_OSD_SYSTEM_MSG_DISPLAY_TIME 488 +#define SETTING_OSD_SYSTEM_MSG_DISPLAY_TIME_MIN 500 +#define SETTING_OSD_SYSTEM_MSG_DISPLAY_TIME_MAX 5000 +#define SETTING_OSD_SPEED_SOURCE_DEFAULT 0 +#define SETTING_OSD_SPEED_SOURCE 489 +#define SETTING_OSD_SPEED_SOURCE_MIN 0 +#define SETTING_OSD_SPEED_SOURCE_MAX 0 +#define SETTING_DEBUG_MODE_DEFAULT 0 +#define SETTING_DEBUG_MODE 490 +#define SETTING_DEBUG_MODE_MIN 0 +#define SETTING_DEBUG_MODE_MAX 0 +#define SETTING_THROTTLE_TILT_COMP_STR_DEFAULT 0 +#define SETTING_THROTTLE_TILT_COMP_STR 491 +#define SETTING_THROTTLE_TILT_COMP_STR_MIN 0 +#define SETTING_THROTTLE_TILT_COMP_STR_MAX 100 +#define SETTING_NAME_DEFAULT { 0 } +#define SETTING_NAME 492 +#define SETTING_NAME_MIN 0 +#define SETTING_NAME_MAX 16 +#define SETTING_MODE_RANGE_LOGIC_OPERATOR_DEFAULT 0 +#define SETTING_MODE_RANGE_LOGIC_OPERATOR 493 +#define SETTING_MODE_RANGE_LOGIC_OPERATOR_MIN 0 +#define SETTING_MODE_RANGE_LOGIC_OPERATOR_MAX 0 +#define SETTING_STATS_DEFAULT 0 +#define SETTING_STATS 494 +#define SETTING_STATS_MIN 0 +#define SETTING_STATS_MAX 0 +#define SETTING_STATS_TOTAL_TIME_DEFAULT 0 +#define SETTING_STATS_TOTAL_TIME 495 +#define SETTING_STATS_TOTAL_TIME_MIN 0 +#define SETTING_STATS_TOTAL_TIME_MAX 2147483647 +#define SETTING_STATS_TOTAL_DIST_DEFAULT 0 +#define SETTING_STATS_TOTAL_DIST 496 +#define SETTING_STATS_TOTAL_DIST_MIN 0 +#define SETTING_STATS_TOTAL_DIST_MAX 2147483647 +#define SETTING_STATS_TOTAL_ENERGY_DEFAULT 0 +#define SETTING_STATS_TOTAL_ENERGY 497 +#define SETTING_STATS_TOTAL_ENERGY_MIN 0 +#define SETTING_STATS_TOTAL_ENERGY_MAX 2147483647 +#define SETTING_TZ_OFFSET_DEFAULT 0 +#define SETTING_TZ_OFFSET 498 +#define SETTING_TZ_OFFSET_MIN -1440 +#define SETTING_TZ_OFFSET_MAX 1440 +#define SETTING_TZ_AUTOMATIC_DST_DEFAULT 0 +#define SETTING_TZ_AUTOMATIC_DST 499 +#define SETTING_TZ_AUTOMATIC_DST_MIN 0 +#define SETTING_TZ_AUTOMATIC_DST_MAX 0 +#define SETTING_DISPLAY_FORCE_SW_BLINK_DEFAULT 0 +#define SETTING_DISPLAY_FORCE_SW_BLINK 500 +#define SETTING_DISPLAY_FORCE_SW_BLINK_MIN 0 +#define SETTING_DISPLAY_FORCE_SW_BLINK_MAX 0 +#define SETTING_LOG_LEVEL_DEFAULT 0 +#define SETTING_LOG_LEVEL 501 +#define SETTING_LOG_LEVEL_MIN 0 +#define SETTING_LOG_LEVEL_MAX 0 +#define SETTING_LOG_TOPICS_DEFAULT 0 +#define SETTING_LOG_TOPICS 502 +#define SETTING_LOG_TOPICS_MIN 0 +#define SETTING_LOG_TOPICS_MAX 4294967295 +#define SETTING_SMARTPORT_MASTER_HALFDUPLEX_DEFAULT 1 +#define SETTING_SMARTPORT_MASTER_HALFDUPLEX 503 +#define SETTING_SMARTPORT_MASTER_HALFDUPLEX_MIN 0 +#define SETTING_SMARTPORT_MASTER_HALFDUPLEX_MAX 0 +#define SETTING_SMARTPORT_MASTER_INVERTED_DEFAULT 0 +#define SETTING_SMARTPORT_MASTER_INVERTED 504 +#define SETTING_SMARTPORT_MASTER_INVERTED_MIN 0 +#define SETTING_SMARTPORT_MASTER_INVERTED_MAX 0 +#define SETTING_DJI_WORKAROUNDS_DEFAULT 1 +#define SETTING_DJI_WORKAROUNDS 505 +#define SETTING_DJI_WORKAROUNDS_MIN 0 +#define SETTING_DJI_WORKAROUNDS_MAX 255 +#define SETTING_DJI_USE_NAME_FOR_MESSAGES_DEFAULT 1 +#define SETTING_DJI_USE_NAME_FOR_MESSAGES 506 +#define SETTING_DJI_USE_NAME_FOR_MESSAGES_MIN 0 +#define SETTING_DJI_USE_NAME_FOR_MESSAGES_MAX 0 +#define SETTING_DJI_ESC_TEMP_SOURCE_DEFAULT 0 +#define SETTING_DJI_ESC_TEMP_SOURCE 507 +#define SETTING_DJI_ESC_TEMP_SOURCE_MIN 0 +#define SETTING_DJI_ESC_TEMP_SOURCE_MAX 0 +#define SETTING_DJI_MESSAGE_SPEED_SOURCE_DEFAULT 1 +#define SETTING_DJI_MESSAGE_SPEED_SOURCE 508 +#define SETTING_DJI_MESSAGE_SPEED_SOURCE_MIN 0 +#define SETTING_DJI_MESSAGE_SPEED_SOURCE_MAX 0 +#define SETTING_DJI_RSSI_SOURCE_DEFAULT 0 +#define SETTING_DJI_RSSI_SOURCE 509 +#define SETTING_DJI_RSSI_SOURCE_MIN 0 +#define SETTING_DJI_RSSI_SOURCE_MAX 0 +#define SETTING_DJI_USE_ADJUSTMENTS_DEFAULT 0 +#define SETTING_DJI_USE_ADJUSTMENTS 510 +#define SETTING_DJI_USE_ADJUSTMENTS_MIN 0 +#define SETTING_DJI_USE_ADJUSTMENTS_MAX 0 +#define SETTING_DJI_CN_ALTERNATING_DURATION_DEFAULT 30 +#define SETTING_DJI_CN_ALTERNATING_DURATION 511 +#define SETTING_DJI_CN_ALTERNATING_DURATION_MIN 1 +#define SETTING_DJI_CN_ALTERNATING_DURATION_MAX 150 +#define SETTING_DSHOT_BEEPER_ENABLED_DEFAULT 1 +#define SETTING_DSHOT_BEEPER_ENABLED 512 +#define SETTING_DSHOT_BEEPER_ENABLED_MIN 0 +#define SETTING_DSHOT_BEEPER_ENABLED_MAX 0 +#define SETTING_DSHOT_BEEPER_TONE_DEFAULT 1 +#define SETTING_DSHOT_BEEPER_TONE 513 +#define SETTING_DSHOT_BEEPER_TONE_MIN 1 +#define SETTING_DSHOT_BEEPER_TONE_MAX 5 +#define SETTING_BEEPER_PWM_MODE_DEFAULT 0 +#define SETTING_BEEPER_PWM_MODE 514 +#define SETTING_BEEPER_PWM_MODE_MIN 0 +#define SETTING_BEEPER_PWM_MODE_MAX 0 +#define SETTING_LIMIT_PI_P_DEFAULT 100 +#define SETTING_LIMIT_PI_P 515 +#define SETTING_LIMIT_PI_P_MIN 0 +#define SETTING_LIMIT_PI_P_MAX 10000 +#define SETTING_LIMIT_PI_I_DEFAULT 100 +#define SETTING_LIMIT_PI_I 516 +#define SETTING_LIMIT_PI_I_MIN 0 +#define SETTING_LIMIT_PI_I_MAX 10000 +#define SETTING_LIMIT_ATTN_FILTER_CUTOFF_DEFAULT 1.2f +#define SETTING_LIMIT_ATTN_FILTER_CUTOFF 517 +#define SETTING_LIMIT_ATTN_FILTER_CUTOFF_MIN 0 +#define SETTING_LIMIT_ATTN_FILTER_CUTOFF_MAX 100 diff --git a/src/main/flight/imu.c b/src/main/flight/imu.c index bdd69ba6d2..89467545f8 100644 --- a/src/main/flight/imu.c +++ b/src/main/flight/imu.c @@ -111,6 +111,8 @@ STATIC_FASTRAM pt1Filter_t GPS3DspeedFilter; FASTRAM bool gpsHeadingInitialized; +FASTRAM bool imuUpdated = false; + PG_REGISTER_WITH_RESET_TEMPLATE(imuConfig_t, imuConfig, PG_IMU_CONFIG, 2); PG_RESET_TEMPLATE(imuConfig_t, imuConfig, @@ -362,7 +364,7 @@ static void imuMahonyAHRSupdate(float dt, const fpVector3_t * gyroBF, const fpVe vectorNormalize(&vMag, &vMag); #ifdef USE_SIMULATOR - if (ARMING_FLAG(SIMULATOR_MODE)) { + if (ARMING_FLAG(SIMULATOR_MODE_HITL) || ARMING_FLAG(SIMULATOR_MODE_SITL)) { imuSetMagneticDeclination(0); } #endif @@ -511,7 +513,7 @@ static void imuMahonyAHRSupdate(float dt, const fpVector3_t * gyroBF, const fpVe STATIC_UNIT_TESTED void imuUpdateEulerAngles(void) { #ifdef USE_SIMULATOR - if (ARMING_FLAG(SIMULATOR_MODE) && !SIMULATOR_HAS_OPTION(HITL_USE_IMU)) { + if ((ARMING_FLAG(SIMULATOR_MODE_HITL) && !SIMULATOR_HAS_OPTION(HITL_USE_IMU)) || (ARMING_FLAG(SIMULATOR_MODE_SITL) && imuUpdated)) { imuComputeQuaternionFromRPY(attitude.values.roll, attitude.values.pitch, attitude.values.yaw); imuComputeRotationMatrix(); } @@ -633,7 +635,7 @@ static void imuCalculateTurnRateacceleration(fpVector3_t *vEstcentrifugalAccelBF { //fixed wing only static float lastspeed = -1.0f; - float currentspeed; + float currentspeed = 0; if (isGPSTrustworthy()){ //first speed choice is gps currentspeed = GPS3DspeedFiltered; @@ -824,3 +826,15 @@ float calculateCosTiltAngle(void) { return 1.0f - 2.0f * sq(orientation.q1) - 2.0f * sq(orientation.q2); } + +#if defined(SITL_BUILD) || defined (USE_SIMULATOR) + +void imuSetAttitudeRPY(int16_t roll, int16_t pitch, int16_t yaw) +{ + attitude.values.roll = roll; + attitude.values.pitch = pitch; + attitude.values.yaw = yaw; + imuUpdated = true; +} +#endif + diff --git a/src/main/flight/imu.h b/src/main/flight/imu.h index f438cc079f..a3b87e6736 100644 --- a/src/main/flight/imu.h +++ b/src/main/flight/imu.h @@ -86,3 +86,7 @@ void imuTransformVectorBodyToEarth(fpVector3_t * v); void imuTransformVectorEarthToBody(fpVector3_t * v); void imuInit(void); + +#if defined(SITL_BUILD) +void imuSetAttitudeRPY(int16_t roll, int16_t pitch, int16_t yaw); +#endif diff --git a/src/main/flight/kalman.c b/src/main/flight/kalman.c index 6bc869aef8..5ec003859c 100755 --- a/src/main/flight/kalman.c +++ b/src/main/flight/kalman.c @@ -23,7 +23,11 @@ FILE_COMPILE_FOR_SPEED #include +#if !defined(SITL_BUILD) #include "arm_math.h" +#else +#include +#endif #include "kalman.h" #include "build/debug.h" @@ -93,8 +97,13 @@ static void updateAxisVariance(kalman_t *kalmanState, float rate) kalmanState->axisMean = kalmanState->axisSumMean * kalmanState->inverseN; kalmanState->axisVar = kalmanState->axisSumVar * kalmanState->inverseN; +#if !defined(SITL_BUILD) float squirt; arm_sqrt_f32(kalmanState->axisVar, &squirt); +#else + float squirt = sqrtf(kalmanState->axisVar); +#endif + kalmanState->r = squirt * VARIANCE_SCALE; } diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index ee4cf4ef54..ab7eac0070 100644 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -340,6 +340,7 @@ static void applyTurtleModeToMotors(void) { void FAST_CODE writeMotors(void) { +#if !defined(SITL_BUILD) for (int i = 0; i < motorCount; i++) { uint16_t motorValue; @@ -422,6 +423,7 @@ void FAST_CODE writeMotors(void) pwmWriteMotor(i, motorValue); } +#endif } void writeAllMotors(int16_t mc) @@ -442,7 +444,10 @@ void stopMotors(void) void stopPwmAllMotors(void) { +#if !defined(SITL_BUILD) pwmShutdownPulsesForAllMotors(motorCount); +#endif + } static int getReversibleMotorsThrottleDeadband(void) diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c index f3a1b5c6d9..20e3bb1e26 100755 --- a/src/main/flight/servos.c +++ b/src/main/flight/servos.c @@ -223,7 +223,8 @@ static void filterServos(void) void writeServos(void) { filterServos(); - + +#if !defined(SITL_BUILD) int servoIndex = 0; bool zeroServoValue = false; @@ -241,6 +242,7 @@ void writeServos(void) pwmWriteServo(servoIndex++, servo[i]); } } +#endif } void servoMixer(float dT) @@ -573,7 +575,7 @@ void processContinuousServoAutotrim(const float dT) void processServoAutotrim(const float dT) { #ifdef USE_SIMULATOR - if (ARMING_FLAG(SIMULATOR_MODE)) { + if (ARMING_FLAG(SIMULATOR_MODE_HITL)) { return; } #endif diff --git a/src/main/io/gps.c b/src/main/io/gps.c index 042286c238..85418c7c2d 100755 --- a/src/main/io/gps.c +++ b/src/main/io/gps.c @@ -103,6 +103,13 @@ static gpsProviderDescriptor_t gpsProviders[GPS_PROVIDER_COUNT] = { #else { false, 0, NULL, NULL }, #endif + +#ifdef USE_GPS_FAKE + {true, 0, &gpsFakeRestart, &gpsFakeHandle}, +#else + { false, 0, NULL, NULL }, +#endif + }; PG_REGISTER_WITH_RESET_TEMPLATE(gpsConfig_t, gpsConfig, PG_GPS_CONFIG, 2); @@ -251,76 +258,6 @@ void gpsInit(void) gpsSetState(GPS_INITIALIZING); } -#ifdef USE_FAKE_GPS -static bool gpsFakeGPSUpdate(void) -{ -#define FAKE_GPS_INITIAL_LAT 509102311 -#define FAKE_GPS_INITIAL_LON -15349744 -#define FAKE_GPS_GROUND_ARMED_SPEED 350 // In cm/s -#define FAKE_GPS_GROUND_UNARMED_SPEED 0 -#define FAKE_GPS_GROUND_COURSE_DECIDEGREES 300 //30deg - - // Each degree in latitude corresponds to 111km. - // Each degree in longitude at the equator is 111km, - // going down to zero as latitude gets close to 90º. - // We approximate it linearly. - - static int32_t lat = FAKE_GPS_INITIAL_LAT; - static int32_t lon = FAKE_GPS_INITIAL_LON; - - timeMs_t now = millis(); - uint32_t delta = now - gpsState.lastMessageMs; - if (delta > 100) { - int32_t speed = ARMING_FLAG(ARMED) ? FAKE_GPS_GROUND_ARMED_SPEED : FAKE_GPS_GROUND_UNARMED_SPEED; - speed = speed * sin_approx((now % 1000) / 1000.f * M_PIf) * +speed; - int32_t cmDelta = speed * (delta / 1000.0f); - int32_t latCmDelta = cmDelta * cos_approx(DECIDEGREES_TO_RADIANS(FAKE_GPS_GROUND_COURSE_DECIDEGREES)); - int32_t lonCmDelta = cmDelta * sin_approx(DECIDEGREES_TO_RADIANS(FAKE_GPS_GROUND_COURSE_DECIDEGREES)); - int32_t latDelta = ceilf((float)latCmDelta / (111 * 1000 * 100 / 1e7)); - int32_t lonDelta = ceilf((float)lonCmDelta / (111 * 1000 * 100 / 1e7)); - if (speed > 0 && latDelta == 0 && lonDelta == 0) { - return false; - } - lat += latDelta; - lon += lonDelta; - gpsSol.fixType = GPS_FIX_3D; - gpsSol.numSat = 6; - gpsSol.llh.lat = lat; - gpsSol.llh.lon = lon; - gpsSol.llh.alt = 0; - gpsSol.groundSpeed = speed; - gpsSol.groundCourse = FAKE_GPS_GROUND_COURSE_DECIDEGREES; - gpsSol.velNED[X] = speed * cos_approx(DECIDEGREES_TO_RADIANS(FAKE_GPS_GROUND_COURSE_DECIDEGREES)); - gpsSol.velNED[Y] = speed * sin_approx(DECIDEGREES_TO_RADIANS(FAKE_GPS_GROUND_COURSE_DECIDEGREES)); - gpsSol.velNED[Z] = 0; - gpsSol.flags.validVelNE = true; - gpsSol.flags.validVelD = true; - gpsSol.flags.validEPE = true; - gpsSol.flags.validTime = true; - gpsSol.eph = 100; - gpsSol.epv = 100; - gpsSol.time.year = 1983; - gpsSol.time.month = 1; - gpsSol.time.day = 1; - gpsSol.time.hours = 3; - gpsSol.time.minutes = 15; - gpsSol.time.seconds = 42; - - ENABLE_STATE(GPS_FIX); - sensorsSet(SENSOR_GPS); - gpsUpdateTime(); - onNewGPSData(); - - gpsSetProtocolTimeout(gpsState.baseTimeoutMs); - - gpsSetState(GPS_RUNNING); - gpsSol.flags.gpsHeartbeat = !gpsSol.flags.gpsHeartbeat; - return true; - } - return false; -} -#endif - uint16_t gpsConstrainEPE(uint32_t epe) { return (epe > 9999) ? 9999 : epe; // max 99.99m error @@ -348,16 +285,13 @@ bool gpsUpdate(void) } #ifdef USE_SIMULATOR - if (ARMING_FLAG(SIMULATOR_MODE)) { + if (ARMING_FLAG(SIMULATOR_MODE_HITL)) { gpsUpdateTime(); gpsSetState(GPS_RUNNING); sensorsSet(SENSOR_GPS); return gpsSol.flags.hasNewData; } #endif -#ifdef USE_FAKE_GPS - return gpsFakeGPSUpdate(); -#else // Assume that we don't have new data this run gpsSol.flags.hasNewData = false; @@ -403,7 +337,6 @@ bool gpsUpdate(void) } return gpsSol.flags.hasNewData; -#endif } void gpsEnablePassthrough(serialPort_t *gpsPassthroughPort) diff --git a/src/main/io/gps.h b/src/main/io/gps.h index e887dae254..92241c9560 100755 --- a/src/main/io/gps.h +++ b/src/main/io/gps.h @@ -18,6 +18,7 @@ #pragma once #include +#include #include "config/parameter_group.h" @@ -36,6 +37,7 @@ typedef enum { GPS_UBLOX, GPS_UBLOX7PLUS, GPS_MSP, + GPS_FAKE, GPS_PROVIDER_COUNT } gpsProvider_e; @@ -162,3 +164,18 @@ bool isGPSHeadingValid(void); struct serialPort_s; void gpsEnablePassthrough(struct serialPort_s *gpsPassthroughPort); void mspGPSReceiveNewData(const uint8_t * bufferPtr); + +#if defined(USE_GPS_FAKE) +void gpsFakeSet( + gpsFixType_e fixType, + uint8_t numSat, + int32_t lat, + int32_t lon, + int32_t alt, + int16_t groundSpeed, + int16_t groundCourse, + int16_t velNED_X, + int16_t velNED_Y, + int16_t velNED_Z, + time_t time); +#endif diff --git a/src/main/io/gps_fake.c b/src/main/io/gps_fake.c new file mode 100644 index 0000000000..e056ed5a3f --- /dev/null +++ b/src/main/io/gps_fake.c @@ -0,0 +1,98 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#include +#include +#include +#include +#include +#include + +#include "platform.h" +#include "build/build_config.h" + +#if defined(USE_GPS_FAKE) + +#include "common/axis.h" + +#include "io/gps.h" +#include "io/gps_private.h" + +void gpsFakeRestart(void) +{ + // NOP +} + +void gpsFakeHandle(void) +{ + gpsProcessNewSolutionData(); +} + +void gpsFakeSet( + gpsFixType_e fixType, + uint8_t numSat, + int32_t lat, + int32_t lon, + int32_t alt, + int16_t groundSpeed, + int16_t groundCourse, + int16_t velNED_X, + int16_t velNED_Y, + int16_t velNED_Z, + time_t time) +{ + gpsSol.fixType = fixType; + gpsSol.hdop = gpsSol.fixType == GPS_NO_FIX ? 9999 : 100; + gpsSol.numSat = numSat; + + gpsSol.llh.lat = lat; + gpsSol.llh.lon = lon; + gpsSol.llh.alt = alt; + gpsSol.groundSpeed = groundSpeed; + gpsSol.groundCourse = groundCourse; + gpsSol.velNED[X] = velNED_X; + gpsSol.velNED[Y] = velNED_Y; + gpsSol.velNED[Z] = velNED_Z; + gpsSol.eph = 100; + gpsSol.epv = 100; + gpsSol.flags.validVelNE = true; + gpsSol.flags.validVelD = true; + gpsSol.flags.validEPE = true; + gpsSol.flags.hasNewData = true; + + if (time) { + struct tm* gTime = gmtime(&time); + + gpsSol.time.year = (uint16_t)(gTime->tm_year + 1900); + gpsSol.time.month = (uint16_t)(gTime->tm_mon + 1); + gpsSol.time.day = (uint8_t)gTime->tm_mday; + gpsSol.time.hours = (uint8_t)gTime->tm_hour; + gpsSol.time.minutes = (uint8_t)gTime->tm_min; + gpsSol.time.seconds = (uint8_t)gTime->tm_sec; + gpsSol.time.millis = 0; + gpsSol.flags.validTime = gpsSol.fixType >= 3; + } +} + +#endif \ No newline at end of file diff --git a/src/main/io/gps_private.h b/src/main/io/gps_private.h index fd35d8540f..6e9abc72ff 100755 --- a/src/main/io/gps_private.h +++ b/src/main/io/gps_private.h @@ -78,4 +78,10 @@ extern void gpsHandleNMEA(void); extern void gpsRestartMSP(void); extern void gpsHandleMSP(void); +#if defined(USE_GPS_FAKE) +extern void gpsFakeRestart(void); +extern void gpsFakeHandle(void); +#endif + + #endif diff --git a/src/main/io/osd.c b/src/main/io/osd.c index fdee5180e1..e891c4533a 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -626,7 +626,7 @@ static uint16_t osdGetCrsfLQ(void) { int16_t statsLQ = rxLinkStatistics.uplinkLQ; int16_t scaledLQ = scaleRange(constrain(statsLQ, 0, 100), 0, 100, 170, 300); - int16_t displayedLQ; + int16_t displayedLQ = 0; switch (osdConfig()->crsf_lq_format) { case OSD_CRSF_LQ_TYPE1: displayedLQ = statsLQ; @@ -713,7 +713,7 @@ static void osdFormatCoordinate(char *buff, char sym, int32_t val) // longitude maximum integer width is 4 (-180). int integerDigits = tfp_sprintf(buff + 1, (integerPart == 0 && val < 0) ? "-%d" : "%d", (int)integerPart); // We can show up to 7 digits in decimalPart. - int32_t decimalPart = abs(val % GPS_DEGREES_DIVIDER); + int32_t decimalPart = abs(val % (int)GPS_DEGREES_DIVIDER); STATIC_ASSERT(GPS_DEGREES_DIVIDER == 1e7, adjust_max_decimal_digits); int decimalDigits = tfp_sprintf(buff + 1 + integerDigits, "%07d", (int)decimalPart); // Embbed the decimal separator @@ -850,7 +850,9 @@ static const char * osdArmingDisabledReasonMessage(void) FALLTHROUGH; case ARMED: FALLTHROUGH; - case SIMULATOR_MODE: + case SIMULATOR_MODE_HITL: + FALLTHROUGH; + case SIMULATOR_MODE_SITL: FALLTHROUGH; case WAS_EVER_ARMED: break; diff --git a/src/main/io/osd_dji_hd.c b/src/main/io/osd_dji_hd.c index 70b14a69cb..e46816712e 100644 --- a/src/main/io/osd_dji_hd.c +++ b/src/main/io/osd_dji_hd.c @@ -537,7 +537,9 @@ static char * osdArmingDisabledReasonMessage(void) FALLTHROUGH; case ARMED: FALLTHROUGH; - case SIMULATOR_MODE: + case SIMULATOR_MODE_HITL: + FALLTHROUGH; + case SIMULATOR_MODE_SITL: FALLTHROUGH; case WAS_EVER_ARMED: break; diff --git a/src/main/io/serial.c b/src/main/io/serial.c index 3ca560cf30..35b71e12b3 100644 --- a/src/main/io/serial.c +++ b/src/main/io/serial.c @@ -40,6 +40,10 @@ #include "drivers/serial_uart.h" #endif +#if defined(SITL_BUILD) +#include "drivers/serial_tcp.h" +#endif + #include "drivers/light_led.h" #if defined(USE_VCP) @@ -328,6 +332,13 @@ bool doesConfigurationUsePort(serialPortIdentifier_e identifier) return candidate != NULL && candidate->functionMask; } +#if defined(SITL_BUILD) +serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, void *rxCallbackData, uint32_t baudRate, portMode_t mode, portOptions_t options) +{ + return tcpOpen(USARTx, callback, rxCallbackData, baudRate, mode, options); +} +#endif + serialPort_t *openSerialPort( serialPortIdentifier_e identifier, serialPortFunction_e function, diff --git a/src/main/io/vtx.c b/src/main/io/vtx.c index c7891ce6bd..495554e93a 100644 --- a/src/main/io/vtx.c +++ b/src/main/io/vtx.c @@ -22,6 +22,7 @@ #include #include "platform.h" +#if defined(USE_VTX_CONTROL) #include "common/maths.h" #include "common/time.h" @@ -194,3 +195,5 @@ void vtxUpdate(timeUs_t currentTimeUs) currentSchedule = (currentSchedule + 1) % VTX_PARAM_COUNT; } } + +#endif diff --git a/src/main/main.c b/src/main/main.c index 7a46b485d7..c002fbab25 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -53,8 +53,14 @@ static void processLoopback(void) #endif } +#if defined(SITL_BUILD) +int main(int argc, char *argv[]) +{ + parseArguments(argc, argv); +#else int main(void) { +#endif init(); loopbackInit(); diff --git a/src/main/navigation/navigation_pos_estimator.c b/src/main/navigation/navigation_pos_estimator.c index ab97944623..b231492540 100755 --- a/src/main/navigation/navigation_pos_estimator.c +++ b/src/main/navigation/navigation_pos_estimator.c @@ -445,7 +445,7 @@ static void updateIMUTopic(timeUs_t currentTimeUs) /* If calibration is incomplete - report zero acceleration */ if (gravityCalibrationComplete()) { #ifdef USE_SIMULATOR - if (ARMING_FLAG(SIMULATOR_MODE)) { + if (ARMING_FLAG(SIMULATOR_MODE_HITL) || ARMING_FLAG(SIMULATOR_MODE_SITL)) { posEstimator.imu.calibratedGravityCMSS = GRAVITY_CMSS; } #endif diff --git a/src/main/programming/logic_condition.c b/src/main/programming/logic_condition.c index d7d96b0a9f..63481d7b3f 100644 --- a/src/main/programming/logic_condition.c +++ b/src/main/programming/logic_condition.c @@ -93,7 +93,9 @@ static int logicConditionCompute( uint8_t lcIndex ) { int temporaryValue; +#if defined(USE_VTX_CONTROL) vtxDeviceCapability_t vtxDeviceCapability; +#endif switch (operation) { @@ -284,7 +286,8 @@ static int logicConditionCompute( break; case LOGIC_CONDITION_SET_VTX_POWER_LEVEL: -#if defined(USE_VTX_SMARTAUDIO) || defined(USE_VTX_TRAMP) +#if defined(USE_VTX_CONTROL) +#if(defined(USE_VTX_SMARTAUDIO) || defined(USE_VTX_TRAMP)) if ( logicConditionValuesByType[LOGIC_CONDITION_SET_VTX_POWER_LEVEL] != operandA && vtxCommonGetDeviceCapability(vtxCommonDevice(), &vtxDeviceCapability) @@ -324,7 +327,7 @@ static int logicConditionCompute( return false; } break; - +#endif case LOGIC_CONDITION_INVERT_ROLL: LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_ROLL); return true; diff --git a/src/main/rx/fport.c b/src/main/rx/fport.c index 79b07766b3..b859390c0f 100644 --- a/src/main/rx/fport.c +++ b/src/main/rx/fport.c @@ -36,8 +36,8 @@ FILE_COMPILE_FOR_SPEED #ifdef USE_TELEMETRY #include "telemetry/telemetry.h" -#include "telemetry/smartport.h" #endif +#include "telemetry/smartport.h" #include "rx/frsky_crc.h" #include "rx/rx.h" diff --git a/src/main/sensors/acceleration.c b/src/main/sensors/acceleration.c index 45be068a39..ed125f36c3 100644 --- a/src/main/sensors/acceleration.c +++ b/src/main/sensors/acceleration.c @@ -504,7 +504,7 @@ float accGetMeasuredMaxG(void) void accUpdate(void) { #ifdef USE_SIMULATOR - if (ARMING_FLAG(SIMULATOR_MODE)) { + if (ARMING_FLAG(SIMULATOR_MODE_HITL)) { //output: acc.accADCf //unused: acc.dev.ADCRaw[], acc.accClipCount, acc.accVibeSq[] return; @@ -513,15 +513,20 @@ void accUpdate(void) if (!acc.dev.readFn(&acc.dev)) { return; } - for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { accADC[axis] = acc.dev.ADCRaw[axis]; DEBUG_SET(DEBUG_ACC, axis, accADC[axis]); } - performAcclerationCalibration(); + if (!ARMING_FLAG(SIMULATOR_MODE_SITL)) { + performAcclerationCalibration(); - applyAccelerationZero(&accelerometerConfig()->accZero, &accelerometerConfig()->accGain); + applyAccelerationZero(&accelerometerConfig()->accZero, &accelerometerConfig()->accGain); + applyAccelerationZero(&accelerometerConfig()->accZero, &accelerometerConfig()->accGain); + applyAccelerationZero(&accelerometerConfig()->accZero, &accelerometerConfig()->accGain); + applyAccelerationZero(&accelerometerConfig()->accZero, &accelerometerConfig()->accGain); + applyAccelerationZero(&accelerometerConfig()->accZero, &accelerometerConfig()->accGain); + } applySensorAlignment(accADC, accADC, acc.dev.accAlign); applyBoardAlignment(accADC); @@ -599,8 +604,9 @@ bool accIsClipped(void) void accSetCalibrationValues(void) { - if ((accelerometerConfig()->accZero.raw[X] == 0) && (accelerometerConfig()->accZero.raw[Y] == 0) && (accelerometerConfig()->accZero.raw[Z] == 0) && - (accelerometerConfig()->accGain.raw[X] == 4096) && (accelerometerConfig()->accGain.raw[Y] == 4096) &&(accelerometerConfig()->accGain.raw[Z] == 4096)) { + if (!ARMING_FLAG(SIMULATOR_MODE_SITL) && + ((accelerometerConfig()->accZero.raw[X] == 0) && (accelerometerConfig()->accZero.raw[Y] == 0) && (accelerometerConfig()->accZero.raw[Z] == 0) && + (accelerometerConfig()->accGain.raw[X] == 4096) && (accelerometerConfig()->accGain.raw[Y] == 4096) &&(accelerometerConfig()->accGain.raw[Z] == 4096))) { DISABLE_STATE(ACCELEROMETER_CALIBRATED); } else { diff --git a/src/main/sensors/barometer.c b/src/main/sensors/barometer.c index ac229de7d4..b28d266d7b 100644 --- a/src/main/sensors/barometer.c +++ b/src/main/sensors/barometer.c @@ -275,7 +275,7 @@ uint32_t baroUpdate(void) baro.dev.start_ut(&baro.dev); } #ifdef USE_SIMULATOR - if (!ARMING_FLAG(SIMULATOR_MODE)) { + if (!ARMING_FLAG(SIMULATOR_MODE_HITL)) { //output: baro.baroPressure, baro.baroTemperature baro.dev.calculate(&baro.dev, &baro.baroPressure, &baro.baroTemperature); } @@ -293,7 +293,7 @@ static float pressureToAltitude(const float pressure) return (1.0f - powf(pressure / 101325.0f, 0.190295f)) * 4433000.0f; } -static float altitudeToPressure(const float altCm) +float altitudeToPressure(const float altCm) { return powf(1.0f - (altCm / 4433000.0f), 5.254999) * 101325.0f; } diff --git a/src/main/sensors/barometer.h b/src/main/sensors/barometer.h index c2722e7d3c..2bbb1a976b 100644 --- a/src/main/sensors/barometer.h +++ b/src/main/sensors/barometer.h @@ -66,4 +66,8 @@ int32_t baroGetLatestAltitude(void); int16_t baroGetTemperature(void); bool baroIsHealthy(void); +#if defined(SITL_BUILD) +float altitudeToPressure(const float altCm); +#endif + #endif diff --git a/src/main/sensors/battery.c b/src/main/sensors/battery.c index dfaa768bed..ef22d74592 100644 --- a/src/main/sensors/battery.c +++ b/src/main/sensors/battery.c @@ -59,6 +59,9 @@ #include "io/beeper.h" +#if defined(USE_FAKE_BATT_SENSOR) +#include "sensors/battery_sensor_fake.h" +#endif #define ADCVREF 3300 // in mV (3300 = 3.3V) @@ -283,21 +286,17 @@ static void updateBatteryVoltage(timeUs_t timeDelta, bool justConnected) } break; #endif - case VOLTAGE_SENSOR_NONE: + +#if defined(USE_FAKE_BATT_SENSOR) + case VOLTAGE_SENSOR_FAKE: + vbat = fakeBattSensorGetVBat(); + break; +#endif + case VOLTAGE_SENSOR_NONE: default: vbat = 0; break; } -#ifdef USE_SIMULATOR - if (ARMING_FLAG(SIMULATOR_MODE)) { - if (SIMULATOR_HAS_OPTION(HITL_SIMULATE_BATTERY)) { - vbat = ((uint16_t)simulatorData.vbat) * 10; - batteryFullVoltage = 1260; - batteryWarningVoltage = 1020; - batteryCriticalVoltage = 960; - } - } -#endif if (justConnected) { pt1FilterReset(&vbatFilterState, vbat); } else { @@ -575,6 +574,12 @@ void currentMeterUpdate(timeUs_t timeDelta) } break; #endif + +#if defined(USE_FAKE_BATT_SENSOR) + case CURRENT_SENSOR_FAKE: + amperage = fakeBattSensorGetAmerperage(); + break; +#endif case CURRENT_SENSOR_NONE: default: amperage = 0; diff --git a/src/main/sensors/battery_config_structs.h b/src/main/sensors/battery_config_structs.h index 9ce524fa77..81eafef44a 100644 --- a/src/main/sensors/battery_config_structs.h +++ b/src/main/sensors/battery_config_structs.h @@ -29,14 +29,16 @@ typedef enum { CURRENT_SENSOR_NONE = 0, CURRENT_SENSOR_ADC, CURRENT_SENSOR_VIRTUAL, + CURRENT_SENSOR_FAKE, CURRENT_SENSOR_ESC, - CURRENT_SENSOR_MAX = CURRENT_SENSOR_VIRTUAL + CURRENT_SENSOR_MAX = CURRENT_SENSOR_FAKE } currentSensor_e; typedef enum { VOLTAGE_SENSOR_NONE = 0, VOLTAGE_SENSOR_ADC, - VOLTAGE_SENSOR_ESC + VOLTAGE_SENSOR_ESC, + VOLTAGE_SENSOR_FAKE } voltageSensor_e; typedef enum { diff --git a/src/main/sensors/battery_sensor_fake.c b/src/main/sensors/battery_sensor_fake.c new file mode 100644 index 0000000000..9c2ad69d6c --- /dev/null +++ b/src/main/sensors/battery_sensor_fake.c @@ -0,0 +1,58 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + + +#include +#include +#include "platform.h" + +#if defined(USE_FAKE_BATT_SENSOR) + +#include "common/utils.h" +#include "sensors/battery_sensor_fake.h" + +static uint16_t fakeVbat; +static uint16_t fakeAmerperage; + +void fakeBattSensorSetVbat(uint16_t vbat) +{ + fakeVbat = vbat; +} + +void fakeBattSensorSetAmperage(uint16_t amperage) +{ + fakeAmerperage = amperage; +} + +uint16_t fakeBattSensorGetVBat(void) +{ + return fakeVbat; +} + +uint16_t fakeBattSensorGetAmerperage(void) +{ + return fakeAmerperage; +} + +#endif \ No newline at end of file diff --git a/src/main/sensors/battery_sensor_fake.h b/src/main/sensors/battery_sensor_fake.h new file mode 100644 index 0000000000..1e5f2691fe --- /dev/null +++ b/src/main/sensors/battery_sensor_fake.h @@ -0,0 +1,30 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#pragma once + +void fakeBattSensorSetVbat(uint16_t vbat); +void fakeBattSensorSetAmperage(uint16_t amperage); +uint16_t fakeBattSensorGetVBat(void); +uint16_t fakeBattSensorGetAmerperage(void); diff --git a/src/main/sensors/compass.c b/src/main/sensors/compass.c index 9bee826c12..4e610ee00a 100644 --- a/src/main/sensors/compass.c +++ b/src/main/sensors/compass.c @@ -357,7 +357,7 @@ bool compassIsCalibrationComplete(void) void compassUpdate(timeUs_t currentTimeUs) { #ifdef USE_SIMULATOR - if (ARMING_FLAG(SIMULATOR_MODE)) { + if (ARMING_FLAG(SIMULATOR_MODE_HITL)) { magUpdatedAtLeastOnce = true; return; } diff --git a/src/main/sensors/diagnostics.c b/src/main/sensors/diagnostics.c index 0702f78991..408772eb82 100644 --- a/src/main/sensors/diagnostics.c +++ b/src/main/sensors/diagnostics.c @@ -63,7 +63,7 @@ hardwareSensorStatus_e getHwAccelerometerStatus(void) hardwareSensorStatus_e getHwCompassStatus(void) { #ifdef USE_SIMULATOR - if (ARMING_FLAG(SIMULATOR_MODE) && sensors(SENSOR_MAG)) { + if ((ARMING_FLAG(SIMULATOR_MODE_HITL) || ARMING_FLAG(SIMULATOR_MODE_SITL)) && sensors(SENSOR_MAG)) { return HW_SENSOR_OK; } #endif diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index 872d189db4..05664e3a1d 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -22,7 +22,7 @@ #include "platform.h" -FILE_COMPILE_FOR_SPEED +//FILE_COMPILE_FOR_SPEED #include "build/build_config.h" #include "build/debug.h" @@ -486,7 +486,7 @@ void FAST_CODE NOINLINE gyroFilter() ); secondaryDynamicGyroNotchFiltersUpdate( - &secondaryDynamicGyroNotchState, + &secondaryDynamicGyroNotchState, gyroAnalyseState.filterUpdateAxis, gyroAnalyseState.centerFrequency[gyroAnalyseState.filterUpdateAxis] ); @@ -500,7 +500,7 @@ void FAST_CODE NOINLINE gyroFilter() void FAST_CODE NOINLINE gyroUpdate() { #ifdef USE_SIMULATOR - if (ARMING_FLAG(SIMULATOR_MODE)) { + if (ARMING_FLAG(SIMULATOR_MODE_HITL)) { //output: gyro.gyroADCf[axis] //unused: dev->gyroADCRaw[], dev->gyroZero[]; return; diff --git a/src/main/sensors/pitotmeter.c b/src/main/sensors/pitotmeter.c index eb2cad13f0..29418e3ec0 100644 --- a/src/main/sensors/pitotmeter.c +++ b/src/main/sensors/pitotmeter.c @@ -34,6 +34,7 @@ #include "drivers/pitotmeter/pitotmeter_adc.h" #include "drivers/pitotmeter/pitotmeter_msp.h" #include "drivers/pitotmeter/pitotmeter_virtual.h" +#include "drivers/pitotmeter/pitotmeter_fake.h" #include "drivers/time.h" #include "fc/config.h" @@ -207,9 +208,15 @@ STATIC_PROTOTHREAD(pitotThread) pitot.dev.calculate(&pitot.dev, &pitotPressureTmp, NULL); #ifdef USE_SIMULATOR - if (SIMULATOR_HAS_OPTION(HITL_AIRSPEED)) { - pitotPressureTmp = sq(simulatorData.airSpeed) * SSL_AIR_DENSITY / 20000.0f + SSL_AIR_PRESSURE; - } + float airSpeed; + if (SIMULATOR_HAS_OPTION(HITL_AIRSPEED)) { + airSpeed = simulatorData.airSpeed; + } else if (pitotmeterConfig()->pitot_hardware == PITOT_FAKE) { + airSpeed = fakePitotGetAirspeed(); + } else { + airSpeed = 0; + } + pitotPressureTmp = sq(airSpeed) * SSL_AIR_DENSITY / 20000.0f + SSL_AIR_PRESSURE; #endif ptYield(); @@ -235,9 +242,13 @@ STATIC_PROTOTHREAD(pitotThread) pitot.airSpeed = 0.0f; } #ifdef USE_SIMULATOR - if (SIMULATOR_HAS_OPTION(HITL_AIRSPEED)) { - pitot.airSpeed = simulatorData.airSpeed; - } + if (SIMULATOR_HAS_OPTION(HITL_AIRSPEED)) { + pitot.airSpeed = simulatorData.airSpeed; + } else if (pitotmeterConfig()->pitot_hardware == PITOT_FAKE) { + pitot.airSpeed = fakePitotGetAirspeed(); + } else { + pitot.airSpeed = 0; + } #endif } diff --git a/src/main/target/SITL/CMakeLists.txt b/src/main/target/SITL/CMakeLists.txt new file mode 100644 index 0000000000..088bec688a --- /dev/null +++ b/src/main/target/SITL/CMakeLists.txt @@ -0,0 +1 @@ +target_sitl(SITL) diff --git a/src/main/target/SITL/config.c b/src/main/target/SITL/config.c new file mode 100644 index 0000000000..e97f78931e --- /dev/null +++ b/src/main/target/SITL/config.c @@ -0,0 +1,28 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + +#include +#include + +#include "config/config_master.h" +#include "io/serial.h" + +void targetConfiguration(void) +{ + serialConfigMutable()->portConfigs[1].functionMask = FUNCTION_MSP; + serialConfigMutable()->portConfigs[1].msp_baudrateIndex = BAUD_57600; +} diff --git a/src/main/target/SITL/sim/realFlight.c b/src/main/target/SITL/sim/realFlight.c new file mode 100644 index 0000000000..4289d87d25 --- /dev/null +++ b/src/main/target/SITL/sim/realFlight.c @@ -0,0 +1,421 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#include +#include +#include +#include +#include +#include +#include + +#include "platform.h" + +#include "target.h" +#include "target/SITL/sim/realFlight.h" +#include "target/SITL/sim/simple_soap_client.h" +#include "target/SITL/sim/xplane.h" +#include "target/SITL/sim/simHelper.h" +#include "fc/runtime_config.h" +#include "drivers/time.h" +#include "drivers/accgyro/accgyro_fake.h" +#include "drivers/barometer/barometer_fake.h" +#include "sensors/battery_sensor_fake.h" +#include "sensors/acceleration.h" +#include "sensors/barometer.h" +#include "drivers/pitotmeter/pitotmeter_fake.h" +#include "common/utils.h" +#include "common/maths.h" +#include "flight/mixer.h" +#include "flight/servos.h" +#include "flight/imu.h" +#include "io/gps.h" + +#define RF_PORT 18083 +// RealFlight scenerys doesn't represent real landscapes, so fake some nice coords: Area 51 ;) +#define FAKE_LAT 37.277127f +#define FAKE_LON -115.799669f + +static uint8_t pwmMapping[RF_MAX_PWM_OUTS]; +static uint8_t mappingCount; + +static pthread_cond_t sockcond1 = PTHREAD_COND_INITIALIZER; +static pthread_cond_t sockcond2 = PTHREAD_COND_INITIALIZER; +static pthread_mutex_t sockmtx = PTHREAD_MUTEX_INITIALIZER; + +static soap_client_t *client = NULL; +static soap_client_t *clientNext = NULL; + +static pthread_t soapThread; +static pthread_t creationThread; + +static bool isInitalised = false; +static bool useImu = false; + +typedef struct +{ + double m_channelValues[RF_MAX_PWM_OUTS]; + double m_currentPhysicsSpeedMultiplier; + double m_currentPhysicsTime_SEC; + double m_airspeed_MPS; + double m_altitudeASL_MTR; + double m_altitudeAGL_MTR; + double m_groundspeed_MPS; + double m_pitchRate_DEGpSEC; + double m_rollRate_DEGpSEC; + double m_yawRate_DEGpSEC; + double m_azimuth_DEG; + double m_inclination_DEG; + double m_roll_DEG; + double m_orientationQuaternion_X; + double m_orientationQuaternion_Y; + double m_orientationQuaternion_Z; + double m_orientationQuaternion_W; + double m_aircraftPositionX_MTR; + double m_aircraftPositionY_MTR; + double m_velocityWorldU_MPS; + double m_velocityWorldV_MPS; + double m_velocityWorldW_MPS; + double m_velocityBodyU_MPS; + double m_velocityBodyV_MPS; + double m_velocityBodyW_MPS; + double m_accelerationWorldAX_MPS2; + double m_accelerationWorldAY_MPS2; + double m_accelerationWorldAZ_MPS2; + double m_accelerationBodyAX_MPS2; + double m_accelerationBodyAY_MPS2; + double m_accelerationBodyAZ_MPS2; + double m_windX_MPS; + double m_windY_MPS; + double m_windZ_MPSPS; + double m_propRPM; + double m_heliMainRotorRPM; + double m_batteryVoltage_VOLTS; + double m_batteryCurrentDraw_AMPS; + double m_batteryRemainingCapacity_MAH; + double m_fuelRemaining_OZ; + bool m_isLocked; + bool m_hasLostComponents; + bool m_anEngineIsRunning; + bool m_isTouchingGround; + bool m_flightAxisControllerIsActive; + char* m_currentAircraftStatus; + bool m_resetButtonHasBeenPressed; +} rfValues_t; + +rfValues_t rfValues; + +static void deleteClient(soap_client_t *client) +{ + soapClientClose(client); + free(client); + client = NULL; +} + +static void startRequest(char* action, const char* fmt, ...) +{ + pthread_mutex_lock(&sockmtx); + while (clientNext == NULL) { + pthread_cond_wait(&sockcond1, &sockmtx); + } + + client = clientNext; + clientNext = NULL; + + pthread_cond_broadcast(&sockcond2); + pthread_mutex_unlock(&sockmtx); + + va_list va; + va_start(va, fmt); + soapClientSendRequestVa(client, action, fmt, va); + va_end(va); +} + +static char* endRequest(void) +{ + char* ret = soapClientReceive(client); + deleteClient(client); + return ret; +} + +// Simple, but fast ;) +static double getDoubleFromResponse(const char* response, const char* elementName) +{ + if (!response) { + return 0; + } + + char* pos = strstr(response, elementName); + if (!pos) { + return 0; + } + return atof(pos + strlen(elementName) + 1); +} + + +/* +Currently unused +static bool getBoolFromResponse(const char* response, const char* elementName) +{ + if (!response) { + return false; + } + + char* pos = strstr(response, elementName); + if (!pos) { + return false; + } + return (strncmp(pos + strlen(elementName) + 1, "true", 4) == 0); +} +*/ + +static char* getStringFromResponse(const char* response, const char* elementName) +{ + if (!response) { + return 0; + } + + char* pos = strstr(response, elementName); + if (!pos) { + return NULL; + } + + pos += strlen(elementName) + 1; + char* end = strstr(pos, "%u%.4f%.4f%.4f%.4f%.4f%.4f%.4f%.4f%.4f%.4f%.4f%.4f", + 0xFFF, servoValues[0], servoValues[1], servoValues[2], servoValues[3], servoValues[4], servoValues[5], servoValues[6], servoValues[7], servoValues[8], servoValues[9], servoValues[10], servoValues[11]); + char* response = endRequest(); + + //rfValues.m_currentPhysicsTime_SEC = getDoubleFromResponse(response, "m-currentPhysicsTime-SEC"); + //rfValues.m_currentPhysicsSpeedMultiplier = getDoubleFromResponse(response, "m-currentPhysicsSpeedMultiplier"); + rfValues.m_airspeed_MPS = getDoubleFromResponse(response, "m-airspeed-MPS"); + rfValues.m_altitudeASL_MTR = getDoubleFromResponse(response, "12"); + endRequest(); + startRequest("InjectUAVControllerInterface", "12"); + endRequest(); + + exchangeData(); + ENABLE_ARMING_FLAG(SIMULATOR_MODE_SITL); + isInitalised = true; + } + exchangeData(); + + unlockMainPID(); + } + + return NULL; +} + + +static void* creationWorker(void* arg) +{ + char* ip = (char*)arg; + + while (true) { + pthread_mutex_lock(&sockmtx); + while (clientNext != NULL) { + pthread_cond_wait(&sockcond2, &sockmtx); + } + pthread_mutex_unlock(&sockmtx); + + soap_client_t *cli = malloc(sizeof(soap_client_t)); + if (!soapClientConnect(cli, ip, RF_PORT)) { + continue; + } + + clientNext = cli; + pthread_mutex_lock(&sockmtx); + pthread_cond_broadcast(&sockcond1); + pthread_mutex_unlock(&sockmtx); + } + + return NULL; +} + +bool simRealFlightInit(char* ip, uint8_t* mapping, uint8_t mapCount, bool imu) +{ + memcpy(pwmMapping, mapping, mapCount); + mappingCount = mapCount; + useImu = imu; + + if (pthread_create(&soapThread, NULL, soapWorker, NULL) < 0) { + return false; + } + + if (pthread_create(&creationThread, NULL, creationWorker, (void*)ip) < 0) { + return false; + } + + // Wait until the connection is established, the interface has been initialised + // and the first valid packet has been received to avoid problems with the startup calibration. + while (!isInitalised) { + // ... + } + + return true; +} diff --git a/src/main/target/SITL/sim/realFlight.h b/src/main/target/SITL/sim/realFlight.h new file mode 100644 index 0000000000..f93ab49f48 --- /dev/null +++ b/src/main/target/SITL/sim/realFlight.h @@ -0,0 +1,29 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#include + +#define RF_MAX_PWM_OUTS 12 + +bool simRealFlightInit(char* ip, uint8_t* mapping, uint8_t mapCount, bool imu); \ No newline at end of file diff --git a/src/main/target/SITL/sim/simHelper.c b/src/main/target/SITL/sim/simHelper.c new file mode 100644 index 0000000000..4f7fb57244 --- /dev/null +++ b/src/main/target/SITL/sim/simHelper.c @@ -0,0 +1,47 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#include +#include +#include + +#include "target/SITL/sim/simHelper.h" + +inline double clampd(double value, double min, double max) +{ + if (value < min) { + value = min; + } + + if (value > max) { + value = max; + } + + return value; +} + +inline int16_t clampToInt16(double value) +{ + return (int16_t)round(clampd(value, INT16_MIN, INT16_MAX)); +} diff --git a/src/main/target/SITL/sim/simHelper.h b/src/main/target/SITL/sim/simHelper.h new file mode 100644 index 0000000000..2a9b25e410 --- /dev/null +++ b/src/main/target/SITL/sim/simHelper.h @@ -0,0 +1,33 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#include + +#define EARTH_RADIUS ((double)6378.137) +#define DEG2RAD(deg) (deg * (double)M_PIf / (double)180.0) +#define PWM_TO_FLOAT_0_1(x) (((int)x - 1000) / 1000.0f) +#define PWM_TO_FLOAT_MINUS_1_1(x) (((int)x - 1500) / 500.0f) + +double clampd(double value, double min, double max); +int16_t clampToInt16(double value); diff --git a/src/main/target/SITL/sim/simple_soap_client.c b/src/main/target/SITL/sim/simple_soap_client.c new file mode 100644 index 0000000000..b3763b2ab0 --- /dev/null +++ b/src/main/target/SITL/sim/simple_soap_client.c @@ -0,0 +1,162 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#define _GNU_SOURCE + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "simple_soap_client.h" + +#define REC_BUF_SIZE 6000 +char recBuffer[REC_BUF_SIZE]; + +bool soapClientConnect(soap_client_t *client, const char *address, int port) +{ + client->sockedFd = socket(AF_INET, SOCK_STREAM, IPPROTO_TCP); + if (client->sockedFd < 0) { + return false; + } + + int one = 1; + if (setsockopt(client->sockedFd, SOL_SOCKET, SO_REUSEADDR, &one,sizeof(one)) < 0) { + return false; + } + + client->socketAddr.sin_family = AF_INET; + client->socketAddr.sin_port = htons(port); + client->socketAddr.sin_addr.s_addr = inet_addr(address); + + if (connect(client->sockedFd, (struct sockaddr*)&client->socketAddr, sizeof(client->socketAddr)) < 0) { + return false; + } + + client->isConnected = true; + client->isInitalised = true; + + return true; +} + +void soapClientClose(soap_client_t *client) +{ + close(client->sockedFd); + memset(client, 0, sizeof(soap_client_t)); +} + +void soapClientSendRequestVa(soap_client_t *client, const char* action, const char *fmt, va_list va) +{ + if (!client->isConnected) { + return; + } + + char* requestBody; + vasprintf(&requestBody, fmt, va); + + char* request; + asprintf(&request, "POST / HTTP/1.1\r\nsoapaction: %s\r\ncontent-length: %u\r\ncontent-type: text/xml;charset='UTF-8'\r\nConnection: Keep-Alive\r\n\r\n%s", + action, (unsigned)strlen(requestBody), requestBody); + + send(client->sockedFd, request, strlen(request), 0); +} + +void soapClientSendRequest(soap_client_t *client, const char* action, const char *fmt, ...) +{ + va_list va; + + va_start(va, fmt); + soapClientSendRequestVa(client, action, fmt, va); + va_end(va); +} + +static bool soapClientPoll(soap_client_t *client, uint32_t timeout_ms) +{ + fd_set fds; + struct timeval tv; + + FD_ZERO(&fds); + FD_SET(client->sockedFd, &fds); + + tv.tv_sec = timeout_ms / 1000; + tv.tv_usec = (timeout_ms % 1000) * 1000UL; + + if (select(client->sockedFd + 1, &fds, NULL, NULL, &tv) != 1) { + return false; + } + return true; +} + + +char* soapClientReceive(soap_client_t *client) +{ + if (!client->isInitalised){ + return false; + } + + if (!soapClientPoll(client, 1000)) { + return false; + } + + ssize_t size = recv(client->sockedFd, recBuffer, REC_BUF_SIZE, 0); + + if (size <= 0) { + return NULL; + } + + char* pos = strstr(recBuffer, "Content-Length: "); + if (!pos) { + return NULL; + } + + uint32_t contentLength = strtoul(pos + 16, NULL, 10); + char *body = strstr(pos, "\r\n\r\n"); + if (!body) { + return NULL; + } + + body += 4; + + ssize_t expectedLength = contentLength + body - recBuffer; + if ((unsigned)expectedLength >= sizeof(recBuffer)) { + return NULL; + } + + while (size < expectedLength){ + ssize_t size2 = recv(client->sockedFd, &recBuffer[size], sizeof(recBuffer - size + 1), 0); + if (size2 <= 0) { + return NULL; + } + size += size2; + } + + recBuffer[size] = '\0'; + return strdup(body); +} + diff --git a/src/main/target/SITL/sim/simple_soap_client.h b/src/main/target/SITL/sim/simple_soap_client.h new file mode 100644 index 0000000000..5b97a595a3 --- /dev/null +++ b/src/main/target/SITL/sim/simple_soap_client.h @@ -0,0 +1,46 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#include + +#define SOAP_REC_BUF_SIZE 256 * 1024 + +typedef struct { + int sockedFd; + struct sockaddr_in socketAddr; + bool isInitalised; + bool isConnected; +} soap_client_t; + +typedef struct { + soap_client_t client; + char* content; +} send_info_t; + + +bool soapClientConnect(soap_client_t *client, const char *address, int port); +void soapClientClose(soap_client_t *client); +void soapClientSendRequestVa(soap_client_t *client, const char* action, const char *fmt, va_list va); +void soapClientSendRequest(soap_client_t *client, const char* action, const char *fmt, ...); +char* soapClientReceive(soap_client_t *client); \ No newline at end of file diff --git a/src/main/target/SITL/sim/xplane.c b/src/main/target/SITL/sim/xplane.c new file mode 100644 index 0000000000..70ecb3361f --- /dev/null +++ b/src/main/target/SITL/sim/xplane.c @@ -0,0 +1,403 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "platform.h" + +#include "target.h" +#include "target/SITL/sim/xplane.h" +#include "target/SITL/sim/simHelper.h" +#include "fc/runtime_config.h" +#include "drivers/time.h" +#include "drivers/accgyro/accgyro_fake.h" +#include "drivers/barometer/barometer_fake.h" +#include "sensors/battery_sensor_fake.h" +#include "sensors/acceleration.h" +#include "drivers/pitotmeter/pitotmeter_fake.h" +#include "common/utils.h" +#include "common/maths.h" +#include "flight/mixer.h" +#include "flight/servos.h" +#include "flight/imu.h" +#include "io/gps.h" + +#define XP_PORT 49000 + + +static uint8_t pwmMapping[XP_MAX_PWM_OUTS]; +static uint8_t mappingCount; + +static struct sockaddr_in serverAddr; +static int sockFd; +static pthread_t listenThread; +static bool initalized = false; +static bool useImu = false; + +static float lattitude = 0; +static float longitude = 0; +static float elevation = 0; +static float local_vx = 0; +static float local_vy = 0; +static float local_vz = 0; +static float groundspeed = 0; +static float airspeed = 0; +static float roll = 0; +static float pitch = 0; +static float yaw = 0; +static float hpath = 0; +static float accel_x = 0; +static float accel_y = 0; +static float accel_z = 0; +static float gyro_x = 0; +static float gyro_y = 0; +static float gyro_z = 0; +static float barometer = 0; + + +typedef enum +{ + DREF_LATITUDE, + DREF_LONGITUDE, + DREF_ELEVATION, + DREF_LOCAL_VX, + DREF_LOCAL_VY, + DREF_LOCAL_VZ, + DREF_GROUNDSPEED, + DREF_TRUE_AIRSPEED, + DREF_POS_PHI, + DREF_POS_THETA, + DREF_POS_PSI, + DREF_POS_HPATH, + DREF_FORCE_G_AXI1, + DREF_FORCE_G_SIDE, + DREF_FORCE_G_NRML, + DREF_POS_P, + DREF_POS_Q, + DREF_POS_R, + DREF_POS_BARO_CURRENT_INHG, + DREF_COUNT +} dref_t; + +uint32_t xint2uint32 (uint8_t * buf) +{ + return buf[3] << 24 | buf [2] << 16 | buf [1] << 8 | buf [0]; +} + +float xflt2float (uint8_t * buf) +{ + union { + float f; + uint32_t i; + } v; + + v.i = xint2uint32 (buf); + return v.f; +} + +static void registerDref(dref_t id, char* dref, uint32_t freq) +{ + char buf[413]; + memset(buf, 0, sizeof(buf)); + + strcpy(buf, "RREF"); + memcpy(buf + 5, &freq, 4); + memcpy(buf + 9, &id, 4); + memcpy(buf + 13, dref, strlen(dref) + 1); + + sendto(sockFd, (void*)buf, sizeof(buf), 0, (struct sockaddr*)&serverAddr, sizeof(serverAddr)); +} + +static void sendDref(char* dref, float value) +{ + char buf[509]; + strcpy(buf, "DREF"); + memcpy(buf + 5, &value, 4); + memset(buf + 9, ' ', sizeof(buf) - 9); + strcpy(buf + 9, dref); + + sendto(sockFd, (void*)buf, sizeof(buf), 0, (struct sockaddr*)&serverAddr, sizeof(serverAddr)); +} + +static void* listenWorker(void* arg) +{ + UNUSED(arg); + + uint8_t buf[1024]; + struct sockaddr remoteAddr; + socklen_t slen = sizeof(remoteAddr); + int recvLen; + + while (true) + { + + float motorValue = 0; + float yokeValues[3] = { 0 }; + int y = 0; + for (int i = 0; i < mappingCount; i++) { + if (y > 2) { + break; + } + if (pwmMapping[i] & 0x80) { // Motor) + motorValue = PWM_TO_FLOAT_0_1(motor[pwmMapping[i] & 0x7f]); + } else { + yokeValues[y] = PWM_TO_FLOAT_MINUS_1_1(servo[pwmMapping[i]]); + y++; + } + } + + sendDref("sim/operation/override/override_joystick", 1); + sendDref("sim/cockpit2/engine/actuators/throttle_ratio_all", motorValue); + sendDref("sim/joystick/yoke_roll_ratio", yokeValues[0]); + sendDref("sim/joystick/yoke_pitch_ratio", yokeValues[1]); + sendDref("sim/joystick/yoke_heading_ratio", yokeValues[2]); + + recvLen = recvfrom(sockFd, buf, sizeof(buf), 0, (struct sockaddr*)&remoteAddr, &slen); + if (recvLen < 0 && errno != EWOULDBLOCK) { + break; + } + + if (strncmp((char*)buf, "RREF", 4) != 0) { + break; + } + + for (int i = 5; i < recvLen; i += 8) { + dref_t dref = (dref_t)xint2uint32(&buf[i]); + float value = xflt2float(&(buf[i + 4])); + + switch (dref) + { + case DREF_LATITUDE: + lattitude = value; + break; + + case DREF_LONGITUDE: + longitude = value; + break; + + case DREF_ELEVATION: + elevation = value; + break; + + case DREF_LOCAL_VX: + local_vx = value; + break; + + case DREF_LOCAL_VY: + local_vy = value; + break; + + case DREF_LOCAL_VZ: + local_vz = value; + break; + + case DREF_GROUNDSPEED: + groundspeed = value; + break; + + case DREF_TRUE_AIRSPEED: + airspeed = value; + break; + + case DREF_POS_PHI: + roll = value; + break; + + case DREF_POS_THETA: + pitch = value; + break; + + case DREF_POS_PSI: + yaw = value; + break; + + case DREF_POS_HPATH: + hpath = value; + break; + + case DREF_FORCE_G_AXI1: + accel_x = value; + break; + + case DREF_FORCE_G_SIDE: + accel_y = value; + break; + + case DREF_FORCE_G_NRML: + accel_z = value; + break; + + case DREF_POS_P: + gyro_x = value; + break; + + case DREF_POS_Q: + gyro_y = value; + break; + + case DREF_POS_R: + gyro_z = value; + break; + + case DREF_POS_BARO_CURRENT_INHG: + barometer = value; + break; + + default: + break; + } + + } + + if (hpath < 0) { + hpath += 3600; + } + + if (yaw < 0){ + yaw += 3600; + } + + gpsFakeSet( + GPS_FIX_3D, + 16, + (int32_t)round(lattitude * 10000000), + (int32_t)round(longitude * 10000000), + (int32_t)round(elevation * 100), + (int16_t)round(groundspeed * 100), + (int16_t)round(hpath * 10), + 0, //(int16_t)round(-local_vz * 100), + 0, //(int16_t)round(local_vx * 100), + 0, //(int16_t)round(-local_vy * 100), + 0 + ); + + if (!useImu) { + imuSetAttitudeRPY( + (int16_t)round(roll * 10), + (int16_t)round(-pitch * 10), + (int16_t)round(yaw * 10) + ); + imuUpdateAttitude(micros()); + } + + fakeAccSet( + clampToInt16(-accel_x * GRAVITY_MSS * 1000), + clampToInt16(accel_y * GRAVITY_MSS * 1000), + clampToInt16(accel_z * GRAVITY_MSS * 1000) + ); + + fakeGyroSet( + clampToInt16(gyro_x * 16.0f), + clampToInt16(-gyro_y * 16.0f), + clampToInt16(-gyro_z * 16.0f) + ); + + fakeBaroSet((int32_t)round(barometer * 3386.39f), DEGREES_TO_CENTIDEGREES(21)); + fakePitotSetAirspeed(airspeed * 100.0f); + + fakeBattSensorSetVbat(16.8 * 100); + + if (!initalized) { + ENABLE_ARMING_FLAG(SIMULATOR_MODE_SITL); + initalized = true; + } + + unlockMainPID(); + } + + return NULL; +} + +bool simXPlaneInit(char* ip, int port, uint8_t* mapping, uint8_t mapCount, bool imu) +{ + memcpy(pwmMapping, mapping, mapCount); + mappingCount = mapCount; + useImu = imu; + + sockFd = socket(AF_INET, SOCK_DGRAM, IPPROTO_UDP); + + if (sockFd < 0) { + return false; + } + + struct sockaddr_in addr; + addr.sin_family = AF_INET; + addr.sin_addr.s_addr = htonl(INADDR_ANY); + addr.sin_port = htons(0); + + struct timeval tv; + tv.tv_sec = 1; + tv.tv_usec = 0; + if (setsockopt(sockFd, SOL_SOCKET, SO_RCVTIMEO, (struct timeval *) &tv,sizeof(struct timeval))) { + return false; + } + + if (bind(sockFd, (struct sockaddr *) &addr, sizeof(addr)) < 0) { + return false; + } + + serverAddr.sin_family = AF_INET; + serverAddr.sin_addr.s_addr = inet_addr(ip); + serverAddr.sin_port = htons(port); + + registerDref(DREF_LATITUDE, "sim/flightmodel/position/latitude", 100); + registerDref(DREF_LONGITUDE, "sim/flightmodel/position/longitude", 100); + registerDref(DREF_ELEVATION, "sim/flightmodel/position/elevation", 100); + registerDref(DREF_LOCAL_VX, "sim/flightmodel/position/local_vx", 100); + registerDref(DREF_LOCAL_VY, "sim/flightmodel/position/local_vy", 100); + registerDref(DREF_LOCAL_VZ, "sim/flightmodel/position/local_vz", 100); + registerDref(DREF_GROUNDSPEED, "sim/flightmodel/position/groundspeed", 100); + registerDref(DREF_TRUE_AIRSPEED, "sim/flightmodel/position/true_airspeed", 100); + registerDref(DREF_POS_PHI, "sim/flightmodel/position/phi", 100); + registerDref(DREF_POS_THETA, "sim/flightmodel/position/theta", 100); + registerDref(DREF_POS_PSI, "sim/flightmodel/position/psi", 100); + registerDref(DREF_POS_HPATH, "sim/flightmodel/position/hpath", 100); + registerDref(DREF_FORCE_G_AXI1, "sim/flightmodel/forces/g_axil", 100); + registerDref(DREF_FORCE_G_SIDE, "sim/flightmodel/forces/g_side", 100); + registerDref(DREF_FORCE_G_NRML, "sim/flightmodel/forces/g_nrml", 100); + registerDref(DREF_POS_P, "sim/flightmodel/position/P", 100); + registerDref(DREF_POS_Q, "sim/flightmodel/position/Q", 100); + registerDref(DREF_POS_R, "sim/flightmodel/position/R", 100); + registerDref(DREF_POS_BARO_CURRENT_INHG, "sim/weather/barometer_current_inhg", 100); + + if (pthread_create(&listenThread, NULL, listenWorker, NULL) < 0) { + return false; + } + + while(!initalized) { + // + } + + return true; + +} \ No newline at end of file diff --git a/src/main/target/SITL/sim/xplane.h b/src/main/target/SITL/sim/xplane.h new file mode 100644 index 0000000000..04d8c53a7a --- /dev/null +++ b/src/main/target/SITL/sim/xplane.h @@ -0,0 +1,29 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#include + +#define XP_MAX_PWM_OUTS 4 + +bool simXPlaneInit(char* ip, int port, uint8_t* mapping, uint8_t mapCount, bool imu); \ No newline at end of file diff --git a/src/main/target/SITL/target.c b/src/main/target/SITL/target.c new file mode 100644 index 0000000000..5c7a3f7b23 --- /dev/null +++ b/src/main/target/SITL/target.c @@ -0,0 +1,345 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include "target.h" + +#include "fc/runtime_config.h" +#include "common/utils.h" +#include "scheduler/scheduler.h" +#include "drivers/system.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" +#include "drivers/serial.h" + +#include "target/SITL/sim/realFlight.h" +#include "target/SITL/sim/xplane.h" + +// More dummys +const int timerHardwareCount = 0; +timerHardware_t timerHardware[1]; +uint32_t SystemCoreClock = 500 * 1e6; // fake 500 MHz; +char _estack = 0 ; +char _Min_Stack_Size = 0; + +static pthread_mutex_t mainLoopLock; +static SitlSim_e sitlSim = SITL_SIM_NONE; +static struct timespec start_time; +static uint8_t pwmMapping[MAX_MOTORS + MAX_SERVOS]; +static uint8_t mappingCount = 0; +static bool useImu = false; +static char *simIp = NULL; +static int simPort = 0; + +void systemInit(void) { + + printf("INAV %d.%d.%d SITL\n", FC_VERSION_MAJOR, FC_VERSION_MINOR, FC_VERSION_PATCH_LEVEL); + clock_gettime(CLOCK_MONOTONIC, &start_time); + printf("[SYSTEM] Init...\n"); + + if (pthread_mutex_init(&mainLoopLock, NULL) != 0) { + printf("[SYSTEM] Unable to create mainLoop lock.\n"); + exit(1); + } + + if (sitlSim != SITL_SIM_NONE) { + printf("[SIM] Waiting for connection...\n"); + } + + switch (sitlSim) { + case SITL_SIM_REALFLIGHT: + if (mappingCount > RF_MAX_PWM_OUTS) { + printf("[SIM] Mapping error. RealFligt supports a maximum of %i PWM outputs.", RF_MAX_PWM_OUTS); + sitlSim = SITL_SIM_NONE; + break; + } + if (simRealFlightInit(simIp, pwmMapping, mappingCount, useImu)) { + printf("[SIM] Connection with RealFlight (%s) successfully established. \n", simIp); + } else { + printf("[SIM] Connection with RealFlight (%s) NOT established. \n", simIp); + } + break; + case SITL_SIM_XPLANE: + if (mappingCount > XP_MAX_PWM_OUTS) { + printf("[SIM] Mapping error. RealFligt supports a maximum of %i PWM outputs.", XP_MAX_PWM_OUTS); + sitlSim = SITL_SIM_NONE; + break; + } + if (simXPlaneInit(simIp, simPort, pwmMapping, mappingCount, useImu)) { + printf("[SIM] Connection with XPlane successfully established. \n"); + } else { + printf("[SIM] Connection with XPLane NOT established. \n"); + } + break; + default: + printf("[SIM] No interface specified. Configurator only.\n"); + break; + } + + rescheduleTask(TASK_SERIAL, 1); +} + +bool parseMapping(char* mapStr) +{ + char *split = strtok(mapStr, ","); + char numBuf[2]; + while(split) + { + if (strlen(split) != 6) { + return false; + } + + if (split[0] == 'M' || split[0] == 'S') { + memcpy(numBuf, &split[1], 2); + int pwmOut = atoi(numBuf); + memcpy(numBuf, &split[4], 2); + int rOut = atoi(numBuf); + if (pwmOut < 0 || rOut < 1) { + return false; + } + if (split[0] == 'M') { + pwmMapping[rOut - 1] = pwmOut - 1; + pwmMapping[rOut - 1] |= 0x80; + mappingCount++; + } else if (split[0] == 'S') { + pwmMapping[rOut - 1] = pwmOut; + mappingCount++; + } + } else { + return false; + } + split = strtok(NULL, ","); + } + + return true; +} + +void printCmdLineOptions(void) +{ + printf("Avaiable options:\n"); + printf("--sim=[rf|xp] Simulator interface: rf = RealFligt, xp = XPlane. Example: --sim=rf\n"); + printf("--simip=[ip] IP-Address oft the simulator host. If not specified localhost (127.0.0.1) is used."); + printf("--simport=[port] Port oft the simulator host."); + printf("--useimu Use IMU sensor data from the simulator instead of using attitude data from the simulator directly (experimental, not recommended)."); + printf("--chanmap=[mapstring] Channel mapping, Maps INAVs motor and servo PWM outputs to the virtual receiver output in the simulator.\n"); + printf(" The mapstring has the following format: M(otor)|S(servo)-,)... All numbers must have two digits\n"); + printf(" For example map motor 1 to virtal receiver output 1, servo 1 to output 2 and servo 2 to output 3:\n"); + printf(" --chanmap=M01-01,S01-02,S02-03\n"); +} + +void parseArguments(int argc, char *argv[]) +{ + int c; + while(1) { + static struct option longOpt[] = { + {"sim", optional_argument, 0, 's'}, + {"useimu", optional_argument, 0, 'u'}, + {"chanmap", optional_argument, 0, 'c'}, + {"simip", optional_argument, 0, 'i'}, + {"simport", optional_argument, 0, 'p'}, + {"help", optional_argument, 0, 'h'}, + {NULL, 0, NULL, 0} + }; + + c = getopt_long_only(argc, argv, "s:c:h", longOpt, NULL); + if (c == -1) + break; + + switch (c) { + case 's': + if (strcmp(optarg, "rf") == 0) { + sitlSim = SITL_SIM_REALFLIGHT; + } else if (strcmp(optarg, "xp") == 0){ + sitlSim = SITL_SIM_XPLANE; + } else { + printf("[SIM] Unsupported simulator %s.\n", optarg); + } + break; + + case 'c': + if (!parseMapping(optarg) && sitlSim != SITL_SIM_NONE) { + printf("[SIM] Invalid channel mapping string.\n"); + printCmdLineOptions(); + exit(0); + } + break; + case 'p': + simPort = atoi(optarg); + break; + case 'u': + useImu = true; + break; + case 'i': + simIp = optarg; + break; + + case 'h': + printCmdLineOptions(); + exit(0); + break; + } + } + + if (simIp == NULL) { + simIp = malloc(10); + strcpy(simIp, "127.0.0.1"); + } +} + + +bool lockMainPID(void) { + return pthread_mutex_trylock(&mainLoopLock) == 0; +} + +void unlockMainPID(void) +{ + pthread_mutex_unlock(&mainLoopLock); +} + +// Replacements for system functions +void microsleep(uint32_t usec) { + struct timespec ts; + ts.tv_sec = 0; + ts.tv_nsec = usec*1000UL; + while (nanosleep(&ts, &ts) == -1 && errno == EINTR) ; +} + +void delayMicroseconds_real(uint32_t us) { + microsleep(us); +} + +timeUs_t micros(void) { + struct timespec now; + clock_gettime(CLOCK_MONOTONIC, &now); + + return (now.tv_sec - start_time.tv_sec) * 1000000 + (now.tv_nsec - start_time.tv_nsec) / 1000; +} + +uint64_t microsISR(void) +{ + return micros(); +} + +uint32_t millis(void) { + return (uint32_t)(micros() / 1000); +} + +void delayMicroseconds(timeUs_t us) +{ + timeUs_t now = micros(); + while (micros() - now < us); +} + +void delay(timeMs_t ms) +{ + while (ms--) + delayMicroseconds(1000); +} + +void systemReset(void) +{ + printf("[SYSTEM] Reset\n"); + exit(0); +} + +void systemResetToBootloader(void) +{ + printf("[SYSTEM] Reset to bootloader\n"); + exit(0); +} + +void failureMode(failureMode_e mode) { + printf("[SYSTEM] Failure mode %d\n", mode); + while (1); +} + +// Even more dummys and stubs +uint32_t getEscUpdateFrequency(void) +{ + return 400; +} + +pwmInitError_e getPwmInitError(void) +{ + return PWM_INIT_ERROR_NONE; +} + +const char *getPwmInitErrorMessage(void) +{ + return "No error"; +} + +void IOConfigGPIO(IO_t io, ioConfig_t cfg) +{ + UNUSED(io); + UNUSED(cfg); +} + +void systemClockSetup(uint8_t cpuUnderclock) +{ + UNUSED(cpuUnderclock); +} + +void timerInit(void) { + // NOP +} + +bool isMPUSoftReset(void) +{ + return false; +} + +// Not in linux libs, but in arm-none-eabi ?!? +// https://github.com/lattera/freebsd/blob/master/lib/libc/string/strnstr.c +char * strnstr(const char *s, const char *find, size_t slen) +{ + char c, sc; + size_t len; + + if ((c = *find++) != '\0') { + len = strlen(find); + do { + do { + if (slen-- < 1 || (sc = *s++) == '\0') + return (NULL); + } while (sc != c); + if (len > slen) + return (NULL); + } while (strncmp(s, find, len) != 0); + s--; + } + return ((char *)s); +} diff --git a/src/main/target/SITL/target.h b/src/main/target/SITL/target.h new file mode 100644 index 0000000000..4b4f209c5e --- /dev/null +++ b/src/main/target/SITL/target.h @@ -0,0 +1,188 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#pragma once + +#include +#include +#include + +#include + +#define TARGET_BOARD_IDENTIFIER "SITL" +#define USBD_PRODUCT_STRING "SITL" + +#define REQUIRE_PRINTF_LONG_SUPPORT + +// file name to save config +#define EEPROM_FILENAME "eeprom.bin" +#define CONFIG_IN_FILE +#define EEPROM_SIZE 32768 + +#undef SCHEDULER_DELAY_LIMIT +#define SCHEDULER_DELAY_LIMIT 1 + +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 +#define USE_UART4 +#define USE_UART5 +#define USE_UART6 +#define USE_UART7 +#define USE_UART8 + +#define SERIAL_PORT_COUNT 8 + +#define DEFAULT_RX_FEATURE FEATURE_RX_MSP +#define DEFAULT_FEATURES (FEATURE_GPS | FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT) + +#define USE_IMU_FAKE +#define USE_ADC +#define USE_MAG +#define USE_BARO + +#undef USE_DASHBOARD +#undef USE_TELEMETRY_LTM + +#undef USE_GYRO_KALMAN // Strange behaviour under x86/x64 ?!? +#undef USE_VCP +#undef USE_PPM +#undef USE_PWM +#undef USE_LED_STRIP +#undef USE_TELEMETRY +#undef USE_MSP_OVER_TELEMETRY +#undef USE_TELEMETRY_FRSKY_HUB +#undef USE_TELEMETRY_HOTT +#undef USE_TELEMETRY_SMARTPORT +#undef USE_TELEMETRY_MAVLINK +#undef USE_RESOURCE_MGMT +#undef USE_TELEMETRY_CRSF +#undef USE_TELEMETRY_IBUS +#undef USE_TELEMETRY_JETIEXBUS +#undef USE_TELEMETRY_SRXL +#undef USE_TELEMETRY_GHST +#undef USE_VTX_COMMON +#undef USE_VTX_CONTROL +#undef USE_VTX_SMARTAUDIO +#undef USE_VTX_TRAMP +#undef USE_CAMERA_CONTROL +#undef USE_BRUSHED_ESC_AUTODETECT +#undef USE_SERIAL_4WAY_BLHELI_BOOTLOADER +#undef USE_SERIAL_4WAY_SK_BOOTLOADER + +#undef USE_I2C +#undef USE_SPI + +// Some dummys +#define TARGET_FLASH_SIZE 2048 + +#define LED_STRIP_TIMER 1 +#define SOFTSERIAL_1_TIMER 2 +#define SOFTSERIAL_2_TIMER 3 + +#define DEFIO_NO_PORTS + +extern uint32_t SystemCoreClock; + +#define U_ID_0 0 +#define U_ID_1 1 +#define U_ID_2 2 + +typedef struct +{ + void* dummy; +} TIM_TypeDef; + +typedef struct +{ + void* dummy; +} TIM_OCInitTypeDef; + +typedef struct { + void* dummy; +} DMA_TypeDef; + +typedef struct { + void* dummy; +} DMA_Channel_TypeDef; + +typedef struct +{ + void* dummy; +} SPI_TypeDef; + +typedef struct +{ + void* dummy; +} I2C_TypeDef; + +typedef enum {RESET = 0, SET = !RESET} FlagStatus, ITStatus; +typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState; +typedef enum {TEST_IRQ = 0 } IRQn_Type; +typedef enum { + EXTI_Trigger_Rising = 0x08, + EXTI_Trigger_Falling = 0x0C, + EXTI_Trigger_Rising_Falling = 0x10 +} EXTITrigger_TypeDef; + +typedef struct +{ + uint32_t IDR; + uint32_t ODR; + uint32_t BSRR; + uint32_t BRR; +} GPIO_TypeDef; + +#define GPIOA_BASE ((intptr_t)0x0001) + +typedef struct +{ + uint32_t dummy; +} USART_TypeDef; + +#define USART1 ((USART_TypeDef *)0x0001) +#define USART2 ((USART_TypeDef *)0x0002) +#define USART3 ((USART_TypeDef *)0x0003) +#define USART4 ((USART_TypeDef *)0x0004) +#define USART5 ((USART_TypeDef *)0x0005) +#define USART6 ((USART_TypeDef *)0x0006) +#define USART7 ((USART_TypeDef *)0x0007) +#define USART8 ((USART_TypeDef *)0x0008) + +#define UART4 ((USART_TypeDef *)0x0004) +#define UART5 ((USART_TypeDef *)0x0005) +#define UART7 ((USART_TypeDef *)0x0007) +#define UART8 ((USART_TypeDef *)0x0008) + +typedef enum +{ + SITL_SIM_NONE, + SITL_SIM_REALFLIGHT, + SITL_SIM_XPLANE, +} SitlSim_e; + +bool lockMainPID(void); +void unlockMainPID(void); +void parseArguments(int argc, char *argv[]); +char *strnstr(const char *s, const char *find, size_t slen); diff --git a/src/main/target/common.h b/src/main/target/common.h index 2365be9671..2bcfe0acc5 100644 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -183,6 +183,12 @@ #define USE_SIMULATOR #define USE_PITOT_VIRTUAL +#define USE_FAKE_BATT_SENSOR +#define USE_PITOT_FAKE +#define USE_IMU_FAKE +#define USE_FAKE_BARO +#define USE_FAKE_MAG +#define USE_GPS_FAKE //Designed to free space of F722 and F411 MCUs #if (MCU_FLASH_SIZE > 512) diff --git a/src/main/target/common_post.h b/src/main/target/common_post.h index 3c991d30cf..1cb2586607 100644 --- a/src/main/target/common_post.h +++ b/src/main/target/common_post.h @@ -58,7 +58,7 @@ extern uint8_t __config_end; #define USE_ARM_MATH // try to use FPU functions -#if defined(SIMULATOR_BUILD) || defined(UNIT_TEST) +#if defined(SITL_BUILD) || defined(UNIT_TEST) // This feature uses 'arm_math.h', which does not exist for x86. #undef USE_DYNAMIC_FILTERS #undef USE_ARM_MATH @@ -72,7 +72,7 @@ extern uint8_t __config_end; #define FILE_COMPILE_NORMAL _Pragma("GCC optimize(\"O2\")") #define FILE_COMPILE_FOR_SPEED _Pragma("GCC optimize(\"Ofast\")") -#if defined(CONFIG_IN_RAM) || defined(CONFIG_IN_EXTERNAL_FLASH) +#if defined(CONFIG_IN_RAM) || defined(CONFIG_IN_FILE) || defined(CONFIG_IN_EXTERNAL_FLASH) #ifndef EEPROM_SIZE #define EEPROM_SIZE 8192 #endif diff --git a/src/main/target/link/sitl.ld b/src/main/target/link/sitl.ld new file mode 100644 index 0000000000..4053d05347 --- /dev/null +++ b/src/main/target/link/sitl.ld @@ -0,0 +1,21 @@ +SECTIONS { + /* BLOCK: on Windows (PE) output section must be page-aligned. Use 4-byte alignment otherwise */ + /* SUBALIGN: force 4-byte alignment of input sections for pg_registry. + Gcc defaults to 32 bytes; padding is then inserted between object files, breaking the init structure. */ + .pg_registry BLOCK( DEFINED(__section_alignment__) ? __section_alignment__ : 4 ) : SUBALIGN(4) + { + PROVIDE_HIDDEN (__pg_registry_start = . ); + PROVIDE_HIDDEN (___pg_registry_start = . ); + KEEP (*(.pg_registry)) + KEEP (*(SORT(.pg_registry.*))) + PROVIDE_HIDDEN (__pg_registry_end = . ); + PROVIDE_HIDDEN (___pg_registry_end = . ); + + PROVIDE_HIDDEN (__pg_resetdata_start = . ); + PROVIDE_HIDDEN (___pg_resetdata_start = . ); + KEEP (*(.pg_resetdata)) + PROVIDE_HIDDEN (__pg_resetdata_end = . ); + PROVIDE_HIDDEN (___pg_resetdata_end = . ); + } +} +INSERT AFTER .text; diff --git a/src/utils/compiler.rb b/src/utils/compiler.rb index dc44611426..29b8f10418 100644 --- a/src/utils/compiler.rb +++ b/src/utils/compiler.rb @@ -30,7 +30,7 @@ require 'rbconfig' require 'shellwords' class Compiler - def initialize + def initialize(use_host_gcc) # Look for the compiler in PATH manually, since there # are some issues with the built-in search by spawn() # on Windows if PATH contains spaces. @@ -38,7 +38,11 @@ class Compiler dirs = ((ENV["CPP_PATH"] || "") + File::PATH_SEPARATOR + (ENV["PATH"] || "")).split(File::PATH_SEPARATOR) bin = ENV["SETTINGS_CXX"] if bin.empty? - bin = "arm-none-eabi-g++" + if use_host_gcc + bin = "g++" + else + bin = "arm-none-eabi-g++" + end end dirs.each do |dir| p = File.join(dir, bin) diff --git a/src/utils/settings.rb b/src/utils/settings.rb index e0b7a75898..8fdf8e9288 100755 --- a/src/utils/settings.rb +++ b/src/utils/settings.rb @@ -274,12 +274,12 @@ end OFF_ON_TABLE = Hash["name" => "off_on", "values" => ["OFF", "ON"]] class Generator - def initialize(src_root, settings_file, output_dir) + def initialize(src_root, settings_file, output_dir, use_host_gcc) @src_root = src_root @settings_file = settings_file @output_dir = output_dir || File.dirname(settings_file) - @compiler = Compiler.new + @compiler = Compiler.new(use_host_gcc) @count = 0 @max_name_length = 0 @@ -1130,7 +1130,7 @@ class Generator end def usage - puts "Usage: ruby #{__FILE__} [--json ]" + puts "Usage: ruby #{__FILE__} [--use_host_gcc] [--json ]" end if __FILE__ == $0 @@ -1148,11 +1148,13 @@ if __FILE__ == $0 opts = GetoptLong.new( [ "--output-dir", "-o", GetoptLong::REQUIRED_ARGUMENT ], [ "--help", "-h", GetoptLong::NO_ARGUMENT ], + [ "--use_host_gcc", "-g", GetoptLong::REQUIRED_ARGUMENT], [ "--json", "-j", GetoptLong::REQUIRED_ARGUMENT ], ) jsonFile = nil output_dir = nil + use_host_gcc = nil opts.each do |opt, arg| case opt @@ -1161,12 +1163,14 @@ if __FILE__ == $0 when "--help" usage() exit(0) + when "--use_host_gcc" + use_host_gcc = true when "--json" jsonFile = arg end end - gen = Generator.new(src_root, settings_file, output_dir) + gen = Generator.new(src_root, settings_file, output_dir, use_host_gcc) if jsonFile gen.write_json(jsonFile) From 61790c157f649527f5e7e316621f7e5a9dc815c2 Mon Sep 17 00:00:00 2001 From: Scavanger Date: Tue, 24 Jan 2023 09:39:11 -0300 Subject: [PATCH 007/130] SITL --- CMakeLists.txt | 25 +- cmake/host-checks.cmake | 10 + cmake/host.cmake | 39 + cmake/main.cmake | 16 +- cmake/settings.cmake | 5 +- cmake/sitl.cmake | 143 ++ docs/SITL/RealFlight.md | 20 + docs/SITL/SITL.md | 112 + docs/SITL/X-Plane.md | 22 + docs/SITL/assets/INAV-SIM-OSD.png | Bin 0 -> 353983 bytes docs/SITL/assets/SITL-Fake-Sensors.png | Bin 0 -> 12872 bytes docs/SITL/assets/SITL-SBUS-FT232.png | Bin 0 -> 12444 bytes docs/SITL/assets/SITL-UART-TCP-Connecion.png | Bin 0 -> 2900 bytes src/main/CMakeLists.txt | 5 + src/main/blackbox/blackbox.c | 2 + src/main/build/atomic.h | 2 +- src/main/cms/cms.c | 6 +- src/main/common/bitarray.c | 2 +- src/main/common/printf.c | 5 +- src/main/config/config_eeprom.c | 6 + src/main/config/config_streamer_file.c | 105 + src/main/drivers/accgyro/accgyro.c | 3 + src/main/drivers/accgyro/accgyro_fake.c | 61 +- src/main/drivers/accgyro/accgyro_mpu6500.c | 0 src/main/drivers/accgyro/accgyro_mpu6500.h | 0 src/main/drivers/accgyro/accgyro_mpu9250.c | 0 src/main/drivers/accgyro/accgyro_mpu9250.h | 0 src/main/drivers/adc.c | 17 +- src/main/drivers/barometer/barometer_fake.c | 8 +- src/main/drivers/bus.c | 37 +- src/main/drivers/bus.h | 0 src/main/drivers/bus_busdev_i2c.c | 0 src/main/drivers/bus_busdev_spi.c | 0 src/main/drivers/compass/compass_ak8963.c | 0 src/main/drivers/compass/compass_ak8963.h | 0 src/main/drivers/compass/compass_mag3110.c | 0 src/main/drivers/compass/compass_mag3110.h | 0 src/main/drivers/compass/compass_mpu9250.c | 0 src/main/drivers/compass/compass_mpu9250.h | 0 src/main/drivers/compass/compass_qmc5883l.c | 0 src/main/drivers/compass/compass_qmc5883l.h | 0 src/main/drivers/display.c | 2 +- src/main/drivers/exti.c | 6 +- src/main/drivers/io.c | 8 + src/main/drivers/io.h | 2 +- src/main/drivers/io_def_generated.h | 4 +- src/main/drivers/logging_codes.h | 0 src/main/drivers/opflow/opflow.h | 0 src/main/drivers/opflow/opflow_fake.c | 0 src/main/drivers/opflow/opflow_fake.h | 0 src/main/drivers/opflow/opflow_virtual.c | 0 src/main/drivers/opflow/opflow_virtual.h | 0 src/main/drivers/pitotmeter/pitotmeter_fake.c | 33 +- src/main/drivers/pitotmeter/pitotmeter_fake.h | 6 + src/main/drivers/pwm_mapping.c | 4 + src/main/drivers/pwm_output.c | 4 + .../drivers/rangefinder/rangefinder_vl53l0x.c | 0 .../drivers/rangefinder/rangefinder_vl53l0x.h | 0 src/main/drivers/serial_tcp.c | 307 +++ src/main/drivers/serial_tcp.h | 51 + src/main/drivers/sound_beeper.c | 2 +- src/main/drivers/stack_check.c | 4 + src/main/drivers/stack_check.h | 0 src/main/drivers/timer.c | 0 src/main/drivers/timer.h | 7 + src/main/drivers/timer_def.h | 1 + src/main/drivers/usb_msc.c | 4 + src/main/fc/cli.c | 11 +- src/main/fc/config.c | 4 + src/main/fc/fc_core.c | 13 +- src/main/fc/fc_init.c | 13 +- src/main/fc/fc_msp.c | 25 +- src/main/fc/fc_tasks.c | 2 +- src/main/fc/runtime_config.h | 3 +- src/main/fc/settings.yaml | 6 +- src/main/fc/settings_generated.c | 1697 +++++++++++++ src/main/fc/settings_generated.h | 2209 +++++++++++++++++ src/main/flight/imu.c | 20 +- src/main/flight/imu.h | 4 + src/main/flight/kalman.c | 9 + src/main/flight/mixer.c | 5 + src/main/flight/servos.c | 6 +- src/main/io/gps.c | 83 +- src/main/io/gps.h | 17 + src/main/io/gps_fake.c | 98 + src/main/io/gps_private.h | 6 + src/main/io/osd.c | 8 +- src/main/io/osd_dji_hd.c | 4 +- src/main/io/serial.c | 11 + src/main/io/vtx.c | 3 + src/main/main.c | 6 + .../navigation/navigation_pos_estimator.c | 2 +- src/main/programming/logic_condition.c | 7 +- src/main/rx/fport.c | 2 +- src/main/sensors/acceleration.c | 18 +- src/main/sensors/barometer.c | 4 +- src/main/sensors/barometer.h | 4 + src/main/sensors/battery.c | 27 +- src/main/sensors/battery_config_structs.h | 6 +- src/main/sensors/battery_sensor_fake.c | 58 + src/main/sensors/battery_sensor_fake.h | 30 + src/main/sensors/compass.c | 2 +- src/main/sensors/diagnostics.c | 2 +- src/main/sensors/gyro.c | 6 +- src/main/sensors/pitotmeter.c | 23 +- src/main/target/SITL/CMakeLists.txt | 1 + src/main/target/SITL/config.c | 28 + src/main/target/SITL/sim/realFlight.c | 421 ++++ src/main/target/SITL/sim/realFlight.h | 29 + src/main/target/SITL/sim/simHelper.c | 47 + src/main/target/SITL/sim/simHelper.h | 33 + src/main/target/SITL/sim/simple_soap_client.c | 162 ++ src/main/target/SITL/sim/simple_soap_client.h | 46 + src/main/target/SITL/sim/xplane.c | 403 +++ src/main/target/SITL/sim/xplane.h | 29 + src/main/target/SITL/target.c | 345 +++ src/main/target/SITL/target.h | 188 ++ src/main/target/common.h | 6 + src/main/target/common_post.h | 6 +- src/main/target/link/sitl.ld | 21 + src/utils/compiler.rb | 8 +- src/utils/settings.rb | 12 +- 122 files changed, 7144 insertions(+), 191 deletions(-) create mode 100644 cmake/host-checks.cmake create mode 100644 cmake/host.cmake create mode 100644 cmake/sitl.cmake create mode 100644 docs/SITL/RealFlight.md create mode 100644 docs/SITL/SITL.md create mode 100644 docs/SITL/X-Plane.md create mode 100644 docs/SITL/assets/INAV-SIM-OSD.png create mode 100644 docs/SITL/assets/SITL-Fake-Sensors.png create mode 100644 docs/SITL/assets/SITL-SBUS-FT232.png create mode 100644 docs/SITL/assets/SITL-UART-TCP-Connecion.png create mode 100644 src/main/config/config_streamer_file.c mode change 100755 => 100644 src/main/drivers/accgyro/accgyro_mpu6500.c mode change 100755 => 100644 src/main/drivers/accgyro/accgyro_mpu6500.h mode change 100755 => 100644 src/main/drivers/accgyro/accgyro_mpu9250.c mode change 100755 => 100644 src/main/drivers/accgyro/accgyro_mpu9250.h mode change 100755 => 100644 src/main/drivers/bus.c mode change 100755 => 100644 src/main/drivers/bus.h mode change 100755 => 100644 src/main/drivers/bus_busdev_i2c.c mode change 100755 => 100644 src/main/drivers/bus_busdev_spi.c mode change 100755 => 100644 src/main/drivers/compass/compass_ak8963.c mode change 100755 => 100644 src/main/drivers/compass/compass_ak8963.h mode change 100755 => 100644 src/main/drivers/compass/compass_mag3110.c mode change 100755 => 100644 src/main/drivers/compass/compass_mag3110.h mode change 100755 => 100644 src/main/drivers/compass/compass_mpu9250.c mode change 100755 => 100644 src/main/drivers/compass/compass_mpu9250.h mode change 100755 => 100644 src/main/drivers/compass/compass_qmc5883l.c mode change 100755 => 100644 src/main/drivers/compass/compass_qmc5883l.h mode change 100755 => 100644 src/main/drivers/logging_codes.h mode change 100755 => 100644 src/main/drivers/opflow/opflow.h mode change 100755 => 100644 src/main/drivers/opflow/opflow_fake.c mode change 100755 => 100644 src/main/drivers/opflow/opflow_fake.h mode change 100755 => 100644 src/main/drivers/opflow/opflow_virtual.c mode change 100755 => 100644 src/main/drivers/opflow/opflow_virtual.h mode change 100755 => 100644 src/main/drivers/rangefinder/rangefinder_vl53l0x.c mode change 100755 => 100644 src/main/drivers/rangefinder/rangefinder_vl53l0x.h create mode 100644 src/main/drivers/serial_tcp.c create mode 100644 src/main/drivers/serial_tcp.h mode change 100755 => 100644 src/main/drivers/stack_check.h mode change 100755 => 100644 src/main/drivers/timer.c create mode 100644 src/main/fc/settings_generated.c create mode 100644 src/main/fc/settings_generated.h create mode 100644 src/main/io/gps_fake.c create mode 100644 src/main/sensors/battery_sensor_fake.c create mode 100644 src/main/sensors/battery_sensor_fake.h create mode 100644 src/main/target/SITL/CMakeLists.txt create mode 100644 src/main/target/SITL/config.c create mode 100644 src/main/target/SITL/sim/realFlight.c create mode 100644 src/main/target/SITL/sim/realFlight.h create mode 100644 src/main/target/SITL/sim/simHelper.c create mode 100644 src/main/target/SITL/sim/simHelper.h create mode 100644 src/main/target/SITL/sim/simple_soap_client.c create mode 100644 src/main/target/SITL/sim/simple_soap_client.h create mode 100644 src/main/target/SITL/sim/xplane.c create mode 100644 src/main/target/SITL/sim/xplane.h create mode 100644 src/main/target/SITL/target.c create mode 100644 src/main/target/SITL/target.h create mode 100644 src/main/target/link/sitl.ld diff --git a/CMakeLists.txt b/CMakeLists.txt index 04623c6774..6e6a6462f9 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -10,8 +10,15 @@ set(SVD_DIR "${CMAKE_CURRENT_SOURCE_DIR}/dev/svd") set(DOWNLOADS_DIR "${MAIN_DIR}/downloads") set(TOOLS_DIR "${MAIN_DIR}/tools") -set(TOOLCHAIN_OPTIONS none arm-none-eabi) -set(TOOLCHAIN "arm-none-eabi" CACHE STRING "Toolchain to use. Available: ${TOOLCHAIN_OPTIONS}") +option(SITL "SITL build for host system" OFF) + +set(TOOLCHAIN_OPTIONS none arm-none-eabi host) +if (SITL) + set(TOOLCHAIN "host" CACHE STRING "Toolchain to use. Available: ${TOOLCHAIN_OPTIONS}") +else() + set(TOOLCHAIN "arm-none-eabi" CACHE STRING "Toolchain to use. Available: ${TOOLCHAIN_OPTIONS}") +endif() + set_property(CACHE TOOLCHAIN PROPERTY STRINGS ${TOOLCHAIN_OPTIONS}) if("" STREQUAL TOOLCHAIN) set(TOOLCHAIN none) @@ -33,7 +40,11 @@ include(settings) if(TOOLCHAIN STREQUAL none) add_subdirectory(src/test) else() - set(CMAKE_TOOLCHAIN_FILE "${CMAKE_CURRENT_SOURCE_DIR}/cmake/${TOOLCHAIN}.cmake") + if (SITL) + include("${CMAKE_CURRENT_SOURCE_DIR}/cmake/${TOOLCHAIN}.cmake") + else() + set(CMAKE_TOOLCHAIN_FILE "${CMAKE_CURRENT_SOURCE_DIR}/cmake/${TOOLCHAIN}.cmake") + endif() include("${CMAKE_CURRENT_SOURCE_DIR}/cmake/${TOOLCHAIN}-checks.cmake") endif() @@ -68,9 +79,13 @@ set(COMMON_COMPILE_DEFINITIONS FC_VERSION_PATCH_LEVEL=${CMAKE_PROJECT_VERSION_PATCH} ) -include(openocd) -include(svd) +if (NOT SITL) + include(openocd) + include(svd) +endif() + include(stm32) +include(sitl) add_subdirectory(src) diff --git a/cmake/host-checks.cmake b/cmake/host-checks.cmake new file mode 100644 index 0000000000..9e08e1b61a --- /dev/null +++ b/cmake/host-checks.cmake @@ -0,0 +1,10 @@ +set(gcc_host_req_ver 10) + +execute_process(COMMAND ${CMAKE_C_COMPILER} -dumpversion + OUTPUT_STRIP_TRAILING_WHITESPACE + OUTPUT_VARIABLE version) + + message("-- found GCC ${version}") +if (NOT gcc_host_req_ver STREQUAL version) + message(FATAL_ERROR "-- expecting GCC version ${gcc_host_req_ver}, but got version ${version} instead") +endif() diff --git a/cmake/host.cmake b/cmake/host.cmake new file mode 100644 index 0000000000..1ed8c7432b --- /dev/null +++ b/cmake/host.cmake @@ -0,0 +1,39 @@ + +if(NOT CMAKE_CONFIGURATION_TYPES) + set(CMAKE_CONFIGURATION_TYPES Debug Release RelWithDebInfo) +endif() +if(CMAKE_BUILD_TYPE STREQUAL "") + set(CMAKE_BUILD_TYPE RelWithDebInfo) +endif() + +if(WIN32) + set(TOOL_EXECUTABLE_SUFFIX ".exe") +endif() + +set(CMAKE_ASM_COMPILER "gcc${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "asm compiler") +set(CMAKE_C_COMPILER "gcc${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "c compiler") +set(CMAKE_CXX_COMPILER "g++${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "c++ compiler") +set(CMAKE_OBJCOPY "objcopy${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "objcopy tool") +set(CMAKE_OBJDUMP "objdump${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "objdump tool") +set(CMAKE_SIZE "size${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "size tool") +set(CMAKE_DEBUGGER "gdb${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "debugger") +set(CMAKE_CPPFILT "c++filt${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "c++filt") + +set(CMAKE_BUILD_TYPE ${CMAKE_BUILD_TYPE} CACHE STRING "Build Type" FORCE) +set_property(CACHE CMAKE_BUILD_TYPE PROPERTY STRINGS ${CMAKE_CONFIGURATION_TYPES}) + +set(debug_options "-Og -O0 -g") +set(release_options "-Os -DNDEBUG") +set(relwithdebinfo_options "-ggdb3 ${release_options}") + +set(CMAKE_C_FLAGS_DEBUG ${debug_options} CACHE INTERNAL "c compiler flags debug") +set(CMAKE_CXX_FLAGS_DEBUG ${debug_options} CACHE INTERNAL "c++ compiler flags debug") +set(CMAKE_ASM_FLAGS_DEBUG ${debug_options} CACHE INTERNAL "asm compiler flags debug") + +set(CMAKE_C_FLAGS_RELEASE ${release_options} CACHE INTERNAL "c compiler flags release") +set(CMAKE_CXX_FLAGS_RELEASE ${release_options} CACHE INTERNAL "cxx compiler flags release") +set(CMAKE_ASM_FLAGS_RELEASE ${release_options} CACHE INTERNAL "asm compiler flags release") + +set(CMAKE_C_FLAGS_RELWITHDEBINFO ${relwithdebinfo_options} CACHE INTERNAL "c compiler flags release") +set(CMAKE_CXX_FLAGS_RELWITHDEBINFO ${relwithdebinfo_options} CACHE INTERNAL "cxx compiler flags release") +set(CMAKE_ASM_FLAGS_RELWITHDEBINFO ${relwithdebinfo_options} CACHE INTERNAL "asm compiler flags release") diff --git a/cmake/main.cmake b/cmake/main.cmake index 0367e797bd..fa6186fc3c 100644 --- a/cmake/main.cmake +++ b/cmake/main.cmake @@ -23,6 +23,16 @@ macro(main_sources var) # list-var src-1...src-n list(TRANSFORM ${var} PREPEND "${MAIN_SRC_DIR}/") endmacro() +function(exclude var excludes) + set(filtered "") + foreach(item ${${var}}) + if (NOT ${item} IN_LIST excludes) + list(APPEND filtered ${item}) + endif() + endforeach() + set(${var} ${filtered} PARENT_SCOPE) +endfunction() + function(exclude_basenames var excludes) set(filtered "") foreach(item ${${var}}) @@ -73,8 +83,10 @@ function(setup_firmware_target exe name) get_property(targets GLOBAL PROPERTY VALID_TARGETS) list(APPEND targets ${name}) set_property(GLOBAL PROPERTY VALID_TARGETS "${targets}") - setup_openocd(${exe} ${name}) - setup_svd(${exe} ${name}) + if(NOT SITL) + setup_openocd(${exe} ${name}) + setup_svd(${exe} ${name}) + endif() cmake_parse_arguments(args "SKIP_RELEASES" "" "" ${ARGN}) if(args_SKIP_RELEASES) diff --git a/cmake/settings.cmake b/cmake/settings.cmake index 065f3a87db..fc35c2e016 100644 --- a/cmake/settings.cmake +++ b/cmake/settings.cmake @@ -29,12 +29,15 @@ function(enable_settings exe name) ${ARGN} ) + if(host STREQUAL TOOLCHAIN) + set(USE_HOST_GCC "-g") + endif() set(output ${dir}/${SETTINGS_GENERATED_H} ${dir}/${SETTINGS_GENERATED_C}) add_custom_command( OUTPUT ${output} COMMAND ${CMAKE_COMMAND} -E env CFLAGS="${cflags}" TARGET=${name} PATH="$ENV{PATH}" SETTINGS_CXX=${args_SETTINGS_CXX} - ${RUBY_EXECUTABLE} ${SETTINGS_GENERATOR} ${MAIN_DIR} ${SETTINGS_FILE} -o "${dir}" + ${RUBY_EXECUTABLE} ${SETTINGS_GENERATOR} ${MAIN_DIR} ${SETTINGS_FILE} ${USE_HOST_GCC} -o "${dir}" DEPENDS ${SETTINGS_GENERATOR} ${SETTINGS_FILE} ) set(${args_OUTPUTS} ${output} PARENT_SCOPE) diff --git a/cmake/sitl.cmake b/cmake/sitl.cmake new file mode 100644 index 0000000000..ba7448623c --- /dev/null +++ b/cmake/sitl.cmake @@ -0,0 +1,143 @@ + +main_sources(SITL_COMMON_SRC_EXCLUDES + build/atomic.h + drivers/system.c + drivers/time.c + drivers/timer.c + drivers/rcc.c + drivers/persistent.c + drivers/accgyro/accgyro_mpu.c + drivers/display_ug2864hsweg01.c + io/displayport_oled.c +) + +main_sources(SITL_SRC + config/config_streamer_file.c + drivers/serial_tcp.c + drivers/serial_tcp.h + target/SITL/sim/realFlight.c + target/SITL/sim/realFlight.h + target/SITL/sim/simHelper.c + target/SITL/sim/simHelper.h + target/SITL/sim/simple_soap_client.c + target/SITL/sim/simple_soap_client.h + target/SITL/sim/xplane.c + target/SITL/sim/xplane.h +) + +set(SITL_LINK_OPTIONS + -lrt + -Wl,-L${STM32_LINKER_DIR} + -Wl,--cref + -static-libgcc # Required for windows build under cygwin +) + +set(SITL_LINK_LIBRARIS + -lpthread + -lm + -lc +) + +set(SITL_COMPILE_OPTIONS + -Wno-format #Fixme: Compile for 32bit, but settings.rb has to be adjusted + -Wno-return-local-addr + -fsingle-precision-constant + -funsigned-char +) + +set(SITL_DEFINITIONS + SITL_BUILD +) + +function(generate_map_file target) + if(CMAKE_VERSION VERSION_LESS 3.15) + set(map "$.map") + else() + set(map "$/$.map") + endif() + target_link_options(${target} PRIVATE "-Wl,-gc-sections,-Map,${map}") +endfunction() + +function (target_sitl name) + + if(NOT host STREQUAL TOOLCHAIN) + return() + endif() + + exclude(COMMON_SRC "${SITL_COMMON_SRC_EXCLUDES}") + + set(target_sources) + list(APPEND target_sources ${SITL_SRC}) + file(GLOB target_c_sources "${CMAKE_CURRENT_SOURCE_DIR}/*.c") + file(GLOB target_h_sources "${CMAKE_CURRENT_SOURCE_DIR}/*.h") + list(APPEND target_sources ${target_c_sources} ${target_h_sources}) + + set(target_definitions ${COMMON_COMPILE_DEFINITIONS}) + + set(hse_mhz ${STM32_DEFAULT_HSE_MHZ}) + math(EXPR hse_value "${hse_mhz} * 1000000") + list(APPEND target_definitions "HSE_VALUE=${hse_value}") + + string(TOLOWER ${PROJECT_NAME} lowercase_project_name) + set(binary_name ${lowercase_project_name}_${FIRMWARE_VERSION}_${name}) + if(DEFINED BUILD_SUFFIX AND NOT "" STREQUAL "${BUILD_SUFFIX}") + set(binary_name "${binary_name}_${BUILD_SUFFIX}") + endif() + + list(APPEND target_definitions ${SITL_DEFINITIONS}) + set(exe_target ${name}.elf) + add_executable(${exe_target}) + target_sources(${exe_target} PRIVATE ${target_sources} ${COMMON_SRC}) + target_include_directories(${exe_target} PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}) + target_compile_definitions(${exe_target} PRIVATE ${target_definitions}) + + + if(WARNINGS_AS_ERRORS) + target_compile_options(${exe_target} PRIVATE -Werror) + endif() + + target_compile_options(${exe_target} PRIVATE ${SITL_COMPILE_OPTIONS}) + + target_link_libraries(${exe_target} PRIVATE ${SITL_LINK_LIBRARIS}) + target_link_options(${exe_target} PRIVATE ${SITL_LINK_OPTIONS}) + + generate_map_file(${exe_target}) + + set(script_path ${MAIN_SRC_DIR}/target/link/sitl.ld) + if(NOT EXISTS ${script_path}) + message(FATAL_ERROR "linker script ${script_path} doesn't exist") + endif() + set_target_properties(${exe_target} PROPERTIES LINK_DEPENDS ${script_path}) + target_link_options(${exe_target} PRIVATE -T${script_path}) + + if(${WIN32} OR ${CYGWIN}) + set(exe_filename ${CMAKE_BINARY_DIR}/${binary_name}.exe) + else() + set(exe_filename ${CMAKE_BINARY_DIR}/${binary_name}) + endif() + + add_custom_target(${name} ALL + cmake -E env PATH="$ENV{PATH}" + ${CMAKE_OBJCOPY} $ ${exe_filename} + BYPRODUCTS ${hex} + ) + + setup_firmware_target(${exe_target} ${name} ${ARGN}) + #clean_ + set(generator_cmd "") + if (CMAKE_GENERATOR STREQUAL "Unix Makefiles") + set(generator_cmd "make") + elseif(CMAKE_GENERATOR STREQUAL "Ninja") + set(generator_cmd "ninja") + endif() + if (NOT generator_cmd STREQUAL "") + set(clean_target "clean_${name}") + add_custom_target(${clean_target} + WORKING_DIRECTORY ${CMAKE_BINARY_DIR} + COMMAND ${generator_cmd} clean + COMMENT "Removing intermediate files for ${name}") + set_property(TARGET ${clean_target} PROPERTY + EXCLUDE_FROM_ALL 1 + EXCLUDE_FROM_DEFAULT_BUILD 1) + endif() +endfunction() \ No newline at end of file diff --git a/docs/SITL/RealFlight.md b/docs/SITL/RealFlight.md new file mode 100644 index 0000000000..eecb0b0d7d --- /dev/null +++ b/docs/SITL/RealFlight.md @@ -0,0 +1,20 @@ +# RealFlight + +Supported are RealFlight 9.5S and RealFlight Evolution, NOT RealFlight-X. + +RealFlight is very well suited to simulate the model flight specific aspects. Autolaunch and the mixers can be set in INAV. +However, since the sceneries do not correspond to a real environment, the GPS data must be "faked". The position is always shown somewhere in southern Nevada ;). +GPS data and flight modes work fine though, only for missions with waypoints it is of course not ideal. + +## General settings +Under Settings / Physics / Quality Switch on "RealFlight Link enabled". +As a command line option for SITL, the port does not need to be specified, the port is fixed. +For better results, set the difficulty level to "Realistic". + +## Prepare the models +All mixer and servo influencing settings should be deactivated. +In the model editor under "Electronis" all mixers should be deleted and the servos should be connected directly to the virtual receiver output. +In the "Radio" tab also deactivate Expo and low rates: "Activadd when: Never". +Configure the model in the same way as a real model would be set up in INAV including Mixer, Expo, etc. depending on the selected model in RealFlight. + +Then adjust the channelmap (see command line option) accordingly. \ No newline at end of file diff --git a/docs/SITL/SITL.md b/docs/SITL/SITL.md new file mode 100644 index 0000000000..ebc4696614 --- /dev/null +++ b/docs/SITL/SITL.md @@ -0,0 +1,112 @@ +# SITL + +![INAV-SIM-OSD](/assetes/INAV-SIM-OSD.png) + +## ATTENTION! +SITL is currently still under development, its use is still a bit cumbersome. + +SITL (Software in the loop) allows to run INAV completely in software on the PC without using a flight controller and simulate complete FPV flights. +For this, INAV is compiled with a normal PC compiler. + +The sensors are replaced by data provided by a simulator. +Currently supported are +- RealFlight https://www.realflight.com/ +- X-Plane https://www.x-plane.com/ + +INAV SITL communicates for sensor data and control directly with the corresponding simulator, see the documentation of the individual simulators and the command line options. + +## Command line +The following SITL specific command line options are available: + +If SITL is started without command line options, only the Configurator can be used. + +```--help``` Displays help for the command line options. + +```--sim=[sim]``` Select the simulator. xp = X-Plane, rf = RealFlight. Example: ```--sim=xp``` + +```--simip=[ip]``` IP address of the simulator, if you specify a simulator with "--sim" and omit this option localhost (127.0.0.1) will be used. Example: ```--simip=172.65.21.15``` + +```--simport=[port]``` Port number of the simulator, not necessary for all simulators. Example: ```--simport=4900``` + +```--useimu``` Use IMU sensor data from the simulator instead of using attitude data directly from the simulator. Not recommended, use only for debugging. + +```--chanmap=[chanmap]``` The channelmap to map the motor and servo outputs from INAV to the virtual receiver channel or control surfaces around simulator. +Syntax: (M(otor)|S(ervo)-),..., all numbers must have two digits. + +Example: +To assign motor1 to virtual receiver channel 1, servo 1 to channel 2, and servo2 to channel 3: +```--chanmap:M01-01,S01-02,S02-03``` +Please also read the documentation of the individual simulators. + +## Sensors +The following sensors are emulated: +- IMU (Gyro, Accelerometer) +- GPS +- Pitot +- barometer +- Battery (current and voltage), depending on simulator + +![SITL-Fake-Sensors](/assets/SITL-Fake-Sensors.png) + +Magnetometer (compass) is not yet supported, therefore no support for copters. + +Select "FAKE" as type for all mentioned, so that they receive the data from the simulator. + +## Serial ports +UARTs are replaced by TCP starting with port 5760 ascending. UART 1 port 5760, UART2 6761, ... +By default, UART1 and UART2 are available as MSP connections. +To connect the Configurator to SITL: Select TCP and connect to ```127.0.0.1:5760``` (if SITL is running on the same machine). + +The assignment and status of user UART/TCP connections is displayed on the console. + +![STL-Output](/assets/SITL-UART-TCP-Connecion.png) + +All other interfaces (I2C, SPI, etc.) are not emulated. + +## Remote control +At the moment only direct input via UART/TCP is supported. +Connect a serial receiver (e.g. SBUS) to the PC via a UART/USB adapter. Configure the receiver in the Configurator as usual. +The connection can then be established with a programme that forwards the serial data unaltered to TCP, e.g. with the Python script tcp_serial_redirect.py (https://github.com/Scavanger/TCP-Serial-Redirect) +If necessary, please download the required runtime environment from https://www.python.org/. +Please use the linked version, which has a smaller buffer, otherwise the control response is relatively slow. + +### Example SBUS: +For this you need a FT232 module. With FT-Prog (https://ftdichip.com/utilities/) the signals can be inverted: Devices->Scan and Parse, then Hardware Specific -> Invert RS232 Signals -> Invert RXD. + +![SITL-SBUS-FT232](/assets/SITL-SBUS-FT232.png) + +For SBUS, the command line arguments of the python script are: +```python tcp_serial_redirect.py --parity E --stopbits 2 -c 127.0.0.1:[INAV-UART-PORT] COMXX 100000``` + +Note: Telemetry via return channel through the receiver is not supported by SITL. + +## OSD +For the OSD the program INAV-Sim-OSD is available: https://github.com/Scavanger/INAV-SIM-OSD. +For this, activate MSP-Displayport on a UART/TCP port and connect to the corresponding port. + +Note: INAV-Sim-OSD only works if the simulator is in window mode. + +## Running SITL +It is recommended to start the tools in the following order: +1. Simulator, aircraft should be ready for take-off +2. INAV-SITL +3. OSD +4. serial redirect for RC input + +## Compile +GCC 10 is required, GCC 11 gives an error message (bug in GCC?!?). + +### Linux: +Almost like normal, ruby, cmake and make are also required. +With cmake, the option "-DSITL=ON" must be specified. + +``` +mkdir build_SITL +cd build_SITL +cmake -DSITL=ON .. +make +``` + +### Windows: +Compile under cygwin, then as in Linux. +Copy cygwin1.dll into the directory, or include cygwin's /bin/ directory in the environment variable PATH. diff --git a/docs/SITL/X-Plane.md b/docs/SITL/X-Plane.md new file mode 100644 index 0000000000..a4c85ab086 --- /dev/null +++ b/docs/SITL/X-Plane.md @@ -0,0 +1,22 @@ +# X-Plane + +Tested on X-Plane 11, 12 should(!) work but not tested. + +X-Plane is not a model flight simulator, but is based on real world data and is therefore suitable +GPS missions with waypoints. + +## General settings +In Settings / Network select "Accept incoming connections". +The port can be found under "UDP PORTS", "Port we receive on". If no connection is established, the port can be changed. +You may want to incease the "Flight model per frame" value under "General" + +## Channelmap: +The assignment of the "virtual receiver" is fixed: +1 - Throttle +2 - Roll +3 - Pitch +4 - Yaw + +The internal mixer (e.g. for wings only) cannot be deactivated without further ado, therefore always select "Aircraft with tail" in INAV. +For the standard Aircraft preset the channelmap is: +```--chanmap=M01-01,S01-03,S03-02,S04-04``` diff --git a/docs/SITL/assets/INAV-SIM-OSD.png b/docs/SITL/assets/INAV-SIM-OSD.png new file mode 100644 index 0000000000000000000000000000000000000000..59b936c676539047166e586117db935506f94cdd GIT binary patch literal 353983 zcmV)vK$X9VP)TWWSxw5gF;XGL|K%4TR)hlyo&cW2Ym z(X+Cvc!hC{wccWOcVc>nWNJm2hhk}TXl7|;w$A5vd38NWMs9mbgr?DlhwOd6;Iub3q%6Exq3N5{{#vqLmiWA9ZVG!JTwkb6yayJac7Bhm?HQ@A;va z6X4s?U~6}r#@sPEJ?-k;t=8%ZvdiY(0t3zGj;+eTzpOkvG@qq;p`fA8=lAF5=fc6k zf`5Fi&gUp}M7`ecrN-yA*6+R6@5HPUf3YFXew)Ve%p7%FDe#HT*J0_JEV+g5)<;8l|Z>@rDS+-?^ z_u$>@_UG9wzS-=Z)nr>ww>5Q}xK}=Wu~_`RK-;RfTA^L575M~js|4Rb|6So`1wLUr zvTp3g^nR_7Z!H|(G!MBsIc+m%rr#c8w}%Jt7QTIfmm6>qw#k=Cw(V|*tqw19et~aj ztAnpJ+dQ}}lWfoMja;6`&(HAPIBYu=FQ@2V@~r@#$Oyh)0qsu)-}oQ;e4B@bZ}7Ho;2YY^ zRaW>81MheYe~1Nd@dAPT3SDj{HxtcU6nH<;kKmFCz3=AajRLre-1CTSxx^oIC_bIi zxA9WEKoB2K$t4E85rV6L9tqzTeg?m8e@+Sxe)moE5%Y13-REHd&cK}=)r-LIo($hB z1lKDD*=A4uB*FP18GKv2!#CsMk>BC);O&?Mx-ov6*+O^|z*6}~BI-;g(Qncz!0 z@SfaJ_C3kUz3=9Lf8Pn%jo$QI5WOSV_msUoi|GA4eFpC#a8Kj8H^FY{EslK?3T81v z_PYJ4NH~IUNejTRtO4&HgYEM;`fXD7eGUF0@LmbzyGO`3hwl}9pBBBXP#Cvz*dk64 zMg}v3cxRVV!l^f6-;wB@h0Nm(9cIquECpz$sq~4Hy zFSX=*N-xjqB^13+L&1B@p?e(9zA<`Rz0IHez zjljFNlGu086nJ=g@MiF>oOs{^wDN-Q1nAv7D0+(+Y=+S9MI!We^wgW`CbKNU31{B; z9pc|tgn55StDD?m_WcCO_v9%Xc;C(MWbIqU?l2I?$gNdP#LM$ixPUi|+!(v3(W*%% z_D!C_oPnd~a=UG)&-J!#2%oo=D-GL-*a5z3Cju0sjahe)d~@_3FD2RyKXBBZ#(+0_6LEVSFP;b&@_g>N-LBga zpXgPu3wC*J`ng*a@CjYn1u)9EJGujpV3tvYUnKz9s^@y1?|ZKJy(6#{9Ec822;l7^ zIX>ClqaOp^!0W2t0X$Oh1521(b-Ut*{;%js1O0clj}gAfuZ+=fj=@c?nTX`u3fD~p z0mUTro5|lRLc$dQU-h!;-px?3-4V3YptorrdfC!haqew8I`oc3a74Wwt#CpwyDVB_ z(HqJp=p9CHEqLF=SxzAPe#$C(Bgy+t(Y+PsjoEh?c!w=mO1g=_zQ>e$GYp?bu2@Ro zJw826&%W`c<8DTynp?$yj*-%Dj7A%X$X46)8sJk7)&|@$8u=W~s%~dAYIq(6!Hsln zD0;j8s8TMMhZS(|RuZr;p~Fjll5+z@`vy9`zj2ERPY;{^5Zt0t@?7cB8!q_oU_T#u z@U@Y+ZM+UY33Tv(=P@hbl6KN-2HAIVV5RtsloA5m@BMh9LfwjsI zv!Dpx^APQXB6sM5r2ybDn#njB^VYC$%*Z@{J2)A7Mb5}Oh05S$Fz5r`Y8md?;H2z( z48A*VWdODcypnKrw*rnHxrT*Muu(n%H?78^cVjp>L0iR(=f?m-E9CHDB5d^BJ~_TT z>L%geMYpuYH$Xp|^iccY=WB?V-tmU;e~A5q|3UN{*UAI%BNdMvyb1kA2;S3Z-_ejQ zdQiX@jDB+hzCeqZD{<}8`a_fsb3UH>TJ_gu4JS&v$=)QaAc<}H{78TICG48h|B@8saE zXWwnF2ykxe7unjD?RjMcV+}xy4S-!IgPO;l{9X;g;$Y)3sb$^gAPlkYl4%Hv2=&?tSZ^8b9+HMD&1H(qOk_`|8dZ-DzC*yZhQb#E9hFl!)Fay@X=25_RBJ_sL`v~A$!D$J|Q&I0Q z!^vZ2*<19R++eHsmz&>2;+?{6@EfidQb_*AN=i%|PZ&^NJLbkkoNeOuffU8%STmZ)aj=1*% z;`fR#SR&B`xlVdJqqmiVVK5KtPqK4w&c0`lyE1R;^(Nr0 zXWx-dZ|oL)$}p)zeBKbTqx~lJ5b`aoSVpPd&+>{TfbVf&$#NRGW~s98qyVmG-@cZ8 zgPl+iF}#w%z9BpVD!K(%4htP=AHZ|N0_3v+uB*h!8vu^MVdaJkHg6p-ly^LU_Jh*e zMckf!>j-HEy&!Pi^=J@a)7lN4g32}U9lTLV5l_|u_HB5s54H-@atgj*@Pu>OKj906 z?*zV)xr75ML+~bjucP4PilF|@JcQW$y`bthqTmAQP6Oa^y7h}#y=7!S0`6^c+{T<+ z;p2H5-J%hMZ@|8VpUEhCo_l$Q zsJ$!M8NUbiZQHgKd&2c-iGPRF@8J9;dPlVF6?1)K_X#22{AR(swNg)1zC3#K7Z=AM zeTy~|4CNfavkNDZ?PRAZOXfOZGnP<0Ndey2=?&TUQ)baSsCfr;6TRpyfcHG%ln$~A zO5n{Q{4{(%KE;?$BIij6`>sIE8vv}tzU^wa50zesTYV}?ST>^Eh~pw6F0OQjtP}d^ zu&&-_9e^6cL!930z%@gp<;3{%ydsfs=y@WR-{T*l0bdCiRn<^f(aQNqR|1bpI=uZo zuy2OmRzM8tNis@0nWM?cH(9cztCuUHc!$7uP{YV&X)^1e4)>#&N3l7KeG>sClk6R$ zddJc46wDiO?<;viUIFmv5qV0yC#kSo&%Eo}F&)Id)5#{H&s!SO5oUA}i{3(1)i^bP zN3d^SW#4_ob3GTa?~X^VEkcR7vW7RoW)-rM_ZD+*+udvvXeWTfZz2A#eSqI?ymo?t z653f1lnzGSIQVX$2iOsAnS|e;Y)e7cx0Zd2@GUDj-wpe=^&lp)Z#r6;9KM-=vcjQN z)P7B!d34W@E)hKn`G3!`$z`qce{jrLr=J6Ad-64 zb+LM4sOm`-+4W+ziZ)W3howsSZMiav#c!+X5fHY}cN&b`7`Be35Vu3tJp0{P_{J3b zWKb^oigu#YzJ*oXiXy~+AMD!>gE6LhGxSd50XN0zoE4G4Nyv%La3U$#0R*)U2jBP; z^H_8fDtoissvL4onBio$yVo0!S%S-ijp=*|vhT<#OFANt9fMEV{3aiX-y}F>IcK9f z$-RQhX{c^89xtDR^EuO~U@Bp?a-351=Iq-_s(n{({Vjy`OQwBW#3MNHJ(bgXXyMQE zkmek(o!AIoPq0&O(D%GJ_(rD(`28?^pLLD6`#+K3JKlO?xV0hmi7V%mQ1-pnh$r6% z`?f4Q9LHqYq!;iBMv5mZ>L6V44}^Sc?j#gWt(V`V94wveeJr{O)4okp2s<%%;@*#< z-kk&U#=3VPS&)HuoYVV`v+qfk8Os>ao608j2(Ms}euwKO!f>UuS{Y{*l!TMiTfyR) zRk7Olx{EM#&Dl4x1y;JTS}&SLFlGypCLaAfXe2P=qBR4PPUXm{gUNl_IN6d)%)QKQN6!RGyoo(3rhez z54%Zy&cmoAyU9GG=&cg(r6QOJUqqWtc0g_l-vRs%)4nS%#^@Sl-xk$Q`US6moZ$^d zNU`Ch?;@%m>pLN;@yW11D#801#*AGu_H86(-=4z0yGb%wTz7;ALBUT@O`&~%kL)`b zTqVYva3czV^5|JfdQH!i*|*6tyq9t!=cVC0T0}9AWX%%E+$N*lrWjIX?x>qQ?(Frx z!4vWiN~-sj0^V`L2?Ot^jB`4C%u?(0o)f!CJ!U{&Lh-OzLE<*iv+o4polW!>17qnw z@*ECj->!#2lTKY))bF<)z8#{8l?o0@LEaO%7FjObLhYmw2VHm)A5c`+?T)tbQ$AMJ z>u1rv3tT)&k^yLVZefHJ6xmq*hts}81{g*37L}78S&|HMfU_|lo@*i|#mbg%F|H(h zB*)t07DB#{1G-hIJ1}gSK{r8{+0K;=QncU$;@&6~ma5)~*!SHNX=R|m{gge^n`N6w z@I9}G+D(?p>?Q*7rdB~|NN1Wfm@1Rtt*~#g@-RyK?t4|QR)%2BohP0z&5Cca$PE`Y zk?1{W_}gSk1%lUpw`h3qc3V{}uU4yuhUY@(Nuh$K`DN#cp&U=0Cq;701ja$)=5`Ae zX$C%t_Wk`iPb`Ig6FREFZ{{a4bs^n7@wy)KePh;bu2@f+c3tpTwj%}aK+ZSSP0Sq) zC!*#(+l6{F;aiLrOeLK>VYeU&^q!=5dJCD}A9YhY^-!-MWZv_ot_p3+#^Z_Igc0xY z@;Nx9lM1|d7f-||Zlv~&d?a{*5ozCu)JjPocsvK41F#OUP&A$>CJ+gLY-uyH-_za>Mb{+@kH;b%)awW6->y!=@U5I z_YD9Mo1vNZjkJ?Ne{=>mq%xpoJ6zg>oZRJdBHsyt*RAhXT|ame&nxx&a^x(5W4D7H zhcaSz+)=;ZknkH#4-FdKj*I616AaD6Q-Ig0R=c%-CT8Ce+P8bz?YdpB`khE9s{Gwk za7)Yma7s$wTO&~$%Ey+lP8lS%=>CW6*i0<&O)DcG{9HK4#7&`n>zpUs(x%a9Yzp4@Lcl{u;)%L# zYS=f+e_gTFN~)gpbh?Q;jebnT+dNj`#L=Y1?xdSMW_O&3h7%g>ee>mu2;PZjEU|9F z(0kV+OWlBcm|1YSWTMGDq1|N4!cC+eooQ5)PNr0<#O&LW*mv10GBYsKzEKu9XWs_O zR0Z&C*oNWZn5wQpfSQ;|kS?uQTQm?}MY8c=SbBw6ftnlF-O`WBF zNJju~NiYfUZZ*j7m~<1$zK@Q2OYA${#EyPQeij|;{gB*nLb3$~uXkebrr{=8>?X|U zP2GYY!@#>9C3?q9>8SJZ&&qt|G}7svw!|_Ed=t2Cd$kjheOqLOQb?d8+IJNZ?1m?R z?2vm;NDeq=!Ex|yWArC{eO(N?1SNsQ5|1Cqd9g4MC9v9PcgX7o{CXgM9kJTwdE)8~ zV%WD%`zBk({Z7=As7&u35l}(`PAGQc@k+dgX@+v|BU-Xl3XhL<(K4&-9hM85xy|y6 zZ1={}H|u0bF=NTyf?2`^sccM8YuK##`F%&{wA} zyWl4)Z-OhbZlk>2stnun{=TK#nQPeJ1%7Mco5#q87`MfY?-j|ZGU+wVkW4}ADDm4o zLiBdTgxHh-KFic*naXg&gcH^xpAfupdHf{1)4NWs-eNFpJ&9QmdrkDCI{FEDvSz7_ z=|mg7cZ@bkx^#*8b`?ff!@z2`(}0z|1te?ZU~2$?@Ia3wTcg7|u3z(g!oHy`#lt&_ zwrxdRI39bW3fM}uK-_l+etQ{>;iD{&;{#l}ijG%82w~S{9~|G`xQPU4@Z*g7`UeC~ z1^)lzYdR&0`2R+EH1L0kY_9ixpto*vUi6=Y49&BESoY2gZ_?S%JWl4dOY0a_Zyr=- zIy-}RT$g3iF-scj{pD(MCFv%~hU9sR{8Oer9i>etjae{}(_5+_M!AAP>`vNYnWJ!` zXWz(B;-SE5VW$CuTn&WhMhAReG!S*>2ioFS1enp0@Me+lZIP@y)Etl68iKG0?^&s8 zk360{T-6Ckj!)>ou9ExLd;=Kn?Nv1=fsXDQqyHDY6_1*H$I|a4Q}V${cSZwdsVK1%t{7TCj{0y$Nz_ z=HpfJ9jABaOuRK?J6tWH&t#j9V+zl0{zMnzjszktiX`&&p%>~EuU0$Nsy541yEE+g zP(cJ8Z@k#?-~VPs1fL{L8f1>al}Sq(BG9{egyh>iKH0?Nb2{ek!pS3H-#Jk482FK%SS#Gw@cK_vtv^ZIVBDi|{QFFaD`5d=apRQ}D(-oKbXD*tXIFI1^Ot*X?lD z!9XBMYWxm!njE8IqKZbxhu+eHrMY`4!>)c4Io110n+zMrzFDl`B=d~ror2wgI-Q6% zo%uXLqPHNNjDg|wz&nn36D*HRg`J1;?lH|1 zL@Sn3GSxJCOh=z>@&e>rH#9FO;Fgwrs}OFBItss?0>N3(TfURmZ9njB%OQUm@tczG zm`(=kNLMb8YfvZSie-rEy}NEA#CoG#Scu&>6D|9WuCf%Vca~^D)~FM#(+M#Orj7Jo zk`CfPZG5ENM9nsN5%7*+-;p}FhJUNjt*lCBx>)hUny=eS(eGwb5nO)+9=F6i{QH6L zqnweaO*-bzjXFXw)sESMe8}(ZgR zNw7Zt^dN4N6zn?$wrxwaiG<;}w7&TQm)Gq@jDxmXkPr#oS@iK&(K{{m&cMBAk<>do zc;8UboA>Exq?4N@`6d~x-T~FSt}%MkJzCjhzSPRzLZY`6ZZc-cR8p=cV4#~#FI4an-1RO1KxHH7_1#2Wt*wrX`1kCMX{UN21CX! z@&AeTniue!n7Iz>M7*iZE6KL78TRK<#Z$e({Z%96 z_-bG|y~74&1J_wb@Ob(SY%^%~26qPb2R1lD>%tLW%{862l{INID5=;Q zpGv+2oV2sO+6;Fdx3ptYoGh{RJ&4~4eJWw-4KTN@xuOctQun}MWP%Ym)~{{Q#rKRr z5S!~(HQd`S0<3Rx`b-hn?znD8#qTD{@u`8k_Y4*8;SXTv?G|+M>XCnp8`Mc@_5SiO z(Uzelq23cLcuz8R$k&w)`9QkKJVG{!BHwD2j=p|azhJ4XSdLHk0^@}pfZGmVxQxG@ zmG{DCVA%5&#WPq2^{r_NK8ILSQml3AVlMrX4qk1qHq!04I$p`^*y^!E9IHO4sJAhz z-lzuPH2~jWzYq7T_}TUv4OivZhUfRo+rgmR_ln9bz&Ag0jTZoKGly(J+C)6d#p;dh zCRcK{U>fR8Wbcf@f^ik{TG5-Z?>TuV0k=L@P%g2QWbZie9-r=ufEV&(-a6-akbKKC zLH3JXUe`9$sU^~SLL`2NULV)@8!dc$ql(`Ne)G0lf*I+-%%~Rofvn3h7L$?!P z=9M!*nS-YRzcPaNqmXZa)cw9nvF)NqLf{7tm1)Btz^huhTD?uj*}X?Teo7~0wjjKS zl?-Xno4ULwcXt{4bnYm6hZw!2f9n~E)2K2L=;%Sfa5OY|`8Lp;e!zXP_E z7hvMT(xw$%)OI}V*XCl-ORrDb(hDd%uplhraC|Pe2D~{xPv$u>ywXrenCDB8ZfWRg zU>&B*Z#=shfbT)21h!3pv3LAo3BYkvUAF}L&j8B~;4XmszE@Sr_t^>j2K^y8byzA} zhY!@sN%f}aoeTBerOPtFyCHi2mI=H`h5Q{u@zhT5$V~5fRJzGrSI3~1>Bx!RqRE7j z@6#C7dp|3dIceXqv-Dx)o5QxMtK=(+TTDDw`G9+1wDM1H#+uR_EGa{fUtKw1mEhJ$pS3?46|=bg>OLn1CV}l zQdxIh-wz-)`T=r)Z^y~eZ$bo<*^VogO!b!iCO2t%Fk++7xKjItOo~_l$R4!_Q=MQ$v5F5l9eljTe=XMhzY3xmCm8T zCh8!_zIE`OnthiGmjJzk_oQLp&~AeEyM~T^_bV##+NZ1 zKsw2necQU|!mxxZJKTS`2UUC@9u;bJj|J7p5{tY*JWUAA%hcCI!*>SuJ#6UM_n=hU zY>Hmh(y(s?(~{z2T16kS?`FWYtz+Nd90PUrkq1r>fu+vu?AuXty>pzhB+HevU4#=U z--M#KI2fORded-|Nmi%#UAWyOJkmR?1ubI6axAY{hU+G3zR7-7la~-r5@Ng^r@GjR zIpqb>+)`O-j*~zMRO}cIoGq-&vIT8B(|@4-67U^;P$>KMQnK%p!FDhR+?A=YZ`8>E zAsg-=c?sFK?fJ0(bTAybo@z?5v$JnUqnqSWM9d5)JAk*4ZvsCjGnQ8Y@J&pPyW3>QhkFm`(`7SDYb7CJj}wV0s*}5 zR`X!r47-`jgcj!R*lT>W^Ef|gUk~~~=W2o24fNbpty{*uP6aHy58pkXU=MCQp z{ycJYo_MYX@HzVy=Ho@}I|2KKlln!^8pt>d3kLfl~CaybxswR9%DI?I#F@;nYkzv~kqV6TTB1l$-Wl_T5e=5T7Ej zZ!z73`@YR2?7NNPPQ32u1biFC_?>}$6Kgk*78HHn=8oXKyIYW1PJ+}sRT-L?3!7=k zGD`H0nz4*drjn@l^HkAGA|-E0G&$VX+8_J2qZTm}l5bmG+#MTzusmlrKfAW4$=n?GO4{@G^vTq&zChS{wn55LcJ8o$N z?%XXw_%1egW8bU;4OhsU;*k8VZo$WxY{7&>mPqi%E%LaBI2HRQCGvN7nPx1NCY@jf zF&4eUI*7Gy!D&di$#ncIXTgq1E>+x+&iIhneGv9-NAhet#fjkMW`2^EM_B5>O-L+^ z>h6~3mTc+&#FmJ)w9gj7JB`aS#t3A~_nkZawsv9PNIcOE+5Z)aCuUIl?(3#58T+=B zh*#u1NyxszDWE(U_DfLw-dX!*c+JRmCa?EwHVa|j8Jmb@tM`LcM4Y7z?Fo6kpVD@r zks-_QHk~;Q_SUUf#&i%%_#NodnMSML@`U9f)+}4(^7-@-;)xw0f=82Y{mQ2;g^C}F zjf>)QC`_t&s&~D|M)2A}_)YcV$BsXb9t-=ny+&!Rjk3~e-vc4@q^W1$L71-Tk^=SY zdr0r!-^qC*b}%SzL37twZx$^$%hl?QF*#|U4v!YhG9Vw5=pCY&NGq1}#71v96gDcD zN*5}4IOYxUyKulK>}~^`!I67A0x$Q+$<@~bI;~khuVia?t9xxd9>-YQt%Umb!RU7= z`>qyz*S5l(Ckp!(5(j1Y4q@MLHPS1%I@Hx^--cJKlm~-tx$g(g1nJnfBeCy{Zb7YC zaJDme6SE2NdQYy1aFU`74f{>fSLraLH}66VZPS_SMelhk&3ify!R`p~KD2DoBG3)C z)50+juk_^GjskpJ1xxL~_zTkSP#1e5@@>a4>HdoI=Yx{t@EVndj4kfpT6rE)(%sbjv$*T+KIVqzR9jV#F%y? z)%ynbS3<9M`bvfj=_Ykbz3GspcD<6c>D2Yidzo~^68Z#DDy&>SJdLeEV?LAdfp|B@ zZurILf^~G8odf+=39GGPnJ;J~kHlU(!u@V*mj|LIRTKO-*;)Qi_f5aU*tZoj14^7H zrV90*3oo#3hfl{_&2aV&`M0)YLGSy9WjmfG@r1JPX2KCmDci&}bI3R0r8-f%cfwF_ z`bO*~SLqrV$dKg|i8pylZT0?G4-Kc9hqdWY_C1f%O+@Mqk$Nd-!cwbXL|8a%QU8 zCSmM5Y|~C%!lp}f=fN$5?^{}_GxRcI*mXZUo%6q9l~vR|@R?oGFi!eg8GczMHV`lA8u; zxJiEO8^E+z&^c9-ux~7rh~i0>SXd|ADws(&k(oE?vb>>HmT5x0NxaGAF72WvHJgwT z%lgN8JrD{@G!uP~WsK-8Wx_sBd6SMXr8AAsggqGfCg6>M8)J8?b)@V&D*#36$)U1= zT=|n98@IwAO(KCLj(*!#=4ApaI$h=YQV=2zYn@%2HZ$4$2Db`yq)FG+fH&VVyV%Af^7^3Cf?R`f7W;HgV*|Ypvt%iPH<7$CcEfkyJ^M~VEA4Q0Y3uDC z@O7Hi1@lSu zX41)Qw-$Lkr2|8~Z?xbY>-3&v9FP}#EVT{t^N2o%xdy_gVRjRVc~7Ha1&<=on=9U@ z2*6t+`~JS+J30AIitX`N#Vv&Hhk}2X1 zJX&xU(VJ`D@WX@+S*idYn=FWRlS%dwOP$+p$ep?#)ZO5z3wsKXVq2lGx+s=o69~F4xWWkj1t<}CEd~X6vivU&A zvTq}deHSWyFEjg=QoYUHmn>)bq9pjZz<9nYu?~9JR+Z}3+?VsOcqQ& zY+2VQ3)bZoOMMgCG9=j~T=N!E1*dYXU}PP`>4B3?1l0s%cZ)!GE1rEf|0uBj^7MO; z=$aS(J_gk0kFV&D+-l;(O{-HFc^xYV-yQ#~pwlo6cT`IQ-+Pox zh~vO}d?@6`k%9!g$xqcqyZQZMxSe%ZX7a7maqNBmeBbw0h4t+zjyF8lYpZ{* zO$e{9RwJ>CV1F|Oe0K_7RdX7ExhJ~QL$m7X!&BrE`E0?kkz+cKyM}s`fD_utFwp^c zf@Hx-#z^luH+ly}?^K$%Hqjf`Sc>Q!-asrVCx--YLcGD{Gn7xLQILUmBKB=1Y`Xeh z>9_S#^xJ+>fXzz3kNcNYt+rDfZdyiFPNl+st1y;CJJb&L8>vRx!2{Bwv27UI{Z`2F zLP`~@)!DtuQckGKUPOFDVqtl}NgD8G$%0RJcNv>3??T#iNTy&tEZjt6I0?z~eqN51 z8nlF6ItQWOEzxU&**7-|GVuQ6EM4Y@>oEWv>rt`yhL*PVr{Bkl!&xCih~3f~B~5qvlE z0B=0)-qdmXrnvEi^(GmxB=Ak}+dLldX3aY0&OO9}@V&#DrC>Mt!mQqtFDZ&Fd8T)! zIUV9P`S1V!Z@yv)zM4y#Nj+h>$yD-rbK))AO{NjyCW>@&kp4<#yb`P3En&H`B^U-7 ze6wc*e#ZPcIr#1}h5ZLpzMIWvnm>hR%Hw11M{{3Ib>n}qrg{9jNw!TN>bm%9-9zX@@M4Y;t$q?p?54!LR4%SMw;*JDh!snm3Px>xh6U@HPi>}wcAhP#$)pe_1 zF;s_y!cx&YgnNscw=kqLj-=g3FkdN*SAPEdS@oK<0*Xl_e7|lv%Pz;c?iUB8X0K~ypf!#)=fS&^Z%2pMx_A>aKjs}Hnj}%ZsojKHy&+IvrN|W|E0qwypC(!2O}N?Q zy7=bZn|1XXg7-zcczgfOH7@2<^saLxUt-!l*VAssyyY?mNj4#?mT~iyhv;G;w3`?O z*?48E6@l78_tWGe!TY!oqs^|_Wi=UAMf3BPPmEUK}IY&coR0Q#0rX+Wl-$a z$tHm{%fkfH;0N|^hxe{5p`Uem~&zpI| zH zcT+;|UJrpcxbzT$_e}L~BWyj9d;Ic(Z=Ncm7flkNch&V8eXxx@SBf!ddv2`+ z_LpjI(dGxce!=b7J8ItCEVwiGe%vV+R>QoxSx~J(i|>%nlx~8V_Z_bwuFo$z0Ikoq zjncN^cHBz2)-V6h4dpL)wKJ`HhuF z1*6WilXI_DA^Xq3{^?SiDmabHgbmgYA4W70X5(9;%R3lu5(?id@Zxx7QV2JjdO{V0 zIyo#}y>7>{athZi!CwLda021r44-9bG1Ly;v}BME)w`ugzpP+txD5=_@L9j%afDXU z?bH2(62WWRtCh?B@-|httODJRN`RuG*yBt;g%l;4m`MV$Q{i|_(e(i0_^f$9@6wWF6{_59;>^C-Y+so&% ztedCwN@HxM&AU;=dS=y`Nj=-M5umYii;&t0Q8=PI90XT1GU9mK? z;CAGMd>(caO1w!dENLRXNrc}|yu~tAyda&hRGQGBIgr42qf{=e-=35%OXW?a^6mqK z?|I!Qpx@YV2v561zgj2oZ4@eKe+BL@`<;vNl8snO%zGMTHaVQnL^64!?G!Inwjy#( zBH?=lz#Abr=HI+wu=Fx?gPm|>hnUGigCP~11awis9KBcaZ4_Hpnw(NNT ztSbPtE4Ph`>q8(P0YKkejHl-w{DqVXRRgJ8{lfVa!S}U)hQ4eV=r`6cw4X^LtkQ!v z)#@f%(R;7>-J-nvl(KK#Y9ffkAvj-4G#__UWwD{8HnOn6|qqm6J zX~VtsPVZT6qBr8+O!Q73PKC3)S-i>9E*0`phvmiQ{>OKt?dWW~84YXwx3$U;IZvj` zaodN#v627#S0BD`s`za#)eL=M{0g3l*m3iP!JDUuM0j3AX9@g+z}Owf zz0vx&DJtaAw`iK7@SXqkV-;#7;1#%mwQklYYO4l9K>xp zj#$c&gVXzQ$9NMWdZQNN8=C2zB3bZ>m<4gLV1{&)dRQOB9Q(cj{T}(Hx3x{!)q}ddX{_dkm%le4n1<-&mo2?bqN5x7MhS1=&Pm;E6I}_pO<5$(yt9m{6)X z_!gKqdOl@bq_UDPUA=A^?0(7rsEFT4_$Z}m(m#xN9*q}I=#jCn<4ld08$|d@c{eS!L;Z5~oIiF&dT`71zTCRZbjplQ%eWY^v z1s{2d%C%~JtWWfgW8V7)@s=oglUx(Zz6Fn9YW1YRbW6ycdiZr~CUZfA0qhmO4>+|G z{R`25V`e^y|673I-9w8fOg*8vpO}90+r7kwHIqTVF+wJ98NQ+Y%p#j zEMl+tedzN*7@A?l=&0-s4-*v+u3i|)idl{71(v7#HV-{$Nx5`nBVF#sx|eT(-T@R)TNH zzQ@bwb2iR1VC;J=dQAeti2~l^!_HSy?K_y^-O38zoGO_FyAghyDfI4F_&#PyhLYso z$`lOTs&vABjS^!IlI9*{+C4S~3GNX_6FTBxB%}If9Q$sjvY0F!^loJ~ZNsqPJFvBl zwoP%}gmAbB;J00L8JkTDGuDknsUg}h@>+SVuSo6+%Mx)(3zrKL!R2PQ30l%?rxdQbrymSdK zb)!%N`~MH#|F&iYwF?K(kwqKUO@CW0i}`^H+q|^g@fmMc(5!6=Exa>CjV16YSa1u4PP^D$7jD;nq2P6j1xUaF{k~}X9{i2n zHqdYEoD5e!*V|AfuhrJjc>)cE5_ZSL3hrI@mU`n+sEL|svJ3O3@ZB?;;>%s~)Qh!$ zy=veGpwV&vg(0tmOh~;~rjq=sPDDn^+!(MR*ESbSaRXn1uS^+?n`%Z$*z#o>>g|Bj zgo(i0u|2<3@?5V}sq{;Q(g@=*K*Pms_VA#AZ_~1&o5bxxLqmg(Q)1&_-!&{Gj=%Lg zRtD9CV0JDg#E-KaL~qW#QHT5&R%CgTY{?SqCX;j{I)M>ODv{JR;EmC{UUlDn`0(z2 z4L-cPzkCDUyKmmzyXU9NDd5>(+l}fE-nxX1-lR)s{0xA7RQ;jY#q&Go&%(N8T(HR@ zcsK2hM`n}Ht)R(!H}cKdH-ApCx2!IdSM+{q_eg4|36_p~(r;8lzv;0I^cmipBnHJq zBf4}}01Ds47H%r%e=enH|Ax|!<^Y;cI#F>8^f++_Jh%=AtJ-XxbQv*=BQlNja= z6TLhC_T!Hqe*Ey}9eDrl%?I@U#}5#`m-T-b?eni!=S3f>TEz>}Aiumu`>#7bvhw?1 z$Ip73w~l#_4`4Nsn=7U1${m55mZebP0b@TxzB1wqc>l=)DFo? zqdI&_NBoprLk!+ThUsCyiL_EeNOezu?_9>>9Zd6AIICn>uB^M=%hI;AE)V@GCEpJc z`KF&4-rDs%K-ZD~yHMqh6z~dsyXoR9Najfz?k%iYn!9=hXOFYkAov-`BNu!7CR10`h-* z1{}GB^!vKAF8IZwSHS-7DhfOaHG0cU3%HD8;K5xpt2|$~QLN3I->O9}gP-96r zUakoHw!KDq(+4cNTiXuZTf)B0g)@`j+W|MgpLYDpu+-R;P>S7#FHj=M`=mT-RFI7! z&B~>wLMI36okyg%TBidCEfa$`9*|EhdIx4KHGUHryb1gMaQ`14{_Pzg;cqSh`@X-V z@NM}0VQI8EgTJ3a!@I`8g5zb|FAe*n#t3Cco_Xh|p(B=>9<;qTpq-wI&6O>wh9MX3 z&3xZY{$%68%|9j?rAr7guNa=v2-r+s<7-7=HwNY=H|&Y1Es}4Zo4|kH!wUAKD=C6q2;;qUH0K=>ZljT-lTgI7gMR2~oDTl9VR-A4Uc zH=}b<<}Iiu5T{RDasZ-0UB9AWZmNl59PCM{_)SwpZxOe50`ONfegWE@%!M!f7I`>{ z=spPw-_4#h1YnZ*STtdYdmJ2OLeZ>nt|SAYnLsiD0Jvha_e4|IA7~Z*@=3XTQh~{? zx0h?gzD*2^2)=1i0y3dEh<(#1{kFtQ(Vz;0LaPw0_r)vX6TL-~_wJeAv)Fi($E2FK z+@_Nz6qY!>pR!=L!n#$>d(I$Sgzt{~#gm=_;Z5quZ3?e`cg;iz;P)$< zzXW!Nz&Ab{(2f?h_iOk!R@u0nug}kPxboVs_3{3OTe}XTx4y*kFr)FOEDpAnt^h3+d{f5LL%Ff5 zo}i+LGtJE&o24^%Sk;ul=@p@KM(?PbC3EukOl3B*$xq*iaU*t&=H!3>#+xt&lorL0 zrtr6vY<+TtG!Fp4D{Y{k1HpLIUw1ESl~R8=99C+5wC0GR@f(s)W{$wc;rEB-!+y>8 zr9ydT2(Q(WHxoNfaL6(T&3l%SdCQ{r%@<+D@+u8@KS?W=nMLm~&3hie@8xp(-X*?0rtII*4rNZy?|egZ(PtwSiruQ=RVti6_qM@kn(tp-E=fw zS*~oo0C?lFG;>8Q1^9DGOX0e>v=(LVOu=8_`z45Xr28a60G0L&lVUPL?-fGt+3(-J z{r>HDq@nbfT0;I-R*n*4nGC>J$lSdO9glG!sM{US^^7VT+JR#`lzjul{ze$Mu#V|8 zq3zrAI)<%2469uQR{&JE(mjtiEv9CHQXzX>hV`I6WwNQ~Y%QgD*m>3tU(D@Zi& zx(eOPC3rt?dv2i!ewT#;IEQw?2M>Pr!^P=x`V4K~old9P{<=JU79s_gU)u)R|NI;h zDtM4+6O;xEP2R9~xb-=AoDSE%SJFjz_VfauHG9Hq;@$B3RSeG?yXDt5R)qQ;LC_=6 z9M4>?R+xwX{_y+5*KgkzGpeYF>yQgBil_5-F&%c6y=j~Ga>f*c&zPfI=ub{&lcIcpfwCC}dDJQu9>=f-keU_CI1-!?H zkWH}3`;?Bx3w*ovVqi|#w}{{LnIoY03I}G0qGoS53H)^}Gk^4M#@tQZDK{*ngyrBg z@zl-=$td5xK0y8r@f)UAi8?h*uwtnusSt9dMouBOAWEr1fVmPeT^6Jl2)-WyYJYn~ z)cXOTqHGb-HNvNgg(Vg88NyAnRmdmxoA6{oAr>}ag}h|+PD#D7)BB^oPG_#wya9Y8 z`n?pk=~VavO;;k|Ms!>4upCSF5-ou5cgeCP83iTw-Fk5nUSRew1-$Wk5i$8X$Zufs zQ1INW;IC+%3veev?*M+wY1{gML6yI+7Ci^AT+T3d&+rnaM8C6=Z^}FBfcP^s$PTZTOn>--wri~0YDJtaeXd_zk z1xq%hBO$k%30v1{-b+Nkm%(j1o&p>nFX;s#x!jvkdr+CxRJPtULcENN`R}G^3y!AJ>nI#^MUX9yE22yh^gdF#+96zFyaIb z?;yp5U^n~&QMD5%D{^z=H-%*=r@(i#!(C6F9jtxNWS|s0BJ#K-VEMB}8sg33XtQiD z8R^YLZ;ahnlQbii%;-JI)F2-wdJ~s-P&W~fTO{05!oR0vHXhCBJU`3WJ&kQa+rMnm zIwj+kpQ%w0)x@`6#N!ahu5O`&4(K9}ZK1hE$VNqLhe4yR{ebWW@n|CA@yc244ZZ z7u=U3cu-6srHFV`dIF()h3}jJ+)V7MkG-u)hAewxP-sPRt#_ z+oU=LUCJcr?aU$s4}!|UEy%vXeIaJPNUnKP>tasSd$#+4yg^mr%$k07yq6tNBei`!$w5ilU90lIv z1C7RG)ubf^nY5ITFACpy4BEkZ_exMq$W+}z-5k|}67U&fLf31?1I{b^j)QMj37Lod zP0j>zq0UOI$%zXFq$n-U@UXuYhm5+f(&tgB6FOurW<{kAii3`0%FC7%oe9HM1!{EL z1sS$s6neIpC9<9HyUdMvbJ2UYBl9K$@?VJPEimr{=sn?)-jn<^?>YnYpyo}WdoC?j zj>j0h$0X1D8HSq()O(sn^WJ-^An(voWRv|sH#H6dj@`rF5(%wm0pwo6U?FNk(QZ97 zy}1&nH_cc4-dQ~{d6Qkluw`;3M#Ar&qMMjzc%Q?2gxZ2hjkS2j%D7N zlBwo*Vt;(VDmd3@-gByX%fbo7?2C)~ax7ku0N zVBArC-cBCbRNN*w%UsBCLwPq;zR_ak)fag}CqCUI^?W=_^bYk3l5mr{cENHU6urmw z^J=Gk^*j~vd&)*Er=nT#G)y;M6QyqTn>y{zpo6T8<-J=y1EvqC22QsEsGWSM* zBhJngJIZx}xc9;lXf-hf&X@^=1#ZhzG=v|o1ng$=$pVesGa1Ga?`fwAfdk0EGk*1X>bI(NL?W`O<17C3d)mtp!bKOCi&8W$C0iWbT z7@dd^5QglwVHma@HFdHh6yh3kJJsQ~ecbS!L41mi0hi;qX)K}H3?{sarapHex!LuxGN0nJ;NZn6xlS`xEKyYQD^fBql0KYT^Ny=2qzLTNl2j}Kz^ z^5Xg**VkX`&j%>5gf{Qf&s;V6eAul3nYM#p`EsL)Fp!~`PnZW~v7$z?Mbm0miyhaK8Xe2HuOVP=J>v z8hM6vxNrjr*Yu8Va@wI$8jCkVLXtGy!(I-F0{E z8Fr5^aUzyx7u_}3cpN9hgtq7Uqf)7~ab1`_L=mX!g8RT**R68;UB!0+-@5A#N2aRR z#e3luMG1|ou3LlOq2Yl$qUi0hyMZ@w4e_4VwX;&`tmBG%(FPtX`2h}w-brqk`8(+W zRH+2~n-{n@MY0U$ zK)oOHN;jd@dm`FR60vX5E11P@@)4=tA9Z$F1yR_1B;ObzQys z+HluiyH1NMk-_`QZNoJ`b{OmH@ZPg7H9D3#czlLL4o!F!h3ZX)a54`03rGnTBAA(dBfk|~<1 z9$`0`hm2UxgXvVv=6w#~`=?)j{q?8951sXGp-?a`_+_l+0|mPybvWyR4O2NF4}g`?O}R>(fKShPFc zzrBCoEe*D{?!D)B&XIiu>nc6N9iji};kwG^KP=Cqg-0jl4NTg{AY!}nUcX;s$M z{iAn^8&m5^Gb}AOH2Or(s->!qRle}OijDOX=F_R_F{5TbCacUAlIPnI(VI7sQOBGB|q?2;Q@_{tS2j+7k(fjU+0{7D-ZHc8&r4uY;(01u8LsF?I zc0-rR~)usT#ZwD1a9T<;F!-3pBp7P#q{TezTN0u-V1#`%mu?k`BH5PxswUliy*p=;6ju z4&SC}tkM5}xjaB{*`XD=B76@hz~v2PK+`yPi^+pR&M9+bhiC^PuBJKkF@ zeA}IM1s{&Tfr!(#M=*bw7kuxyA{iEUf*Or6YFjZ&m8KrPb?iG|{7z!DcG#qhDN=Bv zoGe5^9Os!pO6^EZI1Z)J*iuD^_d>+hZ@dwcTUksNW+Hyr8NR96JKKzgRt`6r2YPfg^YPT>J=b729<8h!>svs+fBN;Ozg(_;WB6Yeet|W|1C(xH zPBpAmm%@UGRTBsQ8!ffB9Rt+9L|giX-xnw|F;U(JU+)#VxS_UYi2@9#s1O-Y@k_zQ;sy z1H!kkp8^@K2_KgF@S2*-Npr`Aa9kdF>q2AXd7P6s;GzHC@58@~EfY`LUI*OIcI2WK z)Uq$C=v9}zQ22X3@V&dABylxyCioV<6tBsr?H~@+g{etN{|0|+Gs>35DR`!3FC4M) zoxv~V-WaM`0wKXuhsiAh$>u|wWW|Ds71yot1%q?1e}>K&F$ zg_(E!e0-33qsw*Gy#?I+r`yY0|Lo$wJ`XpyRV;rm#}|GBP;bn>jU~_WuK$2uDGxUV z*B>kTs=%1&{{%mW$UmYUO=%_H1`CpTmtmPc0mHujx@?6TxMq5z5n#f`}g;k zwSNxR-S_W*`SdrhP2!83wpZJp42D|?zHJZcDHYfA5b5m$nk}&JxBlhYUAtY+VAzD% zce#f53*6X-=iz^DF5NELZ}a`N0lb0RsiIab?k;h=aDnymwlAq67@|vS&nrNt-SFBX zkN+q50S0-AC+Qo9iG`9Td|7(`cB(s0G8!+=@VxA5B@glD7)sPvkMRm}&3hiky!m|mvi^^TyS}}}+`BR=++!msr=m++Z~*f*PxKZh@o z2P3zAeGQG@`>A2TygN7>e;ncoBHWOyteAVyS#j`2@J+8F;Qj5};v0Mtwb$=Ixt9R5 zyEOpc?x*|9dqBT!{A_Q#;J<&+@Co}SbJkU_g0$^+)7xy3_)Vt$2z+;4*Q*MCaLT^B z$R}=_GW*^(F7bZR1qi;uwsr}9+@9#yZdxX|;M2#@?J#c%6mzz|XJe^{i{Idc0=~mw z1Al-}_RW_I6{~d)-8opzwp4~K-u3R^MUEBR`^J19ro+c<7S!m+c=CdqM;0t{3UTpo zCvH=wVC8^)4=UjJh9}y-JMbHnYtUIf@?F_T0ysPRu7fkmvB8cFdWqJt@mgpFyn0~k zmhcDY`hzg`9p%loUVtPw1H3*@_-^hWz$MOW3PbJ=Q?BJ1OkqTacu5`}zRiT`dQ8mu zLM4^Ig%iOn28_)-H1GIC?_@@Awq^-9clsL3Ct4t%F<0r0n#@9w2{eahP7>*wd!MfiLa*f)UhAD}B?=-1%0-iJ<=7x$U~@W#BmC8{T_;{b0w zw!X25we7>)!uwms@R8I()H{tlF|k>U>Sy;M-}8-JIwS0p?h!1rH~Ylgu$ z7sc1;<-lc4t9`$Sh_Uz0JoHB8WDLF?ofxPbxg`G&<5u`SIJMt&8JYdh$ zja%36^bz;&-u`9%!`D;VAOC!MdQogp?VC2~)H_J|L{IKPc~mf#FDZGGM8VIWMszUE?Yl^7 z7PRkP1q7GvMkkpfRVCGZ1i+4r9cxK}T0JaL2^6U6|cPGKtS`;kmgVhw!ZpphJe>v%S2 zCK$eDoA^R0bjTaLA9qYQVS(Q8vn#1gCs`fCgsoVn*SzOpPQehP_fp7&Rf%_yc|&jD zvVKvoUsP}Xex-k18F}5y|NqyY)<0Z4vt*NJ4Byy!Lbi+I|I5w7C)Z*Rl*Z)=QA+g|PMwv6rLa4E7);kbqeF7Y+85zs_R zjCe2b?uq|gVc+-%aPj%4()HSZ9QaOE_`V1I#N-_e3+fz^`-p}7DpW^|wQoYc`5-*} z`Vr4oKEPLpWRX&YZ)MbHw`~?ygf zL}1^EnD_Mg!l)VTjeqM_{%dH|3b&Vk`Ss_Y|7G2{V)OA3zM1w-l1=a~@C3#~8biPI z{6bz6Dbu9IE=QwzlM{=?zGrB`hhX$fWZyHUfuqm9Euehz@C}M5m)%c-_6`2QK}xgf z6#?pS}j9AEG_B>yMZp-0HZ#@4AIe<%AeRNT_TT@2^z` zc*U_vQ5}ARO09sLErXFOnol}Vj~8b&O)Q?g^#u0aWd6g!=(gL%>>GL+zi;?9wfzgx z*t+6bz}UAGK=ewPa}Fu%sVl7W9TMslc(Ln zO%%<0t`9d^1`%B6HW8Y1mYX*p-dw(WSE%&;jo$Q z?h=Y8xA(uizkL76EjCduRY_2(u-9aT;Txju$ZK03GE^7nqGr=>+qP+1*nSPidB}Vq z+|R~qD$FNt**5YEV$B??AEw|u@jY@yNo3!6Ad|ZWks1!w9Vn+5EuvS`zgKV{jq)* zI$=4l2jje1e|(tNWXgy)q};4Y=XBY*|Bw62cOTvq)|cI`+bFIf_x|bEpa1oLU6U4u z=ZhLzm8uEsdx@4Vhu-M4U4YyyNBEX=O@u_j))B2$a?ym0f3_s{JrlHV@ogcmZBk5s zSXJHkaP9Ja*C*QdC#apQR)l?v=vTB6Ca|#`15M2%m`3Q*?jZlR-6;$y`^Mqm9nXXN zF|0#vgT#Y(u&ujFjNDb6`(dHm!>Fn%n!*>yaBOdb^%OBautS`T2L1*kg3>l(-+K7o z(Z8`LvMoNYtS%E2M2UbJ%P2`ylTOi&Hz(2PNA?uYYfXnDjrr~Dio(I7D-UVE{ym0{!|Kxhj z*~(coi-l4jZ55QndIqCm;d38L6hq(jkPHoIxM^3bZL3-IY6aKxJQw<~q4rIHr{mRp zw7-KrBSciOs&v0k;2!(On^hEO*a!DdWtyfOVKVeQ%M^1>5ZhnlHOehXRe{bK@&llV zl*)+fFaN0ymizk&@twJ0oZO``szxFoea%tmlP!{+QWmcj7 zNpL*hUq&1l5=*P-56k_H-#J6@x`7%A_K$lFWF@Sjwa#IoLrHU!m{Q2~L74j1)9=c}uJ(>3Fw3V&p|uB~2pE1l5zI@J%fLMBj$7+bgN6s3g?eff=i@(msE+tuWXS_fyuUMSG-MSyZAHV}sNpfTD#+ocIjFq}~0{UtGY z^F;4S`X0;Za1*WOJ*R2j;i-a>+e9d_JYAlzFFyeMzP#)fuK~Q*dxm@a)2~0>!UhI7 zG+(S$h84W(RH-yrFT=S9CC%+wZG@hzg?8>y-pcZ1>zG6nyjqE7h*~5Ku|Ow`Ljhd& zf;+ON(yIde{&WwCZpnTB-gS)?zKa#Avos73!#Awk!LPqbir)Z96R^jjQyZ2W#Wof; z@NTGYkf*SPFqiB{hHVq7Bqq-9ru+NUCyuP$L-q}}P$(e-I)r?eMG+g)?2dT65M78f zQVg#+z(0UxT4^iP4)h-edOdFx++&>dijT?7`WB zdkDb>*lYLxeb;|m>B3l&Hd)u4;U+={`@Dy473R>w_W2cT$>H(cMY{=?FiW0M(N{HTxfjBJFl`eLQy}`mlXdqrnpGSyZky!DMcZJxmv>b^^xATH!J5J1*0fm@2 zVpg|Exvze^02e^Be?uq^KAAxLhUk6q^b`W$l3OtKqGd>jCDy!Wk2{8&&_wTtFB-Q= z41kkF@AOkTbFn{OTVkmby;&8SK2>n}%%Z6v`IP)UATPn?mqwnM`Aa`Zv&RS zATi__CJT!2?Nj(ZZ5P-T+fkwYyt`(CL#aL=qts1#cZ(}0h<%gC4&M~^jcZI~`Glm# z3PbgxD`nA!NvxNC;j-&hZNX=VUx!z{vwpt;$@BtTAWXDfuU`hVdGPiOqA@t4RPs9j zMQeEX|EX-&MVmc`0e{E)x0QxVhk2UN+fwKc(SA5fZ?KRN=v}E*w&(_%HJ{G`G#knB zz8ZtVj~{N<9b0jCTj1g0A0QsQ#ihMw`gKZ**-fErvMD)M!Wq74#j7i3V)qCE*A)Wr z)j^|L*m$_X7yzUPIkG`^`>4U#6!6>i z{|ffkT$qHy010*v`!&43C@32iG>W_A3aKI9hH`w@GsJ~UEOWbVZ3B)kz^E+o3KJR0 z*WI<4p_SThlEUO?V(eB(b~FAvSg8kf5V>~Zn#)!%#k;xK9fj}Q_TZnu<@3^>C9QK5JCB8ygFL?#<h0ol4fc^l`3H&wH?sZ6sFbMz{rx*e}0nj#-&YKcx4NpXrWDe{|UqA48* zHz=jaI#H0;$=Ji=FpGDD`t6vGQcyV)fb@}Q-dI0@y!+w_UY>q?f^rJP@(E?%j}Kfs zk%CSZJDW}N@Okt4cnIFVg}F`QnRl8{!H_DQc^r82Y?B1o&CMnvc+;Wy=jC;~TC5r8 z_2*MOsPp_RNFmQx|2RLt?)T2G&(F`LU~ho?9p5kh(7syk9BguWDjM;QYqT=p5~PAR zMsBhdoP{GL4I(96*ufCl30#D+o*AFA7a~+3e#88HVHgOFbwaub0Fe_xy7p$-5Xzfs z@CMwCju(VriyRKFfS-w)2e|>f!c>vEX{qRKnN4~}!RvTm0u!Pma5j9pJiw@P+^lQ_ zc;%#X`8lGoP(|DrA|1}YL+~3%ZqG#Kjf1+GfsiwAz_=lFV+6lI;0-=N?HfX@XaNuC zCE493i3W8N)iK;K%gIEXk52~P#A-6h&>v5D_eY)RO~6~9ZKB#ura|}?CM+3tPet^G z{QCkx^Y!wXW>n!VL3R9c2_E4x2b1^dXE~Irbv*hv*Sfh$kV__ndTZcYV9$;;rV|8k zcKmE14cJQ=SSyF;gj2iW0#%|2!yw7S?gaX4F*GC{y&`^NPz%s(Q;*Og$BP<@;u;ii zc$F#PNzp}`kw@*r=MgJYYXDl9uu13kc0}mrp9tLz3l%m|X%2@|$?g3chHXT^A$CJ0 z1-S{CQCzg0EYd{{hRx_a&UTI!WU4nx^cIJ7lDSQAfjpH>vQ+7$&GXi&CZSG2VXZO% z-iUxN>&s_~*m~T~Ig*OvH&sneKkE|(kHaM>iYA13GXSUTd&b$e=r(bb@b4h^#!H-R zga@TBf1@;9u(3!nv@|#+p_3RUZmcv?uMFd|)xrvC`NcqN=F?ZHKgHyw6bDZe2TkUt zU`vbObw$IblT=CJu_nrRr72wDsMI^yog*w`USSW)1%YnHz8~cI%M6i&aWgu*R_Wjh zOFm+m#%*#(?Ivl4$=VXU2&wC!~^X9o!OCD_^3nwyoGqycW#<}xCZbrO6Ge?KS zyjw?t-L%kN)Vn3*Ch$$F1O+f&D9e=sWUC0yRFelD6U6sw!c)kp0Cuy{{^@>)vG47HlD-ycwg9!jDn;?C!m@fN0?yH;mwySsbxlh?*(Bu3rW7#KsN($ zg{|Y~(6(pi;SK{-^j(C%pupm#1gsFf;o>EB3vvLT2-N#g4LsS&DM%w>clUX7=KX~%S>7ad zo6vBRyY%5EQL%#a(E4~nyCo2xYM8e~y){dg9K2}-+MWPh$~8G{eHOv{NMsW##J8x! zn;RS@k|pp;MTG8X}62cz*d2$td4u!8uMm{zDzo^euOHT9YpplEp^2 z@`zZiC1@-XSGU9uQo%ddYGFM80PKk~zGhzlXeTpV@vfRh9BfB%6qzNkLdpobV^Zi|kV-VX zlU}C=xyoV*`%>iIc=i%pCIq~no+iHu@ck$jUG6eo$uT>xJa5r$BDPq@Q12%kZh|m- zk}8=>DUa7`-gBMXBqGmStwEcL$UTh&@8o8aT-z&U;(b)pIn-(*Xg!p7hr#zueVMx8 z72OhsYlrD)I`GDARkO!$0&sIN1zC=f&)h`s;OgWmv;4gia9RpU*CM(li!hk9TSwCM zyC?AkA)vgL$v$$#c0x38sd;!I$Rwr~y&a`gJ{(&g9xf)oVFx&J5CSF+-X!*|@b<+n z%sZ|HEnSHve23O6QGdKr#c&fZn@qB_SmJaOO^fB6I!+R}O+@r&X2G#6n@n}0w@keE zjom!gzO0_15xmV(7?mBlWzig3(ptvz9eTjH5B3x zX!tL%CU&$N)1qmfiD~{>0Nh!KY6tg@IAX<_6I#KebP%(ucLLl5#AV*C8H-#<*!oD< zE#VLkf^n>&TruAXnT(w67Ai=Y_YSg&Z1ldtfP1`Ox5?*Vd*!h-=*Xj$qGl5Gcx&Ms)|V)&m$HC@ z*D5iJ3*BktFZ&zAZ-(BAO;9>1a8nE3ApJJc$bJZZJ0vzK8(;i*8)W|Ekoqs0y z4^GE3uL$vtkRoBCsW_qLL$NiU951kMR*1F;b(|~|J>wfJNSol?K_Yx#aM#J>>~WR` zzGt&p))utK#AXvTp(8ixBnEG4@_xEYp6D&xy!9oPAq$p4w~1yteo0z%_fyKF zXf><|?~+E&C6@(Ex})%o+FVSWg`$zVQD*=YSy1Jrom8xVL-1`|gS%)y8nYMo%JY{h zPQUVW&EO65nh@k=f=b*umZ{s^aO~fq0mO2t258>!Pv%uu)g*b2{fVha?3(lw)to{USzxU41&ld|->Q85O&tdc*K+9@- z@fcVGmCKG{Jx^EI);LNQJcFB6kME{sJE-IVUbXfcqfx_mJzLUPnlN<|Y+hT$Rc|oIyFT9U@%<@JVKAON; zFpok@yo%rOh{p#RzQqOybqgE$Nf!u96z`oi?+21?Lc18QCP4s??my>*pcq?(ROren4E04n_NXBzyli+Cz@CI8U@HZEH;smgp ze2p#NJ($k=xA*VggAbkaAOl}WYn`@N>sR=;@!B&qE4>o0fSn4&F$`;uX`jMiTf((H zY-@XdA0N+A7aZ>Q(c!Si!4}ZlCB+ZrlFMP*s=8f^-@OA);1ApflW8W*<5NiT%2Q9i(UYz1x$i&y^2_^Ap8$q`dXMn?+rw<8S`6va zNP+JPfNx|YbPN%`OK#giAsglj++wrE^`ryXPTF)#R)21|xcP1%z_(po3)RC7m&z&@ zfqJxmfGUiG@V)hm7QZ8RRQ|v0z58!k*_tg1vew?B1?tL4+6fOGU|GS+q0m0k25xby zf7sh9A@Ku_s&&(?xB|^O2=GPLF(k6wNvd@J^*g`sn~!g zCsp)jA)WO%8?kIAg>-IG^*k`I8RMSyP+5s>?8Z!<8`+n8|2d7gj!*3(L2h%*?Hwnn$3GI`@DIvNg=fm_VBzLJ7B3%&}yZ6dxg_pwzb(J15zD1EnScAA|M~s*0>J^k#pV0&1q;vrm-Rz<=lY3! z4bThVI#@|pIkE5iw`9xKrm~YU2qZ7>zX$4Fd;Y1S#1kOj0$V@a7cKaHjvC2_e(iNF zhcsM@-_Jex3t#rf0+!#Sx}LY#_gnOdGut2x(+fiW{tv~zA4@i2mrp8SDNiIAIa{wOs88-ZGn$5{}PUDoD?yn*>5K zDAV?C{Pu0X@%BI8e*Znd`1faLjW2KCjz6iX6aFJ-i{XT!A9CZ9l{AhaeE(Yf>ihR! z1o*0ht=H%yd6m2OeZO&bhBk4`hTIN79r?xop4hj<-O6*6zF*~PCv+BCl)$cFef%e~ zxV*RF`-8Z9*sUKh{2qu00%w0L_I=V?-Qn*+@&6zR~#Xo7?RG=b!oW{vnF&_ z-{QPdQEwTs?8sKZfc1H&nN3LZ-reRMU5`&btTb(~v8{skf#qz@*W*(QVUKDQR7|&f z^;EnjIu>uRn*nzQ2%k9>6C&Pohj?NvS4(3rxub7wd5S63a6!fw&->rszxvQW`|=;4 z9RG(v@0aiU-{;N)>g)V8807PV{9y2o0XV*VhY|-EOteFVP!-+X?;B@`-+=5y(_g*< z!}hPQzMj=oH_D&9oS@~ezPu&)KCh?~N(IgmzTXZMe9IHd=Vt)$@84SRjeqfnqK)6L zB~$++9bG;$_tr<3$)THN1i96RTL`+0uxERu!Ekr^cP2&Sndk6GS?U>pJNM|~CcgiCmZqC2;U;g=*mml;6cx>ZKUZD48vH7oj|H~IV zs2rbfHayTQu)6gNxwy5Zocq3Cem%>}(v@>$&H5b;FoYuj<`6;lGzodSm)uw4 zMsH{2KEWu+^6?K_K{KMac;3inlU>kzuNkx^AJfsANklejW}2{coL7G4oq~zzZI&1g zE_~}=6EX^3S-mEYZSppWcs&(g*x6}Pa1(F%w{Ong4F-c;?1NDRZnO2eRJeVoxXR+L z_7=T$>;hKnFZl%)=%4q$zQ;>3mxm_(js9ys;W;9}A~%G$F z*M_rBdI0{s5By!wWeMMd*8~oleOJQlyA{K}YiA$y-}`4PcKJtu@94(a<9!)&Y)9`9 z$C{p2G4Sm;Xtc3C!o4MlPrRq)QgM^LRg)<7HW{7H^^VjVG;c~;2Kz7RL$QqVcZCo{mHt5v%CK|*#2pSe^MshA*k|LwQ)cg>H3K|aU7Guh9B z_3bJs_cHR+CGh_7aMFB|vj@}vLjhsN8p=hPvj6FR@%kN*p{zcm3Lpc(MjM*sCv z2Ygq`*szA<1D%<`1 z$v|n}uL-`DCN9~xhU9$z{;T-fzrF_qe|a{xT2g+$@Eut;du+Y?B&%X_idt=i;TrQoD&ue|p8+&J8Um{`- zsB!#t|0^6h=FY}v_kR_4^|eo@ns^s4U%h|-3O@Y9`vwGk#1pY>LDGqR|57C9NkuzS z6#LeY{HJ`s?};bU-W!&B^81Bv)2{u<+Dv+wdyt5rOw+7>BMW^&Mk(m>(J79Txs>e#??|C zGhE3|E2-Cn3nh=z5p`^p}y+}CI_=YsdFJ^zR&iUz(lU`uB=T<>h;`6IUw;;JCx zJRKo{aq#TzTd)lN8@LDm{`T#E{{5}Y?Q{lxUp7$XYMnLR9sbago(--+kYeQDxw<`n z{_fqUcNnh$`b?z!9Ufi2Ivan&cL00?O1~c8zx=aRo^qCl;;YI4*}8yf0li=xoDduf z_=aBtf4w)xK~`?^{P~~$^t=yoorr?5~ zK|b&Q=ihZ~=kE~P`FrndAm904wX?ThzP$bNA78w4-J%b2Isz-W2JaZXe_iux&{v45 zNr9LHB4wY@IQa73TWR=)pY4;H?w?}iDHSjpex*av=i|O$>;KS;)_h)D0@%Rk;0w-tB@5HB{ zuWm86^ULIn-tn^0C)aTPZ1Uk1KEZvxgyz{3iunL)|Kfk~&c2e-n^c6?H4Ix8-%@D) zr4G|S@892_^}R8PC%@*#tV#AQD(ioK{~zDKeUb!R;WevneR=?HMDJB5Sk3fNEF9^O z_LdpI+ht_gqthgi(HyyeMtb+9YXU80!gA+U!6p;EN%D4U-i{$1hvsdtTNCg3%%yp! ztmqseqJtw0g{yFt_oHSj<*6wVZ>D!YOz>7}cj2b_Zg3vKZUx`^XGVX6;_&N+9?6Ej zcX1U~uye%Y*JHb~>hDll#SLIc4ag38O=JD>VrKfIdU_wOeku(-AV z?%lY5-yi(%d=5YQYrlbddA~+wD9=5pMgdS{o{h1JP~bX#{L8Or{$HhRO&CW; zl$XA|pR?L)rH>R}zW>_qkBig|tDPtLGceA){4+`HXWsKCsgP7c$AVAui~N)b-kEUS zwH|DvtXunz-;Gb0j!yt?%VvU1TQTt9GGV{+GIdA?-GVz!SgKONpJS^{+-8$x)x_=; zv|0rd`(S5BidO>f#vKNO*pFUFWzH(QU9%M5-LnNYa#Z;nAayP8f^X$4VRjQ39+uNn z%cw&Du)Do!2PlItqlK}Nv(AqA3_bqc>D*Euw*XfDJK-JZ;lI3m`Rgy_-^(v*_wPUW z-Z|xV#Jk|-uV2q(ZvNzXz6SLuV=@lD&A*lmk3{Z2|N8P5`ZWNRSb!jcWwZNfXz3f3 zoL^t!%|PyTc}o7vE2GUYvE_*=CKiN0vavhi%XE7E_Pyvb*N|vp`%auNzBERaoh9#U zh2DZ+qtJ~fl(NbjgYf~u_YQ5|O7h-K^KP1EDxTA6CRdw~t~vIE9%Ym&z^v25;AyqAFOxFgw)^K=lMZC{*q(!#7+JSt6kGOm8 zz3l;ji;J9V;8KhHBz+Ewe!?O(YrosD54|-b3xEDaaNT#S@z-BL0>7)7JkKx1FEu^a zLZF3Y8)G{aU4>FqL7!j!v%IXf6SsfSw?hNgYYpElF64jF{S%BlbH9V@tAZ1YB0IH z4$$FE4wF!gcQ&_)9MaiE^EPf1E2NWQNGH-tthlmW}xF?QpxhWauta&ZqPI*b`6V{NQ%6h~PKgADwk}1p2Q(jX||O8^1HkH{MJB zEZ3M6Tdl9TGXdI*JJ`_l2I5!7`S|R9(kj9`YOhrST5jA{UPFKQ85}HX5-I@s-p7x} z>MICuVnY&)V8ZQw-`XCAO*CKp#eU;UpGPjm-F%VVZyxvFh2}j7}J5{`CC$;JMq`{U>~S%tOgrwF!J%;mG~TaPi6$1@9Bx3%j`E0^LsMm-Z|} z0!_9=?bR~0y|8jC-m%~4pUFtl%wi+u<{r{lCq@AS-gqkIMy;9B-t| z0pEO`D0mZdmegCm&-#!~=)!JC2*$rAkY}Ibe#G0IPFyTsTUOwU(XN$cbT|3dbU9n- z7P6!*)mMuj?u?c^t^5r^Hw{x5%6-d5BDLZB$p(q&zvVVkPL<~Lw$3!AAfo6q;|uZV z%`uuKbav28uA@)a(rbdeI{=qpz{{vY>^n%FuteEpzdG-q$!_9auxz^8yb}VJ){IVw zct3ubw*hahRfII}?&AvHYH#?Vhm``n3x%8Zd1mlt;t6Wp1mJ+N#usQKDcrtp2NHv$ zNJ}i+yzFrJ-T+`j4v0uNX)v82dOvq}Z1+&=H61mWe8+zHZ`o@ExlanaZ&w=4!y_%r zl?8W|rLXdY0yTD$UIOhB)IIe`uoJ|icStH( z?V8Ndlv_ZwJsRJU#2d~l74bF~g7S6>^A429J9DKV+pug}^gFE)R;Mft{hqTY$BvG@ zq~pxS&ko-P+cmu=g@Vy49{ae`gmaL3e~Sih=@9(*TUO1aCSTOxg=F6nzL9>nLC#Z> zxOD*84wPds1ki}tK}X(Ahgi0j(?K#P(R_`VEzdvK?Z8sW7tDyV)W0+E9lBuj&OJe1 z(bJf>IH72ia0cJYRY+*4JW543dG|s(1SNJ8fM158o1~NEfThIlozE*1 zs!igCbhh!^@sV&mPgo`dERWbqMXJdaUtxH}N?1Le!eQd3k z6W~qw9Z28}HX6`7bVHkP8(xcVJ`g?vTVF9JlScCxNrGWVMO5 zj6180tAbrw(w+D=fN#LXrcDUh4&=KW>^l{}(=zdw@TB^_7W}>df6~Z1PrNfB#m7R=#ESERm8@6nM-R!{a&`e-= zVK5l%0^7AbuDR#oMJ>0cZ!F-*ihqM^u&sc&Esfsm^^^?X@?~2ed3KcB5abnk(I=I3 z_Slx6Ng_D@R*(c-{*I8yZwNUlD0mMYrJl%zd-JH8vF}^Wzb%azv16&wJIqs`D*cwq zvFnSBk?t!`=|6`*T8Kn;-0AsBI2maJDl&ovekaODf$(QzRB*TOy-%Tup2|^U3vd;j z-7=dKm_v1z5 zjoy7_cX)RnK)dI1H0Qjw1M4Q>ChY{p6NAZQH<92StU<5d$ak{u7A=FUjS?=&H+`sh zG5}6LaO%)gLN^lbHZpSh^Z>~f-h~w1%`XNm)2yg|<&Giwg1Jx(0k;qNSdU$ZeLvBN zxqMVmiGjsi7YkR52v6kU!-=V3iE!-*d{eG!<*JUgxOYIJ8=bDxw`-#Iz5m=WG*6+- zO*JO6f(i~QuL-6*mbfjiwvz#Ts^=JX>7`;DmeUyUZaQQW#=37D*uCYwRG;Uegk?gv z$-%K(`llK3HsJlpTk+OmWk&FxB@}q$^ZAa73B3U5#>$Xdjxf2Y*fCOWt#rV}e5-8f zV|~Z3=%K(+-8`4 zSGWvbk;7ct@NmmePXf%7^lWe>whWTD=G^irX5{VutlRW1Dn}Jz1YbK^xx;VJKz-W< zv9`fIz?+PMqYk5hI`J|}c(r`WuaZ|^-GKaJaBXvQ2?#u^3Zx|PZ>Z;N~< zETA1BrPBr6MgX_^1iO!QWXZPTU2F0C8cp!2-5%_ub<6Y0n$*1k!gE|hW9kTDbklL6 zkD0FR8v^su^t)gqpU^wfmaaqce=mrA%d<;j?uwYB+=8FCG1fv!#_yDfYH}bP1#Zcv zb{l@=j+Is+8!>>Ps9P`!W^3vBf(u`|-Pt$4}!V@1}b@URT1p zGdesSZ)5j7egy3}oq}D{oK7iGbycgM7K}aZCOolo|0ZD-mOn5<-ufo7uIdsymue4|G4p3n6u+goQ`rN&UG!UncRTc;5O@VZqSjV2vu|fKUc>jL z9v4>3`;v#?<1T6VEyI=TUE=XZ@wS-vjom5e7}C+$eUsQJI48HsJSiN1)H3g`_L^X$ zpatHK;x)1K?rxzF@_6shyTK{=LsrG4W{KW41>f`mBVym{W`@f;beR%XEBtQS$D0zW zxrDOT=97*zk7KurEWrY;+}KqF+G{O^^<@#J>&-O{;GlvSGvRWn0fN~0GLrZ+aX=^o ze`?^Z&@h}~eEKOJ3yGtJu$A~rRQ&FsMb$=a@iayBmQzr&r6;p?;>gBdvgw=+9aI|8 z=)S1KprjM0-$T3SKZf}qi3(Dso;&Jg6Q%N_VAkQsCm1+#~`x*-fSqQGDxq zW3A3O73tO}9Vj41Q_7lwds}}*N3v~wBe__R&f9&4(i0v!E325YJ4bfj2J|O_-}>Co zmt$<~!%lp6>PDa5iCV5{y zCh@if?{J6rKB5WJOy=9>Z-dNgca2LYl6Du17X;o!y~UdZ--xzT{WIbc!q=LFE1cds zP@8e_HFL5U7A3_L!?)M=D>9^@Sw&_w@kf>n2<;83EcDae)+X_#6uWPEisus<2rWf? z$?#kJMBk|_{ZlD;Qra=T{-hl;Pt>6vt*2UPODFwbVfsk|e6#CIr)?0w2gC!!=~NSl zknbcNzLRRHhyFON)T%bIC2yzC+l-*OG;eo0 zexB~~o*k)A5LA;w*yP=PbisR<4(~MR2F>JrkTsi=HwTv5;w`ZH;-V;F8=?FCMRAl1 zxXVPFxnlsFVYgc|;qO?hC$6244cy2ulZM24$#mhk1CnE3yRYQlZu%v++jG-b0JECOv4H0TX~A#!K-yFyPw{zvAeKszss16mz-OjPAa#cfbM4+ zyNlw_`wQUVlY9iVW zt`qj_^D7j^rF?=`M5CnOgo72KzfDY!Seq}Eq&)gj{U)Xiwo-ZWsC{DBlH1f9VSFiv zZ&tBtcf>Rp+R^FIulniQ`bCZp!35kc0tbFa&N1U`-g-ah8jaqUYHHXVRN|w)fLOl< zaH8LIH9_)5r}ugn0GB53*nFj<%3C`HBf?3-fTb0&jQ5%x7Q2<+&5+Y#!QICYyt@&> zJHwHs`UM!ny9=}C59i5q!v?O|S*7s{=7DElT*#{ewl5I6^OF|BxBcVMOd{TC9+fQz z_B99awPf~S{6^29j{C^tOIabST#4qhBnxk1J&H6NE~qm_x(g#^ND8$9U~ctfK*bVS zO>K%cdptH^@<{yC2X6V>j)&uyp~Xq3@NNB?typCz;R(x)JlvkH=@FW_P+NmjKMBEk zVw*P(>Y(C%Y2rEBVM4mK25;m1lh>w!Lq8!@-z#5fnY?eLu{(J?-Z%wsQU)xyj`PZ- z4YVUHpn={EIN7zQD<9*y(g@yHyLEWaBz(uXOy&Z+fp-tG+XV9xx(U%yGLeEeVRsQ( z_hd2=x0H)HB~b)z38dj8%Lw-lBRi4gC@l}4aVpW0jv;k73jEb;H3YFSvPqNMew#$T zu~TJ@@QrL;7t@C6^{rA+m`5;tOh!4tiq7pkh1$NS&$#Vw7XIjFnE|{jq1(c7c?)pq z7_qI6J_2)sLPM+@m-=nJnGlUf=B+xsNj0(jforCdtk=f)$8JtAoUEriY2JE9XUd&| zX>HyJ-Z$IW4K(gHv1W8KoLC+Zz)@31=r-*8>d`WmMlX?lRGA&#X}QX62jp(?G{~BW z*Hwbj9|(Z`z9^;ci;FknYO$4XwFL2&@6PE7oy|u1_?qiboN}EQ=V^j8sczp!%_x?6 z1y3)DeK(mRE=`4js*+VLEQXn{rDopLzW~+|Ct+yHp<dst0L9{Tveqb8;X&B^RBe$&}9g}Q$}=y4Y z=X0_;*=${QRK+)ZE62#;X%e_O$CRN=j^J&pf>vwZAf_*4D>Z4*K9qY<4fwl zf~<%oqL}_zi<9%tY-aTMy%;_oOOfa7yAnzjMUXiLx+{@kv@m#g==(3&1dNGq)J6j- z9gFMePH_zT28&6gnhGr5*GlwugyN^5o)EzX8g4V{`@!bZV( z$@|8cue8SFw~-}=B#ZZPYE7&&O8eFEch4-*q?_&%OoHx0vpth)cPj5Tgj;oZOUb18 z{sI{{Aa;vDJD*1kA4%+fLl(l3xR}(X46&2K7;M(&!RnMVVlH~D^?_xqi7*V_vJb^l z!%53thg%DIJfA1)Ro0#~dlj!I?L0hXZU)q>O_z%C>D?;C)>!lpv<|awL%1XCJ0*(~ zeP6{TnlQu3#x-Oqh44sSf~|BX99HU9DogmLekx1#o~n3dpny6E`MxEpPopkx3ERQ9 z>J)Su1!I`^e7g-Jx9NjTSkXDIQ}7C9?{3s5_=uv(PJ;I=*4|y%wwpf;2H+8l!R`S! zcI)O>-To>y6HrTPc>wR?L}NE_@sX0d#rsBt-T7KIr*{|HfgO`kMnYRX;YplyQH2^& zqU@WyR>;rY4rwa-*TdS3N$Ae2c1KN00DN;gzLC3_OC82s>Ew=Khqs~KniIJVe0%Z_ z^bU0hhS+z-UXM805xyDwmZoqTgjeKSV)rHj)Qe425Q+M{V=PX;StGO?N{QvgI(j5&E)gSrt`cqBzYrpN5FfgWs_OlZhT||?ZENMf^q3R z)^MfGyRFU2?#}jZ)n+oAwSPO$r_k_KF9zs2krx5oB$@zn zmjS!02;VFjV~~2f=Duy0-DI7it1y!8u>o2hQ0h8x{+mL6RqA&}n;|%M50WFHqnbtK zsVGJ9mUf@jZD>Ehp2NJA0Dk)q>K&roVfJlxjwf*MWm-X%lE|0gGs{iKiQUc%!|XWh zz7EH9C}W9^6S)=78mJVLHeekXzO9AuZ{hMbMnUZpY-V(M-?-A1*hv*T93PX7KiY92^5U(*h)yZt@&>UR zPAl`oy46K)T?Xrr^vs)1GT<~5Qnv06D?{BwfqH~*oxEK0%2|D{62I4`jCK>K%99RL zSlB=hpJ=$P=kB~wj81D2*!5TA6V;5=6J zc3ZsRLt@x3ad(o7rJI2=tDN8;&% zX!o;=ixKf|!MbZUe6MZvUPs_I@uboK?Ut$C&gK;Ucj$r5O|Z6#39YYat(A7OgRGGn zSB-}90J+Y(N$LmTq447L+Eb}OerNaCJ4ngtnA-@Vwx-E7iqrVLn0%#KONM^qD5 zZIX!HhiBf@1zS+=YM!p_J_W%$8}WAdy9IPNKdO_;L8efp4pY{oXi}3Uf&(U!6d@oF zA2llGK{2^_Q-rW3ux=Dg^5tr^8i8;7j501?nXYvkqhO?2cHInnPIMt*TN%Q+=FY`% z^Xo-5q39(aDY2+lD_T2VsA3a&W*JKFR4A9plyEiJ3PKk~qcn9kpZQjjz z@V;>zSZ<}+B+>`#0`EC*rHU85XGii0O39n3?<1ALcDt_eoHX_w-y(?M-EN-evuP$Z zULmLl&&VSms_>@#V|vec`c!+aze-QrFi?( zAKFXEyzVypc3^d)aH0q6(w*KmcyI7QQapOw3CaX>_vJzg+zP%mj$dC&>V173bl|x1 zI=Z7Hsdr!!I)Mi8m@e;NmnLrl?;91c{MoIV#P-2D519YpC$(phUnzgfHUJoxw>OBDb)>YorF*q6_@8*mfaC__t zB3=ggUPtKjHlb25iFR-K_Kt3xVwEQj@{O>)QS6&`FgH3juk;hc+qXQviJx!ixth>y zD*O($peWT_^_bpP)TFVphdb!Ea;E%Y)e^(3jm&)#!R?b&?9Q6fi4+TNQcowt9upUE z%keW~F1b_`oZSGrw*l{V*g~@A0UgP?r|$VmJsBVDHpS4qvC6!gc1Fi3d2iM8O-iL8 zle`s(yN)Xle_+{-O5WYaTF{Y#cVs-LyQjSyVwE2U8L+!%aye>SxW<+$%>_6(#&pyc zL-EZ8ZR(5wyrsuPUxx6a>{nZ(vSQy1gT*6*kXu`aCmA|#LzUlK1K=U8WW8QH<2tpInY1<+!}anpAM?=}dPe0tybPDvLnOr8!=B*8a8oV`z3xFotaDUToIoH{|PX=U1ZR&~H^}B>JE}CiyQZT# z>hKZ|BJ;)3Ks;fha-gvrz#Fi;I4Ywb)biDpVRaJ$SL_4lydJMJ21SjX=B(l9h+pp~X4uUqDP}4FA*$CV1PP+rQtyQAF zttwLRFUL`}JH&3&367ICtL5DSeGhl~Y*PU^KsQd_$biZxt*Y?6=I^;K(9OPG4JPL8 zJ(1g-X0q-1Wd`mYMQw|Jhb0pmy#ra?a~T*i4tA64fI3d-y_VqwiFd%Udo8)PBHwGv zD5wPQ_0Gh58W+)NIx{-)je_BPrR5ZyCznzkd_w0+swPbG?jGGL$VV$p4{Wy6%Ge6n zkH2Lk-nG0XooL>ThmwQQXaIYa61s~;yhCb)ZH@96upA+D*UF<2=_X~;O$fw2L~p?G z90zKxp3E&F1Xwu%xYSkL9NYl6lFsezHAfBYS~gQ{+6>7-{oYXL%7zuj@<DDEp4;B{uWEeF*!u z4=d?kJ`ufBcH(X5zjV=WTFvPMM*fD7CGqYc0PQ^SBtNi^AweY=QMI}W>{0yee0J8wMQ#vQ0^ zCPjqx0f{6<1>W?QZ1c`bqlt8OmuqDO-HLPrf+Kt*|IWGF6Kq`GqO773-G$%guv0?0 z1+*HyjVD~fv0U5<*f}Pyso|!Y)KJ#ijlxHe+bUGgr;tr9NEM)LRGF2I%`X>hF|DJ$ zg|hy{0`N-2sq(vvy|Z)I2>Y&>w%j;l$?bmZdllVcP;(3k@SO(T;ZMD^V(}_cNfodt zdn5Cf6g=o$8?SflIQ%qFmTw!sRc>c*m-o*MyfgH{ZsW`*gx$JQP!_@_OWsFG#%r%h zfi-DA+FX3ZB$zrj?9{uJPjKFBr$aZdGGS#VW+J|LK`Zeiw3&?5`J`$X98r@=8B8Sx zvd0AEWjeJ)$wWN+WfV|y1r5v*00$awH1ERPM(J1;JnCCvV-9)>lWF2o^;kFc2rU7) zbdt~rk4(n9P3i0QIy`QS1xFp}DmOM1wkU9?{l=^Y{F7XJ|775cmw5c1QtxVqBFw&z zaf!MFRahq$y_58A1L5(VCem`Up)x^a-V(dv*m9w!EH7nh$FU7hdbb|4RPJv1F3q@u z{mQ)Em4XiN-kNZH+=@;_HHno?!giA*cunjLh9hU=HFjThGjHe2sEaB_@CK7N5$_Dx zT{Bieh26TZdqg4$Sxf-D^IGmE?9Qt^e65-X)Gm`yLU>)Rli&?#?w8Axve$#y4rkUD z7K?8f_1`xyL{J)D&t0DsKE1RI;M`a^U9&(AFBZh=aX6Sn0N#);E|ZyNJd>MPSdo@i zVNgStF?)T838$hPYolDQ>MCx{IOnGb^RE1E4ku&TcjQ>|B#WQ>A(DyOnpd)S418zf z-SNzwDE2~QHYwin4O(RABoS{ZoCK<7kg$8L9Vbfb-W9u(Dg}3Oc_*nRGrobAWE4E) zd1b*FjXyR8?_Rly_s+XHa~{w+&!Tp-9DL2f?m_WA0{4hS5&_;2sFZJAFz7DVYSnVy zI-;bv>6lU)zI}n-K4~kypNmyO0M_+o9ztma#4gyk_AbK<_4W|GGL0BJNwCJ@AC;ZN zb4SU>+o3(>Xq;c`EVPL%UE}LuakrG{Ez3yZp6|>o`rU%JfCJ%HlCRk_ezH~I6$_~= z3GDkgyt@)oOgQ`ANAqU2RI#2xYrxV3EHBlpjwaogK^*lCbk35!2uK4riuZ%eCO6Gy z$S4@?gmvWNqx+R4o6KyR_dIF6^1xmb3Rf1omQV2L2yQ9f87C`~4Bm4odFL~gck7u- z=I<834NZa0|=V7gZ3=^S~rJSro41AhCcdP^K1R;y#boQrHL7#3a7 z^m|*FM>w{=Rxl@>q1eDua-vjwku#& zfp-jIXM%1Q0l!qQ(Cm#C!g$HV1TKSs8NH`^c4t?Aw>85MKg8fH^Nw+ON4+Mqd6;;o z7MmQ>;!T_JOz}QG_qJ_<85&@<;2kqpiNt%`{B4jGyldPbsKb=+-(TRm!ic)M^BTK} zbpvt>=q}gFecY_rt7Qjr6RN{WIL6$_ z<*ki^@0Bs1Sn#8Go0pAlz&{yncDL4Dpi2d#LkqqdqC^xT#U9th4>y*<gL_+s^x?4Ctl&;h-vPs@qicLOeB;Lm4Jv*$` zvjW~}+^1H=~baea>I11HAmi9c4)k&z2I`39SK6&&6 zeMR<4RpQyVb57x;a#ZrITVW$ocB*D#%`YTDH**e3#?3>Pi)*8rbb?HmDQDu6eNUyZ zk`=)v^$zXE?^_Fzoh@0J=n*8rd)EFfOQbS%L8vCB z8^sZP4SlZ{@^i}4Ehv$@hOn)kC02u~tztUjjiJ;|P&~n-%u~8)jHyeWyAg;D&$e1( z%iy*ijxO9jY5>f!u_bR;sbGAu$u(& zdv?(CO3LSi;JSNU(L{^hhIhw<_bf&4Cc!)1-)#;md4(W(0cmYmV)upWp_20p=nmA3 zyR6ZBr0MrihI0V4iE<0R?fZUpI28qBAbT4= z)U?JOtc|uduOS5f+>ts6;4Xx40>i0apBzk=p#%|+2 zA@Ri629G>OUtuVGQi);TA#i4L$q|n%o#XM!HnLh~yF?by7K>dJZ-~ZYwaFr&Ih{^s z>~@sF2Gn`7f0ehc6x>(xb}gWNj(SZVg?O8EWr%5aj~veli6-n9%P#%h8oKdJp>saS zP$Ou$O!5|Xzn3m=#O{&i-6N@(*o<3W8$rUdJgSa|Dwsnw+>;RYnD!`#|c z8z`7HqVl#-;5QbmHe8$jC-?_HrgSnJ_RC7SFMuAJHnXd#n#MDpHhmv@G2{4BfVeb7GG zu1;5W?MA923*N@!U0~75-Fdgh?%8a+Z4VL{H^Xb)Vxq7ck0BLy6Ytiv8*GCRhzHGt zY6KN{%hv+C#j9bhRULZL>|LGs#R-{BhIJ`=Gx)9#fqk+i2itwnb>Iieo!u4}z z3ZFaKx9PMB+rgQ1GG%sds{x$e+Nf1xGfPbMRzW8SOD?8rR+I05^b%}Uk*vL=H;q?r z?yc#!b^D2_bYkUB-*&0YV%ARf?Lg*}&{^flv9P-mW!9WxVmxbx z^32Q4htl|Lnj+kcX`_Uq;MkVU**)MV5pttyBHt^6JA!)O#lrV(IJI-j)#l2H(ZMU< z!1!m_wq3yOVBZm0D|igttndy?|Hc(h;9^{!%TNRzA3pj3Ew)blLp<=q^%S4ya0uX*97FIY*2QA z3j|j6u{5Z|d3u`sVW?ZB4=@x~!ID*olovu8zQ-erT}UR8kiq^jcZidt8- zM{sDQZ^6ok2<>CPSe$tMzUSrG;U5NuLxMFwf0WFe`oGEijc)M7@iYs)rzYKQ@S7R8 zqeL9+CmXCGR6A;6aiz`3Haqv^7{2K&Itcz|R88TvLT~wY7U+ty?@9*Wh|1GwysxCQ zZyTILTFMS1W=Di>1Kx*%Zb!Oup>Uh0D|Z6#sZ_j!X|PW+z8N-~M0Vq&E^mk8t$l*T zx#yvHWsKE?$=wHL-GJPYBJZoCmYRh6sJa;nsZxz5Dd8NIr&QYu{IHT?x5Dg^mQ&E+ zJu2t(t)igaZ=Ss=wg9#fxksb2_z0X|KyQg4-PKxaqQTp*diJF!74Pb}SoB_9wETwW z^&7dh<6`ZmZMXIWrY=O8hv#)118S~CdiU(ky6He~C3J7p4w_N88ESL1r(lm($mM5m zI>Cmc_hwZmZC zSEEGh^dz&hGZzIJf^AyQ@c37_or7H`jPVmTk@zHor>RNnC zqY3<*ejKD31Z#PlGy8V_g(ogI$;lHFOqkhwrRoKD!S7wMo143>Ts%Fu4RW`$ z99K@KX1j7Xw@KoNPSZ8RASLgJRWMR)!ok}(y&na;b-J?P5W2g^#qMw_zPqd7t)P3G zT1TZiOnA1^yca^110vldZJQP<*cl$dK_$>`1n-eNrW{qP;{7dgKXO8+?s>lC+O1aE zSJwf-%`qi9z{lcKC*Ig^H9+>R*X!jfvF~X}H=eGW4glwIdVPqQxIG_7zRk>;iQF_< z2YA>DPPP$@@i0}TX(rUvZw2@;B-)VzS!N~N(6YHjzZdq|rIUKw`SX)-pfSwDv$1bm z3OTXLNjL#Nc{H6nJ95)u!g946_g?G)-3q`jO$V%7D`{u5nglzq#;g=`A z_tQ@epy%~^&JA+SX@p0cSkGK~!nY}N^l|WwPCy${)n0?CqB1q!P28ea@=7~oOKGo7 zUkV59W-NZo5GH5eEP9!?4t5fz*P2YHvv2buC!t>h?quX+q4jRaElu94p-O}I>f1rL zZSU3yPX0iZ&WXBB+S&3sveje{#Tzv5M3Z+j4!dvCqw(^@lDWL&vHNf~@2;6Y;~wv$ zuf<=PwfOYiGpECw>D^oLsHT1M!yu)+yT)3)mBqUz!TUXp=Kyk#26#w$0r|=zl?p;a z=Z(4)p^~arZsp6+Fj)4e_?4nLSZ3lIj2=c5Z-L{(`k1DP(Rd=r`cI0J=M3pq#Csav zM6l6Yg7-X?e8=nFYexBT;v2+iGnZpCYJ*yOV-A;fxYWvl-g?17)9+LO zkHBma`;MP)Kd~L!5%PWV)CKrg{qYU~i}%|tM35Vn2UY9d8#C^ZpR&|WemTX!`K;8nrM z>&0TZE?$j$y`I+)935T@{yofv&35PxnTF0Fn=u>n@jxx#n1*m$ohh#M4ki_FZ?vsM zi{#U_$y)~Iw6g8S?}%5t$qq@i+c3}tC?VsC9y4CCdB^bFqa!18qW2IY?E8eHy5%T| zXdx#Rx7XwmfqMt3d$n3xw0reUH4_HjWH;d*-W|SxW-Z9Kvsz7pV8>*92E{w+xYBJm z`E2*WZtdmDG`Got0NfOLUs*-o$4*v;1@CSK;vHKgDE`4`fZeYKNljF0exX)lCT|Je zi2C?J6p|NQ91bfnWeM1=)$(9^H?I`rXO-97CU}|EY$9iL_6X=0$s0tIpJlu<9lW>BQYv;@X{jbQ zddKXa8I$+Hz*`l0clmVX5qY<}N-&LiJAEb+yJxe%%~K@rJS(B9nNC>cHYsXjp!9X4 zVgk0n;)p3G7Ye+^WdbC7tO)mH@>QEjs$4J`s+*N;(i;Q9Ls&;J@6&p9=!;9a>h=0P zZ`c!f?&YGk6AQmxi#j%Z6IoxITn*bjbO4g zhnCrJd$||uRs!I5ZGm9sBe_lMA$ad&ASZAl~Ixt1Or| zNGCmD>Mr)J0GKbMZIjuzSrJ}a=a$S7LVZzYReo)nr>K1@VBl*^gKa`_f!#P;EXj0R znE}nrrJ>_EnbyVwQ3m2|8ZegdeRoHX{MDQfQ&TE@Hf;y&PCe>;+L!FmZP<5sjo~n7 zmCWZ&ZWGi@fP7zHS^%CwHIaMqQyRA1Js6L~dum!uZqiOGsn+Bs&f=}J@g`n5PhK8A zwA^jCnqViDD)TyvdbrxBZIIK3w0$u<_bC9GSfZcJ28?Y)L3)3>F@y)gz6ssU7s3>_V64=d$>_yFK| zzA1aa<^H_*EA4_ptMOY)G9=n`0=7{sc=z4Ps-ITqeY-1m$J6gH|9+xizS<4CCHr3P zW-`eR-JEt`8rrR~8yR?@srN3j2^~{TchipJdyJex3Fi`{RY zJ$nO{C&0RK;;fD%3)MOTd3EAfxkh3s-3_4B4ZUnR@jV}q8}gMN4(wFxbq_4xUSFVh z-#Z=lsPm*P9Vb)xqoXr&`phEReCg7k@4o zx6w)xHMC%ATqf(i6mKVVC)b+9oLB02r8Jv_ zR&)|g-m^o3w{A5#c9C}|6rUwn>71-&v>P;&zkNJUF7ejKl;&lPy@nNdydYRh>=uZP zZ$5iwvF;*bHw{yw!vvI*v0&c*1*q3_av4!g5X*aBAB=)nSmn3Mr(O?CDRm9_tqFj4 z3ymjeJ;?wtlGHr~CSGWNZb>TOKk%{boeY=c!k!7zT$BNIAdr%7_3;NeZ) za(4LmMcyHUca|=}sMCZO35rKH^I3D&{^2|&7|)PeM|HIAM4e>5r{Ob9RT6g7B!fn8 zjOWxSAc^IHqZse<*SF>FApzSl?imO1nGI&2usoXCj|J`newDvd;Wh(RZ;P~z=A`q^?C=|J5Zo%6K5ziLudAhir zSuRn9=t?hH?c@!72=BIfysu?6K43-OOzh5-iw}&)WW7(3x16v1*)f0SRJ^x0ab>V} zx)Sp_;bN0QjM?OXx(QWgcdwMyM0aYdS4RQw?v75Ac)eR*Z8kripQlJBOd`o!+ru@} z7Ms5Sd&$LxkxX!jSTb+$cf$q)M&ZX}RvB2WSN$;^Uw#!ZK5TfF+}+UEPyJrMQHPLD z)hk!aU<(`$tH87C^^*J)|J3*E;({;gUc*QBy^#dQ?vhFiRmS3X(+DRz$u7ya+zVbS z!$}Cf)lR(9#_9G=Tf;OQU`q5>3uqk)+=1DVJ0f?>mzVS`^=^RdYX;tz8TD>8!9d}h_4L7gg3Sy*K{&Du zmBC8rc8%zm;mQDxKykl$oKx@!nm0<`=A`nNP7|HW>FzQXA0v2Ek6^pqp5OfNZjdrI zY$g~OoY(SvQm2LmRDj(VMJbtR@CNQp$CM~{S5Y%j>d4ryN^f@^PcE&w1p&_u^am1t z3rrTDh9p}ca}RDoT0ZQT;DbxOeoqi@jofv=T&@pun-2aEXb!F@xGWpoZX=94gz9z~ zp;1+gYOzrOzQLo*K&2lyA@ts$%A)re^vXQ3bQoShzP+&lUtOnr>)<@SrN|(lcj5$- zn3*&Oct;aFx0a~#hXHP8FR_B~I~lw8SGy(qmH|teth}~@l@@?!!|v(MF2O8C-cFyO z+OFKDDBkEaF+Rb0%yy;a6g;5fttIa+lf1iE#}mA-qHR>WB`ewJS@QUpK!kkDJa&j&kseOSsN!Vx!?CqQ=NpzSr;Mmq&# zNII(C@}X_VVE2Ypnl-(>Fc97$Jl9q~4Z}#SH;V~;*|(|_ltr+YG2nffp$QhCTeh04cXxRwY2KuoG+p~= zBzoUO6mP-5KSxDx>)5j3mQD^B&!K!ySn@ue;?0aE-7e$Z*`t-Ap?Cq^=~MAKlvAr2 zr+1ARP4I>m(QeR8E);fa&HF-OcOFxfq?(L90`mG;fHB78t5uiF#8e7`U^1?b>p-?k z2(}K4LA>7Z0KVz6A(l(WfB{=jV|$e`rLc~7NYz`OPfF}2 zhQC$^j-6n^j3<~W z;;?_OCCkF|H2mt2k_i{OrM-J`9jI25Ah7c}8Rz3={p;=%3>NdAvd#ERs>#;1T`6S~ zi+Rr!^PVRJ;}4#UFHrkafl1!SR81nHNk-lsuXo=-e|IW&n;P$$4(G5_N(tUA*+W%C znoU)LE%Xgyf%ixS;>jC0rY@6V^(!E`!0(~-c=IHDPl5JO^X{P*Q@q{~u-gahhGtw~rVP#%}@Zx$qAhDi{JTrO7&i%h5AT2Y^$i5}bPk(|Eu56v&dQ zfQ~XZ3rjv(&=_%hZTSPG(WE19h~v^~q&xyju9M1?jmz7JV&XW=ysbQ42w&}XVgDks zJaE6uKFF=*?rT=$9bl^op|_ok&j{YiX|jjK+tq543A|YuY>L+eBbH&_9S`0I^_m!& zq-&p69^K)s28ZK$x4TGC>)o^S!TE3bl#6l(hVWa{aWkd^@-||(qTM*ZfJvQ;3nrR) z#Jk5hor7nW<8d9jV9|qOcTf%OtDuRuCVsy^tb4r@Kz6kV)^6~XV7hWB;2Yji>X(N7 zhVT20Ua5q>?|#V}=4|d|vJ|qmwYo?LzF;q0cF`$HasxrM+8r zz$%0HrGtHE=%bqMJix#w&Y&RM!rycT=5Uq1(Oc9(gN1 zZhoP=o6W@32+nTWgM2D>n<^@miq|mCx~X8_?1C^`LpLm)QO5}~@3KCs^rc?nSHDuD zAXRyjEP|(x)ew3cC%0er{fi=4151K!hPbU#WX*@~tJ65PWZF?2O7z^ogf}|4tHk zs|WirAZ2x(tkMoGLxz&u-^JnN9^h@W@4a&HyMuRxdTX=EB~fmCp$*=b&T5kk(`S3O znoOH2pJTxLCM6mlQwHm9@+RqoPgurxQXROGO4bQ-#(kvYO1I#>YoUogtek!PErZ~# zXW~u9(p;bDrYan;q(nRbI1~vAsy%`k;^Lb(u+vb^*C?7Z#tC7JNz!m-ordBOr9n1v zuSH=t8-F^B@#OrN3@n+TCCK_+* zs7xiSEEJ?VD&*ZT6c0_Xh~3ZL6j3rEouociJMcAu+4Xw0EZeDuA;R6W3H|NF_eHO3HrSACf)LM{eHpzN-)Gexpa&?Tt%~Mx&HtDg(lqvW_uLdZP|B ztsTs!>PX>5v8D!A{?U;g7Mcu57al`ez5vg-sNRq#&IyIuZnxtl{4??K98Wla~DW7@}A*lsEQ) zPuI(!reHP)+XWkNwbbkNhP~lw{X6e;>>=&;dZk9G-*d5VP0q~E=0*j30t4Su`h(AF z(7UH>L%{&}Mgeyqqw;M%nc#>(G8jj(MPWX{ec*^pE=+w=ND-*4B*ew@)&EntHsjkY z0B^zd0o4+hx%<*85rhLu@(4seAn}-tAnjbe6#;^6r^At+Xd};;klH z@tze9shV^jp~l-$M^(shSQ(>tV~rrJ4W}DTnBSzv1n{DfPFki(P^;bOECB#-5%Yd? z0W+1Lm;hxS%V;Gqaq-rWolH&)W&={w74QW1hgAs2mwK)L`^^~0HrNM!A7&T?g!_oz zb)ebhR@tAFDWlUX(LrUseu{Tm@=7JJqA>QItQapk=13nDa1z0x;Yussq26#_Yyu=& z8WJVPv5jf(eP;Js!JZ%kP3Xz@m|o7=pbVT-pLyKkf`Fc!Qc$CXwyRjlTHFwulnQgy>^ zRNbQr-i53U-p)c3db9b%$MXz_m1cgS#>=UoJrIiofm`S0PCS8kOPT`F)IE|_-bGp7 zjc~2E%&OAdO>XXxzobzjyamJ-DD0J6{^?KNPmQmCDYpD_eOQK5N)Wrt0=FB2e1oYQ z9fN|A!&NFi5zqHtsWB9kTX1f1r;Soc0D2;PJ9TipY&4RinldHfJ9G)qIw-paWwTH_ zP~9hsO(*S#o~XJ23H>I+x_8<*?e)gKH!QcR!(q8x?P1=sUWd>nyetm|F4N&;eF&g0{xm@72GOKZ z0_?_@rADux%kaY=kFOGz18wD&vy}42VBNO#Z_HIj39C&97=b+fVkHg!ZK5M!fyvb@}PcKlL$$T53 z-vXth$CbLsI|aOF2c8{fUX!kE6YL&YG|_r@9D+ytyN%v0-m~ot(mjHCRvc)=?IIHH zqLRa*i3)~u-pDG!7We~4N;fIXhz?=5?lRHbdtCLQzuQ_l8@h&caB-n7KD5{GRWFJ| z1ng5^ui= z;ZeSoALYfXS{_#_MH_DK<+4A7`fgBA>H@jpQy{3*?|FSdY_ES$Lbtfy5U>u1miHund%0M+GxZm4aESYX z?rb=IgK)hG=ynjhBM`hY%-J7+bZ(5;X4H0vqSQ3t(vgI%7dR+ zh7T)~WAU@Nsd)LXxcwm;>$Z1t@+foXaa~wthJAk8~m#aRgewU{}kB*tz$y2F6&sHT%Z7Gg{429fG03%G9Gu zoEQ$KftnhAfJuI8)EWp0N`!9k2bOEKGOfdp!1djdr<9Pb z#3F8Vn?OLmTpd=u_)E_#LEus`bN^Y9?B1Ay_sL!&u=})(UX!}t^6QNrO;`f)ZhY4O z)(z0zClm+hZuIUwe5--6`F_3LQ1HE~#By-EN_1tXsZ&oM1Fd-kntDeqBoAQU%cyk1 z*B72Je6PO6g(uwk9_8v`D))Yz+tnSYShrHU14Xpr8v*yR< z$Me*KN@EW+PYS+yOnyYzeen#Tn>cs51_zb+gv7fHS$Hr6QVypoC(njsN?CH58)Xp+ z!&kjNTVw|rQ*9Ad>uuiyBIj3r*oIu*zKud}G0}MP z{kZtOA}9JcfbEr?BGrz-P2@53%v$_)k!ypM2N8BXUU@@}VQ zGFP>X&5wHPJr%n1d@HBOVmm6CGXms(gATzF^-k4lRSDjs@(2=^<-C-;$5j3*V>nfe zz^kU$;dtnobPjG$4l&-|CrBTn`2?RahXW%E9&DgNwz7(y-L0~?I)q9SIMk#gNGZq00PO|@bVxtBzrRP^E&(S$J*}J6B|kQ^oDUT@`{u=TQSmzwzB}pz_Lfy0d3lF^ z5=U`=#{!8tP&WU)OUu3eaOmFif62A0$3#z6UgKG%Qo9v~?*ZPLdULgVj~4GK%U1FV zLDOj>(fcO4lw)0;$pcFQZ>5^dWs&!s7n>ZPc$>-it0OnThKP4Jg?Y!ERl>{m5AA0A zJfH2N{ecAJEoJW>5%w1a(az)A8JfFCl5FQ|KEQXr3_KjLy9Vvso}4(V;!Gtp2M)b4 zmX%b)JthL5PjOuValP*qpFyiDY26;gbU@#xgUVCL;Q(|`1ayN{5PM-uy+)nlI1P0| zdEfZ%pI+R9)D4zFWZnG+N-20}4FTT$em}R%gZ$-6o2;#7qg{T^DgVx^TX(<=(|SVJ zEUa?#Y{!kO-EwlTSu4n7fQYna_i1+U1g#c;sfmubP3&=L-ElTsvW@F5N_Mz zt)1P?Pz#lX-uBZ>A~&MlTCsVxtp}8<{ToG zI8|B9TqUUcV2iri1m8l_iQb8)FuXu+shJ4KuGPvTNW{}tB^^@wRR0RIXJx0>-9XTV zAq7%UhOo0R^3mcA_1!3x0Cb^lV34?3va@9~ez*{u?l_(}k`S*>mQmNMAcfxRY$t7D&5D(t?p1@9R49b+@W0`FP- zT^lo%gLL!`%`dP)of@Jx)^m>xc8@^dhI2{@-hy^d{91legA~qK#o=M9vg*?cLp^#r z3FzI!*FCS^z-B2V+(XQ_qtuNRRQ{xlMJAw>oPuBiz21ER?sZsQ0J#K)bI@4QKPfg1LiHg(u?|c-<9NzFYfzZBO;zS7-~pVmTI#N71`PMbw`fuXlKI?pT4nZ zJlzRfi#HUM#d*wIteNXuMr$hH9I(Uw?PYin$NtBEAZ$OJbBCPWNW2#)c1yWLySw)} zsWjP~y*Rh!@SeJ`+to&8jw^YNax0D9if_w64%`4Y%|2Vpm9yESR8n=->M+%s9QU-+ zEqL#miihWq5Y0Kyd{}9Qa>!g#l+cYc!$k~Fg4j(4LEMCw*gYzbXo*3N#7m}K#W1{2 zta}&<;|OjImTv^_daE_57F+aDJqTa|f|qb>SlmHtBA#2VR(aU#m+Iwu562fEN-0P_ z^6gUpzDLe(@O?v@cmG~Ifx}xc>;?@L_j@nIrIahZXfzuA(pPX6=CYt!1irQSy^NV8 zi|wKUD~fb_KUDfA0o~rvS+cKcr6d*Zmcd)Ti6*jF;a^q{pyj#e?0d=WKM(f>?)~o{ zVcqnCF>iF3$R-m-yY~X`5bNH@Bsf*|-H8tGn+W?3`Ak0JNhLtIqTK}ED4C#^vgJ;b zv_8Q@)_5z`gdbEM!)emZEO^KJyP?YD-47DDi>bLvD^_V}co8w27IP51(H}S(wE(-t zQyDFSc`Sk*A#{60y^(Z#ICoYZ%2ZASy|J)(H{f*E_?NQqk#vQSl>N7 z1#bypw?Bm01t8mq-kxCVXbYDvZuFS+>2iM$F9rI8@GXG8B+wgl6d>NE(vRYgK=IP4 zKdJh;)jry-ogp79UlPSfolUTx){SSP+=o8xbKvOJP^wc6Yf=rQER); zL$UgsL-(~-y7fpUk?+e5C357*u*=$=@uV_PyE(z$;2qMtBi#EYrbRG(Vo8x4rg(ow z&k15T0C!k3nH}BZ%{rhg)#Uhxl_`SvEWSxlU^i6=4zlp>JRe@jE3-*0uL`K%gK8qH zUq|?>fCLk=nMmv|`(uj0d#XW@?B4ZZI0(;Myb-=3Q#m4Sr3$h)G`#kD7>@7bY-JrM zqOd3<{D;>TPLo`1~!hzFRH zNv@Q$*9~?$akCYa(7r=kRh)zaJ)JmZd{_0vaR=5{vRvA^(dEjO@JXl}`BomktR37+ z+~(|ixr)l$tH;7^m#>@UDW%;+N+xkx%Ix61R>nXL;SVXKnkEu&%jJ!)|5r%!M%84l z7KZT(_`CtcKP#hPoZfvLr-^3XS69~RFctkB3%d)cf_IGGP5-9T_PhK}J`;UnNn$sa zbIUWzK@qVVb{D{NLLF36F(KMrY?Wn`2|lA>GMRX-Vl}qFq)sKUw7D?s!NDcGDJVA} zHl@p<5uZ|MPg4+*{na>M1v zo}k}#@l}f73@_?Am#uF1Gc_9)aBN{?mKu`a7)nvH!}n&Vz>i-3(qF5i9OdEFP~RwV z6K3DxBiV03z8BvFxoxf6I81br$+ZquUdHtZX3)E}QSd>$+vF-!up7%vH2apkn}PRd z@(0c}c1y+k^XKS(&hahY*aCG0gYktf>+wFud8NCKDqiq*55?oZTl+jC?`FG{wVD=D zD3nu_y|0MS7jjfsAvanDfp-7pO>rW7UKQ!C`hbg`@72Obl-45r5ZVQY6wT=YkoQ0W z5x`zYzU>1sKJ7Pp;s(EjLCQYXyn6M9s_JeGArD`=?}5mTf=R!D@f?8fQ~wmtJy9#^ zl_Z3hast8cf9#ijgy_#{{j^?cMCTeZVA*o%B90bBbQpM3)u6K-MQ-W@D#NqEJVz4u zRuTMk=(Z%4m3`c|dhClcakDhFfGdvTt49_~5(>NZG(0-Hjm6~pq2Rq{n#rCBuA-H0 zt4Wx5qfPLJ4lDmx)M}!zn;orTvJ!L?4%^Nm?~v*}JCJAsMw5bN@9sX5Xp-zRaW3b~ z=IxK2EV;^>QpEX44jZW~>eB8!_L+=iG)Jc@iFOy^Ow!a)f#_Wv`Bkr2X%^PtUrWSZaAKlMiMBaLavS?i9l_y2jR(y z@3&fhy)S+x2&isNPQ|C@;2F?6*FQT0<>klHk0s#W|C;Lw68^6*AfK80Hl{XUlSK(F1@Nw+nHIk5jF`RdIY~U=v4SFvY z-;#D;aS_)7J3L?m$0Pjglub;Hch?G69vZ^CyT{@kdN=JZKs2Y8tpYaBSI*4vf@0kl7Xz{hLI*5F z;%ijgElnnZb^pcp<<79|5v=;qVN!=9%c@#|w>wShRVXXLS}B3CL&{S2upAJU7|n&P(vnosbJQvWOm z=$-r5A9JOgzLXk2{nV(}bEdz4e^iRd0i0jUm13M*&@5aMZ<>$aScu*ZY@>IOiEtav zzp+m;bumg94Oda=;&A#%I2UUD{)m2UPl9nfI5#tPUu)J)p&Xs2ynYyXlSMF4?XUYV zZ%(^2Ho@NLCRkTG=kt7K^KJ>=cAZK5`q`mX6WwZ}rIO<~yp7w$61;aAtQ4=B?e@p> zL1w+%ELYa7kWTTL!0iz{6(L)R9k5tJ1=$>mSB{DTx{DJiGw~=BU#)}kT`c>fs;5pb zZM|CtEK$?;PETP`7@n$-mIMY49uXK zOH}uiIj#h>`Ajh#1aB^!%wxPJ2UAQq@s_P7SI3*Kw3C%-f_Kbt&TQLm|8RbuxkZpm zCIsLzOo{!0Bb=%%5_Y3%QqEUp1=VO&Y*qa?Egu^Lt78J@>ez3!ibasSwdsW8cin@D z1^6HjEQCF;SVsIE*UNQ**d^rO{azh7HE1Ob@N|1n%H5|xCRw@B$qmR2-jf`5n}E9z z%S!;!U!3*(0{R6YBQJ-$%;nAiwf|e`Uwgf?GvMn2zJC-i&(0b@)lX0Tdi_+3C)p5; z2mcK4*`I5}w^^7M&oqGaU{c)P)PMml~EaM_g~%=sWK4slB$YTR;$(8xK*P} zB`c$n5laZXSL>5v@nVGafgqLmb-&#ATYgU-T6*da;4U0!f?=dog3fOo&GBI4tkkd9 zOZB0I<_3l+hiCu?u6^o*N!+W0hY1*~?fzL`d{N_u ze~$+7+`fv51|lbbg~l-%Xv>96TAY^vPS8%^ZMJprDFD4CVqaNGP27TdBI+IcYS;Yov5h&@`REO~wE z=Y|_-QW%Whf|m~)IK9v>LGg*#uLAid8N3AU@P6;bJ;*J&9H2B_1m5S)`uBo%H!%HE z_91ZT)ypk`=zVeX*Lv=u5&Y{{z_4>F-r+O3aY!e`#6$aMH<5vOSsSRpyCCoz-zunBe40=2(1JJd z?gEJ>mdE?>4)3nz@ZPPBYHpuZX36C!qe-#G{3dj3vH0xS|9A$(dvrmIIT+6Ywk(G# zi+ZyzweI`ChS7)J>kVlQ9`q9NPD)Gm zFgs6V8vq@6wV>A|nv_ULX$;Zq4Sgr|I<%Z1+M_2NzG_sw?|TB6OQ-cZJ=cE%hq(Cb zTO-)S?4RBHt;rbFaQG}wd|vLMW{PBwMdS#xtqFI)vD}C$5z`@UXtv`wGM7mn75zm- zNjH~I_G#EoWZ&ODYjZfQBr0?pcgdwy9SH4#fyz^MSdEDrz_Z)C&E(m1AFqi^@Fv+L zgx%pK2Gt3xWN&L7ekPf>#2|$2!sjRhKYB3U*aSoSIo%_qb4(wV6uh(R-7;0#YXq>u3$L~9tS1n5SL25c4|*eF4(cO8QCje4s}YB`Lk z!G?SZs=<3euuqHi`gf)K9H4g}tGtIV;FBA`wOgas=+qbYdq4Idg5>wl#`k9k-w!tq zrh4Q;9zcPx%88;R6Qtc?DV%u@rHaxCdBztZ^iIuk+F#7l4)-LRMl9!un|+56dUXhG zdvsAbA)sy+60feIvjGE>{@7|`%E&~OltOPn1nADS@|n~H(@ssZ(JCrW)r;fmtv8Q zDWS<^jB&~`oK;rGb&6T`@KjQEzAEC~>s5V{PO7ac%;taxaMQhkB~ykOmp2AEa+R--s+70WRCAaJ_{joKi8rOM@|=>I1o85Wz#A7SM;f||7kH%w$W2Y%Aa&QtAXt_0 z999216uJ68sbWXqV0$NV$^;2l364V>l(#ox}_`4ed(%;^n!dF!- z7AMfC0w(eLeFL=>zm;?I&DC-lk#oagK~`Y8vQFaM(*ai6QtlW_=H1qd#&ozD1RDn8 z&ggt6E9162C~j3{Y46u0vG1kx_G1Vn-;!>}&Qdb5TVb~f-Aee@ZDZ7VF=Ujy=yt5aY z$gY9Htdn&%M>6hWQPS@k%`LQKI_KH5_ZZAUwym$B{0*dgtRgvMG?#eFDp;@9S@o+~ zI)hCdvJUpDvK|)IZLfz`lwldSh2d(+BVUP!9VTcUffPI*QZ`DZdb#X>M|N)9wFFhX zHx$1IzD>>-V^9whsJR6jvUN4lqZdg_c=G^W(mNEYcR@C_1sO8XkhEshG*Nd37v9w z$e|*|a7UqGGJHE=4!>F_%rC=fOgH;}Jf?k6PJ7pgQ+mY7IeH*YbyjAh?hI|Kt> zBN#kL?*^j@D&9Xk(VMXQ=El+IeZ!jt@ujH~EHL3jDFL>C@>s)_1-UxR{oUO|YbIA= zlVEqZLKEyW`C*W?$OKO-(JDB|*Z9gMg7h;q1{P(HpsaiyL33aW=5atFA=L!WAqDIT zBp-o$+hd~}2NoKAgzrfUv+y9A^oWClRDumA0;$CZ2n2pH zd@(H5Cw{A5B0o10^FG+T0lfu^zsK`QLC;VB8D=W)#peL)h7Rx2i__D8h9}=Im;3#* zx8h^|`%k%2>7QOqPV40cO+t7RP|Qo>9>p(&$;Edsiom`#D6f*(_tG(r8@5z9lRGiZ zQ=LuQvZ4gaBQ6g)$&2C)%wq^Yas6@`JN6TSZ}a%UbjvzPwjt?9hV8=vcc{KZi`|Ib zo6A6tEyRpd?#{eX;x-4B>pgjQQxorGqe(LkySH+V;eT=bo@1G}w09HZR-imDSVr$c z^hsj(!Il{KVticrW9c7bNvG}!I_QrKn0ozmUu)w=}y)h;xQ3)B=;gqs2w<)28s#lk# z-zAW>QQsCH(V*$~5>8w~60(&0vD6s*r-YV8C>8wYhMYYs zmrq}m@Du;}zfXSp>8BUs7QgiN?5yAV7s0fDdhvfjS9saW0eydaCjOFMsh`W0#^MeI zVQ>9QPCxj!aC~L$bMZHqE?Y(B#T*{f!ThBTTdwhjK&I)*9KLQlaoV;AM*iZMFC_uJ zSFT44tL3+D9(gpn9b+wV)R!n*w>hKiI8G%)0KS9Tjm&$>YXsL1DKxQtCe37%psku% z7hP~7nWBPh&AzQ#lSdn_w45e~kLPqlf_IAE9Vd4~EI#XKj`WrAjd)VMYb|heKSSaz zV0!>B^N_j`PXeoJV`(m-EIjR<3GAMf^F_hBedrR@vf>#la_}g@xJFbJe-K{ z4a-%~wf!=TEVMA6<9R553-*raEk3LvO@e^Rn4T1z_(zbwQTQesxPWe0)hUdTJ1YjJ7qwb#moke=vvyULDyEwMY_kK?}UwPNhdTXCv|Xt&$GsI%|o zTYz&Q{6FuBGzTX7gst9xF~*XDh8xYhQd10gzhV0KmwBgvHA*!nr>eM{q3~i{cIiHUBr2h z-QL&ZKD4pyT~|gfwZH(6JqG^da?iW$(k;~ zDu8M{sVu~l8g?`FZe(bKhqHt~6XPwTF!-9YcF50<-U z7Axn^DsLC??h3o7sdp)vl;Ax!d|y^UOS3k?=>?rl=25*e1v(E#ykFH8E00z#R?atg zV=4aKnqgFxX40rKV9P5T4Bmv@=TN+HJrQnz_NXwI1Yq5~2tO)Vw~tV&Ad_@+76nYY zgNUIUZfTv`#Jr964UcyURU1BP0##@zsh=r>-99Vc8tK|}2FN5Fdv1)*_r#S53q)c! z(`^FSoGsw&23Pb|3TuckmTx6Q)D`$b!%yN088asLa1b1WP`eUM^jW5dYABlBEFXpt zQF?i3A?PIO)BU8|4>__*dGv-))(WCInH@5_#(1Bq971dkt~wYi+(tK9a9qvJiv7zJ zrvESxy{FM|hI_xB->mjue=fOH=AKo$3*ueG23F-}lfi)>Rt;b0-KE-n@#e$V;-~%H z--g;n@QC#a5sb{F7XZdKY6vr8$F02^?eU}-UlZOJl- zWFb2)@=8qI8BiR+&3boa_S4b2fNOjLaV}$UbK3~ou2gWAq%y_OF*iwqh?I(56G&wd z!n*)|NuT4y6@IrH?RAxH`${EY2$@_6m#fbRjC;iwo^H`2Jj8p4O6JlHL)SwsLmVS* zkUn^roLa6yZtT`;YYp_C8_xPc?UaSlWK6uvB&(UDh$oys^{o3&#;20kOMm?z7EL+- zHryo3aCdH3bB{hu3+dx$0z#QPM;ozZuv z9Q?`~I|jQ;)?Gq4W|hXw4b_AT;zzbj33Um)big*L#&VX5W4Z7>p z+YoQIbfas5cy|_<$XDq{+KI}I9HQGgu!B2i;7eYqBtVA!FR8);5kulvxNzTRD5l>f2lWB8G47);RM zL@L$RgGa$KVw(M&$uz+SUah=`-dzkUpZ#_J-Sg)sjrASgozfXtIZn(qoE^yb^c!`( z#OU2jv`0nD8QcFLm0)a1H|ny&67UQegt>O)OTh+eqT!s{jaw6}#v?_L;F|y(0t=l7 z^k6sQ5hWIH5}rrqv6rS^YO{$uVc2$a0`SCR7a+!)GI2GcVI^U`ohzLUMR%_o(a&%R zYE_Qa`;?32hl;@8^NQx2P!Y>^RjUOE7lyS<=-VD^BwpBWwZOU|kGF|+!@HZ1WcLm;8S65e8p9s9)Toh3zAA#D_IfB!9CM%65Z>MLKb9gse&_KOS&PkEt zU0cq%UP8SuA80@4p{AAf;7B@up9wW?`PoDv@K-2!cty z+xP=Zxf}X6<2Qs7-il|%#19O1(|0<{e1`zMR((cbO}7zn^ITFI&0A;41>rAAn%# zW=$b>{Zj7B@0TV*mbmLecP#{Ev8G*bNSm^p{P6lgx%TVL!uCSGT~O}HjBfMARq5zH zD_tdvRgw=uZb&0<#=+fh3gP4<`YNXzD;MeAb7=Q%4YF_N@or9rElL@H-ES{v+RwHg z+G-ba(z{SfsFuci`B)=q&fR&y?1yf|4Cx{FW~;}CQ@rD9?bokIgTgQ}w4Jfkf2 z6P{Ai6_TfuIXx0Q;lse#|^mfYTMu|NXF#N%@WccRgaEzk92hPw@whqfI-ccC9?t>B4c zd)*H|{4n*+oE(uFh_BkZEUDU?Hw9`JD)_wcL1N)&ukp!TmTbt^e$A<0>VatY>x~~b z%L#Y=n;Vw6`MaxecFCe{oDVKrm}p$61$R&62!4=cGAGdF*;;z{Z4JC{=Rr3&o|$CW zw=8#GPjpsZuc%GI5}Bg@9vaQ-i}ksB_*7n z8r#Wf))`MK%TGm+2{<^XnV>B`V7S&Wc1y#$p_BmR@1m5DJ5E7|rM&CvwCd0)2)Fiy z*{zhm@AEt}&?q=ls5#>}?$`uSA>qXMx?v_^9Cz&$mO_NOYF}}zVCFcHFa0PEW1`AF zhg?Bqw-Wqq53YSl?XoZw~xJJI0#uaA->I|+-D1;@Q7=>xF3l3 zP~{v>h)X5N&g0&5SJ7AE)fzx%DvA%v<#>R0IlSC|Q(^Z_`4N~@TozAL4cnffp9;pl1vtaQ7tzKmc;u< z7P~K@c2DZv*DHfyFE=iDKPd5DPw-w`zwqqmHFaj&FP?PK|a4C2|Ma z_)J*p#)nL^&E)ia*C|z#6f;V?BjIQnONEdsAiON7xir|#74PLcG3-D{nJN=U<=QX= zdR2c;%yw?Kpxty^>bZ(=m8*IPw>1O2Ye!B-aPIn%j_v4Fa2W#(DR!)+t#W4&6YZwQ zE6G7sgw4JnUeDPlSwOKM}!+$Rohs*>_$wvrAz4T@m5b;U~N9J!Z1u?+gcBU z?t|Ye9DK$=0vX(>A!bTh%a5&z4XLBRV*AE2ROIi2LjNDz-;+&O% zfj3o5_rZk9Js-U99sD|u?Y{bWy}L%dFII^ri^8a&c>nKd$)wJ_4eMsB$&}rDS(xAh z3f@N#LcHtPy;|^|HF)!1>+SyY^{~69c(Z5{0lH6l4`-~G`whR-sk=-Hb2mr70=rp8 zVF=d**8a$Mz`5^~)R<;!XQ1grB)JHln-@}!4IE{saGVs9iA?zmBIVg$SGi^B8SV?F z?Z&waxf!-XuBS{;_HKGAk>jcfqJ`qp8#)kDMQl11Dj#N1HWZFXv8S(5IE>LJWR)b? z9Z0QWC5%Xp%}L=YEpj(k5uFGu$l*N;-a+X-X+81UJfrmB76g8aEb1Oc#JuU*pe_;D z*O9dbm!8);w#=lmNH3oPaK4}o?TmnhYteYDN#Ct1h)}3JBXu2T|bV5*`VLoXCy?Ho^2zD&Yg<68$ORyf?dLG$S*c4&;;a?9@0wDa|We) z7`2-M?h&2&SvJI@bK>20p6HQQ0g_dK|572egucw_qUhI8F!LNd?luA6k!X2HHffpl z94W!MiHIL|yFwA?rhnuvC%;6Qw${-AYAZ1duzT^1(@*}xVw7SGKbwSigr1!J0qT+l^Qpq~*u2XV^Z>j+@3x9|-&HL~ycO!?&PDUuCm&$ZCpi{xnY=Us8E0Mv1+U_4ie>~`-I zfcg%(hBg>C>gHWOmq1Gadef5y*s;vrJnvbq*$dJsfTIB-LdAv_vzN?l924?tEtbE)3FCblk~#x5b+ zzZ~0Mw0<+!R8rI`R5Ewz=dQ++wdj&n;C*k!glYEG#q-4Z0*8~Fe1zmZUaPDXR#qQo z?cL9A7pK6^Y{gG@5SLw+Z%gd1ZC5T4ye~JccpsJ1N+X}VD!$mH!F!GFoJD%~*5$Jo zYe^<2gTZ-0xSd+_+1PZlN6;R0YWD7OpR!Q9%iM0eq~4ukmom^`v@*C;FrWm*0=z&j ztPHf7QbKk%Q6^HB`Pv9FA<(t`J7hyCf@J8~%Edh;FTlGxjdKkZ1rJn;p8&Wjm6haC zBsl9el}St(pNt~9C!8r^E{UttLlJ7y9nvYpV>zDA2f1sjq}cR<-#k$gQsS;~yNWf5fZmS>b!&Hp+dcp|=vF z%52ZkIvNELI5&sB5?57snuT$oE7m6qgP?(Ld=fq;k9u(EDgY`y=u|77RVp_Bfqc7( zv{i&KZZ0tnd<-Yy#fB9dU6Z~vl{$#0ij|N3cwzk6s^|8sT(M~zF)1!bp;(q3$4SWG zO_Z5_ff1c7ay878+!n`iKg@@{95VPY>ptxgcsH|C=Tw|J+41qVV3{V%bdrZ5EQbO8 zUQ)S3PY7>~t;;EWd%cB~d##dx6acS5m4BEDm3>{bOZ?)ny#%}G7`bmI^0~|Sl1eKv z!%Cx;+^hlKbMbqB;?u0$U9UL<2Y+|M|3RJ{eDq5Ey?buo@a@vA_=Fdy!ueB1HL*=^4kvn>#8*>A35$0YAeVa-I8eJezyxYas+7%klOO<5 zt=1_`go)%>SSf5J?z&Hh+#rmsKp9DtDxgbVCTMPugyLK%Nl)izu}%0)cT8IX%Qmj` z=sA4fH#;?uP}sBW(!I^q1manwTSB51Ck*qv=Shh)T9txg$4NhxShzu0c#bKi+smyS zF(%FKqksNquH13m$T>BRL0C^R!tO9sE?x-G{RX?cfBfo?Q4>SbrSQF4_*k-USmNqh zCx;KD-=F%9zb?i-Y2-euXLG+UdMK;q_tFx0b5_qSSq9)2WeWEcy*Ajqh<0CGjKilc zih<>ui%;(}nY$CeUUSZLq)ElRO`yr!Nq6@z*`BjiaP9iEa%=zm1jmc5O$y#Cq6BBl z7mO4B*#L(?c)#0|MrRG)Js6yyI2A$fOi*vYct*_IIqfu}S(8b?{=mX%!i$w!2P~7o zyls#C(TE7QudzU>Mye`cVAr21VKBfA#k)XlsT~>fw$AWQsOBBe+Kx?*AmU&N#S^6u zPctXNQzR}SxEi)~ocWwXs8Toe`j$o9x(CBI!8Cl}5KDl<36z{udiHI>lTlw__$cU; z=SjaEMV>1~+eg&`LS@mogDGZiCyF0#C1UVccmH{Buj^z<0$qeoDndN<+nFFb?-GEc zU>@y1IwI`;;)^f7@3y;9cW=*HcPzP-eZOA0!?Q-7_^*WyZy2*z((PJ8V8OS?8G*0I zjX3q)_nR5GT?F36@z>`kCykTm@1`Gy%!(6Se=#j}SGljnBITP;VD7$;&*XMlbIyFd zyTtCoXY%&PdTq}2lGVx$TTQC^oUNm}Igl0aeVy~6e%{)UN${vx%->qGIj11r&yXT` zvX;-pIT?4wccza9_fj(F9ve)G3FW9{-bKf-*{vKAc8`c12O~%tqfGO9q@5aFC1LZ4 zN(l^$T<=t|+6^~gQBrvqDMH&67Cx9u5YWxwow&TqlPH`1;95IT5~`s>GPvu;N<_Z# ziu3+uZem>p{2#(i`lfXlZI*Th8z1tnR91{gAy)gu`nmK0tCNJ~ZXYW=!0tRz_(Cyy zTS+duSu@Wen4F%eS50#{j3%dXfgsTjhmsnEHgX!Gope{p8xp_0Q~1E_Psy7i1Y4b zl!Wg?D;YgMs59)>xE||VqmzUBMoz`b-(1wqfp0#6$z+Z6?!~lw0r8&3?rWAz-cIW! z3#OGDPVqJlJ)Tw`P4&gYc;cvC%!0qtch5eV^JHo{=V)t5g!jC?$}QMT%22?yu)9+h z40mSm+h^$R)JS*1x<|!IJR42QfT@wKgTQg3QE=)+fxJViR6)6UB`2oaQ)RYmY>3vJ z56g|ju1x@FYek=JqTji#bY`cq&FyA@@mN79NnjC45*ZB!P89M=j%G7ToSqWdjg%c* zT*u&=RBj;%N?nwead!ifue9&RKH+O(1x9MmxHkvZ?@X76bQ6QzHu{Sb*in=fqMM=D zbir&8o??OoKhaXv(IdExf{=&~j+SZW{>`^B&*|4h24K%xyKIe|ujHD($$~Iy+L3DH| zyL-y@9|zK`R3>_$bqwCi>o_i&%kG?vzXmXe%tO{xgqz@w9 z%0!f)b)G>OKNDcCBN@h7b@;l5-5}1c=OyEV9^Ctb^)f_bLsKBSTZ!N7e7)1(`T93e zMl2ucvI*fk-y=yzjx&hpHHE?|J$C`oOA(>0PYThM&9HPI&bkSIJ?83P2D4}M?Rw>V z-BMzVfkp01LAn{Wp>yBVM3L7gc9>_5bM9pH|Ge-&zIoaC`D%uJk5!d-oiO|2Pyay2 zpT1YgNp;KXMyS8%>;K{VJL}}?O(le1TzyQ*+1w1l*&x9+X?IQUp4(bkC7P7O%A!hV ztd=ZWi{E65cd=PnxVsmuR_@;wUY_S$8`+A#N1zGI-TMbf5$r7SbvGIgA@=}AlPW8A zTrxbyZu24N)JS(Q8kG~vu|tscl9Abqj|jdA*CQv=_SC`iN=;}U_}GIqyjyD&>BK3= zlmLabZ`=AblO{UQRj2$!(&s2CoyG~1Z6e^()pn@x$}=ZG=6bTkQc@tS8{kd&jMhmt z0ZO4X!XVP{1i8(POrf3I&-}Dor?qINY z=tTeX>#uiqc0MNvZxPFf^Tkba)LdfVnb?lg#p-3Z?WH2q85cYVVSN%(Jr|1a>l^%A zfbpfEy+GftOx$D2U9G&At`cMCKA7^1@Q1%P!rVDOccKUg{{9;}!p0I?;K51g7?1`| z=k|A{%zYAOKb6;iktffqYWPop+{>d()}B;O>fKXOg4Yvk@#SLt^<{mta$#xZ!%QnV z)8uF_?=I>0{t3G>KE>#A61ywGd;U`VwBCJvx%JEhQFWG1De-FUoa4ER;FB4_n-IGJ z@b;&RD(UEyHSwlo*hHBO%nA;-4hN9~8C=O4a-(5k6q|)g+gMD%hhr?oLlu#}1UlOa zBsEA9p+_c+3VSw0xAz2*=hRIFL=s-Af&9V&-buoM9CNp%>joJ?vPl>miec^{5mpI| zH*+k^1TpjH2wvI z-Gtwt!_xhv6(%FpuF>fL&kaXmmI1oEnU1Z#6cT|cZQ)OgCu?n3){*)3+93aWdL`&@ zWK?;xY#_N(-=1)j+?HI3@9(6}t!u%=qVCL#Lo1B2>P|ljw!fi3g%3fu@3#+e&hT2YCEDOwMpqH$zgkE!t(`tG zZ{Ek*5yJCW4hlmhlxPl{S#vmK>BVCEp@$_*0c!uT@VyGP|JJ9H>$B~-`u5q)WMs)z zUE!`=fr}j5XUv)Jb~DBF`~3Xwn{SerVBbqNZ%!-+v|GKm&i@3O9lSIB3eS^>zW?ej zWODwKvR_=h85icf`Ls5ZMgHzmGkJCoz5BYBB>1+vT-Os#Y8?zq8izMFt*lbK>y^Wc z!UVZke(O_6-jjhQYXx|hXSn^<#S2WliFTi#S2?h=(9LQIk1Ojtl{RSisH}%anu)<= zm;{3$lEKK)qacH1!pN?Q5R=r@4v*|Ci%to*BciRqKSRC=jAew7Z5BfWcG_VrAyS=n z{S+-_i7io{;If+poElR}SicEbQz*cRCK zo&Eo?w0(7w?9#Vc*cpZ2Jzxn=rwnhiX1EsQqfvX>zn)pvmRsKRw$&S&iL}A>Aj2c$WY^i`<I;erAahPz%aT}wNeAfRTq zw@r^tZP-X+%aU39X){Y=4<;3&(5j0<;mnUt>0NVTie<%EyFr&dlDkE_B|h`FTRw^y z=-xvQ*22&Oc+-2k*%WvQpt^!y8MInnKe0mOBxWLV&_@IcZ(FrJ$ui^QzmE@?M$RGE zQ|$Zfrk=!IBn2MSm6ECn=cZ)blR<&A(cG_zd=q+WsNd%q&^!Jn%)eW<_uhd<@>4#d zhn^EmJ4WQbxN77K>!TOXnVz2~Cm(6f zNbFHMo?L>YX5&d_%9F^LC2y`eqi>~#u^Ny~=KyEd0Y)c9k&c8j5IV~Ui!@@0p=HYO zEin#^S@2HbE1@qeDe}bTDxH+|2p&APAur>pTvuSxT`D5WP)od)*Agw95)#-A`*5Pz zt~+c#Z8nFN^!vTOhrp}Q)!3>b_73;A&U_)QzU#Gl-bn9Yil)srPF5-Z@wA!*9NcfA{j=;_ze{dhZ+fR`&Cg_vZynvmemF zw@99!giuj-0pFj3bWb-`&Oz>_n>mZhhU)>|)mr6c%_F!xj;cntFE=`@tVW1q;{6a& zf-4ieX9Vx9%eOC9hnbu>>=2|kr!jVTPat>UFEJ2aug&2D(Nm+KKQ!Hy2$x9gfO ze1YZn$S1T;P-V&HK$ZG!V#QfTh|2|&!b7Jeo*4#`c3XI^@=}?4u5D+wF#wA0@4L;W z%3mf)G}v|fZm)0khZ03O(ca_7d)=pd1JCtR2;Z1v`kCi`-Xo;n{%qT8ZF}48Zj=ps zNpWJ!(Vo_RvV(4UM(;4phr;SV+2M^Lc^ANjGt#4%iLjOWZ}^@c{kICc&&FLhQ%;ge zGfA!YhD+X!z!s}q4AcJ*y{8wB z6Yy=s69)rtuI>Fg7-}DzFY^p3AG14VlDfrlA0_NQqnZ6to>k6QD zf=JvmqOTfj$Ct_?yfVlocrJKJ&D=( z(Y5D0NoLF>MMB`Xz0<@@m7~e4n|YDks{z~`KQ~4v&rdqxzlY!a+c&=>0v_7mE$+p+ z;8`b7`zJ?dyMHQ05**LX_2)V}hcjgj_Wkape*ATw+FfM`F2e3-OXcom#W}NqCZ;NW zVotd%jcS8A-c@PM+U8IKwc6&~nX@$MIYJg4i4c@z7#EZuEB?GkhocsG6eL2wd2d9t(fHD4^t8|HrZ z_z%55c)fyPXBrOiJA&_izt!!w+?}2Xza*qi+8OIDo(Hwvwtbx|kD;4RDc0XNWZ$d> z*>xHFY?6JC>2{rJSA~;=(0`dKzqz?GZ2M+HELj`8XDorQ5B}Up!sHusBy*&bi*aD! zn~RI@5?$H8OZdk1e@)a+wd+^2?-!li>g7Frptn4D@og=*``Z<*3#HtByF~7OTNURl z7EQ|LoQWL4v4vvJW#iaAws;o?kXM`L-bXcu_bQX%OpxF|J$tsYtMY_Bg6HQ>V^EYX z%sql4&7^bMDLN_(47b^7QaZcwA>#P%$kBoBLg&sR;@)yJrrm~yO9JnaR3^QfD=L!! zB%C0boh7kBZaW>x(FhYrrSH&YV@H{d%ABO<76)9^any>7QU+H>dxJx$C%#Ofm`J`$ zVq+(ia2-|edWfAILf3f24iYU@h}1zyFfKfRDt!5p@SHe$Kizdg+iSUqm?8o_Yy!Hw zOI!VR0?$S1z7Q%3A)5Cx#lcXTO$TNV8b615C$G4VmE2dAmh z(w7`K1ty-RN^-nO3?7e>Va_>HZc5Aj`e zyHCyjr9@4Rj(Be2@3fxmJR$B+cY!T%`)RWY`}f^YA#na;kl{kbO^B|LUQDtd3M$H)n-VQn2lVtD6r1?5FrS-RF4;)9*&1{{9QP zes_1B(dBJN(X)I}Tz>jqb#4pLUZ-aG*|Ic~`J>9~GQWE~t2CNPxfVYun=F`BmOJs6 z8=Y2eZA}#Y0jC3@2$0JhRt#gLHA%>RoQ8D=7RS`9M#xqQpCS9@xBXE zd!&O7)?R#ADEurs)pWyHH^DkQ6ZOQFnIG9wr;@pNp4=TqbR(n?pf?v#BF==rk5Rh- z=(gE>?ZzIY>jXRSbO+f@A%G{Au@0(8#aN95#I~?1>81VH)eic|glM@$q!4j30jq_{ITgVx0DS4OfAu^GzlneM zJA&}v{f^)pTY%OLGph;pY(UXD6a<#XG7sqd&zer6VG9eeDr+G zz84qftZ)dH>D{;U0!=1X;!DlsdTLU+B1!Oa(~>tU-XH8VIl8~WdzyH!Y4G0KKR8*V z?hJ-h(C(931nd;=Hi%tCQ3Vs|-7(-@N!dEE(=>?aTHV2pyW<4(R*N!0h<5;y#5S__ zodUN;x+{9dctmLycwBf09bfVMGDf_KBm%8eTgS%IO&r~_!YFEc(rDXAbz>Ra;?4yC zHOO&`c($KmpGQVM@H{m`PYYF-KAj${Fk$Bo3G{nob2j`_{BGqK`g~KLMcX4_5(s);hImPQwva^ zJW0Icya&a*=j{Qrv!=+P@OYf_o%aw^%b|l7g#IuL=xmZ%7M&F$>H1>Z`ny5vxg>iY z&91ZW$~iJNZ5xM41==-fyC}W6sRoQUXCDCI_dFn-y!>7KO~=mlxnpH_@9(V9yNj|- zrvz{l(9J9G2PkUz^NW+@j!5?RR;MgF+sE}U=z8@9mgz?at72cD@#m>IkPeXV4q0tzdyKR2Yf}qB_f!|p)VnrME@K~+nET>u&6%k6wW$~%4xJLmY zQ!&R$;SJwOE^IgHfqBfqQ?P3j2X=jpS_I`LmQJw^ZzYV;dK9O=&xx){h-LN`-7OPC zmmre9ZToF{j2aGi`b?3z{>+ksNv|uDmoGyb5wVeTI5;1iJ0povruUCs!fqkDhuv<} z_Du+(Y_~kw+IiykU7hy(E^8;=uywpmunnxo$EG+w))|&Bg%MgT53|bSc9)(D$tDU3 z0G`*wF>D^YMdWw*GECeNT#{0`Azo4lx92s5_4feTtL5y8Xp*{hq-5S@>^9dX6ou~f zY?8uEV#+3qe)qEvW8e2Wo+k+}%Et)m&hlvYE>rJM_KPO?>iudQ8+dh+ytfiN5840i zSe3+0*Ta}(2<*9d-1C+U*;`yQs}E>+YFE z%~?R09iR$cJ9;!>GNG4!S|GTj$S+}o2=Lx4QOYEdnQ(J#*dV$)&Mh$T*i8k}L_~yw z8>ErgK6l)pgp$JvmF^CCO`h*fL>bNvrS~Lpa!nXakeTOQ5nCSD4NDWgP2f!onC>Ck zQQH|fXw-@J1W;5AqeJ9QAt4UeIw0bL-rJtFv-4zUX9p21QVG9%c-SSxF3_9a>3kJ6 zg>HABw%f<}0T%eRE0i5|_cHoT6qh2q$DR_0+0&=TCNS0t--k#(%;~psdp-KKkcfir zWb0QcSNNOybnRjW^u4TAh@pn9sEIoi{lV9Brz(0U?v%38P z(#h}sY zxLs$VvbIyXQ0-m<-EWtrnY=9rmE(o@x7f@vx=CFvxn2=yvQgEf;N9aEhF3=)<`aA? z_4i+V!EgBBns1@C{lez%U^U7&ZP2Hu^zTW|uoI}P1o=XOcEZ4)GDmp;KF zGcXwVc5oU&J_%%0w{|0`8-{PXp4;6OHfR9Si5pAlOBahYQe*^(Xr;8c4xTPtffIu# zdt6RNhZZmawpwY+L!~@ghGP-kviUAT$u$>sVoLx4Yo<*^UMGNw3daHlB#~9{=`_ zzy0mw!>5Gd8JF-x+0(Wa_C>qdeu~w2x*Hx7COLt5&r^KKz3$%Lqu)PmHjn9-dr8QR zxn|GZ>0vI4#!dWo_~KUv-}go8RTO(p*x%V?iR9~=qFs^gazzpwk`T4W7LqaDHuyaU zh3^aAA8`cDvMyX6kp2Swd#d2b}t9-4bLh|-uVKf$&AELUncOq#>Ywcz(?Nycft_uI!2r)h%~ds_G1 zJtyktNzXgZt=K|DAh6qUR5BVV-vR%2_6Cq?GU*Zm?^yjF@#oLIh=~4B_=kIgLsOoH zVtVlOzGZC_DL45iUf=2;x4qExHw=gQ@$nEM`S1DdnEovxmUrm20MHtWPSKxc(A)Zj zEg>HP)^ig_&L%1LeD*zAB3b9!XUwT9nq4T{RUvR`-M*<07(WESuRa#J3;6DY*wyJc zjXNY~-eu?Kd2&)IC3ADSiGBYxM(;+YaPJ4|tMYp1edpkIzF0C59(Y?X7@kABSGi0| z=w4JbJjZ7;S$DRc;Jwjd17FIK$RY<} zCPb^6tTo~s>S(!E{(@#8~ZXu^8>QF)U0VbON`Zbr~c zPfY9_L`f%F(fJ`k7cnt#Oery@eB$o>2GWM>NeJcwO3jdvJL*0L36Bt<<%zb5t&&*$ zk;m|WM~gPX@OS_ zD}%lJr?1Y{`%Y~>d1C3^FW3)03_I@@Xx$5p-Sf8L4WchryDQATT@c^>vJkjLU(c%!n`Fi)(*0XmnRv1l8?g0mQ z*V^RggZB*U22z_aDvTZj8I(=K2=68iZr^1o!DA|IUAatRTLxUJ!<}c{u5Cw>>lWf9 z;lfJ6BTEgI9b;>rlciE(B1$@U*dy)b z9-Rn?gZo+5B*^BLVsF^|{nH`5C|*jBN?WN%KlqMo-Fb^9w7|rP7bE1=i|Kbpd2vL5 zEkx9gxJV~*qEml|AX|Dn?vA@n^ty++<&aJvP|lwo9(E5;3BdpO+sA|MY4k8kfX8@_I-12%k>Hs`)tkz zO4=(I?CBo`B?|6$bA$15MuUzgU?f$a2YGz}qJmVmvE4uS7$0$ah`L?Ycsop z1F`RUsc=*2sf=(P`$6iFMU;K-P-H}r=^mL-((nIY~YkygwCizbO=L2623O(ixo`e0O37{f+PT*T{2)?VIl0Ihk^H z?>}z@<@L`d?IjDf?zw9@x6c-2nT#ERw@X3h*PFF9?8C6d6?#rzW3*NJ9@f!^i zoHlr`f!){Fmv5iFJz2R{*#5SWlx0CFU-J)>17=^g~yLQ7ub;T0Q#c*&tt zaj(~RBf4jddP*HdUCkzwOg;YUvFQ3yB(a_Ew{0u&+~#md(5*1m#JsW9(jv>;K28@o z8r~mu_YS+hf`cUMcAsXh+s$JMXNt%ex-(yL8S!ACjT-Il$fmcw-P&#+vdI0k+jjeX z?`gZsV=442jI^VnF!|Z3<8zuxv)OJ6OBwX;8MOp(%>z|>ZQ;2+2;W}MpmnbhPI!We zJAY)0<0mK9lN~klIQA_2o^%_q5#JgkI%B8f#K`rs_GzX9c^5@(e>)Rik^rb} z(IyPegy3y;mAte>w=JS>*KcP8-Wrr#LHBmD08&k_(A!%r zEapfQ$hYC`wp^7*##Yd{(@v0&G`uQKBhn+$YKb&=?C(YqPW zd$0^z;rrrC&lm1A`<{U7&7k&pWI0Qp&+f^-ZFo%a2rG5 z6dHdJcz6*zzLmVFkNHLKql#x-2&$cwRy=f{(hzrC<4n2!MkTI6ziLDQ_u5Nbo z98_ETsBIUhu;fj6j5O`UU>@N);cWzZog?TKZ$sk9zVFJ@Y=maa$R~hAR-rx8N@?`W zqHbeiq@^aYL(T2zblu_q^j{ zWp*vwK3x@MdB)7!9%Y(-AKAb+1mTY#(+NXz$hQfrdT%kQ24u6uO>RW-vu(8w>r(P-S)b!j*JU`Z|WJ_z-v?KUL)KK5c!?} zz5&i{k^&8K8|q!Txi3CFf?v$$bsO*=zunG@4qS-bw@YdFGP!%ICVm~C$%7@DY`(Sf z9tQ78y&HeE|Lfh!Nn?#flfm>({7m!09B-gqswRGr>WGJxMivQz*xU%Cprb3bn?tl^ zsz(W;VpDF6#~vlelh`gtzH*dz&J#*Ef%67-KpjVc?sj!HwzO}p^6xLpO5zT_RxR^)-2mXwY%MR_b`h5 zLrHXA5Z%8Ux_M4do~R6+ILOCBN|x&noCwib_K5y~1IKz97VwIb$Z?bNy|+Q%i96fi z`TRFX@QMK`T-q5t-UW6ehE{HiRs_T)RpW>R$YA{L^dRw>2+PuCWtQO>_XB$Fn&K1*m`hP*#T!E zd42Fc`{eTWRb3#ts*(b$tKO9SyF~6cpAfZYT5_J1eG3)ko}}H^245EjnJibk7lc?7~eg^ zxhvv5;^iD-(^;T9QNth0+C;7$AMve@Ha(TRJp)5G5I&Y*+6bFs^EH;>v0h16+9QOG zz=fi)4UgO^JM*1AM@C(h1E^!dK1HA{VJCqZ(9M$^VI~%)orJeih00C6+={)HOhWj& z@wi>7VEiycOJ8iaT#vpK8JZ}a!^6EthvIM`G9lYAVrPTh^WEJ+OL#*)R7v(Iv0}orPnNdLheAg&Q%s&%e#!AGR<8hf_`dJKzRwn!K<2tW=1SIQGhBOueb@XT z6Nc)wCy9LJ0O`Lx^goh`=gI_<6}z)r`%UN3hDUT!@=`vNqRqbhFX z0aIYt_IDf2z7O0XI*=$t|^uO`J4!Q$I_6Xy63mNu0+CA*6JCkmE!tBIU8h!VXN}3A%w@ zB>H8i0%@(5!UPd|3g=C6Y!&je2{T7waysza1imtEa0a{XvFU{E-q^I{JGfq%gMtt1*Qd{; z))Q9ioBOlxvEnfmG*W$0WJXo0b|GXR)V$eKe!q%ppG`Ej&rTLU0=zeg+|%s)q7+L? z#{Fhf;62?6U*E}@y9>X6lDvN(zJG6>?9VlsRGj;EY2n#K_ri=v@Oq65*v+XXg~Pir z@=a(aM-L&IEUT=X#%{c9IrzDrTrxk@1XaVQC$+}2Mq_@ONqtIbzK{mQ(=yf4h$yB8#hAJVd4ep9S!5HLo3~(CnaTjc`_PFo|0p)wZ$6jPx zPds_(OZw@EBJqiI{}0jjVeg|;is#8J%b}WBiJ{?1?)HieoLH+%nKp;Q~pMD@Z{(eU+(p7_mnFN}>Quf~n>8#f6SPLr*b2Jg!m?B06&?0IL^tdiqQPEH#Q zr%_*rFOYm{pK{XNjY|r_n_xI)V(n*G*MXB8a6W?CJ+2xa@tx!;!Cqjy(k{dYMrE1G zRKrkh3l+=maF|6fo}xWG~o7K@NLcXSA+VVV(NCdS?Fb~9d;2chK_ zcu#sZQC;XYNW_*|*AxC{hg#lAI6Nfk7)JDaO4-`!!%7`v`2~^;;rfUpYx#E+Xs%be zh(v3<{eSN55qjS-_ijgRdRCZ622ilS`s3raf!toK2)gNJLG;@P`~K2JmN<|%OblC2 z+$Wx`cnPOieuumb5yUeP9kO=99(LA7cc%@kN~3q-4_qvFml=XZ4AmUgU0bPK1>T#@qbeg! zihajdo1Ru4VQ*)(!Fwjqiky|$#2+pj^+H^q;4mK-IOrL@g+C}REVpY*dujsL|NAMjP_)bvho`f%z zowk0nvx9Y=ILy74N8o+9x3?$F?}o@$9A2Jx+rQcQywz?KdZ($NU!T~!()vzG4m%k} z|M=(;_S~%8mF;#Wd`^!A18@6EifuDPwV;2~o1H#+(yQpRk+?mUNSKYo7x*QIQ*q39 zZ+x{GSQ^xZ{lqE*P%LZGfqnA{*!S5~)A~d<)HMI*uPX6+svNT7*{q0Ev8#l_EX~ksDGW^)tP4D}iT;9=@uIpBzW`N<-zlnVt0dgb6D~o z*K8~vRO*`IZ9eOuT8PI+yQy1<0t_TaRb5W8$isIaVylFVaxD^ObF4FTAM#Mgt@cEUQBR5wQyO3AozV=z({ITG@S=cU@a4yD%z|s+TH4f{T)?qq|( z`6i7=nhY^`Jayev&}~HEM@bL~ zpRFR&*S1dXG6XpdIR+dnngm;}@G$%IqycZG{LflS^(~L+FGx2ki(Rf+h_Z-yJvhIJ zgq=xTLF~G3S<>xW{hhCOcAg+UM0E#;lA9zg^v%;rB6h$28aG>3_&M?We!m}vTzgOV z!HGdU>h3-2o&vL@GPs1!71fvY4`r#_Vh8%jhJXS&q?}KNJrpxQ3+WYONQf}_$4JlY zUc&p`LrohJPFx22Ua@^y#DItQVBfV3#_?8T<;R}reXJ+=)gxA??buT?c4g%&5~6Nu zy}rwLAwLy>Zx*=0wrf(!RpBow%WyU-a?cMAtUgS=%~ee1B~U$kwvW=C^%RpycQnv6Rz3DIdZ2x&<(Q5oj6>2gV z4CWdH8`GLeMYzX`iR07TNb7)wYg{7(KZtgn434^DRVQYtgc$WHfi@v=pv+EAUDWT=}Vaog~;;E6{;V{mKB@!VYCp_ z7ht3)S=dHnJlm~(879`SoAz8!W_#VN`}pte7$&q2loNyJ6o$?(Fdq zQ|sn3DUUdCf!!{z!vlZ6v@FknvInJv&Iez9$$r5xKX;4!A~%c2oVX`qtBjTKJ!|3< znR~C#rj+XOj?4t9p5ojEv3`A4d9bTdHzQ#s`_scq)eiTCm(sts%2mEisA z=mCb6^{sgP?ENg~|Gd?Ur9P8_b_2XGUz{wqnw*UHb0%1KV{QK316qWU9hln~R>qPW<4=V#e5)+dCTl8% zpPQa(*nQOfJyBoPJ=NI!alOb_sUi}eAZ?`Ahxyw=B@Usf6>Z|D_6WQ{5H>l%lCUE|MZwMv86Q_6OA4V$kSvu_S=rWe#} zX;25#P7&i4DYj`2u4Y8+jRN>X97Q}}wSQCYPF@un$(s!`?kUo3F7tfd3yN~es~3e( z@#S`<*gfqs!A5+2tMYP*&*VXB;wJ=eh$dsLn_-hHCZVddGq)6Z4}ny}a8 z`f~r>a>d((csq@`th+NOg{n&LCej@Rj^h)2LvzrbAPdp}!gb)EMnR-&{qR_ubR1&O ziS0zTK7~&(i$<=?(@G-QQu_qZh@!Fyvs0A>8Wt0eQ%kV=E=AVNp5E!ZIQE3EA<0OW zhlp6Ow_+g)(J%;fIW5}*muIHy5ouO;nb;QF+n==vbhEwP@11@R(CiUk@4Gr0?23Mm zo9GC>o9&@O*QHDM5Lq0CeGW_!7Nin-kN)`87yo(+D+|)BdVTDuL;5gFGj1;*7Fg{= z=Z2NMDOf7+(FZ`k7Ot^t19CmHnA0mZ;$0I-CAsMgAZ)S)fygG;q}MA^oJ}hXm(<@8#C>c$bMID-vOeC5srH;4*ZRG2b9t41I zLHMf(v9*G0&<2SOGA%M?XMwnr^hmeWN^>_SI7jgf7Hy!B$3n+C^;!axNuv9nmCzjt zz7^dS8}^u2vgDkh2@TS+D+s&=5p5#U{lV@zLI6WI@{vFVxy2(K_Ie=QLzS5=8hW0L zo(64jn|_mp6EXBy zFh|z1%2FHDS0#@<~{-^swg~ zYH8JZ^;CjLwXj&9G0v_y&iJs;Ca84<%7vg((=2YLOAMA(ihVSIUp*w-o{k4Bzj#w+ z1&)m+536*qu3D%iP~9#=?zd~3Os;EfXFt|9;wQ}}TT7dUw;sYHSj16nKGNi9EO>9# z4c;%5y1OF|nxDK~w3`FHoBq6)|FpjtyPc`F%EpY*WQK6lRoZD}_!`-*woyg`m;(uP zi9Gw7z1_i`j>avOsSHL6W5$eAO#*$FWvr?Ih|}1Y33zvmbXaUbX2iK2djw8R?{Nzi zl8KwkA>FKa(r%$mx_~NTw6sHY13Kln= z?*8#{VZ(`iQ?Fp3(?GK!@P07duCwj>{>@e0!@cqG$Z-%-ArsNPwcf*dW86mXF1>had+3YIPkR}_xnl`gu97UVH-`tIhP1S z;-I%MgbjNrVEf29-5W@o1gBBUN^C4&A|M4}RJh)Cb_WAL#q&bAfnXvsl<(vrBR6&` zrB0HUq0+@FWwGYYX9ZQbP25sB!AXN7w!Gphi<4nJb92ZdN>R)J?>BmN0P7)_6_@+- zDP97!q%~(VX3l_dEQU-o?8?!1Q-kZ9!Xr{=*z+ca8wK!(JSus6>;)|IrrwlN$t-HW zc`(*}QQyd!n;bah>t4#cmyzz;O65$3;N|t@+=cknO~aR)@2oU^!;=}_n+`OYm*D*) z{}nH1^zPDVg1;+)_s`3_b4uA{Vp!QI<4k6#cc2?tH?)(C_;Z?JE8c8ZrZ$#q z7|H7)f^lgU6cUT}s>iU@O?xGJDKhLeNvTJ}}9t=Ns7pb?qCo6a@VS&8mP9^SboZFRU8>s7fCS9;(-|Pphw&cf$$@Ydx z-Mk8@GErPF#r#(I*4YG+HgDqz+2^25Gx$Bty=AlUUw-elZMN3X4b}yGqD$RQev?o?7r%WcSm>A8r765y_Y&B=| zHSrUA_e2WpCKoHmdiUZ4@9Ix6h28uYzP$XWizVxo1m4ccg7EIiZHDgDNZ$x=BIqWFOcjTQNUYru{dT#w($_Er##l@A zU6rPUg+qm=N14LvEtr8O>JI8jqV2#-m5)svBHgj&I)w74j$fET=v77LhGFaylkaKzv3RoB;uP9M zBFfdJ?+Kw@wny5@NJWt(0*(Tl-VlvE@Tl}Xv;hbB@bOJ1qqZEx7%*fXU2ZN z_n`}pZg%R;=KFh4Zm(yA6cYeT%>R9_n0d!w&-BztB-n1uUVvx@A64zuBzR{cJYAW8pras2bruk8V{Vxdiw+R1XOC(t@ky)-@CN(VL zLxLbDJ;~TjxGg?Gvzg?*oj5*Kex&0p8xr&l1rcv{Dv^F>u5F7Q5wSC zO(&Do)LKecxxm^m(F12N5L$10Eg?PC66lm~ce}3Tik^Z&PwGTzdO)sZOYzcWqy^&t z5&~#shbTovoHy-xkJH6@B6FNf!wlj=;;}GL_2dw(u)~)0`fi^mhJCySkVCDkJT?_( zkVSldyM@EEN(6@W(+Uaez0xRB%p!R}>AB_BB!A?rSdZN&Ov>Q_f6wvXbOXKM@QRxG zVxUQ%J)|f`2-_O_tH%){V;)<$`fjG`9_M=SHVxiqQ;iD00B9FxlBv?Ni;4Y77P=os z;a-&&I4yL~hwfqleu>3o^_+5{+FkYK%*fqamrKBVYwJOXx2Xr7(Yuc}xL7&SHaw4g zUryF9l+gW_J>J**Kc6fI?}n*qm|3l?>D_+WmQ$?5M?9&FGKsHZ-!CcosSYF}y(f}P zVyF$acH`XT*jE{+KE|z%hRZu0bR*Lv%z?0}Jvh`Z=fhfwMnSvEZTpUX$Z009N{@R1 zw+TzLIMrRheTvK|x-m>7bPO9hud9$Af}bnx%o*&SJI>x9@;q0XoWGQiRK$dhQsiM0 z0lMkc0IcG?ERXUv7t5I#KK2r&WSmRq@bI+h5f^ur7N|JN!9LGYcoC_t1IzzA_ z`tD-o5@tQNji9Z~vx;FNF!xwA#c@lxhAz7%%mmVOtH%PjVb1R@>{zlnkQH*{3?$h0 zj>WJ{gzcI1D%1VoxyQp}&*Yu3a)KxFM4L{L?W`>XA^F6Bv4{|vmXjAE_X7j?FG{y- z2_?0uWTl}PT%Vxc8#b0KAl-|E?z!ER<&<){$>er5bk7mHOSyYuF=yGRa>^oj`5^x8 znHbmyNbp{}DZcP`^B5pf6j*gxR)X%5aY;}Oo+Fq7E2Sp<7;B@N+z}< z&g-Le$Blb^H%&O_Po^o+*lrfMeW_ci723dWZO4R~Y0Ha&@iKDGcL($f4jw=5dRE+G z@=ZYagaF%$y-0+vrG$dK(JHeIUCc7+PFST!j$lA!KRP`;?MCgkP%6^hZr06)?$A3v zCR!}o?WV{TZ&7+Cx|M6*c{7q=*l%ysQDk!)vTPj_K_{Z^7S8U_8u~1edsY#1;ubuRzd!ifcMoe3fNQb z?W>EKspM6C)&1%LW|9kJ?!~-&slTLx^xNAdEoVz|Os1lxX2JWi7G-k1G`o8$y!!$4 z?lREi)#jnQmPS=$+()a+7Ycv3ahfb!(5a*P6z!e_Z+jfzZ5J6-e$g?k8N)|BdvyFj zD_twDG`w5INl}WXW#U5fc4cOdWU7XCHW(@5)>$kx949ubB1F(rtV4=C^uf!0yRX1+|0+~_cpDdD_qr7gFQ zLU#`xJZ*`mBizg~`L(MN(#`OVE(M#Xl30!Jz4zLF_ptle>FT?oqE`i{QAP|p>K-17 z)^OMoVkn4rqgY1~B}dXY*HMOF_FAoN><4YTW$;MID?i39(knWKEzhEpfM*rnZZpSx zZ}m#hF4ghS;5Xs4TZk;IkVD%(26-2Z-fp?4!)nWW9~MUNbi`U&^GATcAb|fGAiHt_ zj@{cAS5s`eSh{)h5UV$A+h-TNJO3NT^YO!>^@q}yK8zk{*V{%p0BRZY0N9lnIhdIyUYwMi*wAUh;W-{ zmm|XTNCy+RZA{zjBTQ}AwS!dI1kZjZZ8)7_Jt1P7?x} zWBqcNWy9tOB6iZ*n~oM{ zimp)_6c#f9-Y6s%{qRd|Qo6BtY2~41BY8IW^5f&4*NmcQsPzy&a5svj-#qT_?d^4& zLL9>!Zh9549mJ`I#M_N_0;24dF@Pb`T|>9+9~T<95lN7!#Q`NA8&1Y!M>d38y)rD2 z!>C+vY!=ab)%gI0#2&PIuy>D@aXiJB|NipJVvUDSNJPp#>sJ8YzXrITM(x^FQ||2& zu&l@=54xHb(u;0jQCa1iye_dP4nTy@aHgg^ziE6@Va`fsU z61>NOCPznGM+?Dwa~+bm9X6;wp}}QImbK7q;mBg-&?tMZpT9#W)2m}R*O)0gurbg>b8h7 zExKLA@S*Xn4}YH`0-p+#=#<%s>qG?d8c9{MrPRpSTeR;ueuSSK9I{_UrY(g9%$Dap z@l-o2U=@j~ZnK>kw55+NX(jaQ;ZOw$rnf&3pdO11Me#Csm1iZnN8sKIRr9!+(Q^)w z0*Fn{96iViv9r+8LrdAv!^3Q^?d^Cbg~XgTq-b}Mc~yWj8@*dX8u7ZYaEF#_mU7C- zSd&r(=>Gq?d)uEjvV3cF)0)zBIJIMAZSSFE$lg>vs+dk@?0Y*^ZlEWV$ znC2!kg~;Js#250#YUhmZzkYw~w|Cj)7r^wHkn}NW0tO68)T@@)UN5pzQKVzjTu`OP z1BJacz&sywx@jIh>hvCR`ab99#PYu?`~L9FfVZ#OUIFcTm+J@LG4*k!SnA`GA5pTp zT~Y3(k(~SOB{k%}hjnkKbrVFNOyB);fBy1ry7TLbzk9X4``H6sR9`qx!$_gM$(aq8GM7KcqI@%%07+)!M7D&eRn8Zt!CR2V9KFG z&%$Eo80M6THEG)G?>2$cv6j{5SivWcO-Vm|)K|{XM_<_>eANRUTQg`VAvA_9P)?I6 z0XHn?#8Z+f(fgm{}xpc|qGrB~X~@>#b#6Hmy#zb&4;;Iaogkg$7aa#s!AM;nZRcNR}=>FQqV?7nXt{^}O>9E;mOZG5$4?q1^G&mQL8U)UqK9ISjA zgZKOQZypj&)_C{a-;KY&o135hesZ73dy{6eI=rwm_X?uynw=*od@VWp-Z>3XBZw(= zkZ?Z0tRGkA^j?-vCOn%nv9R&wSr(Oadr>w@3s;BDGg+P*_(Jl)#-rdY?rS6z4bkgJ z8yy*0nyIz1wu)^jB0~}<7hu?gu&1X%V%xiDiN#@~()80z3@3=r2)O}Rja|ZBV#Y>_ z7F`l#bGO-YQTQQ|R<0%)X25QdpC@^^cic;1=7SPWSUR0fC#pG_WavB@7DBZfjln>D zH=tW%S2O6EaTB9!YOF2m8VUV2o!BaX(`>hQcbg8ot8#7-fBNH9-arT(9Kw-B%elC# z0W@bn@v4W{xA_T!@_xapZcxk=#x$}0qgm{pIk$JhUs32riT-k}ojtLed@1(*Ei&v{ z+J>PTsJzU+FBc!LLG{P^(d5S`gzQzZaIcfqpF+x0pPyBvwOv2a{Vv* z|8a4%XD^>!ZPZL2BHdrU(Zn59RrSRs}Pj|<2fZS`~ zjknincM9bsDpAv2hEXSqqY$kmFmq=?8HOpW-T-wIuNVaR=u+Z8GB3GWT-NN=82Y3O!C^+%g>%l|l;|XEHV+jO zb|Un+a82lQO{ZfCEr)~M!EW=r!{)9=Q8*KCHVKZ$1jju1kYl!Ig2ol1&Wf-byxfcz z@fzqq^d(Hh{T+$)tHYHCg>@752!g4%iaGTL-5${6xvd?idv}rQ5hY!C=$S*?`sWLL zr$6V6`-JT!qChT)Pml6%1@CW9%)X-oZ~@hq^=05CDSOqv{qgci!Fvh1m)9uQV0#;- zdy7QQooe^>0=O5koZEjLobe5VJ7@9B+vQ-+gJmX9U=XbFZdWAu=KU8hG+EZW?>3rj z;@t}*e|7oNbL*2;YYD#_df?t!=G_NN!JLTK&2|X6Q$p#8Sa)<5bkYNON`g*#W;myV zBTKo6!e;>OJa^;64!%vs@NL};WH7-YWSjL5G^uA`kKQBYYb|wk8{mG?Jk)9O7GPOjurZqf#(ZH<2kk2^nq=~9Q%?xE#nPx)_Q-`_G~FP%v)v+ue{Qn^Sf zcz?p!%~rH~d64q$_R#&HUUIXZ$k|-|x{|0Qs<`ycZl7&=Qn}vVef7ol?q~C0<(tKZ z&YLf55`6RQp2^Bh9kAE8uRi^R+uu)iPMA#Jb6i>5TySr%({5llR&UZy`tIE+*3pTB z0@BZTWwONNLKugs>F^@_oOdH1LzqqMoJh4rn+YMWi6?ZIo=gy99G88m%k;R^M7;AU zQan<}=_zm$vkqwh*9k0vxj}zOs>gYbCMsg9G6VSrk+9H7}$;<<1F3iRdS6yJ^E*vh{>SM;;BWQ(o{5PHfWkE2c& z#pzBNX&kx2H{C)5i5@83@4x7mR`H~bYNEqC(m9LHMP&#vde=17q6n4%7S9HJRI*?j zNTju#*Ojnt0tYvw4sRCpXOju^@qrq6W!!5j!lotClti%|8Tb1R0R6G&-MU>uRzL3+ zEaJ%D%)Wmgw-qNzy@up+>4fsbV(n%%=l=0)0r!%%WOGUP&4bW=^N`ei?>^-niwo7( zS^c)URQc?I-GwJIn$)s6U;MCgH5C8m4vXNk^`Uqcyni}l1~$96z^~+N-PFCn?%F*3 zPG>a}zf(E9qo_Qcqxoq`?;{^?f*29V4$$1BZ#F(OONU5P{za&W2|!%_Qu@{DPCFKzSLq8X1>p>$(BZs3OZ3hy3K1mC-UZ-FzE zT}+#4S(*Ei?u?#V&{uQ!lrwQ-{89j0MHQO&GiTbWMR_;NCg%z0KmH(vlg9ZH&`rdE zn0Fh>cT~7uSy2@d7QCm~WTl56;+)BR>k+>1-w|T_N|MVpC&?n~UKId-*icRK_4#%! zLU|`{-+e^64RkL_-FF{Tu1r+=fnnD`b?Y)EzS!jIVZr3-2G44RCeNO&0QMI>t97#&SA69nENp>sIu?e*iHwINt81e3s6 z#N?B#(4$-he#x{MYkq>)Y?eN>2z4g!ud2@3gaBl_O^|_ooY4@g$ z%0&m&_0`I4a}8CUc0bKg<(s+Q&4-osXwH{Bt6YHh9J}A#PrR?I5?JT&eif8|f{Ew9 z=;i?lAs+fYyZCF$uoj<z#MaqGLyq1A7(?5a@3N(OH`U& zMd&>gL!>Y{&?)kKI6Q0#OgF^lG#rJgEzvS!TC(6~sd6;x_mBH!qwJ69mRjMK5pXie zRy&lOaDy!I>eJGU)mZ5?e7Cp1w>K)|w2eLymbN8glgTc9!kC$Nvx#lC7k}yhh2Z;V zRGiG0$e8%@DnexvNfJL;R$2RI1x`do#nubqL>@e&_Xfe+6L0hn+`Kvorl#iQndS#eP7^dz9n>1U>&*LL5s1g_6qGxPxlJ(U zfR5?FPmP^n7pUYmL3;l)an_iVIT^4RpPci$WB}bHo1*p=)qfGvm3e^G;NZpH@qVuy zrNqREG`|bOxYz5aahh5_X@fJcfW)0dAubPw<&%NV^sd16Okh+N8#7F%&`vP4230-; zO!v~Ve0S<DwA5_7?}jfs(m1auK#_*~$^Vht`FjiS))@EFj&SC%<3 zX5y>O-L|{IL*1P=C-h>BZnhM#yHWl;ozCboA|3Pgp+_a=aT`v=CxtBLi)Nt9h#WQD zUa+qLOa@JbzQL;N8z15{>#_DaVsG&OeOxU8{P5LbyY4I57@$15Su35o`R|=kE~M_8 z+xr(6ZZ}m>v0_q-cgoQlIyoaJd>m!o51#l|4)9^)8O zaMz#^Ss{i*cr#ZT6&sspR?8?1^HhB8)!}#WjF_gX4x(p@BQJ6w-5bp4+i%fRAAtNStGSjjnn{ z%Z+0GE)|l>JW^xUt2vv?%X$sq#}74eu_65~U$oOw$Zab+aHa}ss zyPrMHQ2cwZcfYSDE4TD_JCESCFYvzk^QXDL`{a%q!Gontd}mqgK8WY1m2t?S_$)Yc zqh?vv8Q9?ku#^aR1oC}m&tRzI6ub<|KHVkbc!C85;4cP$+5IgoVRnpV_K7q$O{3C8 zVW`7MW~q)tOdNzJ>i1Gu1GR}^>;_}!5KU}`NkG_5Ao-mPaGW_%QEyktY{*0L{qOr4 zPXf|u5`?FzwL+%K(03$oV1$$)5I|)eYfGTMVvc7Kd0+Kk}%TJS0$?K@9JGw3s@a03Ll|y?SA3I-$8d#tqXJZl95~U<$@15&yy}E-wO@!?w14pd?m&F zYH`lj8ztR}argY3*msv5Ec64y5c5q-B%6(Y^98c?QmKuTl6A=b_|0+dqYdVg2W^2z zi=ytEt!VdcO)dN1BQSz+CE`0gw%FC3KK6_|#dG>A(g!5LiJ?uEmXZUP<}co-w?9$?B5 zTfsRpIT-K;8@8pURk zW+2{z{!8dK^GWBlg zDG$YGZrV{cr9*F>BAiprwqwh|#<{@hrzWh!y1`VJ1EmLp?+(>q4Eheicqn63Jc;3M zi@zF2fPdKCZMyLU#hS94w_#0!nXy8=QTo$MS3aU$!IXn&{xN3*`1$73l+F^a#&mh| z9DKem%wjf-k4W*rK*C$}1mQ)Z+YP;oYd{xrxF|eY6Ra0*9CN^(-wEKm%YP2X<-3Xa z#yIu@us_a|k*mhP54HNg#erm9*8Wg;Y=8XPQprZbeR;G5-Rs3A_apcHMco@la(=sD zQtuC3?x4C)?Y?@F8mi?I*rn|S2i8bo zhED^UH_UiMsY4^_@k98;JL%{+;|5qx;Ky;a7xqs}m#S1yTSSs)iLk=ryG@b=T~;xI zIxJ)pVGmP!Q_|-Wj+OmWx-j&@J~k^$R>}FsB5#i0D^{FJ3||s>_eXojCc*ZCz$86C zd}#>=iI$!xW8HVgLh$b9ch8Gy4*iAU+cbgl&8DyA=GhwU$hJ?-lttl(aB#<(cB2hLB)s3} zU8ePHY7sM0{ZaHlIp+(@Gv}|989(BnP~w|7hg@*%%N6#$Y#~|V(;t=wZa#cF7Vd2b z_eQDY{tV^Tm4S8SzFEj6_ml4ReM;POr^DoGX-;?ZQ00@vb1J>Ng48GI5q!UCePMgO z`p-I{j7*j*3C*B2@~2M(~~ohU?+NgSSKFq&|=Ytry&}i=O$JLtCbK`u!fVS>AO){?nhas2>(q=-!ad! z_!ucmmc5Z$XPiUyk;r&Cwt+n(UTg@)ht`UqEJOO9#ZVSQeVX?6_V+`7wy7~kS%#ay)?PWA{6H z8Zd16Mp^9bG@0^NM~Ouh!*NX3^W93L7Dd_^3nzg9;fZA<5HG5V5)f~pn`7Q0=CZ0; zw-R7%Qz<#GVqyAzkpPR!cB<*p#5nJJuL>k}qCWjG5Sr&xO9b%QIZmvbk3@a@6@TXz zYvRQ$!StH^y6}DJLpC3lqU&{Y$TIt`6Y~%28^B*3uD31cetQ@1zPB!LOXOY*E!?kl zU)Oxyx3x5-59nM~?!cue<+@~28)&S9_tn#3_p_%QJ#$jJ!|%JX`)b|bJ=eSWZ_pV{ zYLdxnGH3O;vVK^30HS>m9YkRmmMFxIF_{y1zRkqDrhDV9iF0;KdIK4jz-_@#@PSFd zXOw}=ITzv@vIE^OJI5&+PB4JbNTU*ly*LRZk3AB&25D+_>iSHkxeNL*d}Hs1d9=;X zK*EXnX30>cc!1N;WI(fNINIOeJ1%?SagQD&Ez2|vM?d`1BQDzS_e+B|G#h8cstL2E zd6M&}M3(NSz;2LkUD}~)e1H5sZtX_D=PV|>_*3lKF;Vp*hk<2rLMYk2Ej^d^mEFvv z6R~6m!EaKuwXbr;omL6hLgq3!?$roEs-oiT?oKt}Qdf6jxIj9RyRD=e!`9vJtAe4q zi&P~5KN(=2nb2D%=Uu05yKitIxFTFuay>-{`jph?q$NglAL^d=jmjv(DjZp%59MQc6n&w=HX@Gc^aqg4uov->)PZ3 zzq_)QbNlMgum1e$&#!LRtGl0$crW*Nf64irrPZ^03Qe9}Z3@ME=)U~)@?|A(&!uli z!#860a;Wma6~1B_{xnR(C=KJ%({5i`;(sUBj5kfkZ&xBaZnU(hrviG@Z`MrAgx<7R zgGZ|%#tN*FaldcF{a?bIXz^)!oZ^u3_}B_GO--aGus!RTc$A{pH4ZSb1M*G;Hz$&9 zC%TNS#5rjhM>#JuXc)x9aQ83@BS%mPw~5i0?INrMzCz}(fw>rEVVxF4_*`l zt#V@YZWzeo{F3*FBf5rQX$_par&~kTl~t2RE_ZjWoK9WL#?9YwwBCi_0fl<(BbH7^ zDF*H^vZ%ZyibZcnvYl-N8ip$hobfXPk*FCLd%L6$6z+meelBO}7ZybKoFnmL!fhn^ zkB>_n%g(yuyqk2-FV4F&(IooaZ>uUJ#Q5#6H^sc+%GH63b1r`IXQFO5^C{JlMO{=~ z9l48rf2hmaAJ!oI;}b8GJ3+MmX7*4)cb#On8s=d0v@0C5CPX=%HBm_Vth=uFt$Ki`q3K1s$Vpe zfWVU*6Yhn^({5vS?Ep2e+BE4g?5;v>tfZfX6P>0xu(@?kZdX}S`AR&OF50@1E=09p zQ+NiAybb1$y*llfx+{+=oQY(Xz%5d=Ii=$=I$o2(mb@1`MCBo&Z*hFw=NqwXU0G4E zXGs@@NSFO~smIF8;rs>eV#6)7^Ibme)HyO)`l0uInVAdG+EcXujl^mo6Dbwcc0Y2yB4Wj z!1zIh-8=P6JiQSg5ZewJwmO{U(lAPbSW~UBS5NaIv=}j!b;mFw$n|2+ZL! zvGiWRnu*QiSWa_6y!;)p^4!veAx~qZ(W5xa(R@vCBV}pgi12=5G=X;s-J8BtutOv# zI7Le!-F-$6-zqF}nTSmiQ9lhw>EXcOVnK9VeW&cT zw8}DPFVTB@qtF=Q{m|W;Eb?%F6WwC^$#}UTj>lu%{|7U$$h{Zron|J>N03CVp;oA| zD;t?Rw5!9+YJj2O=%bqz#*1;g#L{OS3%3OCyIx(KM=-4898(vZly^nnT!k_#($XD4 za(TCN4bq3E{ggN3`KKY8UU^Pj+>?J^PHj30E>)`%?J>0Dt|;Q)AKUp@)v?w|c0CZe z%Dz9;HSG$#YZA#u7vQ%ka4(76mn-w{E69Cs&+F0FI`<}}``#e@U0U}dOgTTFteZ_X zf%mV^UfOp&wX;8cN$)+4+`ZfZyJ$3d^CdNtMWM-W8mxq5@~Xn_$`*LCjM~-Ynb%Ir zgM(-%PKm)@$lY8_5-fh@nWNi)WG)aiofPj&*J*+SN1J1QAw!u7 zoE)*qp`BRZp&b)~PX(Oc5+4oX6lEeY;WV*l!sV#f@5SgSv9XSO?XU!T$5`~0m=_~# zF}OOQCtKtM>ICPEV01}H!&BnwS}09FGn%s%K^?kad!yrC*=YBBy?$u{{Sx)9aT*zg zl`=V%*qS7&ZP{fK^Ohwvd1F8G+kwU0FjjZuxbgj1?l$LxI8L_KZS5R^L%?pr?AR~d zxD2Fn!F6}?$Qt>4Gv2iXYCnBeIM^2oCy=fHmPgN=s)A!iJ@%u+h3Imp)GV1xDwY4x z%j7ezF~K1#pHz0cV!o%w1IDV#eyYMPWeRtI>DC(x9`O0Mq%Ldd%az(yUZ(ES-ps!1 zqX^ZW_8X*enZ$fc3$2ZvuIO(X-!J;Jp|D{cDWFEsOldMuraDEt;6GH7EGZQ!gaW7amDyagDP@*3&2kEfzlGEp=+R!&LCO_L}+1t_wrc+5AJx!NqwKCz#q`>Oz{uU%&4ok?(Pj@feM*V+ZC1L%9;wS}-ACG1gU)VBzd0+UY2s z=<=baamGNgFb2+asg@e9ST9$003w}m5tXwR^4BN>14-d_=(`Tpadhc~7P^cHcW6mS z-vVi$bt~nCehrw)C$GWH{ZP-vtZ;{;#cw;hyj(%-m5<)dzCSMf*!AwH58pb&-YPhG zxmH)QVTAI2p?fiDc676irTccZHSlhO$*S7DfH-__syq&oh)wdxbkE?{bX zd``aDIGga6yfJ41{2cM;{4D5124|BHyaC}-29_x|^b!=BoW)_9OB`b&a|s_xp2=Yr zjM6BL&`Uz}RuF9V=<{tE2)Zt0Q3Tm!Y6(1%tITB{pGrm73j`&HQvU64t(KI{=B|yn zo@4->TXEwlJDDv}{gSQ@y;L9f;QO}NV#5{UG^Nis!1vF(U;gFAcvqK!D`EGImZuLYG}_2P1*#h zxCf*5$_dVp&iFn>;f9bI;I}-wTnf{CtPip;kFrX}a_4}H1F?p)T>c8< zM%2MHd>Sx9XWY$=RWE?H0dTVm5UPne>zpA5gNd^UJ+KpCGUg=>Tc%Cm)DnVYZLxQm zW==9;1Gpgg#+(_rcRaS!sVNc28Ah=!``^D12<{Mi!v;c+KE<|VKu|hrr$m(D)y^lX zMSQp=zf%$!AJhD9!Xr7_jp6WbF)B$+zu#`aYYrwa=~s++&{&TfjTimz`{OA}WeZ^= zNZyA{Wl99~M?aQRi^jw-+}lsJw}@y-|MeGxIEfgKMYT9t89541w7sNWC3tWeSO^xT zrBhTGDs|J!7Vvz2ib-U8tmdwjx!IeTyw>!`pL21y9k2b3uO&|O#!oZr7F~&=-7hN{I@B$|QeTzxot;CmS2C(7O`6AE|fq-~H9it54NYr3dd5&%BpL;%hF!&Os-i;dYS(bDtoF z&B7??gh21Wm6}xM?!02&+~Ms$M1b4@90p-zZF-ExKZ0%+7?Q8Nej2Jp9!N9FcdtxIrp5j~46@suDhlxX# zBI}|ihpkpiO{{L0Z9TT*aZJBP$1h&=U$oow{ii{sqg{Y^U{fvm&4dFyV&?dAA^dJUf|6YhN20PM8aolY>wM*joLOXY8Z4=FlcJ)} zGgjB}%0HYB=FEWNT{X~U)X?MUn66H$Y6+*y%M6b!xN=u1zY1|K)_L|yuiu)!@nHqA z*QxZ!50~|5&4hzQ9f50;3J;Z*Ji^Xh6G;|A_szY7@N=bmrNYG1 z?%P#g$yQ?b)8qES-pyu{H%}AIsbG8A;QdIw`+p;vQxi=V-6j?9K3K8|(yNHjTZGu# zd1po7D!c=?yg=X_MlL~#9ZIK}_-KxqIJtY`-Y~omFSE}hg3L4xF?HtZyK_gf!Pw)} z$SINRPB{vRyW1QMBa+>JsGPE3?AA_mL^mfQQ^t%rnmKf|wJBRNkl3ljZ5jr9efEtQ z(=^;DJ36Mvn*<~6im4^@?zYaS`B+;qO^^G%<6gVO)k9=q^ZD~(4$t#+dR|QP>G=Cn zm-J)jVsUdBn$eFVx|ARyf8O|B3)2(s^blYzovK|m{Fz-XtL-wSy`oWZZ>bjEz%Ft% z)|F0GBR4pQRV|$F9pmR$hx}91gUl|@FJ=(g-52x23TGAhc)9TST|Sn5 zFST!fSOMgZcX~*EKLYonko)br$h|Q-`GA{y;R?KYm~z*`I5!V9b>CiZ-pHB1TvclK zN^4+E?0y)$pAf|>qsf~M?cHC{;O&`rt-<@@Q2bTRBY0FrbC`C|6P7y_h&$*$ajZM) z?0|Sj5WJJA8{8?AY%#y!a2u<`oyy;x`*cpH%2`_P{mycWAWk5O$p$9unAoyA5VJW` z05ZoG&u~x(Ag70ol!+j#Oc~iT8S5Oe8RT*BZHTF3kW2>CA;8}`j?H8!*=~~OHc0Xx zN}LnHECw$cSkg(X zR@l|d@}VotW;vpZXByfG7j(}c6(TZ~!$h@}Ka%vsRth%vIWnBoYX#kVP62W5Kq%&g zGk5bA(w{jm~${T-eYdITorgQ_!@%cl7I&p1b4 zsH%jPuzu!*ZTi@_uct*Z9h76bbl}TgpDXWTlstZ1uphDI8&g_Rte-Nj^!lxzE`F@n zvVPnE!wdKJQY`Z0x6ZZir`sD0-H)}EERg!>ao&;#r{Gr;IaeDhU#r&F1z<0QDxYnI z+fPfo7tx$IZ&vqhzK~+_rna23?P6suSIJ#ef3H;Tg~|J*vUi^>WpnD8c-(UFnU~Rp z&lz?mor$aN?!<=wo1azkK>UOeJY)4lvL7(89b?dKa%N=^Pgvt7M3*>_gxsCyF&rsU zz$799=;9U~Roq*Z%PEI>P$32HV8E<7va!kG4$RnyT?~cpNxBly0~3CCf;>J=(OY5+ zEQWD8&JmEbET$`EoV{6NO{Ne-Ib_&sNgSRsk#R0Dn+3($XkUKJU-pIj;5LhHa>h;@(O9qjwE8UbEZMSZA~?+^7mm)P|; zkJ%4;N>(LqBH?d0R0KZQHgz-?!5`+_o4ZSHHnH#P^_R8oz(sxFa%tdwv7Ak-3r~gN zi~8>R_QIPlTmt)kJrutkcF#A@Fr2eZk~`Uiu(|AX zLN|NX;d#lda(6pxH%lh$>*jHsJmXex1GyxS?tBu~5qc$!wy=cTxJ=WjM7QfS6NJD4 z@p`zkB^tIdjW(H}12&#C+b@8hhF~0~@Jv)VlMU6BNWZml8003^?KX<5%!I!2=UkWl z$Y|4$1ySuNElm=IKnm4i*yPJ zg^^ShvO1V#ZQCc)new8{Nmf6f)P<<*A4xM>BX9P`9VSal3%6IxLpjSeR9hcXJ{|vFs_*{t zi)VMQo^62c)zPzBCjR=>PoKQv{c?`iCp&ZSK3JyR5KVSghlUp`ITHr$w8KS#M8e}y zoOLpvglE2;&11n4rtj56L~*ydyQ}XFX5N)cu(mS1fbME=IPfse$Cic{hf(>L%?nOsFhM&0 z%y$cBh&dV?mYsYw3QNQNQvvT((#Iy+T0Pn`WpC8eIMzJfKaIn5lA1iyRU{^`cDf%; zG=vj+cZxx?RI{FI^YZwZ&otc=eYyu$M9jX&dnxK+U7}qRob|^#R(zTWoEFi$cd)GQ z$EQE;_lc!j2kZRwpNO_GReli!c`+I3nKj*Gc@2SQew_f!CyzeF=!_za&eBWLs@jc+g2SBNq6cj$dY!nF(8`L~;tZ!N zjV+S%*J7?zfApr4m0G{02C2J9_V4R<^q__N^6q-TEuGvo+&+4Y&b_3U-24XQu4gId za>-hn@&VvpBi&CXnJ{!Zx%v2gLiMxyBWLrFZHJiw&z_`CpF@|qId7? zL@QN-4Blt#HJNx9po`(~OnlriQK#bFl20o$252*(H>?cKj3y`#&$Kx$KgX#t8IBuS zoQ9D*&*@P*$9sEW-((_>Q)^F6CS#)K>8V6jAU$N7Bd9~n97mEEQUjJUj1p3Xb~qfu z_<+3yqlu?mOB{X_8KC#)NRP*uhHsQwjhl%WxWR%URyNZtOvNzkjmpmimO~+j&V5Hr zx#EH<6uzF1xI!mMr zuP*}eg_^k%a2MX0VGK=cKU>Krk*faN8%`jQaEl>6q{fZjaZd^FLvfCmS!MSgxQ4=_ zdrpvEnf?gA2SlwCdi3*iA?Idp{x)u!-sSaM5LF5mgm~fdLiiCL{F`9t6OT>QTvXug zClEf?&MX&__Nt)$dj;-0ngN%JN>-{}HzM}~u9Bn2;kF0to0~1VOP1?P?r1P^V)yN@ zYl6wrS>^rUef8x1uk|{UH}9X0c-Q>hk3OsP=6rP$qPlQd=&6-mtxMa`)}-Y$NrvLZ80Vdm4?6?2qF{brWHIy^UXbUOKG0;sBBz`r zu7AWfwJqk&ANZ7k9(y^#<=CZiS~e68>07&9FRVactY0%r*aI#dGQ%1;b7iXzx4Zs3 zn5H(Oib*C)&1}=n&HE){#&lIJq&ZVJ|M2*|q>JHRi~zhd!xTK5jK*3HyiX!q@%*1)S;b>Mno_nrMy%b>lW z-cOp%0eV+Ql~1q}{|JBgM!mZ-n*8sZSARdLfO}`>q-Hx=rQNPeFb%=I8MSK|9(boo zuu#AGw+t)7TqG!YULk-BkOy;uPM*anFIN&F&Vyc>#!yjE5GyA!PAw6Xw=p_gqugq% zQTBwiPX}j{B9ke`YYevNk4qCFXFp-Tbw;R>4>O~N?sQF{O^RKBgm_~DZ^U)XD2mcp z)Axh?D~aaAo1u08c<--THMPnmeOi)m5(rBU9Cu;wGq!Lb8*3UVXB5de|qV}jKT@Y%F$9LcO2L>99i&k zo0&9BWBM$U!upNrN`-`cRF-Vr&U0?)BeEW&lsl&fhLhV$^tIZ!r-?hqsYVW;{dTVY zjt}qLUa%Dt9cfgJAgwc%LhHDnqOC+XIN)N-zaID7eI18s^taZb9_(7TNf`vfkNpxB zY2$PiR!<0+tnx>foMdEnS@}!cabs2Y;Z7%uqO$UN8N~5&;}#bR@ANKk8EMX;**GtW z8$b~L!6Z9NfV6P3R;+A0oK9XtZn>DvlH#K4o{q3blDIjs?~6pVeB#F& zDRFHqwJ!W2EVTPgF#UVRYfiYYOC&c-Wq@xt@a;PY_t7?NyMpa)-6cyh_g000b;0D< zxvhJV#$l2B*Cjvq_3F0py~thj25zgD+#bDJ+>UPl4QrLp-aHlUUN#B-7JoN`_vNQg z)!AgVnX|KM?ylV31l>C@3RZFn-Z=AWi4#tUc~3fKUOz?fJ*kyZO_+O2?>C82bkZ>y zfwm>Y4y+-h?v!Q{#igF0;$%YLUBCw(6MCaXkT939({ddwvF@<1>0T9}vast*~YK{4fwJ(#1sDIq=H@`D+C+^r*(QND3 zP6@e&0>Vw=S7@LSROugA4OlqA+np&2?<4eLiL6c@6OUki?X2p2O}ui z32rVCT1|VszI7ME0;+li-yeVPkbPeRcg?WP6F3`a_Z@TZM_Y;9b1V1uqxeHVDI z)R$b>V0&p;_^Lj(uw)Iq-qvFBD6RYUWC|A<(JTHhJo=3%mG5h7mG7Sfyx(u~cRxhD zua~gg`_ByXV;5**Pe8!gA%XvO2MxFnar-&O$lqRNn5umr;RxOB`J0rqAWC z=zo>geEzII6T6<2Nn7j)Us zF{7)@hS@YpGRY}XRb_VKeAgbv8Q|eOF*4zP)o$V%Q>EW+FXl^?(7BZn z(jg@)+G2hj>5mL6(R=3elTE)BT+G{2TyboRtu5zWUk2;aKLE>Fm90tB*)MilSsO_uU|(`TBxB zZRW$B7u~Mv!K1hriv<6-;fa9kzNVk)@_!C&-)SkisrdJ5GvJ1m_ifH57pn?&_WcMy zcRhx)?L1Dss(Wq^^fLE~WU|&|@*wSAa+z$YnVi`0-QpJ7li#?S!{A-7fc?_hoVwn9 zr)KhORqwu<55==&a`V&6lM1UB3k;imCPcJ%;%fG+V&4&Q?@ni~ck>%@$3Vy?sP1s4 zlFup$uQP^h-dP~JUGABzbQQ1w+I&)CcwwB`xEJG?GRR8;Yu;U$W=YPmb=bP6s>xpo=Zf*B4>k<4f6lq`oL{7xHJbx1vuL*#RxFD6s=C#p61@u_ z-tqmg?AuO+R_;LrA4f9n<&X=vz_N`*`7F+iA-~HrXJUS4sj!OUmd{wm#-|XwcJ`4X zo&NC49`@^#E}ty=u%{k#6QDxal0_91!OmR!Nzv5v98bdNoH#* z=DyhyxUX;Twg%3#l$&hbb?&`oobs{O?)N+PpMT`79lZYIpKSbS-d)uQzIm#n%4NO# z&6a1CmEJvG%-uwW-?(* zH$?4#TdHi}?up|V5t~lHC=2o0n%LU0IZO9O=<_C)Em8TZxc-$eoKSZfObP#wG1OiR z=}w$}4l~Z+m@-8HYz&*R5H@$wJ~5QWM{JmNMw<9D=6T|nzFnfC{%Nm- z-fjP1u0yXS)81Z>ev>}q&O(7gHpct8hu)P@rPy5+wi|;l#9|c8MuA?Yc!4 z<7RUWhK+l`X19*x9>tdiasbBxHV0$a2ngecA6%H1kjSc~#F1g|UxXT+ppEKcCWr&4 zfYxr;#r^%lg40bf)xg3|%X`$>v)w4$?RH8}QCK=5YJEPN`QuVvwNxCmL|bC=TwpfM zuWzFED(>$c?{Pc`zmV|!A*G*Zh8X_quJ|7#k!;LMu1>taz0(S~4REhHxwpsdrQ(vU zhT!M^lB-35NquGE&O^%k)$YxS%HMKG`O?O`A0DQ772B7OJ*=$SOzM#Rg~5BR&tz+V zxBI7Hz56GBPPw$1Q{ni*ifFRt?)GAL5S%e^R{(w%(_drUakN`HgEv99L-0U49!@Nr zOHVS%wrs2`7YtNF2{dofF7 z(>VXN!}_L5T-_h<;h;q-VV2#LE-smP1x6JYc#7cDMCdHJ=!#h})??N09V_g_)9oUu zEiCY$C8QDHZ%Z(ML+mcwy4UZa_N9pn4WCAKUw5mVd_jL}Xwucr$WEYqPG9z%MH#vs z|3HAvx(TqG;k)m9ZVA56#s3VICD?p(((-H%HXU6p<8;zJI^J~ z{TO$-uPVsAl8t^7#BpE@)D!3==q#Cf$d*=FhubEK3oA52@^r0I%-)l8 zoG;D*_84R!3~rP>dn~T%*nNFhTX*%=!`{GuOA7wz)zRafCq7kK*}I>r&*aT^K9l?W-B&lC z{ys16KBy3?I>9?J0$Uh(fUj>4aHvJR`=nePrH;GRIrmfSIzXE6ek zv7Df{TY`b3N05LS@g1ig^UyF$*SXcP%JL!SWat8rS#ug=%8Y9UvCDwNN$ws+o`x?6 zAl*Zzhh7=ZINk1?8b)$h2d?p4nkbFZ*nD;^un=Bi6Wb(`#UBX0WwY7T1{h~mRS)HD zBW|+B`pI86wNNbrE9up1pG@~*%Boj2@v(952IpeG@z_P~s~FBexT^&I4A@EQ^_UPR zGp;pcHzE5Wi>liS4`+N%A7Gd`K=vtqukLu_uDAlW)C1=DxR?8+pbNFjvOxe%A9A~A zGv64F3j%M$vBz<@A}N5Wfe+ez2Tmy@>lxwq3#YwyAe^pDY==w~OJ-)sn4r?#*YEb!%WXOZn@X z(!I2H_G~L-_rKBG{ocL2-!fI{%Dbxy@24q&UGjHV(EVmRy?gF6`OjCt?m2Xy?95?& zXOqq3V1e9OZqIl%C+I{DwyO$Qp!sPUxF(Yqo+^f>^xt$_B!l>>AJFm>vYO2|OqCpf)a}GEEJU^>nu>hfM;=vEhlwu|hGb zTTiHx>cB-?)rVB0V*{^wGy7FlIFiV-tlFEPGb0htsPEvE+gOUK-2~xCr4~kTX7$*= zff4V#3eGrZprhkX_?9#7`j+l{Cg(F~MFZcF#nZyhV}6lvqQ1e$vt2eEwu(fF+0PLH zcM~5OsKkv{zJ@5{+fszf!L#neZthCeo~ggGB;o{-y&v|D`}lNl`q$^K1D7s4A{q42 zM4)Y+PIhRw?ILeZ3(Bf4%J~eg1B&FTf*svU9TJ zG&$Ksx_1t0VmH5$+w`*l(T2zSY;Fpi1iZuGklWe3O)_;}o)N$PoCw$i*>PeBy~|E) zq8QcOQxnLsm17MP3B+x8M#*P=xyVt+YEj-{x$7H=bz;rOdsd@Zut+Rhzp+H-Y!exM z!7vA+%iUeJIiuWUh@R~sOTUEPyz36TcNrqP9i!gcsu!-D&FeVG-} z@EJUThVUE9Iq)|Eeu_%AvhI!6!0QJKyYHM^c;elKrK8Fv?0)~|%ku8^K9lW&m36uMlV8kP!tR=4 z64vGJ>a3ELlY^4b`=9^#Q!IR_vhoOWg&-=bczPjY0GHW$`d|N8-1cV)dj>P)ZUXmt zQd+L$cIwH5&mUPbkwsR(3P>NP-=VD7sZB@hQBici8Ku@}qvR0AlU(AHA&&s}hrB6? zuWNocX*#K6NPxxn8yLTBV5dBrE8-t4uu znLv4MQ@J6v7RKF7!ObMfSqxcBaU~W0{9fDqH9?febUlq-B#$B^)xv&jw(hF|s3x=`1CL+<*ORFGYf^zeFbIN^PcLdgj@4G8ZHdsuac&c)ds$9kHFYfQ&pqV_NcVAz7 z!P{f^&CREOy*xRor*rNk-UmDBLA`|PAf}ffPyhJGKkg@7CRhb@f*?vwC(gL6JNK#h zNsuMPZBzderWT>cfM~6aLX*ZO#v+c);t9NhPB+0hq{~wRN^${UhTM%{PM)XxBV#aX ziBD0Lx&q7|k8x`0^^uGR$uijaRMR0XF->rGs2P@>+f(0NBH~dRVfhShaRNw*(@gs0 zT%0p-B0<>Vv4V(xwbPVaQ~lPjtWcbr0%hgR_T{h8GQ5eKtsetj4usngPDI0%PjR1< z=C4isDJVFv&oDXyE_qQ{7D_t-x!|)!t(`9JzVD2Cz5%YnUo2RWnK@?+Ed5@-gbk9Y|4xbqOWuUw$m<+C@1O^7mRGzO^*i9&m+J$Q8yW%E!F#Lp&CStLKj6_L z`1aydvThK3*cN!bz5~Cs1balZ%UUqF(gsg8m<$N~_D1aMXq=>l5BE2yEt7lPs&ufsEq3xI4}Bk|%yG zz9ftZZ}V)JXKrX7@C`4w#b}vVz=6{Vx=$lbz*% z=xHLXvUVI>oILWm8VIUx>)lBI2LYr^e7|5djpN##3a?;0$96@+y*N(zh)o3~-*KLZ zQ$xQr%q$&CHJpwF`<%I$rT3-a!JAq;tD=~PE|Wy*fpTY-zR^S#vu3rPBe<%Y9}e<3 z&od;T;;q7M#&g>r@|EtRE-*9eUUb2*HODNac%IO|9P&0OQYi|^GFlG?yDu65_TtdF z$|0IK%Zcpu8JPQYCCr_8^V;vmaW%MhF&(@<-gE9j`}*|)zGqH``SwmFZ#H_j7lkFY zr2Aa}ezcuf;tBSOvi<0a*PA7+_OJOK<}@> zx|hmK-mmcP_iw)F*zj6^_k(>V*VnZIZ;r&jdO7z9F0k8+CI`z7!Oq+u=zc5b_U=w5 z!u@cXPn_i>%F+~7uNkiZ1G{;)5>g23Cpk~OTY4iCG6>4Rl+xj@3{2`=fF{qg(x8%C zR32|BP1*#i(gT=INT8eqag^e)Ql>qV!|9z9KIiZQVwG`1pjx;%R1&Wz17xv0y*4{tyMZwO@iTK^0#3TwRJOsdZ8s< zC5DO57_#L;xrk2JE8z~4E7PE#gK$CzCvA{~As}=`f)G!*e1uWIRVgmMX3+OeVd}UL zPFqPX93(4lALlbm=Qu2sU_4jOslt;CZhxLjM$Turhr!-$lqrwB%3HU)K5m3j1qZl% zY>DR{i18$D$g*e+pzn8IGq0BJ`|)OuE}W_jVWbb=q3iE<7aJ!s`IIHplU^BXx-7#J zj+#Q2PjDi8F%aJl-LB0_uG>iNEa859*uCm>y}4Oo-~T;N;6rtRt7^#_a@VqyOU}US zjTKZ|uESY>^kKoei*_L|uvcLP1Z6+rt_5SWP!GuBl!0#?Bo4Y-H z$DNMJ#dMmpWe|h$RU;K!0ke$5IdZ}p2-5Krtmt&2Fy=c>{4GBJf^5cmWJ%}0~O!!x#fw}wNA-9&RI z%|j`aZkKv&iMRiF%8C0dh_N3(3bn$%3~H({XWX;&1YtTAL0lU2u1F&9%^}Rn+N<9z zoEJkMZFDD>g^%JuD)-6ugz2)9E#}h&3mxv$WLx?ALDo=`LRCXKb04AdQwiq@JGWI8 znJ;{1UbyIc!Nx$Y-oD^=DeqVG8B26PDMn%pP~cSFN8L zjR6CBE5Wi^*Ae_K;doQAu#U=>b8k7R);Dn^09&=ag0~C2*UlqrdiUdwCl@mJ zwx+<g zZ`3e*zL}Gr?#$7eu=R}Jh$?G$RY`T01w55wGPJw`ydiynexn4ID0pT6%Und>!~vsu zir(%ZcNHXoMYpSU6|X?|i6vyk`|w~SC0u-FLSLGjV`6JM;%#{s%%T6|^T3S^qq*A> zR^&t0&XXa)d)OMbaBydLcbosKsY*MYs(AFvC>+X36h% znk;RLVm6O@5`H(Z81EjRuQ5!H8S@ns`bL{>n7izSUH(6ufk5#!>-g_9c*QRltK(dK)U)9q%*Xt?xtqV+^b|U9qxqDUZej>fQmaE*V zifXC9n>~UjCofOxHo=p%lggc)j+@SL|8;_V8e73&?H131vxyT>;wTF8PQ)rn#&Wm& zjq^FS%EL z=Z9_RwLk3jt^Ex6-ql39VMPz77-XAHp}9b%KyMSlD3RWwsD$XEkV#D*nHRN+YP!tP z@CvNE>;Odc(Q))-fZU?{%r3+Y!3*wAQRXCLbJu+zx3<=G?Nx<#!5-}K4BS=cLN!w6-Tf4M#q>R)jQe&N;m%d%4C)HqzUK>O4@yh=Jb^g=ywyS{ z?f7CgZa2hN5J}dI+v{uYcW=7aG5qKe1yeVRvG>Q|c15#S&MN(@`?>e#80FeL&TYMU zY6-fpSA8ZAjO45(;lG~Ty(*b}VR!dNfA=8wweBuv9i|HlYz?FNbRcr~ZhO?ixatPMlF>C>XtE zOKNr4Je1!l*42lSsCSsgfsNxRH1uPg_Bj8?9pC1&(LG)?MivP45VM+Luib9SLlmcu zdD*K9>oB+U5(p0bTywXRE?BsBYrMWmur(L8-Apm(;|I9Ube`q3YJ(V^>nA!r6c{_Al`e;hG`?%aKiYX{Ne zu9yv)noly5R&v3*2yZtOKbO0Dpc^l=ZV>-Y<;=T9&XWtaoOoP*fu57y)^mDkiRaJx zK)_2rkm{QQjhd@AqWD^u4Z0rm+MxIRPj*PpP^`ec;tLo6k2a@mHW;^8s!29gZ*Mx9 z+*;#4TCtRP|M$(KId@Iu-cBreH~>GN$Jx+5we8lzT|xM(CxdQ}%1cF5Pc3)9Uy8&( zPVZittNi<1G^u0vlE3?4r*wm7olY%Sxs!JC7zRP%`%I!Jjt-(uMsEYQ*&xXCl+JJh z2X`=;WIUn3_>IDCa~yMr3Bh$|WG1eBDg${&07oh|o@8=NNQpvk6p+w|vI3ts%*Av( zWmkCSRwR+VWE}tw!2+U*Rve+{P7|qJD4j6+Pz+lI5PWLoLbY z@9&=m^hCa)U%cp*FrJuL8|8M8iFRAbnM|pkKbOu;H}=a4&J^fI8{Ofb;0{3HQ!;L< zvde|vE+py4WL(W4caadd&k9#2>liBLFPqRmQ0&@u^OdeMu;l=rWpeN7p3PjbAS{OT zM`s&451?Te;lfEWrH+bZ23OzAYx5ULF`LD`RC8^j>j6hho=av6O#s>`+o?+xx$rzY z(8m|_0s32Nv~>d=Rl-dQv#xT%mJ>ycy8r!)cKh)8^XG^7l@NZj`i|ut-*wp3O*QzL zp1&NzN8g|;f_=^%gP{H`(d?%U;`aY8@#N0a$W^EI<C+q)Ato7nf(x0_nY)Z;BB z%k{47BKOV1xP5(xp?f6(f3?xly~P>j9a+k+pmp<~`B$%*ICuB^m95Gzj@{Mx!uI{$ zOLDjGGkG~D-izh47254Qf;$H_lL-TP)H$1e{>LBx@lJ4&3BmW7vz@R|;sg^e?9QFT zWa0&IoJHnb1SO*$vFQ$BceEF<4i2KM@nM-yp-}i}rOb@h#)?FiDPhah45h%VFrjE( z#v@22zAzBlHb}2(dDT_AWnMQPuWjPeDyqrFR1#;IlQyBb`d_X3U3=$;b1*_6xs=rLImmcFF5>k7KvfnrlN=M^U2PT1mH zj!udOgWb$Y*Ur?}g4cx2BVJ+wv=RjBmd~DZRS8!?Rg;&}&qgM^tH~#Vh%x$lR;93n zJacNhNRN+I(Q{{r@`7g)&MWgG;Wy~B^TD)u9-`=;ir0tm>bof~y zwT~Xdw(A2p?yDbT2E19X zcfGw?kxaIL?RCoSU4fo;W7%v)ELlFUyk}APzH`c_zWsEDrLEll^sJhQf3xTid{WKC zXFE6Z?yD8e1i$Lo{hzDgy6gpN}G@&kW0k1$wmCN{8>G$kA#k8PStnIh7j zXUJF%r7!4)EiglEcg9eTswizVmfqPRX9&m$1|@;?P^!a2MI>L0(ReDqJJh8a0tdtW z{ZR<;9)-5-x7&!B^p1^_zIzs|dkS41sUJSFB<2pc9~!z{jjL3?Vk)V`ZI-LMeuk{F zo`9VT-U;q@-7=X^ViJxw2k^o;C1V4dUGd?4m_1ymfd82`A}ZaO(@~m-w$9xKa;mWLW%?^5RoQ=&nTZh=YDG@izN8|UdS z`>8!cP$y7Bj$wKMf}lI+S}HjtfE&_-X)_!W9zgS+Xay`cF>Ax%dQu+hbhKyr+^%WV za42;c#$~uSIv&BMA@=rqy?%qJCrsbwbF7;HZzkY@<<-0)r^H2<9!(YVJ`)ZKVL+05 zO4w#CrMI4Rlghl!8AoS%P6ka;^~KJ*1qxbO!M-@>PuBxq?(Lfgbu$^rf)5@=;-a6k z#0PigZawz2nYWs$H!oF9B}-20wS5#1yj6Z(rVAkW z#RXs0`1u3fGi-5%7M>5Bvv05p>_CD^o{N^t$NqO?HuJLWb;kX6Q%droYLZ3lW^1uz znQh=OfG-=>E+9pYt(zq-VN#dAl&gz6NlY#@lllyYlbJMWY_q-n2`U7g{aZrqMhqu5qjH#8TkdJd-_pPy z7zbESuz5cX!fc|oGHGNc3biBoe2`?V!z$c|M5c$EEy_1nvJJ|+31%P;C*-)!E(_bCl@x3`(+suXI1SNZ36G!amltpG@2Ml7Z}IIpw5Qh4U8nHZ+dZ!$^HAV%X~v)Kx69g>YaZ>*jQj0Y zh+X&fJx<@gxl8MQ6l~Amf1Jp@DgAy&7Uy;)i?dnmepKV@)w8cBoS?V+)n~Bpcj4!= zSH98YN#yPoy?fo?{p+h&zuw>94d_1lgw3;;9E`scyZNAU2Q4H!RWxUA=Vo6Cy-L$E zN{MwJ;G~k(Z5OFzKZ)z3V(!he3=Glmf7mjJ^T1|tobK<%KaSGUWWIXafEg2lr=t-P z>p{mr=+<%n`~Eo3)9F-8sixYpM2Cq;@}ea~Yd+d*Qf&BsCtJF&^^3N)gARNyUl_Zhb|ch;x0^!Y#9|-yL>`mCUr&u5y|+z}5*ph$Zjh7h z9$kMpNzWn1thDs`1G82Oy;gjgQc|MmM?cv)OLcWy~+73*Cjnz%(bnJo%T z1ap39KI)LM`)_|cl=xTjH#cH@C|Lm)?kR?!b$+~mWSwZgT^Vn`c~leNZ(!R?`u3tv z@KL~hvjW?zlkYc=FqT~16{5VY&M0qJMsYT*3O{=ccwc=jUw5rT@cpxAKgGe6UgDpg zefi$*#kJv~O#IPFK0UcvBHq_mwZTe1SNZbgPB2S4%jmt~tTNpRSv~2@v+-xu>cZJU z97UbeXos+Sf}={#Q?k2+D^1vDf_EhQ0VgP(%CWFOw1r>eJA_gzOKai0auEqZkDP`?i9JVGjy+Zyr={l1J!TCaN?cr_Ug9= zbKoz5NAT#=pa1;n&##_6mE8S)PP^aSWifends4)ogP)#l3g`Ix?teMOBoO821DSw_VVcsN(WH}sS@U{Xz{iL#6z|L?oY-;s9K*m)fE-NX zPMDe~v{`0PN0F-z6t3Td7qt21XsNhfgNe( z#PBJl7z$_Zma00%eW#Y=QJ?3&r_iVljKl7S5 zHWX%VVa!AF(X>K^zli#!eRl-f3Vk)(t+(#Dxpj zu7T!W6+dP#Si0cn1q9a*E| zq7HE<{RK{|s@f#S^Q(t7lFjkRO#=6}()J^5fGhfToqgZj-28?Gvs=%;Z{{!C-mW(n zmu&KLv%lo_jv4qR}P@SWZSN&J^R;BvV8A&W96S2h>d+KK<(Qg?v#( z(Es~yul+po8-_sAXQs_-jCpg+($d;%uT>SH6}o_KPYVdR+xytgQ3zdS;RNVi?&pkL zX4-5v0jLt2^_;5VxE|p-3gYd|Mc|a1fO_k$6Q%vMNK@euF?S4)YvnD+iAS!JyPD%z zA+&I7;+`Qw77{Y!zU^?XbXYD{x(wcg=cdkH6Jp>eCd3Wln+ypN)-984I3z5Hg&)JD zCL)iE+9TN_SuTj%7*8J#q1e{Y8^G*4XZaOP^`V~USj?308p*mdA)#024vBdLi7!iq zb?(*S3SyaL1?S&bNb89jU-o>J?`n#4iic}t)btX=vF08*R$&>o1@x4r53V$0w$45g zz&TOqhUH9<5yd?Zgt=)n#xv zoXgfSJyA@N)WYD44J37;Z^k#10VynC6ZNM5CH8gKwhha`GcH~F#D2v8#L^G&o3FRJ zdY5j>kY5x9Jv64d8x<13`R;$3e`I|<^4IH4!^wy1$(|SDy3tay%D%rFw-@aD8K_-y z?k5uNd-V!em+SRr-+=B17jkZnzI^$z&Y2J1y+;gb=l#(NfPckpzkK;CUJjP8_X_v+ z_ST~(5q|mnT=1SpcOR>LozFWvpFe;8?-*6C`@1*pRUVzWd$aKU&5GWARj%gz{$^=Z zxfSMbFGRSq6R%0^-rowg+FQt@>dc`VoIA{Cd$U~Ec%8C6sv1Oy->7V8SohPWVxA&?6y>sgDfZW_0l-PA+&~G0Ni}u!GV$jbaxEo29D)V0wo)@ zm4?o1=Q1_hvR{9QnwVjlW3C<(Q(q|=*4Q$m!Z&?JXhvxiDPSEP#lp>I))gonrVrKW z8#WKKLdHxD16vhc;vx!lG@-9(e&}+REHC1_wjJ0--|r)Dw$=rg?pkB$-eYTAs~L>o z2IqRA1j0f*BNi+hHWqg5vLTbun@(U-SQFI+!BuRLlq~#dIorQJqG&(j+x}jzy~)5` z#+3XZZm-THpTxZvnI(^GP%d^T9|$gaV#&gzbIPwr??d_EU$BNBww36U?? zy&q_FTXpfhCCI<2ii`6*zGTJhd2;v0=_tfaxLDBM++JjWlW^F z0^sezA!l;qT%TRfRwK)7LKvfB2hp%OAuQyFRxxe_!y(cJ3B6r{se&GId7k#CA$`5- zpdF=dOG}Z}YN?W6?u1b#InolR8omT{1ifH=g0nzm2nr^PKD!KsZs<|TwAp^53(N3% zVwr-t%bpx1JF|w4HB7cG3RbJxOioZJ3f6*DB9;#gn|{QeXmIDR(2JgsJNglD)^4=1 z!ZSD|f-QKb9)h^&72}~DV9_1E8iW#>s`v&2$5eDJw#Hb7^ofjt!i}s!3?6(sg5i8( zt83vqnPAV9*Nr%+)+M?<2KDB-rfp25{*7}aT{ohB3hahsFfHgv64EE+QZMo)`{so0 z2eST3vi)BNzdjMY=NP_Z-F{xI)FuPBdiQyolh+&4O75j|Kg(HiRZ1oIh_`eFUaF0p zdx<40{ghYFQA-xKz?(O&xYe{Q-(MorH*dl`XzdXe@6FtBNeuZNw^bLAKMO_G)IiMXBfA(s)WPYOqm9`FGOgRh}$T5KiZa|CnW2BlW_%>tc2g2k(fBI-}7zFJ|ulLe^4-c)VpmX=G*)S4! zIM4!@ZgD}6t-Y2<;AX!LCXO>9^iG9($hBM|;B-w5lSOqxU(2pxw+EZ%2Cpsx zcIQesMxGo)MgL$)!$KYj;s>Xk?aIWPb@)QAQsOc!dUDmBMVDxj+2b+cF^9PHxen9h z6-ht(z%&^?m1Yxm6-X~Ed=PKvE!1&=qm@D6+@zx|#2$Z2Pji*U&!x(3Sn3lI)`)j- zM5Zs3qQgTr7^Bs`O?P5dFSEZC#op8-`Rk*k`y1f>Ou~JAy&6Jw{R0BGLhHG|WUYhp zDYn3pZ7&Pm_j?uAgzlwnoK3+cS5G6|n`?!Ex_{jg`Rwk+i@Pje;?hTF?!^mr+4IEj zb1c*Ri}M$FqUXKbQ@H-+%gxTavy^v(i>Xg=e{gj3gy3$OWwI9kdXID;AH12}{7>lJ z^Eu_sR(SE2j&GOpzwh$$`ts=S@7}DE?!~NfzwqYtd%vu!RAM&+Hn98bOm0@TgHAPf zTX(HnpE$P)Fp-`>sd-l!q*(}&d9YP4XuCni&1RenTRnA=_&RcfT_`SLGss6H8R_9rK4|fgt%rK4AS@ve+ z2BMpAq0q-oz3y{TReRWOwwZbJLu=1VBg-kWPGj5r$$# z-TtqG>&;b?_ptilu}rChXG8aOS)8!Sw!c>@xmmF9^|+Gfbx=Mgb6>3`bZ?qau0r?D z1%-~psd_$@W#5C%Dv5%ZpVdC^_^J9i$S?1^3%uQumSyTp?Kr5D| z!b;8nMipaLwNb_{pn(YK?d}z_04K{VG0zPLQb&T2lmVV^0t(Eisk#(=_TokG=~>8l z}=F5Y)@Bk<%9^^gbNG^2gzUGG>J9dnQ?~<@a3f=9}BBOjVIgZ6OI&A=C)4|2$ai(2sZ`-om z80Hpv=?OX}TEQSdFjzH&MI2{xemD)qqyCYNMEm}gPY!Q=*a*1HzOTQNZr|LiFS}VT zp1gjxR&w=qldoina&JuNzS>kL{B6p;X(eabUUKtZ%p~Qx2jAy=n&#Lpe%&TgJsQQjVL2QPsDf8xt8F`;8;7WTbb;Qw>jhe( zclB5gP92s*V;S#6bX||9La!vmwXq8#2Z=r#q+uK+7$;JWd754L>Y;V#rP$BZ4aOK( z+~VAAHeqaU6~e{b%yTnA54qW`e8{~B`l?op;Jav@&x+ak-rMu@i;KPUJ$K6FwhS-< zI_skJmmsQ%jeC$adfaFb$<|*`ZTbN*t+a?K`wVn4+H;0( z3g1DmFn=9xmYk+)c|T1tQ*GEXn-B?q7&VG0E$je-w?c1${BHWN?G6TZfl1~V*saqK zgfS>!9kI7QJH>SqhLf75Hbr|9bXk~!0zyAot#U#D{ufRfpXjoFUWzFV3@dFYCiMBW zTCLf}@Uns0XSUKH+Jxa-K=_sm^kLPXGJey=pNd8N-$PBn8;SOU93NbN58GZh0~ z?@&sX+4qvRef_*GoE2}$gL^nCy=0|gVY6s*^)2wed{F9MvzK`J-HW~1-a33Ab=)8i ztGQ_5Z)q03TfjZRcZ--}PNXN7S0ClS{rhhzMw%?16h-Lw{{3&g_n#kN-JjW4!kaQ{ z`|ulmg8%P}(C{s{4vv2qyg#q*RX(Jd?5uVTA9UQk7HlV1HwV8iA@-Yf-aR*)_%5A= zi~!w)&Rg(#6LM$S)>-I>i^3d^5$t%Zb8|l>zr*6mXjG0ZIY5vXEuFTEdxeABtGWX{ zBr2|Fn&a^Y^zif)jqsuGinPe~?gZg%6?^jGD9){sUL$ND5ji%%u5*F{Hf)RB36M?& zMLSmgmmdePTVOy*xFF)h>`MI`OETctCb}8T_=JrmW|uc$qMe@-iQ?@Ou>zDl`$c+Eck#VCO8wz;Qw! z!QQ0>O70h`z5!Q6aGzLER@i&ZrN$95x`x9BPD-F&>sEvuFY#g693ILH!NVpL`lY464i;L~2If5Ym7^9VfB1mJrmLF(Y)=JvHz zlJ6kg2M?{?d@tj^URFwO){WdxH3wd8Ucz~B{auPBU+>o|Tt2aqa-+LsUFyCM-{OLh z@nRjmzrM-C&g|%2nDO7zd=`15`ET*Jcb35oC$IhdSMl4w{o8N-qIDrJUcdkE|Ms_H zwg!z$;4SBdpO-b0M=lq_BOu6x`}@uxt9KuNvwMM41i$_@)Xsza%fDVSRGxSq3|-kyK@Tw~T^Cm6`MihUyukOy`U+n}9eJ zRpQ(zf<*aQTWe>T7ZNy&Q4Z^%O@F-f7nrxsUtAP@fjBDLhJtP7JPMS_u2`nj6N|2O zeIyjPwr;l*%q8LG)&o09pnpp%hQaec_!Vkh_y$b_`Q0F-X3T_8m`u&t+t%f2rVib> z$myY#Uod=Id8VD7VzTWOc(mQQ(ZCXK@vxh6xOeW%v>Ypk7*^sTH-&nl6Z<|tKi|vy zY3p3;i@Wo@uMrhz>xSH^6p<)J6PXQY$*hw|E$u@xiRQJKeowc`et91&j>I^|W8G4Q zLY`Z48ezj`I_*o}q70}dU`9j=TM;34q=N7~`)xrHURecA=sb;uXzdBYPO@{2({M>l`Grbvijf%mF3%wDH-#tG~d6tUwTL8E(@BmZr{a+7{ zBk#Za?925Ua4)m(>+hFJuGP-_d^EXI7<~Q2C7cIa6*l1Z*ZZjb@Qm`C$h~2a@{uLV zuWv*yiu>@rb940WVCVBe4*32*TKHuF-+O@X@T~LxuQz2xU@qZ%cG2R?ZNLAwfBW~| z?El-`nDcp^c7Kah!_>0(;+zgM+IJH0<3;zv&eJ>3l)wAx=8b6Gx%&s#@7{kS{*@Rw z*Dvf>3+?XKhsOltN-23)&#Iw&asJj5)lLB2gj zXzN}(bEO&%M+tV|A!{>h1?}$YC^FDX#l-}OciBh?P=pt)+tq>IgzF{{9r1!9jpzXK zmf?HyQKKI%5A~5hburD%t-++gsU3kbB2MztPp#7cYn3U(HyAd)H?i-#^Ybia_|EU{ z6nrCZyeN8Q&w!}4v(U@N~&l9fw3dYvT*x}wVyOC_3Hgxg~Lx@M0XmfGp83*`3M z5t|T^A_!Ls>Vy$eh=W2=L}k4Lp0G69Y+(H8^B#SfVw(+%d^il69Mc_S^mFniJ4ad( zH_w_`%{FR=O1UMrFJnpy94&P^H?UwRVW&1Gjy1cyyb1>Bqzr~b%bND-hix=Jj2q)I z@cWnHWYYNHN8_;q?w@}q-2VCJpNI7F^M`KN>JoFuK9ALv0*YL+m(xy&b3pJAzVGXY z;d&vF94vB4uD@gFW(~N%7q#c{B=^|&&8m_6`U!k{Lp1l*2Hc)EQ7+9VuU3NspV&zG zkh$b?c>(?r{62W^z2DF8!*{uAh%?#qTlZito`8K{pamrgw~prQTZtz)sioJs=>2WZ zzK_?<-7DVi<0shrb}rzKIe+ms^WAql&o>AjAI~BDcpl)r(cirqXHxpR58lIfvi0}5 zU{Z=Eoe{)s`I?t=0N$KNb>?Sx*|aLN1fh6W8NPi?=Vm_OoBoN?97j$nRhpo(oJjJm zOoMFQ_H><4)^n0cFmyuiW5-5@iI+?!dFZ;HD{>f2Y!BAKG@|=z&npVI?brm-YNL@r zTqo2=$Gni$IELefd6;{FTea;ll)LdtLWy}#zN=#ZYe1C0b&`YrjV^(>>C03;FmBx> z5*WkkZOMpMB8^=i3y1`F4h+;->B||u3;WFVUJeiG$Q4cj&lgb<7Ja@q`h<32*q#x7 zYxOAVO*MYVrBchr=u$i1i~0(_BL(01C>>=Aj@}cp%Z6C$SVT%L_SI&l9Bzst<=~MT zgl1nUE0%55#)Z{*{rcxIOE2u_1H;wTaz2YBQ{vzg?AD-%t=B6jj4;O+hLzS?%vhL5ktL&YgdAA|zz0QH{q(xfjz2k07T zx?O8z&33cd+~)Nh;^SkdVNb@BMq|>Ld}site`dxl@p_2o;m<&dnzF{k@d?W|@88ti_gGKfUsOEpuuk za!Z|Cx&l|h`s$(Jsb`r>mazK?@g?-rZ#@LxM{bVs(uEpP&e`|*-QM0_%M-W!8OJxb z#455c+BBaL_s-Jl7dg88yb9fG$=wgoZu%bT3C{|wcV=h8yLfRv%k$aJbLH-3&E#Q! z_qyJ_D9*XO-goy}VjrlzI;tG~?KeW|-+oKBl;uP&=MY|>`L}o4v^wuzsGgmnZ$Uur z)%fPEfa()pf*Zz-Onaz#=%EV=PsM!0g`hzWBb z5!ynx$|@aMwO~hd#EN8?2-KIJh+w+5KwcYc7m>%HF*hPa660ZN5#t7DaobpVhvXoy zC46V;CPGA@uWD<0$_G<(uQav#_dGpyg`bVWfPis z&8W!>p!`+Mf@6?{6FPgCvh`Qo@Bdu{j67c_d9XC$`LR;h>tTSanXdPHgP&YKxx9t* z^^xuOD>bCNx);!WwH{n@^=(_=ecfc|`NfnE!S~G;kCE;?@ny-W@^}hfsVM&P@?VdtuyJp#4lLOf82|0J(QkiC_ElwN>G3Aa_T9T#8g{(S8J2UZGReD2 zzeDRZ58K{H#|z8m1)f#P`J_xW3FW$_jt>x5PKco+OVzVDvAY@!IC6@f5Fl73jCMxI z%5Kw53{l`-x+UVPj~sMfv@^%i3HUwN@!GEEK?)ZxXP4+nEzo%msXM1OZ^SEYysOt4 z!}YEi(Thd@#9mGpa87S5zpSU}T83F?O(o)zG@k{Rh$UKV`xT*N-;Lq0F+4mx9W)vY z-z_>f$Wy#GOJm~nq411)T!+TM=X+USrIcXnvhTJoa_u7Pi&jhYvx|Vod$R7#AcU0@ zNK4AsdStS6EQC~1q~hG;p9_X*pHl<*^9w!{aTzdO5A6cGFh&Er@C85_7mOuEV@PB= zYxr#ZLkCVz&Pchf(u|~k(VzBH=-33xP2erYjLe(q-(8F!twOhJ&FwY-v?)7-+enpZ zGXEyH=k+EWDIKFd7+}-A2Cl8c31}D<%jyzx>+}l#d+gYMn1F9f{GK#kzI^!$ByhrQ zx+c%_f@>M%Dn3p~dZM;+Y2d(NNTG=jg2-97CgR>a^4YTX@YUFz~TG%4bJ)Kg7O?X=^M)3T?iE^YwjkvG9Fs<=W-Z z5utb9PkEQVUu^N(&gYVMA1^F>-&DJQcRg)!@!U6aT>s+H;o*fAzWa~wk-MLvcVDXf zZq<4A*LUxQN5AUUoBN9QejN9H)A!#i?A{6(y0M<)=X;nClqSJWJL?39kjX_(*t?uV zRh32Xl6L3SQ6k|SBTTpBvE|RzadX!Vh<;;@5-q|BTFsn8Ck(4CEwPa%NElAQy7xjW zQenFU$wAu*Gh0vSsp{%Ep2rOjz`{k8dN&?%4;n$WWhREyw&R%48)~*;nZRRTM}n#D zt8R7#Q^m4P-se?I$R|DSL4cGHt8DBE;gGJ!X~fQxVltuceK;KK?hcB8;oH}32J%@S z3U;g$TIza~_5&VVrm4(;jf&JS(zJl3t^lts@EA+!N0FVws;F4UUXBW}61=m5QveJ% z*&$cRJQf~f`k@m#e z1~zRB-Wg)48daWCy^PjEzx^C{xJR->4d-hLLi<`=XJ)Rd^<&hgRunN zwJ~;qILDU7d^RoSlZlm!@2W~zleZUKeTjWv|0v&jvPBSmUS3}8x!D}P-&Bk2?u8b;d-6)W9FZ=?cRy9{mSYULutT7| zg$$E$YtyuHM1M-vEm=0a-{Hl0F3#B}_-+Bdp_{bZodgXG2o&@}x7v}pfinM<&D?4; zN7_uJNgJK;t`j&|jF;IZ&Y=cG91(Ogb#@UgO9urv8)~PTmeEz7*CY6D<$d9{QQB@f zT&IJ*cM$F*0ndYz0hxha-t-}8k9C6VW)>|(7Xx1 z39^F#@6*59H3xS;AvN;;*euvJV;o#$kue`+>h($+3zo=m#l9y@^(KD*qTb`)2iYe9 z&}P369i+y?Ni=8QA0j``KTIY=cA>n+EQ3vfeu!f$B%{}8Tmz9GM_e3APc;J|EFxf!wwQDL z4FI3H-@ZxpB+3gNARg}CL8o_#k&vCz5ubr&%nMn6fabN`z`+4 zZ`J)^Ys=f8GjGE1Gl(Zeh;bz|@1*Lr*(%tsR_CHO)NQ?58cp=lZh{~xl$#;Ho50s5 z{*1!2&^vW?b%_bkxCG3JL81Lei^o*Rih1>d=dGWuEaFophqQA`JR8nDHrr+1+q(=ny!Pvk?cpBB;| z;unj6H1&!zuM0~VyrqUCX?TybOQhAC69~D73_J1N#1!S0eO)xh#IQe%krcxFn~)BA zTzr599E+K)j2jdaOW1?KNBSCFGpg6o-wuyC*fBOT8GU<(^=i8-dwuA~lBVmLy=~hy z19JnU-Ex+cWfQZ;_PV~50EAWTSpT8V;gb3k(h$AZtLxovw*vK~ zVpJ-41@av9B7pa#@c~22p&Vb{(iLvb@mXbRxo+jdkMDPbPOIFHo&}CM3zpsM#y%FU?EBPMe z{=v)5d&$1t75IJ^y8Nf)=BxQrH($OS9UZ-^x}e{ld!Tl6KJRS#(gBv|g?q#c@lTgb zmP~^0&+_t8&E5Am>e@UE_Fmj+!hLuAoCw&RhXH(p-o4ZlfBoy1g;)}L^qsfv8@#K( z{cThw{65=~f;YFGLGC`Q7PsfKDd5}t=(W8zt0>iZe7ACzz~8N_y__=3n;^T&hLg-m z2&8S-&DyBU2}Ou5Vm)C{24mI@N8x$wxWj=$c0bKqFV0&oI4XOFiC6=kGr+hx@*IG+ zZV_vUcZg3O?TtOCmkcr3c!^*HiPj)Ijb+Spx$m;xa0vWEjByO_&-Ev_WS zcW!4{kmZVfi<)IOT|F0}kj@jo@7laPuk~>zAXEPOxHUcG`byLw?s?nVaPbPJ>hq2? zjuqrdCkC&Etbv3c9brBPe~77iETMQ4lr^|lAu43nAT#!&%hC~NdSmrnCL6W~gJ#es zOha!w5oCJS^`hwV>Z24r`aQE}RzUt!sPSFaJutadItORH`Z30pd}%ftIUi_PKi8#; z#I{UcxuGKhlkEO9?cor{y`PpIl8rQ8c(WCbxL=JTr+ZCELipe+ag3R@wJ*Y4DTc0oP-> zzu6qTXb;Bn``4>`l>6$r4e(EBHTy9Tzd1T8#glgjH%nXd@C>|o>xSO`To0|vcKl}J(W90T(yJei!ZWpXXl;c-?r$S+V!)eou{Rl zJY!TT?cJA(cH@8KA76f7@pgx|cbdQdzVw$Yq?6yw{jIb3w^7-4h8KYM*=S0HeLC_q zBHa$E&pOf=sA_XcTc9M|N;YBLgkH51$00J#5mh6{4MD||gl_9%;W9}$Z#&jUNy)|a zk!8D@7t2awF)e~S9O?Q!!Ls%UbbI8v9E%coJgbb$Pc?P9Z7FXG^cI{y1+g2$OoQQF z2UN>+Z$=%zE8);Ir7cf(nG>#Aj>S_^Y~2T$=Lrel>DV4*jyn>BCCc|b)vfeGGILY) zNcM3S_+rmZi^x)u*J)120J;PLzu^lV6bf+KLSXGt+6FmW+cXeSVpuBB3O^WxfvC{i zQBm|#jw!)Z5_8Rnm22#)q;w#FWgJl^AnW`)SvDO7c)r+vW$-4xNk1RXF$l&}vun^9 zL)lDLpZZa)%WF#!Al8IT&Hv=Bd`vJ60KRSTnx&0$P2PXBD#kXX5^PiA$P3M#-G>Tp zEkayEZ&-*Xba9DvSBQO^F&kavH%H`3qmjFLK8?2N2-Dr(?)8yx<9Y6Q95K1qBVM03 z7_=F#K6W0Qc_`H*Owf-#-G~_j_>GN0d(*POcaNm)s?rqFv`Ycd3@F zQSPe;x)rXziQW%`_vMfG!5?YFhYI<3REVvErEN@g8Vg3#`LbBDk3{GFY|ED$&)&`P zypWv^1h^n;@OUMA>iB!IyO#!(2e(3FK+50TJRt)1^KyLmX2oPh@4lS(RkGlHy@uU% zspfkvzjMF#tRoeZYDa~4pLINdH(az+?arIh2eyKbosx5h^AHnd?w&)q6uuEnLbr3; zo|AYkufdO8!)E)*NF;>eOurYXy@cOfVa6YeMLKoqV0Uqw`pJm(+de1r_vvj~^mI%l z(etb86_hM6esd3lX>xp^uAj)@*NTA|rfG7(pycK7ra*A$5g!>q@v^by<9r7v8rxpQP7RCAv@gk@PhD#+Piwjn^9xauU1bf2q_IT5nxwTkO^2w> z*;lwgPV&)9Kb=-Yefuxny6DnpMvhj+Z8cjSiY)`PffxZtqCz|>^x%B0W z_y*xF%_tAB@9*`LtZ%!o&LwY_$@lg14S{M6=W%bzRY||sw37Qe$rE9FWfNzebpN<^ z^7XyA%`%PWMOk($-ppgYIsWZJvL0`4{C*b(tqeu798=g5G6`HQR1)O=2gC01=g;4C z2tHan`5C!Z<>&mzUxf!W^1UxRj~h+a?cK-UT8UrrcVEd-C2J;cR>EMb#l_pay3)NM zyN0*qRy@7(WEPbQqN;{PYtQwo?T*~7lq)%sb2EHbtBQE*3eD+89>QMrQ8fX}cB-7? z?b-;VA{b8?nnAr8zDJTigC!FaPZGn4;!w&Y#H4#u9Pi%xscsshUIgx{E}83_Yz)M0 zr3+9eB=2%>CGcCqF)P~;OOU5zMt)C%w}|T|VTT{--AY%WF@{$zQG5W}O*p4VuBK%j zKXhF}+uI9o`V0p!$d!A^v;Pt?0VNb4;N3wD|CWewqq!8_EV!1x&7wt6;f_ zwJAFYKH{Q%wCWajzvI8bfZG}YE|yyB&w)l@8?{Zn2u<~HA`_oUmhlAI{*Ui^hp(oT{!fkAG>G-mt$eDTb>{8h**JqLoWPX5s zU;hCD_sz{}D)*+Q_oq)MH$|4*e0@kQDM9;cy+L>_=Jo2S*u80ua%nnwx%0=A!n0{m zr7WKl^Vw3xXfwa1uHz@K)WzS4*^BeN*2P;+BJ}bvY%W>H$>Tq?E$9DTgc=rh-rqbP zBlvkW&g2PMRCAA@!tP%;kGA@Oxx zZp6!V9JY2>ms6<1r4k0B)ozfr5#a4GuSQc2y*ZRp31Yj^Td6yQ;0c4bYEqzo2q~yo zdZ~%T1hMJl;x6hFuN(VVx7x|V6dgb1L+e6Jc6V)Hkw{s0+q-zH zwkyHDi8J@om4{rG7N!nu1hNR=o4tCBys8-;@MduPJ8QkHnE>`MS}mZf5Rm#@=)gU` z+r&Y;kq!GFeNfg|(#>GJ)@{2M!DQI?rRvhdP7u7?%+EPPu#bLutb%sU$_av_DhA!n z0s~+x_Q#FxiK$l%Y40O;egeV58tW)Dqr)%ZvNjl;4m5gd1G>9iZuZf~A8O;q5F0^! zOaWZeYYck9y5%!b?>w(oMKuBEuh6T?iIA?9sq&)051IPd>7=7ez1uw`+2s?w-RYn?5xvo+i5c<`M(Pw;+RMmfrJ&+lwrmp@*rJezkOKf&L9b+t^p@gMW+ z(VIElE?XP$?udnl9yiYgmrt-_9x&e3u_d32Ms_Sitvf5aa~l zX-}klt<<|wt;1PaWta(~5Dl|#RD`Itu_wu)u)?onbDGIJKC3)~<^s5|Y+ zns=h0h_&KiR`#pVJyfuD(WDa&aZ*Vt2JbA&K49JG(lIV-z$lMTNo1QOHY>+K?_AHr zJl9>_mgr6VTUJ2OS1`HOOytad3z19o&Lc4=+DOrpoua{RQub<;4x!PbWSr@j~q>{@UUZ9*K_kwdj&?fv0xnxsP_vIgq-Lif` z+5K>732moj-`e8py^CA-K%(M7hx=0i-WQqg9em#5(dF^yn=H(IdbHssf4}pG)>Q7i z4|DC{p#<24Zu0P~@)5mT^6q~esW__N;S`kUEytA1ze9F$Z|y7UEj@zLA$Z2MIgm|w za!cUd*4kk)yK|>uRTZAe)IfH01G)8)>e3Qj#)I>Z$$n%f3aLxPou9Bbn2W~1Nb_WXQr@BAWyqz$noQaOWW$khh#ExL%2W`VrjQ=SV~Ncs zhniO^bvi?#;{gCYIjNlBV~Iug7|hoQnKGk>p^AA7y(?R8=(a??T~3@K8lSuE;3Ko| zkAYE`&xwVcprB^ecJ8y zdvMs->%&1{I}?|MZQVi`S%_1OLVhDYI>>K>!-dbQOc3(v!y%NnmEgaFwG{3@MkrZf z-zzqf>nCd^%lQ42?a5`<&Eeel7AWsoxv!py+?Sgtl+WFRfAZy>E06Ygq5s#?BzWY7 z<+b!8!uLzJmu$|t3*Y)Og_a_^#bv3H@h=r1pS_xTUK+`QXJy;oP_AHHnTyVYK$ zgl;K#E8s4{TUku_O?5iE%l%FnX@Z$0cjjpox%)(0OY#-!X8cmSktyio%o%utmg-w|~b_w|oul-y(A&nlbTlU&&PO{_M`4hBCrruA7WhnGQbzy1~A4`j`|ztYt$< zmEYk-9BJ|G46)vigaFW zH=0cp^VpefyOxW)uU;n#o+J4cs4Os>gz?a^BgD1P)j2cnTm~QTpq2w8S%INP=Cm(< zBzAi<+g^_-Sw-sW?^~a|SuetQbn#s&B`bcwbwkP3y}0hDQSJwVr~YZEz2ZKZ`(~D| zMDpKP`VhU`?0nrR&E3eKI(YZ)&AWF;Sj<`Y1CR3TuGM$%_6o7LC$|0x&G4IRbDkgH zy|kP2kEPWd$-5c6*ZhGPRKiJ;bAC5(zcb+`@Fo^s<+mu!(b{E&jwIhXONLx z#o;t67O>@7JHnRWE#XjD;^L+>N)t#&hLzyDST~asgT9Jtq%kAEj{FUwPX!V9giu|K zC-~u@6nm$qv)%0D>DyL-=1i;?*#W}Id22t{-7>b8@T@T&V`07LqkY#(EYq^pnhmE= zslEki2DG|F{^jTr@J;9UaBOhSQi;~m>t`XGo9z=d^sWn2Ufqibsm*PIRuPqjHDx=}efN#N#|2co?FG4MdV zJ;G`a?AvQQ0!2ggn|m2yI?~1jwr&ulRv^=)5IE*+N`I? zrH>#mh%8g_2LShS2KO@iUR#oU7I0r}*0?1?-)!D{pI5$1lgTo8uS53L2HyR6pV`L9 zz{{PDQ6~SBmy+9lK3=w!>@2E05(ZN25cxIBkbMa>T=rw~|hUxZ_H=T*gLW>YEmpYD+VhJ6@ zdP0}ZKzo8;FeE2O--d_udzW08St`13!C*gN;ja%4D_)G8Lnl4Hfb3BKp+QHHX)8I{O$#-cB8?<*4QOc6%ST z?m+XrAXCtta8>2h-J8*0VyT(T9fEol^cwa*m;j-mXdVmT9898zV#Hu>5iytUlQ8Dx z_^Oh#aZ`Xc-hd^tbREkL99G8xlBmYHTf6l(sLX_+9qH9#5 z3Kumfy`*cko9!ZqieAwx4czdhce%d?yD6CTF#|OL-D6f%rhOr#E0Df8Y#k?1yOGIg zJGC~kT&Oi!bJ%PS8g|Xtrr$5)Wz5=k5DW>q>9@sQ7Dge^8+`lYAP54;CO}l5s5b;I zm^)B#miAMf-6J{&HFDjJAFBRSdI06&6qPp+Kb&@O`sqLalYskh_tQ_ir-L^8|LC9z zzc!2SQ|$Za;PtGkxA9+69~)zwJjm@+oRTR~$FLi8YJ)m7={CfHx!}1ap*GibjQE}J z;@TTBxNkOr_VqI<_XCXkQI&hqW43T~UtO+;mONNz_AGnJ!W#G|p{h6Je zK`9BmPFu^ej-${UeN%+qh^3xN*}Gaw-PMsxm|b;~kntOcjJ*F0o@j!n$DGY=f?_kx1|G}3NgWk21Z)s(6RC7tg7p*GL21~QT+g)R zw2s$vx)wxGBBb=k3?aRXC=_2vQ3b7N#FU|r5?Qa9Fhu(WeqO>|0t@2jUF069zzE!I=3{?yk#qj(UoHjLAp$lZM%C;PYkfiR# zEbVI-9`C)&aFT6eufjse5>sdHRwKq~pR$9SAsw5Xexw`BveBiU_5ssyuAt}L8WT5# z)56DYahKj7*X#zQ!s9>ATkx}$v(rDVbFSBIfI;;y- zcLCK287U}@ekS`~pz<2~zF99%xc;tqzy}!j9rMhj}4c6czK94}z7~xtf zlLGl<0AE`Mx#D%f9el8$_&l%#X~cSb*8qb|!JV;E1F~+l*;wHq!dRc_a}sR>lxPnzd%rCWvcvd%e1-cMa@g4u`T^VVk)3E88$cty!~yh!K6N zRq4`C(X||+!(op5m%)@SUf}lCR(%16ABlb;w}o&@V44-9>#NNhg7t8cWwvV%P=;1} zReQB96G`kgUCXM744FZI090)uT`jifNhQT~UX7M|mQZqY_2ARD8TZ%KeAks4%Bx5F%)S%6 z|ETP#KOVtVRgUy_&y9NXbdePXzVkj8c}5(>JInpEFF%CUM_X?7%&lf$j@Qz=ms}&N> zK@2!h7{1XTfHP%4MO;Zt`ieU2+*p1GnA6*Br)E3sL5UCy8}&G}&xdZ&Q>80C{>Bk+ z0TJ%U(wG3Chw4D6;2MtFkw*=>by2ZP;RkNbe^z!Evm_3hS-zN^e< zg;&osEwFuA`p%$BG<>`;14c~E`FMgAa70lHs}l7KY~0A>j1;%KVBbVuv7U(|fXNH; z`~%~k05E&IW+VooWzDLiEgmT*2y_KJBJCQT1#ZKNwmIgN;L~mfP3bIY4r_+cZp-`(B0dbprlR)=F;HmT)dFH|^ovpH4n0 zY-)3M;2*z8`Nxeaf!@r%%PgpS6~o8N-t5`Co1@vggQMA-qaPyQH|_k^^Ss;KJ6IW2 zuACSge`{8`$TN}H{p*)EWsu4IO=<9+L$|h2PC8qdQ!;e#!&2HAF)#0HV$rX4;?{LJ>E&bjKkHeUyW}Z`y$TVEr5VHgfl4ms;Pmg5csMuzras1}wyxXY-TV!7iQQfhgkkk`Z#UT8{b~2qbGggS=B+-< zwLhJH8agu9t`}QamciM4tkR?aF;QgA2bL0?0pA7ZWOLsF@ny>=qTQczuBlwn;a?S$ zHfsLwU1%ygC&$8@UFjAP8#KxdNv5MUyRhUx<%ev8J?=Q5RE##^cH6E6heHD;$-Ua3 z@%rWAFYVeSs+*SH6ZY$IjvDu$8wjVe45RFgw1~)tUf}R(R&nmB?4Dn_(2qR9xl07i z%EF0J7oWcUO2z^5Aq7)M!fkj!cmqDSU%-udh!o zwC$@6EtF4l1zxU)O|68N{8?s{kN8ZuF=wZYetmM1$$$KqQ1Z^5aXiP&{r&T5diU{T zRm1oF-O6ord3k;P?(Yk!TZty`mlxyJiVhkpwf+75fL?j?mC8=LgV2f&;W<0LI}6}W z%Eihu#$+i%a3m7~M-sP7D`2u%bf>>bRuFJ2QN{-*wpAruHs~4^NEOFwSzeD-QWX>i z9%{0>jhg_xkt9fTS;Usyr^NE4ju>fz?Zikx=o32#+727ZBSp5%x`I^>h%WeeAtJQO zn+URsePx~NMG%U0%Wh1NYlXfC{gkr>v)rxv)s7xI*-ydY?&0B~L~jqL0eKXz-JER7J2ybkTB96*u%Qni<{T|z}Yy6oi=G!E&{>xtm zhngbb=s44X(Yiphq^&&J*v=7V)HS6TY{&%|nQCR(-p9k!A!zsZAVB}SaX7H-Ap!L- zzx?#eFTX@%i(q^F`e$ykp$qr?*2>ow=8~NHw{+>LN@rP^kP~&*LmeGGC{L&u(k-sS z08xzOa>GKX9ND1=rDG9S1Rn!sVqw(Qc?mzyODCr1U^0yFgyV)U;t%}m(V-hYnz=MG zuZJl7$#6IfEC}Gpz-13)fnGS*(i_8}cp!fJ<{taLmjd{ljFS6&`;mqB%|`ChSn_p4 z|K!?qa$V(q?)Li%a9{oj#gb+0R;BO9pI4$^kDnhP_&wT*>&Z}l_Z1VDCuoY7`LAcPWOzTT=2@19;M-VUuCCDTYPD2N z$}Ct0Zx^kV$PcXQW&V`PEJ>0@(yNRRWIT`LEk=o92n%?cSah<#{y>al)@3?(W(> zoWCQ%bd22~sc|zta|sTM!f8+TzC@<{uwPhFA>|a-MY=?K^%^@2SsdXC2BX`pR4Rcj zTO(Ni;lvUiJQ_eTU4;)~p_J8NUFFOQJ^M(n~shUzoCu!R>Q7A^RHoYEAE9$ZDQZgD^LOIDG)gzhpo@c8rb9~M3J<75rG@{!H!R4|x>2`_WgCbmmcccZ z7&9g(yv^f77g=oS=)6Z6MX(gc0-u5?teAra8M%wtVp47CoQN^?=?fbMb}j3o&J-7t zw=XP_`i5b`w^4};Sop>EWR(DOC! zTHLhR1qy>P6Rw&PP!)~~)jv4~z7c} zk^oq1E?eka{5u}oC<=?Dqua6vpDuP!S^qgbm5yr1v~e$6jn|EzGlK757N|`xzcjMO zB=^HS^GTuT)DLa#a3JzYW>0MUusJqr%~!8#z-|U^USz64rwj!UE6p~m?0aPtxwMb-2iUlm1nzGbOC;Z3&3Ijb?hPC9Px1sl z99^=iasTgx>$LoG!w$^zpF44`SNDT z;5}DO_RD!Co&s%48Uq2^`%)^|?}Yi@ix+pU0Cq3a?y9OBmh}r^sB@CHRJGwUagwmi z5ajJjh1EIie@UXW6n(CxnDY)C=@=YYiBz^Rh|(jr@?kcKcM$u*^}-|FAl#1Cawc!> zU>RP9yXvO=3kI3i5g}s6T|+iBV5=tv`sofN(pQYkdcDTB81Cgk z#X~eNh{rG0RrQseC5R8PHh`or7{W1|G6=2%*B&m4(X(#K@eMnoE=;F ziVobePU)g|EmJHT0auOOKOk{mJrWM60s+6Rl>o56Uae*&Ve;bFkCH;V16h)VUP@4*jtKOKSz(~+Ukh`54dif$?@nVitCL$7fj zgIbAL9tu%JX>wU+;ZLLm(w*db3w@JZFW>XyXxPYp9yTUFAHMvF5d5cnO1KPVd4$Du zIy0$pZ%(bk{cls{>B#em9T3tV{`AxCPe1+CdS7fOrHF@{sILDXK^a)0)0@>^Cw6$to{R>C)061i7l`(ca8 z6GZOEh3-Ei%if6IlJ?4FN(G=hN3$(&e`|KI<|EnpqIvt?{p9xEYV162@4oLd znQJEazdQJ{irq4c>dgvtV=V`>%3v#F$-9$DxJLL?iQMfDJ?&RRcQ#}4U2ay6m_HxS-LV~oBz#C2g z-GvRrm;E@3c0(@#M#YMJoA7^g9XwAtg_xiu(u;hPYhJ7vW%33fKAH*!G*;gWOE3wk;Pw7`~BGGPWY!84eByw(Dht*ZAFoPrJK=0i!ntX;>}+5%n>FBQ*9t z?P8y#uHy@0d7qCbFqEKM0cJp7u6Fm-ri*~F8{)lEPMr7ssm#qn6Ks2PuT6A(8Z+J*6YU4 zjmd{e(~$%iTZ&-CaA8}YG|&|S5V8I{=Nv@D4A2H`d?pMKii-OZYOYLUzQ5e^f? za?G@#r_ciFhRn@cPP72-61jb4&5v4ko!*z9Azxk<)S)Ux_;;4_jm7ppB){* zKllUay@>CguT>sDAp^EtipT%q^}*3fYmUNguw9QV3H!{} z*~RTdJqs)5CU76RH(UuZ<6Wggj0{^~QCW&Go3)Pr3FoWr_*A2@fJ=(4Z*#DNYImQV7$0mf@^{ekJ{c z%YkCkFzMN-ebkC#!1CAPs}=YL&dN${Q2b&l6NC(WFALmGcS(lXCs0=9K$&CVPvU4d*XI>@pkWmXy?)n zJOaP77GIx-3tZp%-3rZu-*e3FRAs11yS?Ap*V^r%BjxTu6)W`aRJ`#!{o<$HuPP= zgxf^Is%h!5)z!IP_#_r5X5nkF^32>G>)}N7>pH%P$#fkeNrYfNSh0Ix$7mt0%d*Hi zRzQpjebq!SnCQnSwux+1CpH^{fOR5zcldH}DAC)_##}*(i4BBX*R@f~8o&Gbs z4c5Jo&Zw9-E8Fv3Ti$GntclEpVRb5I$3HAfVyPkc`VX~~Tt4Ng6uB2V_vUQwdrHaG z6V2QYfcNFv3jCiNx#wc{=i^o6mfSlNn(DgR%ly+)CpkW<<}FoVxaWykdHqc%pLrPp zL_TY2YTxFWdiU|?>p;;12-IrIB_Fr93bAYTCiZ#L?Y!88GgbSlb3mPuBgOkpm*4eyIs&})wLr) zu2ImC5LM+Bdxq#ZqR+MLv3_F011x$mB2?qLjND5Yz75vO`A6xR7Lm4B!@+Q{duZFu zmoEn|2SdA=N$MR04IAUQkZ8285%1r-wX_<#9qQHxI%-6{vTcVRTKzPVcF4$2qw0|(IsuxCzE-VBo=BybWu6hM`o@*>w?=<^! zC6_!5+@(LTB)#{{d%ku)ufV*`k4l&h#G;XKFRzx@AGqH6`NhSHySEp2=QDqH{M=dP z@mdts&J*PBMFuQE_rb5rt2u8Li}75$Ac?ok?q=BD`lxNSc{isFp+d)Sm}{Dwdu_yc zcb5I#Nfi!m?#z+xl_8qXMy#Tg<4NiGQ-qstDOC@-b!l;{FtqGYCQl{2lrB5YIP@fz z_T)&1Pn#HaSCn4x5y!?cMyoo)m`B};4M7Lo7l^>Eu5 zynOlca4;M;t!Sd`-iHG_&t-6QdV3)&t)tn%Ht4g)ALsznOBWBVJ-6RO)g*qvez0h| zya2ocvH{=y!n^gYTXCDYsmQXtr+Zp!S8IcJ$FfU-7`!@&$t|Y@i->NHY6LF%f#h#? zy9S=djbRWFcyo(88(pSE-rI+EmxBN+?BhoDj8K+9tisrKFwCsT7}v%u8l&Sar&qq< zp(=Xi5vv$R(x?rz?w{08fZp|!6Z}^}payCaY%_TCfB;k-MagvNlsoRL3zE}STOg`F z`^9`%NtoTA@^WR?%;@}QFrfd5*9~kKVO?}EFe0@mASbJZTyRw_cx+F_4lO+(WPUkc zaC)^EU0y$X(f#H-cHW_zT&f9WX$#z(61dT0^2A1*hc+lL*E?}8|J-uPd?{yzeXs20 z9CWy6wiPf>YWZb-&X+L5-=n&oa9XJ@2WQ^-ohRPX-<@~2=RZBNs>JTki>~3PVz(mR z^xu7TJzvdPXeP@J!S^zMYO8$VrTG0hbTf9JvA_HL#YL{m>a%vTww{x)$wZbg=&G<1 z0kBn$F&W7uWBP+_Qb258{8`9^KT9<@gWe?0e~4g$6~XO zn{b`!k?t5yBGDVhI(WNvDI4%y)8rO-jun9;+~m9vws%Afccx)hAP-}92}m1e0f-l{TgET8m}7!9=0^MWdZM@&{I*U^S3)M zIz9dAr^9ArOh1@N-Q|bYvL3MR(){Y zo-l_ton`!`Rx>4f)2|-V0ccvl8*+F^tadOAu(K46jR~veXzrZo{eDly!3a4Mg8vT{ z2|A#=*Q@t%?m(Pdc9u<37Qi{MRU&klBZ-AKkYwv*zkHrbroFHQMg@m=O<5xmg=N_d zo8z?T{(s%1{{=d>)a=*8*Z}MxPyvf%#LYq6L;YK?_ZvQD ziXV*OzE8NHv_5%x^?3Q@<))a|r*iIx^Gp8B`|s;1f-<%HxU_a3FZ1qY#{4cqqkM}_ zATwf0=dO1n4TCc#-x@u#gLBaDQWXdLzVN557g|4ma@)@F>Pr01gBHO@?A@q4`|{?^ zTKwx$ir~_ya$iX&3$bo$FR}6wZxYDcD zsqgsx5p=PR==XY-jR`G10ndQ0Y!30V3_+~JVb;j9W{}xZBbneCB|(^txSdzudNvK>mrDHzSuu&`nvN$J;H*GO6p^p%5(+ghr zbj~OIF)tu+`>~Su(hT^O`+^~IUwvJRE4jMdu#9uHZZX+;+S9}Adv!qhr-trDjLGqG z2J0GfD-OQ%UR>bME`PH{jQYik?EmNPeSh1=vSm>wXrX0A6e+&V9SO2XHhI8EiH}7% zmYA4A@F2*7b8vipzl=TZm~)MjkFSA;^cSL)4Bo%~R;{%u%RiD%dd|H)8O3pAS(arx zE*5Lms)}C7?T;cXuvDkLT?@aLAH$z+*f*W<_THs?)u*p&+c~_E+;7R_qt)OR>n8l3>9`>lLD`6h;Y9r15eJ%> z%^QpB;j8(~ptm(uo248hKGIXtE4fM$Qbw zXby*;LFmL9vRe=jizQ3ObI!tMjwOa>kL$=_z2i(+kMLYUQh1EkhE9jzS*BWN8wiJd z>lHlkW20H8ML=B=hG)&@xJi7p83fq`S7gAZwK(Kph)?#amse56|Bu#iqAM)-DR+(k zTA!l5i@k)Q9gXq|Ulyt^5&s$sd|R+LTExEJy?aXc?!9a8S)bljd+m3Zh1PEbz2SXl zMrqA#cubgjbLyXMOE@1rF_q{8j2Ri7|IJP+UM3nerUN@k8kj)iTb}EjsJW~QLExz3 z@nW%+@hn9MqtAY|(F|lu?Tb;c<0&imA5)2FB8X}5R z9Gi%efBUyLb6M0872RZBnKk^igt%gqp!!+2JEosk$1}@K9a&H1H77>x(b>9~%gonO zdRg)2Z5;C&K?+@hzZp?rWNG10R%--KK zmVCX^{UH0^`91^_qjvvX`vbXh;Wq0w)eKvqe^g`)z;r+nkW@1u8mib%_YOuJaR)94GHuqB6Pq{(d0!O zTI$Y+p0vgjp9agO%VPqOA&0cmEgg(J0pF0nhqkx_3DrA_orgdIdQwnMMmWI-4J3X} zA4bfvSaM`Xk-K`5sbop;os~i6WaDubWOyAJ^makL`2}6^k+oL{L<8MAT*+RnEB-HZ zLGR}?xjjqqA}A+PS#P{E4Q0H2VR5R}UJS?M$FmXr*Se@aePZ}tcRUoj8L1n`tl7+7 zMo_v@QAUS0^o6MiUoGnn&EPT8MuuGOo=C44#ugqbKIv(vOI577u|QU3yrCMV6Ko-I zOjLc5x&%}HOYhNo#0+_a*j0Y9IEnTL{e$09N;i>5!aYSvvd8Z1JyuP48aa}U8`hk0 zQ00nG?unDRrA#r;O!Zkm?Q4_Of{7^ec63xQP%GpZa>3fjV%rOBfQ8ut;xz*Nw3E59 zDB059U?XqQ<`t&-{C~~=SHk?8pxpW#a)0=G6ZaQaCqFRTzD2m--yKRmz`WmIe^XH4 z=fL~k_WM8ia?WAhyRb>^zQcj_3seQ^cxgnq}q%)Ymv`|wL^m7m|MglO{1i)XJNK<_(gCPp+VS?NZGiGlD2&n9QdYsLzVrX%}J9O=Woyyo(cSFUl!1;XThG9rdbv48_v;8DZQc(-p_%DJ2W46CVbQVWmJ@@B1q2l&@&60+AOHsV%n>? z2)>$`>fcafM-n57&7=`+2wn&F9S$^ssHO6JDM?@$RHF1fNyNs&@Qn>oMsx7pIeLeT z>zjRp%)Ce9g_QpZ^;*x_g~eSvd`w`oC_)9TGojccWQkh@=BT^ic2m^dd1eI&AdVb@ z96xCKfdIwnEDdf_Tb8}V!1PT@$-^e@`)$GEUm{E^*%LSy=_H9(1ks7j0V6OZ`va*>sJ7ip!g2R`S`e?Ssx{K?U~ap(u%>__$R}rKHTxdAJfS2? z$l?gWw^gv!7x830nkOUUGJ%WT z;xgbUj8VB>)w8~f#GCIF%6oYI&%X@6jokPBfm^Km!|O|t2W}(s)~O7qGoa{iRzAU^4qJJyKUrE{OrTMI1^rp|I35CTTFtt<4geG zF}GFT;CEvdU$&ztCeqCwlQ_K_!8}a(pq9nda(7`koWbmOC(*OM%#&v72>p#bMe+LkTMY0BmH-Eu!6wOe_o|mLy#~Uo3O&cgK^74;_Rj zk_Nmhv(b(-i6|;6PSyf4b58`mw=j^?cYZGOMV@xDtD1gzoX{fGHe7)qR_n8iS`Inm zGoQ+~DjhA;wA5+tE3M|ng}+rlY1S|$8JG1e^RPVKtm9ec^F+Mv2_k|=b2_k%7`KsQ zG8~#kOK;xsOkx1sDk!aQp?{gzF6pQ1YNboPq$7rFeb`vIKW_#6ia*yFS>oEYi3j}c zK`Zw?(d4%Lz4O&G$_G~{@7Mybzc13grD{JEGIjX#&flwun>s#Lr<-lbpQ2LWd*`Pr z-eTW`<{#hPxN`yD!oGiM6GJ^6(EoYD#@XQ2&R1(DcP_6^<=Mz3I(@bya<>F{3-SJS zyESLSyYEylJgOIT29M%eG1=uwWuq~Rp3+&n)e!K;n$B&jNjxA99;c@vTqZ{Go^t5| zK|6tWdr%URhW*v{PR?{{O>MQ63TtsDiGa2kRM4@&a4pGz7MJPRHBSPKoI?8GG}+Kq z0Po1gAZ(@V2%)9~>-13_3?PvoXAztAIOH4NlgDlaoF}4dvj|SVw8IsaFpcV2m$)Yh zAvpKAV{YjsUW=vj5f4$J(5oC~6Ato6j1;Th`4UOqfpr%4M@ba-XN8^n0bOz^*d@ zKc;U~WnCn^vRENN98)~2X5O}(@T22qQ15IiG)2mOIp5G$*3+yI6GTv z`V-PUPl`P`uAC)Or=w9D?`M;Mk&?Lrqa=m(WB0^4$;z zKHKyj)z#G=D+632v#;+oQGOQ@RD#?)H+g}zVsSfJWV4|2 zsJeP5?KU?{l!kqac=A7)eb<$ii81rO`?STr=|Q4fmsf`mtW_S~Yl**);Ey8nZ1{2& z?V8n`I!N%REycTr?`L*LkA>SYQ;5574cXnen8Kh|%$HcCQZVzTi zqT;Uj>9mZebaY84VT{s+m2LJY&2IaYS0*`CkegiQtCcmiB%O8Tnw%#xnkG*tcicH_s@c;?IX~tUWlJ zetcP7peFdu8`pzvS^;R#v|wSCezbQc(I{c;L+R%PJS(W?E!L|?tjw^)4+(@r zN?MxL4mL;rpj|DkohYa9b>Hu6mv}TGwV(Q}(x(U4eo1enS*pY3vR}qaI%3&N1t0rl zydV>J|AW%6oscPm1r_+<>+K-stwQm&%j z)}?)GZ|CstO8gh%Om<%LqnpdsW%OugyKDFcyPs`}&z`-$WfR=3+lC3daVAjBwlb(r zd1l#|RaZZLYFo^+2dmS~PP|QjPdVx}gq{+oM7vGsYl9IwE{TALQ9CsgNhO76^Xc5M zZZ(y11!aq~1TK_08wq6{9>dCcVq)tgkV-nSOg`uo?3$;a1maQJhXbx$lyTbDeb zAq9s9k?lG36AuW+u8t(}9uJ2rZ%9O(i;g`BdBS$(ssPL9Ipn&-o7(hop#K1HId~w6 z8*B60p)<_eXk4l9eSXz4BA)g(a@^3@1e~KHXVsBc(n2~x`4@%&h=es97Zr7 zfhzXQMdP)+HwvqxE-#(X^EUu~He1FH;c-cf&{dz0 z6prR7NTT(bUSdxaJ4{Qpw25|Tod0zBG9Hh+UHVBb7UKzBT@d-EKLp+MYGK{S?ysZU zW*sW3JmsfLkUOcL{FOObq zdUJkx@#?nXy_Mg+9o=1b#bcRrmiF3&-W-DsP)hv!1gYY&1M-o-IYJ}La zY}g@8-3^mwf-n>AAD)HKyv4gcHDTRsCQ(dt=O$TjOIZ=ZUGSQv!3BGoOiczJo!^SY zDQGiSeyR!3;>(x4%ky3wXJwQ`Y1?nPth^M=xal{2g-EJ7k#T0#Hl5CQI1iTdGrSdY zoanNedx{%)Acg?{aBBw^!h~Oq;92ev+4I=>i~(c5R79OwERemAd5OrYbNq(WSxIb7 zyD!h5zdR=pkJszo)2RI}754q^)8!Q%7YpCgS(f=uYi)`4t%!)iSFJF*e8)@iN<1bo z4nlEXwbcAV#+Dy165AcVfn0kLU2b0%^3QTDWy>pXUYDjL`;`Ey)R;&TAMNYblPBD5 z<7)Z_Z%rgw+r~x?_SoT)AtVj!>Pv=iI`+9MXwg#nW5~2eBplRVHrR2#K;+kyCEU<| z>j{W4swgUp+bHxC4F@}!gzzU&LdN625+F|wCR&wQMofEY)A1%*qKBifTqfUix9)=Oi4U0g z>0jwu%9hV;K`7ome?HDqpYBG`KC$jByMM7rVIymsaKO*l0UrSG_t)2dz!Ug|q`=SU z+TX>Ta;NSVX36AEj>#9Qa&}%-b?wLCr}{49@BS3UA7srk-GrOKr}FCZS$hV~{%Mm% z_#zz)J`M))E^=2t#?L;~bv-wli7AEn9PO@cCNKW}?AfLk=h=%7oM^&D@%M(6_m*>Z zMecsf%zKw$I{x(IyS5cWLurUv@DvO34YaY%w)ZLtukA(}a&TZ66X#t;(z^iX-&CaS zDOzDAWNKE}^kj$F)ZZ z-SCE>ka+rVPCSvT4d7p3F1hwb-mt^9JQl+X5oLf_QCF4IiGBb4yw^_C*qYhcE!nf; z9{s|1pO3YDQ9Zq?${%}sYliQ4?|{sc=e9?H;V3mS&J(ts@KjWG=ATw0&w^_HuDtNL z$IEweF@k@JFV>uY+v&JI9cM53Ph0+#SJ9fq{6w-k;J7YyS#rQhHbDo@4}O;zsH?(T z(sqQ%ZE#!m0hSJqR;#-B60RK#3;?>OvyHG7Ef{bcdNz9Cc?L)~DHoy>f4jEoiO=Yp zgT);>TPYxMaE2pG(|iEP={S;es{~gya66CaUKbVdV_WmH2gHI4^95<#*Nyn8h6vuy^ERZCTY;X|7NzSDC+xutgT-->=Fe&%aBqWM03 zIrI*nu1=tP_oQF~Ipt&P{k_hzFOcr{(mZ*+-Gj3o$$igE^8Q}T>(|dGzYN}Y^0~i< zvW4wpcs6(6wR8Vo!`aTWm>bnkA6;z}53_YyTCWGZU5TanofjXFIQXbhUcP$u$PzpF zMlIj@>BEN)FP>dK`}dzdumy1w0Q>W8kKpfB4dad9pq{Z@BG~<3zdm~ax^HVH5@qsM zuGIz;d6J>&Ka&`$!Rr37l7pz~DxEM*Pume{h9wjbVJ1Y<;5b>atUcX01fhI$GKr)B zaYYVp68PpVcdYgx>4WIDY*;3SXs_%DGUqa96LH)-pAeKpPB}h5Y91+A4wK3XoqpWc zaewijz4V0bAePA3P`+(%(~9PKN#c20tiBzzUSdp&dlcSCnsy{y^n$af3gy9$GBO*~ zUZ)sxlqleur+o}y3L-i(PtvHeLqgD1HMOuBI4k@yE@4z%ls~?^dP;B%`2P6rs(krr zxo$t#Nvk!qE-v;GtXM9gNwY#gP{xG(lisr~EZ*Q<>ooJ<63(o7mEh?|Q`Bw^`)?;@ zR22+xm*pBjyR8->7bI@UoBcz#asGikZloR62Ldn_`IWSpNxQx1qAnS-)B?H&2sQr6;Ht;JKyBYYXf~S% z8NEITn$5sRk+Op|dAte&dVP}9JLvtveh{?q9_`4T=(#&ww;W{jm%jQS%N##wW=K9D zT2A5D3t#1~)u7+;l5cwy0E1$C@b5Az8!s}KL}W&e+t;SEy8)2-7Hi)VnrUsme@2Y zcniCx-9+y54zak2Z&~pI>ga-iYsul>bcQgY2TazzcUQgM(;v(A)k`b-u}5%zxz-b9 zxvgSdEu-`kR&$oi>cZkBqdXUszOpXl-*ut$5+u>Oz?9|3t9bcw`SD}4E_?u6szV~L z7a!koZ0u;0iZ>t4`8YT)ydlx;3E&R9?O3{8%F0b84!kucvQex9QoEGMq(_}VQ)#eJT1^XzPI1QlBu z-?lg{b5{y&c;^YvX&HWutSXM9G9{9%A!v*z3s#^7J9}N=Hr?86?qj4#-)I6_yfpWl z`$z^OkX9!rgwzbn4nTRIE`by5I}TxZ5HL*BO}HzP2kD*kx7j>y;$DRBM|6D*D0k?Q zo0FsGM@L6p`imn)GxN(}Vtvj2jV!&tf3UvnK_~ZpXW-5sw{zbC@9(2u;dAkUJM8SP zW3wL)GWn*@*hEoH4TReb8wpga21f^SQ~cDlPNHSlguG5`RhwNV;MS0;3+y@)Cok%RSdeSF zz9Qy5WesIIoe8j7cC-qk)yngTaW8G0@4kIYC~*FtPha+WrL7&}l|eJm`YoY75fN z!;oz?BqTt(zRA~n_*o4hZ+z#9ZRv#Y&iyd=Q{g+XD-yzI)=x(@609?l*z-jUY7!K6t zfhRHbfKi;_-1;ozu3zqj18$-B`@8#+@9$-p{3Dw=G$C*a<4cGva7Ki}D? z{Nv5=zqOOgjk~*NJ^JvXy8Q9e$46INfd~tE>O->glER`sc%29>JZjjexzb zv#89l@^7Z}tgeUO+ReG+?S2$C29FrCcL#m?w=aPvyaYePxbiek5p2>QY=^*xM7Pt1 z6y;z>88!gl2%T!!H%$v%Cu48jAd(6U((?*i8jv}rg>57h6ymZ|@Fx3Pt$28u*cGnw zuXknhN_?LP*JKu6UY?(yPv{=YWkJ-BINumyd1Z(Np)~WkP?3<-^;T+5k6)k#%l16? z4g7W%#*PHv(r`AiluS5RHUtK%bGF}qqC*5OvUX5 z5#b)4X_ldrzSa6T%v@lsGWm$fVqV~9?^By{dNV7#Rg$uf!hHocrFmE3Z-0JIC ziw#^cgtx%R=}`!#SrTDErm!kh9au?K;tr*@mKU;DiSOJJN(qz}Cg4l0A#xB>2O?(> zP6q&PfbJ8=X*m!y=t8#z5LxJh6*_(LiN?z%NfIufLD5z|TnCB6c6%Q%p9X{SWoPzxassJ*GoFBGmu!qG~_A zirPO7*qDn6Q?J_iOJv;H`1tNAog-GS4i7g5lfzBo%I{YV*BP*8Soz}BmPhc}>s!#h zd%N^3ZdBE5CYlN1H%j6grsRxX@5cQyCf?nTPq!8;nR*j^_v4W8GKQ}^!b&9rZiDBR z@OA^&?NzjrKq_MnSs8nvIK4r;;Q}NUjyud*1BX{o41jO|@(0e0(?nH;9ffpy|CWAL z7UTZxv@z&)(i$Zs=a^XlR><%0# zBbc|b7qt4}2V3^=JL@%vWSH0NEaurMvcT~XTw{Z6e?I%tm6_w)B-M!zREG_gH%EXMy`7#a^A`ra#{Xo%%yh|yt%n967HXb zZxQJMxsq@fD>++_)+02Y(Ki9kLG0CFQ%TuO^Etm2L^~s##^jUm^@;NYc+IRjptl&n z>3j=!J<*V_PXO4!S0ofP_XU<6L#FqSnL!7Rux&@w5mrz5k@gADf!~l%goeu55*kH&PmcL0r@(7Tx(Y-!)yr2Aog`~6+S{v7#!|1FIBfo#_Y*Koe4 z5#=^?o3)&qqOp52$v*_%!0*V4FVC-fm$7yF3d2kS=8rFSE@x4@ch&1%ezY2|ZaETv zi=&tCdSxYFE=c zA>K$6JdNXWFd*F6-ii;yK^($nqSHaYot5!Q#|Y&HTC;3|nAZ?^3uew;!!n>m9PA1! zlqPT!5wFv!mCTSRh$>4k>O%j(V)s-OaRu;a&<`P&Mz&q)eoRz03gbx|Ca&<55KOCT zrmARheol9jOgLMY*xNyFH}~NVJ?}B6r95_BUiU$%qo>}$K!@3-)YDi)b`vW12Xy-+ z2%{cJ(HOcA!Lt=>E9iC@LHV|%vUll+#1dU1e72eCb&3MXuxS_}Poz7}7UQ(n?eeyc zv|2`(zrmu7V61|%8w)5Fk0=R`w|2R#wQ_al_xWIRk(9k2{%fr-uz{}ZrCx&YZ@Wa+ z7Tvg9o`8Fn#J=BMrk~!$YiSIY?y<_|W(fMW5o-G-v1j7SX;}fPD>N%$1PSK_VKDqC zZr&mkb?N*jb$I!O-hp@NoHuPSNUjYgc?*!uR&$%b7DcxQP_vN;I9f|6AS~eMN3u*9 ziIlq2y>pB!9gPNef^KZqRQ@Lgtt)55z0 zN5qnSL*Rvq^VOgRY{!5&W4Hl!0qkbe95D=AKW+w1BYER5@_zx{^sHR%SR!*@8&jaU z@&I_he}Ha3RH*Q6OE{ll-}fl@cSX9l9VTq--Z`wD-G{fsy8mJ1HX(wKq&B6IvPAM* z?@{{&5>igVcC4z=esRZ8{yM38M6;~+hr{1(&AF|2Z&u>pi`}Shir=yj-d?MezBALC zv&#;XPo;IUT1m(~I3-fsA2j-J>8;(qEXbQ6@APen{%)*R#^Xi^=B?@q9NW@XW=S(#q%I(bWH2YNP(8qwfoJ2I(P90X#!k0qqr8YRevby2cl^PY#r0fTdI^~Qel zcx4aKQppM39B$#wJv7zN3*=J`y*Eg9#+>twH)6*$Z|)N_J-dMYt;pG_j57*gUcq~v z^jQc$p12&=Wm)M&P5NoO4+!vU^wv>ZHs&1yQ!@-+%{FU0aw*zaJ9Apc3m24txwdHAr}lXd2`p&u52E+?2-|nGZZUS>jeh-aQB3aa zW4^e2{kr|^#qIo(ou6J^(ygzyZkEl?509#fPIBK>gAboy&8f$gcjCKcRw<&%X0>t~ zyC1#Yq`y9@3o9AH2fSN(iIk&c!@3#08;zLAH#h0rNG3$P2jPHldx53O0hoBhzJ1}! z_*G-IYN${*=*-?sD{W~zTTOY%#uj(Cv7i9Irx;=K)=sXb8=;)l5{RGUb0Rr}Z;O7M z%;><#S% zv^v&IMgxs*I4K3C{n#*MP2>^3^m*u)IphXpN9Vc>2!_(k&u!Q|>>)io`&X51LZ2epD!yF9 zzi1KepPcYR(w6`TC8!2_#-A3UE&(S$1^%9~=lz6tFNHfdk1=w@K=D|{i%g9Tf8J>1 zB75T~63}PBL+`VG-84dYvnJpymf)f2Yr?H~@O>P<9Qp8CIR|z(iDw4^QSCBwxYvQs zM-+Cp=r9gXk@dmszJJCJctkB8s&|NMNjPszzwhd)Izj4D^wqYt0M?(2Jl%Iht?8$b4qYH}O9UvDi{ z?$)ArpIs*X-QB_LVq?H}r z>`B5NxDx4mrNe$`Rw$=zJejkEJ>~8N!tbcYX)a}$O1hB>r_5#TIE6iscqpCCA7y3t zJhGy68WHXH#9LU{v$F(#1Xpt>qYmB3ULj`C#fuB~VP{AX=nX-;P0xY{;|WKD6P`b| z<|~NUTr^LJ-hr;tnRhz#;p4}iT45)f3v=P%F6=iQgw1lgooAa_rEL~Pkt2$oLs{Nw zfffc&v~1NEHUtL+04g`!8^8A&+#8D_N)0t$6B3ku=9JvYPC3 zgjgYQ%~rl~YT!E-(s32JQIJup$cC65Lgt=b)bPD7mM4&j3-m*x`|*VE?If>38!Qs2 z3Co>P1;$O^CsfS=qzu~*loG|0#pL25kwr`SDD)5$#xk}S?9G!0Bj~h}I?WXaiohpG zX3`rtzSCkOxfrp1&}Fn4Z;li6K&))D$ev|9pkxPMfCCF-Eejn+6M^`#&k_n_|Gs1R zcP)#EB;p9u7R=wjf%6*FnSs}Ox7-V_VBazbWCgIOaiT3|LADq`@#5VGO>QU z<0yHkck&^nUBfGAHg)W%AyyQu%wU1XlGX+ZHAy%-iqTLn zdfhQFE^?}~!bz<5IE-SYoaVm5APjJDc9xtF=FP*F_6fbq5?g?ti(qee2yY-rw`Aod z(%Il~fGAP~vB*6~2G(Pg(@T?1Xa0sy0id7|)OWnc739jO7(EZ9Tsv;y8=e&7e9LAT7~1Cb3f^CQ%Hb!{E2arszA zkutty`P#hZ1Hk^xXjAUr6az}Fx8QO@-vZbU`AO*vN49bId2@W!bW}?}$qs_xpm_x2 z_vFahiYj@3$H)Etp}yeTh40_ih4UHqeOKqc{!W4WCinGj0M&onl=2S&x7o_yvIzb< zfJS=y?6=>oUa0Ne8^N0||MlW8cT|%{w~QujkxPtX!X}eC%%m|(W~j|Mjr$F$9^R5m z*bvw#W7tX{e20xy7?uXM8|0pqjpJeIi{9Y7W0U&rWzY3bl4%L?|B5M{l4zI zHp?Rx2a}-63;ddB_Z#e!gFs?(I_Ihbq*!(47(;@0TOHnPAp|cvlIso3?jY#|N#9r} znoBvGL_u@LH+>frVJk`%kTh%O5(ORPe5YJ5^8(nW!fb=yCGzZoly}c<>G`Sjm^{t1|16b(g%muXp`E)`6k$~y334o>Rf!O*)aghg?dS;~M zo>+{wjyUmxgM$M!x(kj2t>MZBy~fdvg>o1KWq`;C>IYB67096M3n(`YO_ooW%UqMb zl@6eqPXh$YMYcX>Z9Fi-3O{g7yoHP70h`Ax$uxOz8PG#Q7=pk<2ReG;k8X~GU=sK^ zx?#c6Z%)SaW1dWojv%Q(4bL3My1on5?;l{^@9)F**9UWd3B&Is27afcn;mys(7j19 zssGu^G5J3Z;1W7}czdn##k2P7XD>b>8YdX@`u}Ay>S(tGVs2B!DpNYaORpf({!K#8WsavX#rDl&!?sq8$=0IW>AS zbeA!JyVN0JcsL*OHcpvN7RsA*05oR;<{o_#We-~}=8_!s4SC$P=Pq_HIr}8Rc(Oxp zj8Lcp&4th%))NnbR-Ob~VSZ`BIf%?z)dFxUH&o1#S*mB(OJ1C0zJo+)9I}W}iyEMo zs-9X#ak?}t8{$Z@q(?%UwD0uOl*2)Cz&8*7cxorHTm-*`II|mnz zz}yp<=<*YB-f^I6k-3RZ#ZiQF#kMc@P}1?@yaebxsUqiy@slEeXE0;CA3V;pLgY zVK&UH*x7je@>VO56&j|-`@*mVyK!JJpzp8;T)f@%Km^Fg8^Fg0iGaeQN^KexdhVD* z4~`}dA8P2!G5eSSe_j|(pnZ=6-yef(2hF1($i`U3l#NWfb!@%=tc~O|hQXbGuny-= zeek_D%I^!i4eLJK*@o`hX|I2ZSh5`edoR744>or-?+4Z@Z|U6(-TwnIRogxBr)+kZ z4Yov+jpc-(d$+$E1HrlI%#0=n{dmyl-FO*Y8o`_Xa+i*M+D-XFg4A9ZqEr-Ztuqg6W&1U=MyJM4@poaMaHJMlCU`I4qR#y1O9$ zKEEGGEvmU3CfIf2oZv_+>pi){)6l#&9P(ETXx>L6$^nkc4)O0X&o7$?z9Ywr02qGM z1$=*TM0smA`K==Nmx^${uS%TXRZMnjE8y)~`2UTg%CCj)pAYY*ne2QqMeqTeNiCWD z^5WN5uWngQUO%GqX{;Jsv)ygYWEXlj#+Bt@_f$+Kk2pS%Ltxu!+1NIjn3Wy6Eo`?D zY7$QyVO+)osT7tB!I>?kW+)owkSPZA8A0?4% zJ^JG1`B-O>?vBG**lt9#Mk6C=kHfSV<0xd=DPm8O!2)wW+tSE`9Vs=k9xKi#QB|dM zJO0n}@e17AvqEIfjcpDEBn&3}oV#y^_G7>`iYkX*C-Ge9C-lq|mk)P%q}hS;Jra|N zCkh0L(v;WXi6uf%2$VUx7DpqrwSaTmu3ZN;{h(2&2}KE_l4#*#j6=A`GU8$b`r@=M zeLq)d3n0#262oqVPKxXj%s)X-6H5_Yjucx`aD+0jz1&2$a^ztJu|~Jpm)!zb0whnA zqjbmR6IL_=NYEHDLiV6XLE@7Ogm1xa zjWr!UY(Sbm@QEWkB8Jp5I}7dN>|-&+$8Mx?BeJzn=M2Lvg+q&O1;Gh5o`p zLx65078OD@R#{lnUoot6B`(No6*&aJerT3;N+R4Pz&lGbB(v%?lbAxl_L{JhscZmX zFJrwlr8aa(#*(Ckfi3b!ltxF44>L3(S#gv&Q5%!Rz7d=mevBC~Kansk&NLzPsz8HT zSI1yAS+g{v=z(RMg&i0UwsTsdxiD942B6_|@&MJ|4~${Y4{GxYVL9}X90*;DDrUrp zwI6K0x3Jy9A7B)izz|*S^X>S^15Sxz_+`Qj3EOb+jgv(9u|T%3gZ+AvnH!l#cyrTi z!9Q_KzM!062=R9I<>8Onh`7%piP_BIxA-6c*@Uoqf`7W*Bgo!F#36JepfE>L;RN4E z7>I0T{mvfFA5M4uV#MqB4BngC-c4fn%>vHhe@BSP{|3$EOK~Rm@=R`cH=NzL{QKW; zvIB3$cb_Kd6)x?haie_qA90KcV7pOgzam92Zl`I#WwXoMr7a%qC?V zt^jL5l)sFZ#9kTXrVA18*$g;4<;+2@Ur-U<#v$FBMeYzE2?mX1Bt>_%F<*qroi5Iw zw-=L{Wo6HsereC5*e~OVsOc<`_Jx?>*k0#w1!~}q^NnT(0_cv1 zreSX`y$l>=TO_d5cuK3)rclCT!Mo+Ms3L6=z+s#7tdXLs5JgQ`ZRe#nBgQgy0Ny30 zmvkMGdPTw_Nm8iDjSSP4I1+O~&i0IrB+EQ!oyKjo#52g=la}n4Fk;vKX8@TxkqeX& zlsy8!aZk}z3Uhd|_^lR14_;5vkPx7A>^F&K3sk~XvcX&5&#*}@wiQJ75(oD+ySE`J zWH8-4Aqq|S*J6SV+qE1?AhuvZNBku)is$rM93Zp9OG0!P7lMW_hY;bz46h=mI5(#5 zo9ls4@4$#Ec;b1kjP(z~RUnem2}|DW6z7M;qZ;1{EAAq&>>rEw#87bA(K$lgNrpE9 zCzEfJ=0i}9FBu8q*<^g+`_^Z|UcW^u`AYD<{$5vc?rYtLW)c2o75?x6mE`cxgYE}3 zlf#|gwVBjC@v@q8{nOuGJ-gL&CcO+>>D{{xOIp5XyX^Ar!{WUw;4QRUCYA$KL-fo3 z>8*wMMi`%_W!feLkv9JmTsWf$=uK9TbCZujGv8WUpsW#89X-0qbjhVBD~ zWf-O1-qQu}F;`1pLBByzUi|#LZL2iv$8pR7-EUSzhKB`D8(q4E4dPs))0v~9!Fy~I z&mOLjvof^x4?obs06p;_-`<=ceApRw68aj4m|Q~rCNi$rX+q2&Vu?pbAMDu8rAN77 zRbPxS>}V;t@Jlawe-hjpbqesumSkp1R7+Adm5T0Px=mbbvXNO=8>Yn>3GRPpPaLP#LYd;n6j*ag z@`T5cP8|&^A8KAP%|C9Mjd~ouU{&E04vwJB`3RjCZZ;Ki>9! zKeObaoWSe5xh3B#cpsWrr^Ai2`$5Iz!J5iH!`=ORa`yvz_l?Ws`u#62o^1!fZtv#Y z3@0BAX4s2v)ZqPSumNwO-KPVNGNGFg{(4*Q4hQ{4yWL*IA+gzzx%f)#fU9~bzCw)P z9C;@5nLSMilx?NPDMw4M-=j~BKb&1UI13+*^9 z+ubnMOS;c_I-O6aC6e$4sS9DDPuRX(ocG3)zCDZ2TYaBPEnRw(1OEx!5;_cwC&~@u zGS$$qZEub>NPF&j-U{M4(dr`ckT6K-Y`=Nqt+=Has7rV}blthd8QzvP>J(V4AJQXO z$ns{-N++@CL05C^&D)+OYoJRm65vyW5em`h>U@O_8~)`+F1F9WfyHiucG&0C68YIU zu13oxnp;vpx8f{5rT9Gjt^ohMVvc7hRJw9>gbsC}Xp-4(R^j2c73$&Z;%b zxkyGW1Z)f0s04ajKyS-ByFj)UV3^$=HF87HFdL7)u>j_>$&ObTO;)0cFzMCJY+opT z#+ldL8s;->XFS={5(n5~N*(w?eQeu>&%t_Ko4&Jl4h>Ua#($wbNV{j{;|T!e==2MT;_Y zz}xd&`oOudOw7BSf0ALbXkvZ4k^AAzn>&>IemM7cOu9E>_huFTu_ZS3CNtX1yTG2VT~?p@>V9_+>f;j!@xvVO9~y&L_0 zyFG1$r>Bdz1m9)E3-FN%o0@K~#$$46HCCZX@otZ;*=&+pAu-|*E0n|`Lme-Aece94 zIzL}|WShJ`PDZEUxQrSee)0Zo{t=H?WJgb;b74g(K9d{RLSw?EvUbJ6M(iX%S zt~*3;8h7CmxXtKzkXT%7*#VvrI$PeVu%zgWcPkS}!ceujQ+RHBt2Zu@aI~e_Km6bV zg6EyiC`stk;$CybCXS7912CuJD7lXPUx!Ow(|sP_>+z0ujSnAMVezqP>bf0{ZGG2LzP+*`Kp!#|UEZ(VN0lEZJ*yG8Kkjmp1lTH^oT+hvuzo2Fp~?mqo3cl&4@ zesoGSdzV>vY}9Y?@6>4B1m2UB@e6C%-U(C8$H^Y(~puUIRgk8vTbaCfE`smUT5K>){6y=oDZ1GLW&G{}uJ zoc&j=#kp>wjM#QfDi(%@^TPIuywq@-RI(htwm9~in0o4zPBsx%omlJHQdNT3rm&rb zZn!9;3LgkMPUOAzk>eTi0g1md#e5jcmRx$ETUho~gs{pc&TSD+Tg10zHm7p4cLLyZ z1E293ajSqSI=jiY@Fb0)=7b&`N--UZICUgr{KE+Y^xft@u4Ig!Ae)4v+>ij? z9qhwPN1zGwqA%$r^`%vV_N}*pz)i^k6cQcm8-(5-P~HgKa00@NP1t^t*Yq6?40Jxg zN;$M_R5`#T5}1H)<2hu9ieFbT9GhH0etdB=ayB?#8$n6trAOW8M@Ig}YbZ-Ouf4i0 zCzx<-)db{woZ%RTSJtIc_?AibI`qpC3_HK^(`?lPDgoet&V3)xAlzZYqy#e24o5z=@QlEqH?!n+K z;rZJ*Oxx+A-wzT0%H=uSZ8npZGf=%LvBjw@>`bFHZMR?cdY5tk`8c)Jswjw!hO2n8 zSS-@8*F8Uv2M|9}ouz0R$TFMAXbQ;G<9LRC9foDy55cBoXP#Z+Zx`Lg`OC03)@rU$ zZ_ErA1R8mTkQdUZ(RLlwT+0Y(x6U}V+X8-% ztP!1Pj2Cct6Y`=pM=3E4CftOEs>rK%$j~m=h3RTw^9kU!4)VY%4V_?P7sp!XWu7m2 zBa==gcrb}kgd7FfIEZMeFkFT=ZITEbq~l+U$$7CXYyxLwV6{{M^#?8YmJw%MSGxzg zRjk1fM7BHh&^ps^y#X;9&(|4Nt;Lm|y z0)zbkKRJSBM)J&Df}8;w50_2GM(aR0HzGl5k-C;6v}&2KKeH;sE=JjQtZ#yfAsk)& z+(BK5Q&aFQrx-R5ZBqQAkUIc|=*MKhZ;C-iksjwWoWx4wNs`C0b8^8oSw z{-OJ4qnK01UzrRgw0_!fn6yDTHr zZ3}`dl~WyLw8!xUFWhUPn6Zxv&ae;ahRbjf)!{Fq1{|m&+0f4Z3#T# zUSi3C?TqGg^ z?eIHIL@E(h9H9tdlqM9qHC zu?WrLhI}rzYS&%Dc}o#wOGXKs`oxc79EHuy+-88BNi$cMjp<$cW@BCsV*=N?T;F7Y zH)Zj%u34)eg`I+QNP|!U(@B$eb+E0&iC$xPzb9iOdut~}i<@u#Bj9}}aO!&JUqb1= zw~`~gd#6V3!-oj>pQf4oak+b|uJSz#-tQ&6d*kgk*S5L#je3$o?UubtlSj4ND0dso zyg5TK9+YkPzUi%)_vFKVJb<%g(3pm+FpN&)#!Yr0IxC}9*qE}<+qUdkQfXFAR&-}e zrzz<7V$ogMYML(EfTBgOJ4V4oZ=;2ma%0mmzJHzVT0awu||$Mg;>Y&GG07? zxrk;ndOV65C2S=JvN6RgqQn?7&23%z}EgVy<`8^O65Iv#-Bn{;jdNA!|o zN!YHP*+k)UXVMIoT6A{b5pX7;J>DEHn#XMN+XoM(i;11e#!Yr*2jI$xRAh(EKA)GI z)X9Vx;8>V$FqUV;q|B&L*~OEbf|tG*ZZHlTp{h!*tO5;Fh9~NW+bGvLe@c zsh9jg$@(mz&mtvkNK1qf(POOTBj(65LJlvr=UOdu-=}X^_tg`8qM1jT^_jh2y6fF7BHT3h)A;S`^XJUyNjqj(GiL$*^y27WT%sM zNGyA1uf_{a_a6MUkM}uh8nub*PUn#>m&+(!q{SXCg+?$p+G|`bE9g^u4(@8NWIF~4 zexVujEuK%%emL=U86!!%gK8W?ZVoB2y_M$u`V~z(iR&rjbbsf&zp3>2kgEE!dJ$pVc7 z7j|6vSVD)C1IYXb>@^u5b)RE)NihEWdH1>Xm38m8Y$e~lh5IXg-9O)LS~%PiyAS_) zX!qgo*i0U(tK8DNe=&OZ#@cOMg11eAH~kB{u>^RZ67$BavQaZ{4y8Kf`r&w2e1c`8 z(QkuzPor`$1BhcxIh7dhDZ2!1HI<5YNjKrRlBpdnwXJ4WBTFOHQ(i7gD7SNrASV%^ zyRkxnTGU8qiLKiyQTV8@;ROs8V!esC&#^OK_R=+=d%cdVy**Ay<@Vp&TF&v@mg!d` zP99>JApS_#F8X|-J5XKg+$G5@EwdD=ft787L9Hi zKCyA-jFSl!9foj)+XxsXwZlWo8qcM7A(5RI^Oo7M+4i5xyPxj@|z%F-=RH@zG5PkOfA<;g$SNfw#Bdzk49R@9W;#jt)Hh z=OEm7ZrQ5j5v3_#I7J-QX(@}9 zXgXudNt~uBrwPUa=qMgug^h4E=wr*WF%_E$%iU83ZYU|DcLUU?(`dDdB7$B$*6BpY zF=%WuZKv9rp&33&;?z!NVQecf?{>F0(P>HuI}cl{upeTV5H3Nr96Q38HZGtH&%jGO;u#CcoAXQoG&+SUOCg99S1ciOn4jq#|U+ z4J>fuiB1lD&cL!+BuVTRJ#}7@ms~)ey%ifvGz0iDrw>07jTgoaL&-NGsA$CDhBR#C zjfKQQRr5)K*&OE=+t!7ZO3cyY_58{(M4YcTX2 zC08&vyD|=EZSOmq4zsKoh{Sx*tkbBRO;`LzPB#NuS=8CT88uEsNI~m6Gw0^bHcn7G zyqisjOEJyhRCai3J0XOVjGqiE{}WhlCL(fkpf`PnCLA~rx)CqP(utq-OTW*3Pr9O? zvGu#ok~_xj@3Hm$EAZPWCOZ!#b|2mj?EbUUOnyFmAOZI9>-H+I@8k%w(d5~)+vt54 zyLY!DV0Rx4IM8HZ7UEAEyjdv`C-ETdBd4ly+J|xi1gFb%ie<_MqN8{zUK}RVJGGUS zk-!^--Q^;-W=S-jwBt|_lFta7!nCyQNX@O~eilY$+Ma}Ad(lYJ9{pEdsVG|6{gn8+ zUQ7x`ycxUrX8ncU+w1)(mrv`xi{xT&k1&+Gj0vQcvWm`V&dtBAD2m(T?lcK|-RC`` z{wmaEgo6Rr-RDqGJa09GzR}^rc!JZR=M~6@wLQYzk#(Y7F!oTX#I^~Bb9LfCe+Ka; z&aUIIjgLcSlyGd8u$foWGhw|v*^)LawlUgL3}oJyNPtMPxhLVa#XZH)z3F`#I>>UF z^UfvK9x?Ca$dQ`KOD(6xQ6yZ4;6i?pX(m0D$0h(a*uWx(=ApS#_Q3aRBDq;q3gXGQtb)wM(Sg9rGIV4HH9D)u+gwN7WazeogiNj|4y1g#xY+dQSB1P-zBc5 zF%g^b*kAe+>x+ZQ8)M1!Lsa|v`>ld^XNn?yQJCyVZ6me^@o_WOMuF<=qV4sEoRkDF!OPut^3JZqmXbl9i6 zrJ;`6D{H<~=pI8<${fNoE5_O`_Vzx0GWebDnac=rcZl)>RFKh&O^B-)C8v!sot?H9 zX_l6e<+`3tOdrT?N#&XA&EGusT&_{TJaGhM_t0`_!!@p!mP&~xxp2HdwctdkD%YIn zZFM@jy*w+G3?VUiL=d-~Oa9&sXv-qyMx-`_N(eI}sa+5dPQ)_4rZ3d2z|*P25|OVe zS9wZ=jd;H!{uN_XwDt0Y2bqa^5Z+hkMxerN6`qY{{Xi;kpl=)pxrv#T+!i@1pnIV%YsiFDA8p#u znj(uIA0J7&)wpTOECc5FVlJ<>^!-4rCbeXOXXTr;D+1>d{F+zcjm4yy`E32B@1a^o z(7bZ&E1-rI({$fY;W-&g8sU-kJI<1aa!dXtpnGd4XNS#!K=C`i?!(*htA9Fl*Y57G zpxrwU=-oHNN~~7??Ug|H-~V3o?%SG4Et=G|IVi5|LoX4uhT9}IEc|r9O#3u$4BBZs zj!l5K>8Nb1SnHn7IKTVWI{XyND8O6xJ`gvz+ub%{XFIZEqOWlor(sfsA>nhDF6lRP z{5+n`;zefb)D8*U>2(=K@uGJgT63<6na_(=s9Ksweu-UFb3*I*slfNU_Ql!qvP1{D z8@ekr@3?N{N)K1g&n41Rp6UmPuJY!bMa3?0^x~i)$FscEJek{`H%~gsgE-RZ6rMtf zu&2$UNng7W2TB!7jaD;)Qxv0NEmPUadRDSa&oTwXMmw=3aMlwJEOD!>l_Q@Dwv)MR z(91NlkTgRzhMCUrghK`CM|Gk^f(Q5;lQtuzNr7q}?;E9sP6C1(cFepTdWgmz zWy^^9EaGc(Xlj~BR|epeEic=~?;5_3m@ms+$IXpZ(a`PV+IdnJr8S$IV@Sp>?f z&bB%5Zq3=BFL#@@N^{Wpg516H*&M;Td*N@dHiY}{x0>R&nD_4P=I`K9yA8?vR8}h4 z78o~XiP?Ukm#Wby(^z&ZCD8us4;%tBO$_1!#peRfN*vI89?a zRw^$0M8!FfDox8wkK2x8t+OB^9-fAAn%Z+KKEHxPJZf>tV%l$3gx^I-c#S|n zUX<_5hrCpoU^QnbjCkI$72&Sc*FK%)N}(|L^paS0HxxmgR>p+Rf}sH(^1*348*M$ znDo{C{n}K%&*C~gtaKz``g$UM@76xCXFfF0v92C?8UaLFbEImX#SJ+3y5pdE%#!r6 zS+W6wGtLvj2Aj>z=B-%44Ex@BNFllYmr=Uwg~~dyyEX^b0RE>Zc7M)ha`<~Gg7=B{ZOsJT z3xE4X!29(b?B322tZQ>>>b;A?vr{vl9I(&(6gsP_B2KQOzfr@iRTAkQln8z0>_BN* zfCi3G6RCn<$!d-m1*?XgSoE3@Y&$ElYRqS#y;n^RO?%b?40+V&BTMk#j<~*tMQ1xFkf(fQbDT<^ z(}PID4vnkSdzW-WWOsNHflYl{f5LNR4t z(A!V;jrJktZ+iC+zAVJx6Z*!L%~&pVJLtZw*DvX7GP6hSGG;OR_(%vgZ$#EPwt=DE z0ZTgCoC>gWkzFQD^K~49cOOZJH=jq;p7X6$cz)+`4dt8Y!@Al&;G&7lS?VCuFb~4s z&6+n{F=GL5oT*G|;5OTxV?lEG46TQ4fp^2EuK#6#`=%0}weG`Pj=+C1wflZW{1@f! z>w9{)NG1{iD|+{Ty?F8KU+(bkt+n_~64lmaP}6Q01^d{qj9EdMRac*GE>}@9n+{+L zWYQfY#YEO}2)?IMm{aTB5WH8@89N2-RoF+;w;RqZOP5afh#Pt10cy-6t%>2Q#hB=@ zRi^#49Y@tHe)@FMm?HXGL93plDBX6kpyP%d5jc-H)*mMBkifgTeER7Iy`QEZFZL2h zC!v5h28IPUswK&^+jrf!ZKB>pqp?`Yo9lgh$YsRd8=~CAy_qS`tx=I!7Z<1ii}hGD z11rWCRjaNS8xs{NwHK$0GFIs#S|$RkW|9aw#WOPa ze9m9E=PIxEr9=^~&;wTyJv=?iiNl|tP6IqhIJTvQ+r7?%=g9!$oKw(Dlf!his0jjou^I9Y%S->1b+ibF(t7=TtMi@3)2rt7+ zH`tS)>HAEwW&aT-bEFfZ7OnPam_7S_Gx-d7y`CT1cWR<8o9awh1&muRhON0&P0B8& z&xZ~Fpegq|2(}6tOog&(!vTWt^T;sUqy+Mj<9H)`Gko6+E%$>u8XTYOcwekF_y(SE z?+{48qCdt%FJXkfm&sWDB}W z2Jh3xuA$uxdNYOuZdJXfS1+I95B<}t*0ZTB=a^l1)DN#rqRF)GiZ`+ef~jDXSlPP0 z=yfM)6i0J=X6f-!rlUArjKgF$OU~k>(4Ja$nZ8A@!?+vMM@_?t?{b~x92@UkOZ@+H z_pZHdW7)PSW7ueg7EMZLam9ke$E5QB5f&%PR_Lsz+N>~W0zxMsG z3k?WRQn-Kp&N1g&q?|b2)#vPoyOqSY9;Re>_2AH$V~#PDuvEpx?2flmDdv)NQt+NW zZQj3s^zPF;i{8!0?bD|>C*bR7cL?I-Ujfl~$GKnI@;_1gpR%yL8 zb4lJ#A3OEJxpjeKg~&2{wIP#$bw}n4Yd#snj951-&PAMWQ;)ujfV(PLEJiq>hxwy& z>qK+HNo`Hy3P$q)MKrEYKP*1EF4ySrGNMc!110_QO366V@ak6S_I*A*7%~xse%~LP!znP*|csU4Nje?uJ|3c5487hM_Ocd#ikZQtQ z!e(zV16a@5fQ=7;>jcfjgv(qxK#y4upFYj{{r=mxr;i>1!awza-cRAyPLXImI$f^j z&>fo7<+EitTn~rAVi*mB#PRZTs3+*HJWznmbGm+VzBpfSNXWS(dzz!%i55!dBZb%D zanF|+x(Tk+)oLsF%N@dO&#qNU?=y_0MxkNXYxgf5WAVnrVZ`R92D5rOmc{qoSUlp6 zSFgC=a>b3r^vg>cg6cr|95hNF-3krG!0bE+39q2xC@urbkE%dfy$`-mucD2&z-A7{X&bfghd;Bubj|5Tp zaz38V=Ck$s=tu+;&zep=;o^YrH4G+mSR3ZEEnMJ^mu6WRre)@pIq~UvdRm0Y_sDfp zy?D`N3r|l=ELt8W=oAaqffu-m;_?`eIJWX;K*WUyBA)6bNCWiGBrI$bL#GE3e826> zM4&GwIp8d6KHi_)DySg4|ip zG1;)&l@e`aA-~@p>nR-3Vjx|PT1qh*(gicjBb5q!tn>Ctx`LtyV)1&)-Q`@q1(6$7 z>zpyG0*#*{cF_pHot8Q@)5;1-CHooLf_4>G1q%8X#;~$UX4e#e~aALzoku{x*T(RfCo=DR$ zpd1UHaeFIHDkd3Abd@r;TlNzv%85&}ZMi>z6ak-SlsV!L+1rObOt!x;c*{A(YD6}V zaAMP3%z{oXQWN8J*^>xCaO;?bZ-Q|N^5$BGg86pANrTW#u8Uk}^njcNIega6=LVC1 zHRRss-JP%dEBiNB_hG5>w%jeN{13lQygz&`zI$IZ`QIP@(n;Q}-hHe0Y|m%HF@gy0 zHl=4T&00KN%N{owcQ5eplF0VUqq+1A6Xk|6kiZ+s-GtX|tO>vyJMn8UZ!A~RKLQ(_ z%)G6h_H(3hXr#gt%}z8xGwm;%7cb_JMnVk?3v`McZsP5!r_z-u+gQ5cF2t_KT_>OL8Jr>AgP z568r=>8Chx>hU>RF(IHV#^=QL19(hy*ep&?##^lneHK_nPdqp@fiy;lyZ~Q|w7sjV zbi7q72+<-!TgCh4)vFtG*~!9uJG5*K;5gRCIT<3*m7YB}mGX%m@vlK*V8`{4wFp0O zRahXnr2=kOwdaOmpep+4hSOXV91&`Q6Z^q2G2sdZy`W;aR(6LR9I}cn^)@cSP9fnK zSYnH)z+t`PGM4co)>l{(nZ$Zi8`dmHh~c0Z26;n1X3`6x8Lwp0>wMo5+*e7SA%|f> z6Egl3zjcWFd&oHvxt!^C$Zo}MS;jm@lpE`T6hWnA*I{XFGQL!s^(;xZz4EISir=(v z*ne#6=et%ldFtoaZGnS1rQoNH%aC_+0OTe)aLPNEy~4P@>DS0QN>TU?X!aD~o#*Ja zEXsz9r9;2T>3_B9R13bIY)L;=PW<6rIpDH|Il@LgzOR)OJqfd z;9E(o$(E(>`HcP^uA!OC$1{TMeA(AT8+9{6n}8zx8BH^A?JU7C@=dmFLV`HQOG50- zW4nff@mN{j(%&uiOcKQ=3xGJ$-XuWxVxE@AVG#JA1&*yc=OBunX3D zg$b#fw=E1}FZ3z`XTt7i=tM37sfwBb@5z)^Men@{p<@E>a5 z!3n_+-9V5^`Qeu}>vj^jr>4Y{63Jd5{Tl8+WcUHM9S*Rih*Cu5_q?o@3(HCrsa)Fb?s5Grq|SoPK#%kU}@ z@~rU;BhzE zqfh^4{(O4$c6Sat3Kk{nlcC2AIP_E2CrEQ;8QbwP6h%8|XwZ&wBZ8>_BT(!XIj;6q zL>LS%7gnrL`1F;U7G*wIPWyzot{X&Z7>SNTA0^+_)aF#JYEhZcCxLGSpGxisH&7CD z^i!hoJs%62ym-#v6dE%}FV@m*hTgN17vz~4Ynx-pPtuFa30Fws26mmtq8m)h z`st@%zuor<3hTbro+I0pXFREVz-^TR-8`>6lO$M1^6V&sv&1gL1H3`1kJ2OVs+^hD z9O&M%VF`QS40893H{;hML|)IGF@a5<&hzW(2rUZfi#KobgaEM~C*ER~LLNubNZ?5> zICPhVmuMx@@`_!|gm^OoyacKXr_a`?rb%2KVBawbl(BOI#t|0v^rl5|R17D)p+2sg z=LJ)mJj-;d+zoOA3HuNdNaqDLB|=ntNw5WWu63zHLdiVWs@@X8W{XM1*@6hClHExY zVFFIQvyN^)W3>zLC`d!h-w=WZn*zB8jed%o?ESO$&-?z48+#;Uu&!+$i9^pVHWo)^ zTdR9Fffr#HCsGTCsB}c{1mN*=eN_$!yNS^%?nNj@dRY_$2q!Lqdo+yPAaEo4%C$XV z?w;g*`yxy7yyIB&xRG9$UWJ2@kcZ*DCz~%qtwmUnsKAkL<5^{i7ym^$=! zHj?=4h_+6_IJT?qyhU^U{L<(dq3qaOiA9w8$$lb~4NB>Tpmqe>y^&b07%lPN%7))4 ztmM4~;Wb(qO4d~DYwr5dq<^?u!-;#S=9IhI6NoXduwD-Imh+5WHS`q%0~-SA@|u1V z+&_wzIG$!A&l~%c>^WhyX29ONTpK+c^7z2{7lZCEEGAcbiphNn4!mO_{>R@M-u>|I zIFnnm%D)opHgfmtJ57R*ZIa-F#^h2lfWMUW9Q-j^f@fz9hnt|h5|n$+sLd8Zmc82m zDlvA?rE!=o-Gt%DqMFSKY`1I}Jj?s(eAP6|%;QqZEE}A@8I82#_`Mu}o9e_NU`GD7 zv*0M#WQ{@vq(8LLO;|#~COhhB)EdTZd1$~BOH4Oakb1nk6G-JRMtEp&e|nCU6*%D_ zxH#jZX?bzcN35W?9_e}mB0rRv*Ar*RXM-SE+vy@fJlFebwbc!wZ@`Q3oDAq}x$Iyp zG})>iW9~%jg1s?k1=ohALI-4WUVF;8O`M&Beo8oDw)LC^7c3hBW$Jp*3vPTZuC0_$ z>D)#vnr@WS))4ARq};HCE+Si(m|Iqa8DZ|}qM#p)csKSfLA{ZGyRo@}K8q*S9pDZ0 zt~hJZ_tAhx@AgBbM`eNINj3T;Zry$*=L4FOUM)Ro@k-LVt;JiCS8YidC!c*qa=4vqE`U#>U%Xd(r&1`bU_zEO6pP;kH3jrp^Is2>k}xBUDR2nytWW z+tGSP2In%%PE8SH?pezsJ0Rf`kW~Vs8D*XL5Io-QRsCb{p7!kXg-yL%TWcRYsPaY(h8A=vJsDvm?X0kLDOtu6e)m zNTN;FsVQBMjU0k>(B#>SSYonHkFx%9xoq;~G7lEs>f&O0lstR0On92<>14f5)jDAz zffs$a88`{nz`YsaB{o)!dXh-Estw}fP(HeI1OTs6O~4%(nZ@Je?eUlef?=(o$q)d~ zq@2~B6JfU$Y?)&}%(yO@-kc@hLD zX?}H$qlsUnLv;K&wKG>{FOrd)NI$k|#=G-fH@q~)6n2QCIDwG7?k>9N(7QhI4m^6f zNP0y8BLAdeiC+Q%F7(vU&nt(ZoZdi$n79&RBOE}s=-)?PZ{ zbO9me5?&Y6%hBP;^ zRx^9gr=@JOu&3`*at=dFs7q?8OFvewBxS|^anE+}C@u?D8rz&w6J+9R8I(~u zY)=%eQe7DFgHijsOFY5zn6}KKV1%EPBFe|cSqUazi6v#Vsw(=gQu`&ZQNk7|`;$E1 ze2x_z9Q)dC;~2*vm^RS6K*ULRr+g}egggI2oO^F0r?Z$`eI}FKlbxJaz`6SI>gu}ph z;~BJB^!9{l&p67P^I$Q`6c`69M{fe%lMhC^NJpbQ*WTP&7t=7EX;cIcJ(Z&Va-EFw z1iX99Y@T3lu9C!K7VC{Pv~Bb}O8@%Ik(RG5tcJYK;xJ}wz$^m)77}JccnklXVo7DK z*ew@^-cU-63A+K_qrCqj>ks@=8Y?l2+_8__L7{!3`Rw3HM-TU|b2i8dr~{`XJ5dK%SM=)xdekOB_K_+Fi0dvi*5t8>2@*(b8@-o9=LEl;A;CU#;R6%$ z7Xjv66g2D@sj*wnJeLsN4UbVT$tLl5Iv7l+F^G35<4D;JH>EUK^8|X+w-cWRR+k)e zQupMj3TuR zUtuAY(@@N6y;Kfg+dWENtn6K1x4ZCi-=O8-1l`vXEhrxlg;_{zv2gT%3HE)p*9zZl zh6`KR*jpwwG%Z$(E0_RY{Ykfy}DAsO>S)`HH&j~Bvj7aq$h3y1ZUwMv{Z zGGVorv~I%6fY_#T11weIHf}K1I>_=YbJ6XSYQv5>Ut}@Fp^4io;m;h%S4&19_ttD3 z$81wp9!nZ5Oe<3eUz>d!LhDy!}}+H z0nu0YC539w-MuGw|1Ed-9ro^hz1w6_p|SGyudjjMuV1&Kw{>`b_u!UZGP2z{XPn?| zRTKCGo4m=Gd7tf1De-YOlOS*JNW3O!hi9rS_{_oy_vR>Y?jiAK2Xo7rlPoR8q0-O{9GRxLrv4DjtUk z=Q{C{z&lsmbp~KOcbpVk@+$B!;Z!FJC&`3)kFq2IP38^K@%h+8p)lh$+g<9d0oDbF zbK@$IdYdXyNLc-b9}vX{*i9j1mOXn*KwL60F z-i<@!hW9VmM*$#hYRUNg(FvZN*`Lgq^&JZtxa( zOtjkIAOmd$cOhY&xKhwIQy^;)5(Lq5@o`t2D-~PZe~!KKX{iwqQWT|S_&j@rw4*Ra z1py{{En<6&Hw``ZUK{;oB4>t5EQTd7()6C2I<$!iV`c0HCpO4knpa))^C_J+5QW>5 zqO_GXTK6=bv2bmVz_R>xS;#rFGvCV{(s%m3PYBSAQeD`{5UrXNGwH*%I$>ej(8Q^;ZV( z&kWwTas=t)3t7$?Jw7|zVx6-7G8~F94TR#8LRiY&4NX= zAkw5}b8ohoFTD9YI~`;%`h>Kz1z{*qZ#Eu#YsZ-_QpQFcB*nr!<1gAO6}u1}KAh)R zhRWEzm`STJk1C;!FjB68=6w2qVoq0dF!uB)9ASrt=xfsSOVrDYpfXCe&Qb--dAe$v z7~GRl5_83K0bTf6&KLBIsjX6|m7HE`Z^a-kBv(8qSgGVScCW5G&&k*{Gb}i?gk9b| z=^VeBGZyoYM8F-mSmLK^Q5Enj84l4Q9H3Z}k=$32gI0OPzViHSW2ctfZRW=ZDpFPG zOYCcnwi_-!)BGtcmf^IdAO3_R)`#_wen#{W(_^DO+1spKZaUYXy%Cd0lStyLhA_A& ziR7;6Gw)hXB-2E6XleI_h>cFNo~6~`$df(8ICqZqd^f~4BE2^FFGAxi?=~J8gK@~R z927qGW~vqEKsl&b-~enulfS;5N|Y4sn@DZRF0sk9lM1dE4#0KUG&tc^nde=x@WiU@ z&!td8^mtp8iNYKHU7%y4?Cq^o-f{}EKrYxV5=_x6rGq&}7aB~0*ETeeV+F5!*OpnE zreaY{u3NEt$_{l#ev|e+h2%Xjg384|BYd}7$&V(j`(ewzuR0^g9l(8cZ+s?Kzj-76 z!B`9RZWC!@i1(-u;{EdFZRDQKj9x<2dnTk? z%qDBGcdtF8cCWp;+_~j>CBwHj#};F<9E^zlHVrm+#2`JFhJu-4-`>L0Nt&*t7MS3h zxHn;|w^$H_&**XVf$PM?=7KOm)RA$#A10HpY-PIA3qnu=xB%yXJkOIAXQcG={n&lyGv<3|;FLq6FYL`Vyy zZ^kMo5l)@X=blCH0|}Nw^FUZ4p_{?GLd_0cA@+^sqWn(t79aw5F_cA1A

n}wJRZ+@{+KW{E*6eTD<nfJQhrNq+e@h7u6m2{sHY#PI z=sCx(;L5cfcTT4$go{h|ee<%8j3q(KueomL`Zjn2zT1dchW0{iD%XV_S@w*4A~wRo zKbiC7wyoQ+@4dv=tNUmUyrb^yx465%Y^(h9hyBL07QBCX4Z-{MYZgs@y_9+9 zaCT=5;XBPoS*k}l%5zuinP~-s0OFwW9YvM|ga}L}G*ati9ZBe`I09!}Hv=)e-Nf;D z%*jX&%QWs-uhkZKrqhKEl%{vPId<_!2=@uG8I)zsdcELH8*D5B&ZoKGWN9juC%U;9 zg@cB$bc@5zu&b{Sn7xKRLoC?i&3tF8MB3pOCs`#h!c;H;(oHzFoK+kf5y%ry&ojbH zjgDhz*N%oGTt$_bxM4#M>N>*k(2gBz<%Sv|+hL3lSb5-zu)HlsgXcuMgh-(uu)+bY z9B_}f2o2&`w02>$LHj4P4Fwq zhwW8k_`WvLusGVK+2D~dlvq0J4KMH61aO{O5&%owAvV(7n*! zEz?Pg%tHE`X1Xj;CF~c?xF+H%RzpCxPHUI*Q!3L+>1^w5g)l+L8?q^B0-_`j zmax*-i19X}3AYfl%!AEL_7x&#h2;}s@)ZOW`d&wEYBr3}*9RWqInq)hHLP5vT*7Ml zv{_XM#~MoLY&GrBdjwA(odW2=FpmTfPUt%}#HoYOAC)08H3+ilO+m!)EmabbW`-OE zRUw;%z7s?n-8O843uM3YSUlQ$mkBR$7mzJ@Bx$SCD$Z|h{d{FC`{DAY!lRu8rz!vQp1$88Vu5;S*_qBS;g0Z<0SJ}uSPF;b7z&V68cM+>(Likwo3GBwKVf#VlSv5qKA&GhG)s}gf*fp&R}9ZC{+vIZ!QL0olx@P z%3g1=(MDRLZkI3Fw5PQ+R06JXy5qM;WriVSSzMQN)`XV@I!ftJ>G+}bTgOuNPM&UL)^7QhKU2b>dHKPr0RaO{n!Vu&8@Kwe}%Hi*1y~8kV>6zehCc6YhC^1yL z^BqojWys_aN}Z;WR%Bp0>0#5I5m`KjNMdXk-LE^#AcHb*a|&>?A-pGs6Q*enNNH2~;=}jB_6Bq~Ev~JT&X~U1R@FO#FAY?Sb@@@S2|_#;uc*(`Xp zmU$&meLU_z!sYFFJX>(I$yyN&Pm_!Xbxpc;7|apHjYw1M=**lo7T!6f8zwrvBEU=m z-Vj6x$c)K@XMtF9f$7_m-5w8lC#n9Jm5Poz{nIMlZgo!Ro$7p<>t>}s5}_WydR6y& zP%iwbOHVTG)AMRYIJ-)+EJ=|$n|w_2{<42=R@rOtwLq&h*Iu1M0EfXFo|qZ|RFLS| z4FY-|aKK8p3%><+E4kM=Nj&F-0U7f)wP9xpBC^bV^r=FZj|FdIM79s ztekpS`)&|O9pz4(;JTz=Aqzz?z>m;4fW~6N_-KPq+}1r<*?##RM<+44HHp~#9mg`R^xNP+e=q53!-~&_=YRyM z1lyqI2&`hwMzLD$E$swS#vK5hB2S-{ZCT zDvqB|M2+|D%+luxDHic9@LLlJ`}(H6-k#iT1#P>>Lzm0=GCpokOB3EF;)fb&XPJXw zyJw{(L1z)UyIq`aW+{Ha=SCqZup)0dQcMt-V{yhJQw7<+s27`uYox;Aik{(x_VKw*GFR z;F*L83I)e{C1=ADP$x%5^!B9rjOa2CDEUjsCo@x9X$yD8&I}emSh?q5%1)9xGrip+ zgKCixoAn5twd4`<%KBnvjd+H2a}q28eLW0L%#O^ANH=$bIS4gLM=x@nmIS=Izs&n( zKFHCJ{Nh(Jn^%kAxPJA@DXyn!&7(+qi5EqfB#Fa0fvlg5vMgWHB_E!g zqm_&>7Q5|R4?vu(G^jEcyf4I00`9Dib--}$I4LV2h<@dGIPN5_%s`W9-%w!PgQ`&$W##L4!e$w=TJ{H#SMz z6V5SY&0896%&~dgShdZ`5?0kSJ`_$Yml{f=aP!$>Vu?3THVuClC!vLI;~^1w#h3yw zV_V_LoBJZO*!tzpfGEvEERdTz_-hk8)dDu7wQS3?1zcp33!|E_aKh4w8EP_!Uz?~Z z=}4PS3p8rq-=+DkRM@6ZiMjjg>guy`<=!s*{WEv}Bku06Z^RqD+ZM(D^oL)55$64+ zM{vJ9=RpVFw+!CgpL0b2vNIvxFYy`CCPzn!UDa9hpCcYw@^&SzN^vDyyw_qNbk1)O zt%^G0nKxT_X*Sa7A|;}odg*+AG(uNS8W4=vvo%B#NZz#~t}Z@|fbbIYz!~ce40i`? zji!U44j6liegk?v#qva+q|FPg8zS*E-L95zmRWi<&reU6In)vDU^ZFi;Rq=vgw{>t zptK&WTR9%H+5~G!`Esx5X{f<nDFQNgjarG{7|fW6F%dVL_g*EEAHHhpnL=spDTFs$tMa#uE+>e zAHbchBV8sfdN+_v_&YXe77ol=fQvR!E9^seftlRrrX3x^m>4k`WNB$-S}iSv z-;z!I7-O@dXDr=phvShT%6FAw*sdM1VM8GCCEY}_sc?!2%TNbZrM9Oxk>a4FG$?3-}wkRHlHzhHCeOoZCvYiH(#+DB%PfLK9QUV0LS`OkUc~ zindbcnl0PLWMVdNY;s`hK*zMw2dRhk1anQOL*tCG`9 zFrs9w1T>s|g0cuN6H4BYVIMZnAsuc)OQ%Jd5<&-gKbbjmE=QXI);N$tr=tBuPFdnTC<%1m!x_D9@UP@SFeghWr@hbW2aSn4y8kOiZyT zlS=9oomIAQ^P$e3(9kmmK$GB#L=U~%a^lH?3+N>SmSCPx(sN7!G3dMW;0&RjV*v+y z`D0YRIW?bF_>3?fpWnQ?*`ewZ0(=#Cm}0tgplUNz;VNz6+jZ$R4jrQ42LSsMw8Te> z8zdl}AoD*A-9W<@$W;ueBewQG-YX{@b@w3L?8R^3A&E3mVx(7oBVUTfXM{>Vvl??pj*@y;hcLKE(UgEhd4O# z@B5c|()F7eXW+xGRru=GO3q%@!u`vCz54M^x%;=)=6oJ!VzB$CZ+~wo_v_#P`uYyh z#CBD(zgtvq-iqfKDtrWQrT)tCkDM-z6f=u>B)5l$ZiO`38}F& zA8HSN4kuNf#%? zb0GT=>iDpB^VHkQy3RKBh8#hvbXWz)hp0I_3=k6Qy5$t8tW+F^r5lEb)TZkZ9pu1$ z0th_zty02rx9eJYo0F(QV+E9DO9D?6-q5SIh)9q9;#;p~CTnVRvwaBXFv=MKy z^M1TI4Ms-p&|VZVvTy0`BKs@?>kv5_AK?jdpU zAc%%Rs0*LY5w0IjeWKCY54iRd(YFUs#jT|zCbBLfH%Cx$$_Tr>Az^P=izn*q+&tYm zJ36K8cG%vrwdjiJCOX!4&^-q@7w0?zwhq; z61rQDV5^z1N${sXy#5+?e|Nj|?2Nv80pdLx8N|*Wj2<*E`u+asEaS?v)+X3p5?;}P zH&Eu3temcy4H-wSm zupSdIJFlRd2LM98k%;?l`~DN~JG(h2(A-qs@C4&W*HtcOoUCMOiG1!Vfa>5L6Z}?S z>J^<8>)A*2piLJ1J9;s&zBq9J5d66q?Ru_3w<+6_;kU+nzm!G|MuRHWu7T^XaP4L%%8W!) z2{1}_U>w^~q@<&uj7J8KZ0t6hJK~gy+h7z~*oh%W2sjE!pCT@+5I4uOXMPx?cSWO z^z3WId#|(daTf*K?>{&b-Q?^+A1&*-gb1G5B&yq~CNPyqj35K}8htrO={k`tSjq8T zci_!2u;Ad4SDQ_m1)L;F*&qcfL5>G@cHj(5wDyJz4;*~#c@Snt!K_}u{;Zqj$RoHW zRQi~?2Wr&hT+Nz(Ow#_d({w(McjH<+^RmcSNs@ZHS>@=1?>9}Ju?(_afNK*#XL+82 zl@fcW6GW2k#@NY81-_f<>7%7a#Y4KngYl+BN0A9wSw~xv437ICPC@7 zVP(fN4L`NF@RT-yUN45SeL3VbL7Xpuv9mh%yu^)+rO68V$CwsFQ+zVW#d|E2|sTR!S8 z@6#QN>GW;&u6h6Ices2yt#39Pw%pug@99ye+3sn5dg|=*_mAH9cbm9Z+U~N;uoJ;! zu09KW;}5jfa$BTk=8zMXPbShPZ{oWR_D^*_+J?w6`;JdW$&t&bZd&s!IB6t6W@b0g#=Iqr~vgG~C z-Ozn2#Jhv7Vu+IyU z!(mh}>Oh?j5%r>>pwnFuCw)U(aBc`!v5U#!-^85VkkLD_oAN}q>wrL80mEf5sa<-Y z*2mi4sOmTjeU01M&_aKF&N{?vbX6Ti&c>|(=HgLd9_$80q*Z4`0YcWbfH5wQ>J6hD zq?6sF-|bzR9os|j(pUdqdn+Mz1+?AV^xr+|zkT$sf3tn`Zu{{QU3t5!W1Atxe7nMC z=0x@~xfpW7n>fa%XG-HMS$&T!V~@=~CggV(RxH|#l7XSd>6%g{IR z-|RFD%~14qiXi>0m(%uY+zu{%5pnELv&XCP@uX|$5d^<(v#B_GkQ;S+U5}3uy>0yW zh26QlxR7dwfkee(J+t6~o@;sJg%Q6^-1q+=eBY9~ZB5RP4{sy))n^uyt9yyvUoPhS z-5jbfYT|FT<`~ID8Y{oC(cQ22W|iOV*-T93umJez0ik!scEQmZeKC5R9ho#(;odLz zcH;@6&zO0e&a*YdZxo>sJg=3^EroI`wtTNq6+fGeSubG=AnwX?4YHjc&C~gtQ$pKd zHujafN&UYT!a>CF!L(Jwhs>KNUh@zuLfW(Ss}-Vh$obi1I2So-jjDAZ`9a; zA>w@rIGH$GhVOUy^PV+sC@TJLclu6l6!@m^66t)`5bu8fp27WHvqO$6!}r^#PqR;- zob97eb^mvCWw+auCcCOPX%{wamvG#c5c_5q-bM=ghI#`|r`N4S?Xz!>TYk8pp1zq| zZpuN?dinfPdW>y}a?g%J?G}!W*ectqO17n2`JE0fPctdo&7D1sMf@%tZ*JlFxwN5y zce8O@;;O*Ftrt*S;ljc%2Cab7mNyV+Pi?VUA!yHev62Fg56=H2bX!~Z!-qe1TKA8i zhrV_~$^FYR>E!MoyD$^85&xS@bN0d8j4E;cX9DlP{PfG6yn8tiR(#L7p zY-h6+7L`<^GlwH!wO+5a&hr;9a%?l^BOZ&=gzi4R`(;%W!>{l1S&p5Abm4vg3JP1={s zDR6pQ$6~DWcdPer)7{PXJ@EVOjsvq9zIQjf)8A!)@9f>De*JXk8xV~<(~6{185Ko5 zcu;WcK$G1rE(5w1uNk;V75(J znb?3UNmaBti6%IU?k(Gn35M^B=VFN=g3gM3@m#cS4mxQY(c08OqkZ%A(kd_4Qj&JP z7gc2*#YEisADmK}UCM_KyPBLkyn$D@+H&r(-2L!3+Pl9xs@#*iSvL6@^*MKoCUz$W zCX*Zv!3P{_!hiRcD_frZvL)Q&7!=M8?4E&OGx27B_lz^W?VM7!bnw+24e~H}OR>Uy zG2_@Nnds$tUeY5`M9HN%2^JW&UL^^ZZHR??>EKPSbh=#;!!|vRF9zi(0|XR>4)dZY zi9c(?*M8Py4V?tCWVNj~3M-pQlTQhCN7;6j50=v$1T+Zp`FK3ei<}5GB<*ySBD_Qs z-&FG~&j+V{I$aR@f~1Qb-k|sBZooh^;uKp5KHS0SH7+v3!T!OuT|d_Ff0T%k z^+W$SB-HE0A;Pnfj3TOu%XYzPx62;d{4x`@5Xrd%Ju4>35Hs9qQB!@J?)W z%A_lc7t+i6i6zZ4tc)wsIT)`4DU|OhHC|ij$Kf$v5Mo5c{%s21+LcL`Vwmx_s4bu5 z1TZmu6YM$(eN(fB(t9y3PHae_$lb-1@1{GsqO)iF7kXyJvKQNu_05+{vbZVZ@&5U^<74j+ohG^=gztDaqxj3Y1i-GXOVDGu#)xt@ zle)7b8#{%2W?~T(Ja^{K0>QA}Y(ZbnkqSHKI`~njM&4Ryx=v*b=y_SQ()mbdX{NRW z{6x{cMOrz|q*<&yMaY=t+DnS2A@bbR9=o(P^zgy6Q9{_CZoO3oWGB4MF|W+^_9K8D zbIibvlCUf>>`RDEPjinbY+1yh%{^=v>Kp;z9?T!$>EjG8nsiGao$n3k$~%t?R|0s~cqK_X*!KxnPYOz~ir{_!Sgq&R+% zi0jr`*_3U3?XaZ@A@~pnm5&Blg>9Wv(3#;5jlUCG0PT1H!*iQ+%6UP-hlE7eAfiu z4dDCfE<1hqDchNSOy$RY4 zq;-1)WAckRvcc@LXyKlEH{HD#EFKcszXa7g*?-ttq^M}9w{F8JJf6+EsXT zl62;+iej;tb6m+P%~teP^;|m=`I>s$RIf&jsyVyQA&5>IBGyfkq(sv-eM5h_JU#8x z)ilur=*wsCPt&8cKc(Y)CyvTpmBQ>Dq$}d&_#VQulm)W;Aew0U7D(T`7%vMrHEZ4Vf-~!+?p;{-0$-t~(k%9% z_!yj8C6Yw0G~6I`eM9dKDvi{?<1h$(LT$xa+`2x&F&nL-XyJ?_<&9rCsy_FSPeQkI zOm{@+?DKnqN{r0DDAqDsZK!Cvcl%SFw?u)pu;AhnIxX z5N?i-5kYtfLXN&0zltjd3OZWpk$G6(j8EU4)=zJ???1hL`$+FtXXyD3vu}{^`h=z3 zW1~_qux)mILh1KA$L|Wz__F&5`0np2fE?g^dGpkH^zU1S@25|1PJajMN$iK_`y^3t z5}R3~Z<7xNv$;?Kz|Q5y;UAA&t`x^h$Mc?c zRwagR^X+`=(Vwlx8f48DIftmUmsI|sM+AJ7=_X(H-{v2QH8&a#i*=gzpS=kk`c8Gi zLqa0*#6Oc!qOlX7tcc!2SpkHOih^S`xG$2(dV!8KdNN+TEX#B6bb!I4hqRGEbENi4 z)hQi9uVgXCGa=$b+j(XbZ|guY3-T}v)&$#5lwe{gt(j6Jp(KClnmV1Nl3MbVA2NUyTJMR^^tW=)4KaiXda4GUL` zTPdHu4kE;Q2T^oz5FJ1{_g&==ov23Apc@e8A4B55ybNRF;nO%g_Ag_$5!cUb#=+h6w8ZWl3MmX$}gdDJy#l>M6xdktNL7apSvZL@=>@@{p5 zg-yEFe|PHCZ{MBn2)^me>uleHvB%cnV)}V-N(iNsp(WlXg0_MNF6v77$1pY}K7P!7 zXdD>GcEeWomU6S6(O*Q5>2>2q`^*!ofj^(LO=}&$Z!;AqHl=*;BKfd|tn0)R+2kpt zdiWOCzJ6}6iCyM-XDSrPZu4Pzn90t->E-m2&bHI3Ks<1oskZFavpeO&)T%lEo!&q* zqkQ&SKO#W_X&R5e+ZsnOU@BS-`CO|LYcXw<)k<6=cz* zk;dVd`=ymHv&Uwq5@FuRr<(0;>db6cyqHbW8QRdq5D3#Z(xU+3QhEk#Uq}ywLpKqM z>%7QbHpzNK=*>9HnX9|)>bf8<-1lbnjOaBn@obtW$^&zD=Gc&55M<+$I%zs4C`z?Y z(Ar-P@+NBtA#%bgy?pbmNW3J4oRPlJX_muyLNr^p9&4>~B9ey?bMxuNAlCubGwGy2 z-<*Jyf7A#%K}1!SG;r$Xr5>Mqg$wrwK$#P~iOC{2Tm!%{46Fpb*|aUvyjtPiDc|h^Iy^*_Q|D$Q9SggyH4c7y zTN6wlBN{fooXCzL(Q5b!ca=#@!RunNJN+cmw?voRVrh0Te(j#w z_HWM)cHbuMK)a2ovP$^nZRnP&H<0eKEvV>Ci+#H{tKOGVk%nAD?rM9Wp$kJfFhfnB|sT`vC|v9Io>(tS7W-m?h) zBR&&TS9#kb2<-m(=bwN2hQYh-&iU^5W;f@%b|+raOz5jK6KL|%UW}~-LW%SZLkVZZ zJd;6XDuM|QB_VMidB~`mNj8+`w#f=rC^UstL>7m_@|djkCl;!Uhd?&?wGJC!3n!<`;V~5Lp;*0ZR=&+5C#T9H4~2*^?m&=L;6+fZS%5Kr-7aD<<<}eV zy9^hB-W5&^u3zEt!+Ol`8BR_jj57(ppBx-KIXrwqFXDiXdTmC2sZWg={zA6QPT*fQDM!kie{+(9u}uA=~A2YSP5*CQl(gzzYN4M)Kw;!Rd5r7A(6|aO*@F?AcOG7>e^>4csDi8*AYH z4&~Lo#p%E45d87;t;)YkyB~gycelGafBx`S0`H%G_~s8kh-&idXNq?>s^r4TGw3A` z_NsHl*4>hCq`%H26PCLyd0J_`f)WACB@Es=Nn|CS#qRamH05xz;0#Ta#z4sRl^&7m zIdlyO9E9oP?ORms;1B&h-PSrq>i3*^_QC@L&QR)@&bM0+qt4Xh$PR2m_6LJrF*r@O z(^D+J=cl7>qx0qIo1B<)m|y~mqF+@a)wOoa*1DocCTWgHs*ee03Ce{?G=Vh`Tl-iJ zN}zcY&^NuJBu-D<|6JvScoj5h`ac|(uLpD%@L2-qgg|zAOOhhYAe_zJ0=UwZ<>7LH zqg(S}5t@vOI8a;h8Y-i1B>;Ztv$hj~u7lcR;gVwvouP7WK-uYA)Y#F|qCm%5A0E=T zd)!Lt1>tnna_M{b`=n)xjT_gnw#3U6He&egxH&!H>&_(Jab|z_5 zN9&|bHGyyf*hYdNYu{o*K|ardWIgFJl72|Wyg87 zegCPuyidmsLbGSycs%#&RA&UKfNDbhIl$Z7a^@;@@a**2pv;!1gH-2XGt%fNONwQm zS2PJ)L4?(o&K4dKY)?!fj&r^{$&Qk_Bni?5Tb8Q?se<$@-1x96pZC=F(P9{6SwhU* zF9t#!vOsFZM{3daUz6O-R$Z_+t_GDee)Z#t1h#3&~wJG|$AzO5r>!M49mc(-6@ z?^be^=_#}9x?9ST2TgDi@Z&w@gN|RhhsPnSET2i*yfa@KSnovc-t9sL`?GQ!Ei{w~ zI|f0X*)Ir!-Kr!-@3J?&3~l{RZ+dNr_r;qF8|^Lnw*hY%Viqm!7C;xFoR=*x__#d2 zbp9)qZWc`*8uoohg30Hez^i)--CtyP{}#RbuA2DUJ@Fq})#NYVd}F{Ht?{>*pmg4c8D7+pX@G z2$xoA5TIqAUfa<;F9*xA%;{nX^4I>V5!G4nB5v^jP9k>X8jUpsf!M=TJfXA8lLLC9L%JydDW^w;;W6D1R`t!U|48k0eSWh$9}dr(Pakh~C+-s> z?7DK!Pn?tU8(2&})eb#7Mw&p#itQ!uvK?MVwUMEwO9z7>jydQ_RROe*-EIwkVrn7G z*syKH^kqWmo9^S7L&e2J0<5jtZ5jG{BJv2-n_k?eOtnkwrr=)i_c(;m4WLYv;nakBa!J3ow%n4bw2g=z z42rI39_Zd}&I_dXWV2_#C=<(?7ytRA%P;av9zN`Rc3&o#TzyuS^H1XL{`+$G9ro@I zclf(M{QOro3I0IL`wu_xz|!u;KQPSOgqgJB$>>2>d-fUehF@^DzZMUHyUV8X#M5nx z7mj9g_6%mdOGHzFAA@L%@(uW&&j^fWDEI<+&Y?j#Tdf6I>^#Dl0;*M>*oOk`r!;@t9U4!%D2U?sGXHgofQ8)`wn)8K7J%{cj}aW*EyOudB6=ep7VD8Z2y^tYx4JhQO@DE=fOINfw9Lra7cO33VmOeYJ|aeRHz4mde2*7W%N zXSMBo5!NmFC2Z`zy1KQP^EvCjy61BDT_J*hSMa_g&SYQj7JK*4f8_>-Z@wY${s9w9 zZXNz^uPol01R1vlyc=H4;j)}g^XC3DgKf{8g(ulb+d0wWE!JBw##^OIZBa`}MA(_v z+xDUuxmSrw0j*evZ?c>&oXm|q%?z8GPJL3-eIs^r1NOPUJ>WP)c2juHE2N7MG1p$A znJzbhGbXU~=J2JUBX$~2UyN{E{y#k++Lr{qP^ks#Z!}v>aIzry)0LRNE4n$TT4|(J zyn*@~{>%?zHqD_X9N7(jId4Elc!djCM?6CIU@ap@kI;G%xM26Z(<#S{=x~w8$~vni zLx%ex@`y|;Q>$rw=8kGxEg8KzK9JplM7x6sh|Rzq9=nGjvu&cw%&qB13puWe~@`2ERw z1Ne5F0FufRg7AakIqW6xnwv;+Xa$w)ryoBt_kN1J+nQ6c=+_uXzfZ6+>WGXWZQ!5~ zakI74))8BMdcVouuIu=0E9vaora8fI_t+-A(qDuGbUtruSr;({IyV~(dm__x|NPGS zjW#sIvUEE=zKNoeq_e{->NGI*i<)F);>e&!N zQ}ZB-iLsm5oGP^NKv^#?;b!^IVBc4Fgmqi?-46UdZ>HSe$GQ6FkW79{NBmtrleVw& z7V&0}Ab~eT6M%QuowJ{3(!uwG2csN%_shqfN3e^cdU;2LH#*Q-&BXcyO`^9qpEF*k z^Lf)GDe|}H+nFcJlmy)b-@O%*m33C-s+1l)=q zo$~5Dx^DuNFkUAq;p@lM$Fy1I33uPD&=O3KO_sUh^&Uv*V|1l)pwwcFwt1}n&|iAx z^cKLyqKwYN90(b*w6ZISqC9&xXtHe7y<6w^$}nK_YCLE+oBwPdBrMuI#zbhWv`ki# zW>q6^ii-v$3mdaYhEEp}BRXWc1ztoCBgqKH75WsY#V`=)h6+9u863!5sRM2-uDFbT zh_!YQaDq??xq^2k8jf#v`xnQKE%nL`4|RBW7@`oTI`BEPTUINHKL3%p_V?d^e?b4f zH)G5LJo7LjTqg*B0!{qz_>evWe(8yyJUM`4{P6GzVff(??EB_?iy8FxhWPWx9S(nd zc(PmR-ObJUjl)d)#yL2663E5j0p%lS7rDa!5u8%(ws3;KPv!OBKx~on`f7tBOnNuN zJv=5f#0~>}yF5P;Wu@(YXe;mA|2;vtd;Wo4wuvn=i;Ufi&4!Iho;BBQX*c{dateX! zV$l0mzk_{Ymo|#Lvx1v0AHT=-$`jT@TAzq$C%sbO8cVLRS=*86WlwsGO^YSm-CQp} z5JPv@e%YQ4BtUkrpx%r!F&Mq(!c6D?9=acPox)ws!o!DG?ZEGA2`2ZIdS87#MDQQl z%=uvD?!BUTqjp2?{)v(Mn;-u0%eU+myd6i?#dn_p!5ik?ybyn8HSeRAf**CJ!IpQM zAaCy|ovn#~C&+~5o*cq)bWjpxZ)bCl0MrqOH`q5c7P^%{c)ajf^(O3=&I3gJA(IJp zFKDpAtWa&CB&R9&RpL?7CXm55!=u=x|&T^{-zouICsu$x%0!ibYtIx87&ATcQPRfN_`0{`8|_m7^z$@7f< zyzlR}E%(OR<1h?0Tb&OGSqYZ?OW^vRH{I{yjYz%G1B(C=ZFUvhQVBF=sG3;rK1=G-ZFfB5sA{_dY4n?UXc zbkl{g`&L=}E$rs?oCl*9m{&qH5htLf-7mW^lcUcY80>~6W|bZ%3a(8NS|VT0=8!dJ z+dNB6{{knSfL~+QIG25#x%QJBiBAbp-ZW+K=9y-lt`IDeNvmX%CV8K~AUtkTIxEnB z!6nKkb-pY$a$Qd|FU^)kvnBrBr<=Uh;IvG2)1RK^bkg8W9X9SkGm-ssPpwUL@IuVk z-WvA-nAwr1Ky>M{{$33OG!r*D`vRF><3T=%H~iSV7tivyXWS#~9}%4QL=yMQoZDwK zG4@JH=Zr!TqvBC!z$lat3@=gV-wZ zhd>)E_CLLS`-%QHeETjtXOsAW z!}_*~g*_cR^jKWzIE47X>GWn8JmE>H3uKROPWN-b5jp4z0PpC(vixncZQk}BWM9#x zQf4!rg_RAf)v?X^o=p5ne4BX3Hul>;_CuRZIBEUcBCGU{+Y+9MjhFKGLaEFOr6j!a z*t3;ML|2*Is!+3Mg4pUNR+5)YLw1}OB9s`XNpWqyVhUaW?m@y?9Tx|nDP|A`Ui8e8 zChoJR0U_FZO1fCd3z=iuruu8dUpfERrf#d4F#EpRD|`GxFS)wkQun^v-MYKGAM_v5 zO#XbQzgxf?YB$T>-~8~+FTZ?i+Ty=!(@Y*bz75|a+-eDT{+Ly6T+S@-#@}QQy_tER zp)bc2=)fvyQw8Uy_fbS1CfKBj^CCw=^T;A4C+oAU{&6Qx$Zq3;zh$xF8b z;!Zd)oQO7uSV{69EFm7cDCl*K7xePJham+;lQ5|SBA&ycjp^nAJ6Gsm9hhYuw;r2W z<;uL4uQiLtzh+2FMFjt&mSUip#lN0AvLRny zu=y2v=6ucG{dxDo&tTsF?>9euBgp*=i1+K) z`_OHpsJix?7iKxe(DxH%usm z5VI_Wg%HZJH{<%V8HWpEuYE=Te;|ULXzWTRx)~8lmn&xFW3bsI!wTd7Pu=_VwvA^= z!;B!K)s!ev0!d47C=!&wH8WY0mSgD|OXC3qMcoEE+s|H%WlyZ`-rd`ME_N`0044L? z-&1vdq~vsZrf1)qj*>XGtbcLrVzEx0syL1WhokmG9!z&J>d@tWtKDveabgk6=d%7X zjkevVWw(VY_c%d2K!jbq{(V39BdcdBZB%k_BeR|8Xnr9Ie&wpQ3$x!09XN|#4+B5g zIY3UarSl<4^IX8YlNJDQ;JBc+piO zh7s58&?w5i{rUO+d@~SNJTkl-b&k*dh5md-@3ZZGG)oWm27{4+!g75^Bb2;KGRfbvm zMVcIA_gPt;qs=+QZY)>Qbh3_|Bo|C?Z6gPv-qRhD1RWv5uy=Fth(=1*=m>mU!(!z) z=@trz{7~QBC9yY`@7|qBP!;~Yd?i0Ht5{w`l=qx8iQ|)W3(mfZ1>_6)eitwo@b0#@ zC#}=_RvdUiIv>qfjhk$_?4DkoWZjfdz4lmF;}KO6-Zz62yR5KrSrI%p1v&GcP-g}= z2}ondILD4GD*ij7R?)5xIwYo6#h4_%Rk}%|=O}&N@rvP@S zI(3a3HZ|43Z5Mg6!BMqN91I|hz?;{Qm-H<-yg_XOaMQ0t5aEuE;IIv3b`_~rTqm<1 z)6K|h;WXj0JXDvu3gWfix#o9Udws{kvE>#bi?yKuzuRvt*T0mf9n{mi$(?Uoo6YOZ zd2h@Yfk&-Du4&_169vB6oQEBg(c0N0A0J=uPMJckU}KWC#Pekvz2ZZ8$t+8&-8_!)K*wrDO1@ zuGj=&!4Rl0ePfIv#&&|oXUiEIiM2YpDrcyebZJ9T;kyFz?514Ytk}24e&g0hl--bU z>woPHEEjUh1d}&^{%k|em#_~1+}!=<*X~sQ^our=|M}Er0_^_juRjpI|MC|&1poH8 zW4-%jwODEN?z5MgBS@9xfM^>ea!+L7zZJV zKtBnr=}EMWQCB&|n&s}=xlXp%Y#YX;auq*jYtMGzfxXRW!1A zx-$vb)+l>*)5#Lc*(OtT1Vcv|MEtCr5Tge;PP=#3;C_irsW`X2#e5#5f(AjhJxfo& zyXxix*1WF?-D~n|l}0?*t1eoopj+&6)KC*iu*K*mL$vZX3KIFqU(FbT3d-5G3+ z#T$lhVemc2Y0m}E9i`NBooKppA5G0JvSI*|?aBj`bh|Tf@mx4EU?~#6=WK95w}Ru< zC~0FDsWm#_)Y!M2W8D%P?I7N@9t(nj&LJ(~;M!r&#R^Sm*K1y=L_Ea0sJxe_$Bsc; zjuendsEr7UL$Ic1QumE#@b;Duu3M83qU)EJxIH0!tcyMX>9NWtI@DAOP8=7Se%oue zd$(cjRt`5p-*0OWL*PrP*V=;U=jZKP3Mb9_Kpr!Yd$~BLxK-JEEXSc*O>W(U$0fWC zVKooi^RPZFGy67Mf$zD(_YRvrtg|;*J%f_6=)q`GyV{G!ck~lg6w1*`jv?PS2Us^aUs8Aq=r_NbeSbo_D~HKJ z;WnACZ{B>S4*ty-A$K3SyN|4pzdFt2NbXkF{XdmtLWB2Tv05pl+eDiDt+aQys{HP% zaQLk1&EYDJ{Cb%PdSjt7VOzZU#7T7aTr!Ecm$L@rHWD~OV6UfBknNKgM0{#R*GU@0 z*wUF=)9G$;?L=6a*HCWDGHQhrjjZcyFNs{Iy-uSbUQLHZCtY@v6NBC(%j(G0X=+(W zXSJNQn-{LL@L>MFXbe2z`swoiJ{hEr1&JeC4S?|Qc!!=d9o%PyZ?7Fgipg<}vg~@* zwKH}A&ph1%ntN=G-0jk$lYn*uyn`q~<{&~$g6*)-wn~&HK+x7h0Ry5~5-&gcUf_3D zRI?S{q1Xg@CPxDwUX)9;-Ii3+{I2LaxFN*cm}uBiR57*kZ#m4Y93%#oF_k3w)GJE=c8)oBWe!yKU1Ig8d+@(~f5|UMCjU&B$=}zzpA9SF zHTmx!{`D_v?f%o>0N=;7`*>8T?^5VCJC#Y2;4KH1XV6dJ9Bd8VRbBD4cf%M+#HOcX?kt9Lzu65PVJ@~XS+$4^gQku1g)k#+%zBh+e z(2eNjc1&%VQ|9s!W!YN5pvb!2v`A-=J+>WKJRo#y6T3S={jXs3!gUvmo{dOtSh}&LxuCt; zfq$@9bLT?C;e-)V?)5?}&(};~mEe4+yEB|zhRh~G5(#gJKZ5u!CF|lDdb@{_rEAJ6 zZN3@T?9Sz6VhdBQlo%RH+)CpX;1swPevajMptHJ0sIJHz#^v(m*saxW3A{l1G4+-4 ztzO18`Gdd5xSqdj#(z>bN)5r9Au4jYm6tPy(_HRin_J3*^)|tku8+7xyA#z?80a(r5*eL$LcaMrN@nf z^{`yS^!33n^Zc^O46U+B&D5%y@It;2(gpEr5LzCC+rg zJsuG3`E<1F1m3lvT^zYd+U-XvnD+=fkb&p=O#x^0^hPoAtW2&c)eF~+BbMSIX>j2z zu!X-?R_%BI@5o*2N2OVi+}cxTi7FJ(Nr=XC)jVcftH`odP$bhLNIC-CY-}(tZ#w$Q z$SAqPf?gIDq3IC;*;J~TV1T(5^ae0fFW>6x_9<7OX+dy5a&<8V@M~eV3sD%w@wOgR zuq6Vj7h$_%mz{BOHC{w`N3@5I(!EziJ=%0~efS~W));n$` z7GP$iweNyXYu~WnL=2QY^y^Ku6~pE2!eoN{smn{Bk~XClf_0OvKZH?$wM)++x%w@v zhJx;6;p|OLG(oZ9B5}uD0$N~0p8G&Tsj0gFzyZqD40KF{9@h-o*KTVVdSWwEJ^+(% z(%Uk&MmuY>+3ome4%q#+G@LL31#3UYVzv9npvU-vXk892s}{A!BrnBr!nXcGwGR&+1^0FuzXacJp4U>EElRTQ zqr}%wn4g3Y*DKW>yL5YG zq3?{9IgaVcbhvecjdFRI$Xg3|n_;DLZAaHPS5CQO&Z`aytxCrOzwlCwCW8Wb-B=HT zQZnO?WJEW*LvuFgp035>Ge^01&nboUnd8ocWT!4}tR@mXg3DD%w~X+XV^YmEYcPal zm=*OQdRTc!jyJ^cP;i~^^pNl;u)Gf0e`zyAs)k}p064ALHE$8Bi!bca{XOQ`QaF39 zhrp?3evIBE$7ni6tf1ZO$lbo}guS7l|2VXplV+2y6ZtjfK}HZ6K5(ewbtao&!ilv? zpsZ~i+eB?-fY(T>{oEe|y=^}b?7fAYLNJzppaAgtc1;%|je%6d$72;}Tp~AvXnBV= z(YqAdaXVl>Ry`@txYmBu9&OI8^Zh<-Qf9Wvv$56Q1mYg)AzGkZCUsv7%N!}=JW&n2 zk~WHlDc#X9Z*A*2bYqsf$5Ew0>iq_6oUhgBF8wxnmVaeCcXLJi_qP1&mKDPc* zY~Y_Ob0E?CNGkqPHgP_4cJSQX{pKjkZ`Dh<8qZi0BJ~NCk(29n6hjHWcBYEn z;Nw$gN2B*b;C+PRVWG^^sda6|)*Pm7VEpy<+<`)p2nb>&-jiz)7$}JCXatpjwuh_} z)xjNa9SfO`yohlqUIh2{+V<8?nHVnIn~8>NrP^zF1j~d&&#XWyPIIva@vPP%UmL+8 zE8kBGAA31L>IX$W;BF^LcVPD39W6T3d-crG!Qp$=p#V6&^_lhUS%;7lRou;?0$Ebn zh9phrwoOg#+I4|sujherJB&LqiU^Yfg={-L8-7MtJ=SE`Jf!Q{N+-a2$RuOJcMS)k zajBMosG}L8$?>OrWDCg$Nw0;qj?alCR3N-gyD9%9KyT;Uj*##g0KBdnmnI=r!L!-1 z%ME(DfAhF=^5W1{IW)UJCZUkNK~>TZ2JWic(j-%n!%y;I6|8c!31m7Mvc_R)o_0Zy zmtVA$yt zP$sa9_*b+pL{oT6z`miFAoY7Rb+%~Rb&#eSg9_U*mf;~zAkYK>Cp)5H%!Dd$HCuVH zXO;0BB->o3UwdmP+aTEMYSHG}F)E3pf{8nDRW9)ien$-Zo9RM3O@j*FculmL_(fi% z+{B5!qSz(dB#5^dI{FZ+T~Fl4p-q*3M!=cDV^kwhiD0G;&ZFV$ZS- z#U;ejk;|wlLHk9|4FjYQrq5EU#ta$*}pXx2l!7f}9gTf*S&=D1Aw7Lcvi zFa3JC-{W#0lZ3lY5HE!eGw5U$4-F_}(k>Hag~bEGZTEIvv!R|WZrwW18wSjvmD2;B zS2X2}#3r`u#*od7T73dwv|bBYoV)ixc-J)p%`xzr6UT{y-DJ|#ZFG}E2;tZ5@ztpvPiwU{A-lI5p1UnaHk=vF^?b%!Bg!p=Y4@=VDTpxHap|2?9@O);6gnU6W^$Px7oBK>~p%TCanOVqMNO z`}ZoOXwsl2$CgW%MlQc7vS;GSo6oetm+bn@v9;tE2<;c6nf&?lVJ823z5C!ZQN3HS z8%~o?9hN$-L>o?=qDD7fIr1l<6?z+}^==k>W~8W>o&FU&@q837 zALa7F@*q2}9SX)ElB#M8Blk>@$?;_!__XeU@XqP%GrN?5iEUM`tR)KYX$J+NJ6P#L zPO-&dWh*!wpp;z`T(y{8C3B7|djj4NtdZAE+c($WgMy9}Y+!l@z41~Op<2$-Vg?f5 z>$Q8HR~ObO0J{j?9yf{v_8iyNX9!_8k>iX?<23*=(g?X&Nxz_Aw?OsS_Ch98g{Bi{ z0TrhQG2G_zd=Iio*lX9C`JvVl+#4PhVc-5xw=}t28TNXOVHgVa7M?A~hIV_g2)RMY zIiam8Nhx7~c_W#s2?t2sEbP=_^n)wJ)?p;QBs8I5hDnE^97%*s-!6JJo+PA# z@X(o)n*tq;1aFjeKMk||GX$`MrVCHcse2qzY_st*F**oE^t_=?a!xzJ%AwAfbx!`m zJ$RRLty3P@dJf%3Y2E5Dp^xt8;ecr$fSEXT@?IxdWo7 zAl1MP6H+V}^hG75)1EJI2npe(jt3DD2VMtwOh}R_?OFxTk|k&MVQI zP~*B=Y|MxCWAsi2AoIo)D5%|(XB-Rpbb50x#=H50DU?SFtUO)0 zR0*}&)nc@|a`7=!NoX1z8@*(#c5oZCSPkKI3f8rr)dOV?RVNvne==1U{447IrEiZ} z1c4U?n_->mi7^Y}7v&bchUP+oI%ODntys^LBL`0dG_<7&7Yfi0$0GnRI*AR|n$(ew za<Aw=;(q2Y>fag>?Rw+rXDHyf7A#i;h{BucQ-n-Y_uc5D9*9QT45vb)Solg7D2- z^guLB$VsO>&_a(b zhQed5?P)wPQBbgZB6kHrmm8q9M@|w@moaSM!^y<@`s>dHm{i`t=j^*$q5NVP_b-^c ze_fc#PhbB!e|Kr{u4a|w-GBO&d6!c63pI7?gz}{ZcoWIromJTVj;%RxoJ3gAkV7_S_F5D7!-ttr35aN#T4BJ(LyjYik)dR z2)u|Xg7A(+e7jnC%obeXEh7fwSr8LeBZJDI+lLjK2zC-TDm4+TMpO=U`SDLnhE=bbUd#F@KHF%j^NcYddkhbR%7@UPv&-dsf) zm&_XnfH`vnab)1Z0L8=vcZadu@O{jCI0VGoRK4hux9m#*HrVa(Y#_dIqNE=!vn6K@w)mI$K>QSjyCJ~OFxZ`QQVIT zIKY{Hz#;QSG^y1zo-v`TgALQB*^qBQ${2o9dea2`ZbBJvn%&HcYTKvGILz~6ST5@n zCIQ8iW;QOWy?A|&x79SV4zZqUOG77>fYl7s!y&EPZ|MOqr(_z`Cz1Q}oY~ z`pvVQ_%F-c{b`uVn}04x@Tbq@2p+Ke-+%bwcmIm??!Q%f_rE-wRwmV2&I@YY3gLs7 zReerLytO3$jNWbr4W1?G_RPe<62K!JTwb$j7(Hkwj{d!l{CGM&!Kjkld#biU=qFQM zxLi*iZ*<*ScJKQ|Y&pSTkW%ADTY`Xh5F7N~d4z6!}F~oXJt?f>zria|2_lx|p?&taCWCA3136eFcBh9+{ z#0{WA?WpOVj-oeHW-Ip}QCu;*y?fkldVHUc0hbB>@oEugE-b*=ryi~go+Q{DjVe+j z2Y{fAH#{oTsiPR_ghNgpZB`eKS>@)$UO;Hmz$$q!N`>U}of&j*Ujw*lt%hmkI1z=C z$?+;CALLT_?`4y`TIl}dLHO&CsaOF2BG)dSOh=Q$W>v*JoMa{)7Sz8v;kAtM20Y(1 zX#Fr-k#E%k_?BF{+0>aN5&j{sY$aVYdd$I{shJ3fU;3(`^O8|I(G0>&?^agKgL#(` zSaS0$%Z*vQVI9J{)f#9Pa^4)V)}JL#z4>Ce_h%e}hqH~pyP@;*IFrx$yMH?5nf&yh z|E<{lmofp?H0S)DLU*fNuB=kLU!0YTI`U50d#2H^XGHH*SL1=)!og9i9w~aCMTT_4 zar9%*KZ0$TCsh)-{kKNR~^1?^ZBqDV9bnLFnxO!LY1Z zSdogaVs=ErwYT!jDx_<6+#OAH)s!jp%(!c_J?W`O5P^ZzQ|5~~hosb*aR z!c){fXmUyT0K%1hQf0Z#3KhgKW_SF8=pA^7>0SYgSvM9EmsgEedQ-pz=lp^Qp39;H zEZ>A~t&%|8Qe+9yVNCTyXt6^kEqH!wJlDP6Eys)F@D|AK)${1s?+r6IpR_5^DJTV@ z!gU+jq{;Fec@l0d=Ja$6|DND1!PMx~U9&@bviOQ*^d=ej3 zX)6U{P=t`@jiza^A0BpY+%3~Y4cEfGiQS6c5W%UNz+>VO%%g>MO&dp~W67vmkXd8r zl2$;$y%>W_*JDmKVoXd|e9wvefl*c3ZOe<`^;=jAA+CbkT=8@c0j@JvndyFH$M2*8 zG;ehC0COpMtJqE2J|jza*$E%5jBZXtAd>-M|3z zjSyQh^5GB$?JRoc7?dX;b1iZRK$e@$gtpi0TC*wlY@)|ZE=88hJuwChTstpNpVNfg zJyz_d00JItBhhMXf(CVu#x@DF?ik=tnPeR9H=EbV`=@xb@3lh{N+>S_834V|9G`3+ zs_fgIJpOIF*X}9)LT)!qzZSMFtBs0GD&Td_HeD`vDngIxAUBaJJP*(*XL-;84==lt zY$JHvy2fLwh=&KyHW9qzPnyPD$ZehB6^Sl3?_ZQQyq z&JiWvjjS*UCniiqje>w?b!;CMEijx4x5&!YGZ;>C?Wr^^nCdSy$*|giSwVev9Bz`a z%fT0Jo>gl3(3gkzIk`l9_zjD^`_{>Ws$6pR&SX*@b)TK6#rr4(R;YIpfqkDHl3-bz zqYy5L9bXHmJA?RSCp23w@pLNWo6VI|VcbZkqQgW$avHeKRB*KJ#>p}X>h*yiW61`X z9YyilrTo1LO0io@ef14C7#G(X-s;gS7rBl}1*Gl`*j$s3uPKC6*>)TQ->jl>G?}(1 zWH*ReXt212JA~`;@)vlst(!EU--w=q{iU<*2y}ya3l_s}0*&08DO=|Y^_YtID1eY<9|R9Ng2hQ0H1h7Pt#;cH_ZgrZ!CcQ`-SJ$#Hmdu*E9K*4xz-?t%9%QJa0s&CaZ8HY`o@iE#=l+vVm@DOXc>XU1Sl(E4{wO{8I z0X&-+(5C(}d}x?rhsh=66TL-FclSg9Jf9rWtdxHHuqu}HT|WEPQsn-+vIc%8z~qw{ zsxLIld?r7AO1#zHtHsFq%@oywZ#Lp zDRQ42qxZXLo5<}VC??k@W<$q0G0CuNrozH-vWu`Nk2T8cofB_U;5aBZTjYgsk46|_ z3TYD(8}FiR8sNt`igaZrjw5$1tQnm*9{K`+|T!+LND@*JjFp^F*=vu7JT1kq=<~Cg$Ka)8NBWL>2Ny> z{FE^&o+%hc->{0<@R4BI6G4CM!cmL2%S{|Kt_gM@n^Hpl;jB{#K1wU)yu3&QcIaR$ zC&ZR}9nL=iDK5+~k~{FU-9Xg`V;K=B>-aMc7(r2ii8W2E!U7D=`>UAkTP$VX%3nQ9 z_mmWa%nEqc^AE@9trCnj!VAy~1D^@smY;XumPc+1YQu(7Gug57dWMsUo*GPY^jG?j zdna`r4mOc}($tVbOf_A*EX;vRu&IHu*5-Qw+ceMT~A`onTnXV__$a67D;j)&!dlLX$hu?a)>bu0c@E2q;$ zQ?b+xPE8slz7%f+^Qm`Vn1#zKXxl7F5?K|KsfExdD7X!?35AdBrkp<_t_0dg$<~L8 z!2BG*`ttH}2*lQ69@q`phIv!6bv-(8-KPvHY&0xT?l(uPH^*H2&(HjVUrzq(FGwbD z{y`koFW9?(`ZT`Vtmgbx6%(YuB1-UYe>##($h)64p22Q%c2*`*z0*PEbKZS&k|0O0 z5>1qQCudO*zd7_Ay7Yxg;jqKSAufG+6{-ex3GFn7|xg{ zK6hu)41&o_<6S+k)?2uBZ4nMlQ4IwL-=Il94P8e#ORL6#OTywiaz?tCMs7=GST3nRYm(eK# z_vGJxZa|#uS}qe_dnpXhgr77CoeJvkH15y;_{}$e+-$6;_aEPX_0{{2AD?0iQj9&{ zZ=XK0Ip;LpTWat|V=}rfA935SK0eMjZMBtP(bC#{&^vs5w9apd#o>9}e|ma)jQ1Ps zvA^GZ=s)$htm&zOu}ok}jU!AP3cPPMzDiiQuh?BofOqu%LGJ;MRaWkcX4%Md(WwHy z=?^sJ!2GQQa90f}B?p zv(KJ|ctbbA-0~0xyS|=YueqSZB}*tKirrJ%Oa#54eo9lJGib6n|H9V zATjqwc3?Tc<1|ZCdGOGqD9(cbW{2CJ8~{LoQJsk;{UGr5aXb{)c!AJp*!$$rp>34_ zZ=g52gSA`%@v)9a%xB6JoPp@2R2K|)H;K)?x#P|~bmmkG@pNNDvf=%Ef~t|?pQk=+ zkoC~C9FYI2a^hcBL)u2WaB z>v@xfX?}jBdna`*R6rlGO3ieQc*AVc84H#}F!6fro*h!Hf!waHZ_~%n4E*Lmb$b2b zpZGL3^zfN*zkPqGK11D( ztyYxqeD_p-qHpa(?%@m5Z*R6AtLsPS6u5hv*87kB{>P8o*Sph?^Z4|m;P>7#v(EbX z2*i;uBX51VCYiveL}sugjSe-x5mX+KeA+B7tDs!~g2sSKMOV47Lw@ZeJc%o`h` zXhy4{IZosJy$@CuZ21C<*$7uiuXx2ZEbM0;oS1|o@`o0HU7xQvr&Oi3wb zPgsN5$V!`uAiDgLJ3ZXoJb=RITn*Aa9j*mI^@fJhPyrkgkENTGzhngblEC}tK~!&! z*D2rpGi8;}<4h{><~8hzSL|lz*(bca%u8x+Qon7ELFBbEviODoQ;spD;Z4>^L-eHuIU zdJnS6$U*TLb}QWoP7}a)nIna@ofQHDqX@x$4lN=UZ(uoLySL_y(x!T>(R|KgF&j26 zI@(W`E|+)rr-HU^E7CC8V78zl4x6`A2!p5prPUIW4j|tKf}F1LkaJmQi<~EbtT}ql7JHf}jDaaJ-u5 z)G9XXwY@r=ANFyAprX2~&19~e;tPb1A!%@hCIn>n+U?p{-a4$BgpLBz4q}doZw@Tc z(qP-Vm1AGt#YgBJV5kWp8G|apks6IHVdyt*hBo;_4oq{*SJ_25$B z*mZ)ldh&09lVQ`(ISmsKpOBI_m8{pT^FRFIk3XJoHoKO!>3`MVzZN3yqQSnme*_sn zC5E5Q_wIn;9W*U=5(`boCt8~}ZQXJV*`t46s5-CTZrUi}2?f3%Uw^-Se>xKQwpw33 zzJ9&iv=7F?ny&Q#&3%(RZW0S??wAJ~0pJD>JeQ5PZ{M1Dzl+lB0aD&PB%n04>$r2# zsVdXB9Di|K&ZFIG0RBP~1Unji@~j$J$D&PWQ3P=6-Z$)M;MQfKtB`pmg<#>GN{4(R ze<&S;H`u$8uX`iUl&F(8`!pclaL1C1@;RWo7|OZRv+Syy#?A3`RA;IWWtic_`V_K{ zs?FYfIiktWmMZ^=Fq6-@yFZCDIS}uk82_rY``=7meHX`ce&PY>>jXZpGNFV!sf_D=4?>)OrQQfj|*ay=_e|)e4x1N{9JCJkaXfxwN&&+f>&@t|~ z?tC#veu)!00BUaC&mC8_9Cu+^ZHyfkj=-nGwlr+IlMQ>!;cM0vouQ53FW+}HT1r<} z1d!FrF0hH`hG>-GIP}53c-3BeK8ydYGV%$mFHfEVDrZ>nvdANDV=rs2IVj`y% z`yc=C&FJ+8n)K`V-7j&?xtQ)_<< zdt~jly=lqES0DDg{%LfM5UU#Cd$T!z`sxGNx4?KJ2Z&H}u8cFiR#W(Hj&XPz-;RZV z*Jyc^mmw&skUeBG!U4d2Uz1tiUYI5wV@avnj!h&u_b(6mCd#^-{;(?XDYON1SeD4^ zZl|85beM_QY+m}tx7R?*32AYoN+99tJ5=e(yJxo*@$ zRLO>oY{+f-Y$E?3!$u{`WSQ}mHw;-vuFA0N3!-<$dh_RJy7!lOdGoo(oP%WYkKEm# zvv*gc$|KtS(|@9NL9zQk{tfID=TTCg2be43#4wdWw5-@2F`95e-LQ*X0z3* zXxzN*V2={YGf1@?N6Gg7%5^QvluQNj&RZ?7?oPk!BZ&`X?M1ifpppcRRjMRdzTfSl zbb0^OUjn$6r}tNVqv1j@nfV2bCtIvo1}ho^(bzC!pq25N%*p_72PJA)yMcMdTFepN z>Ofit3y1Rr;*RMyo;$aWW&%P+K|~2Bo~$@S=a`mADq@@95E%OoIZ%XaEItAqT{5=)@6dXsvT602Int+Ty0ki~Q-{*qfujSJEn7n?y znNvk?3Ng3hJ%)`5B=HX$TSE@(Ay~Pv?)_#iZ2Nt(54DHQV*mUHd90oA@Ao@&VJiDR zKR(&{CAQnRLZ!&1PL*_;C34EpeNd#zb>PC>{*) zIfZm0F=@DfY}0s8O#WYKI=m<|U@wM8tq>-b_BgOsjVevX+BVVOgL9aSD>gvVe4=?K zWu?3>;=tscUtV5LxcAO2%8Y%OxiIcVF>KH_2($MDlv~L5L<6dB*fmd1-(acQ4X2;* zqv#NyTLic}_5rY3ue*eyBCTtph z2Hr}$xuS!`oWYCq1zNWUCP(mDoC&Qai3z9DfU2{yJO`I8Hw*>6@du&_HYTUEogjni zM8)otZ4$@VR8g!cZsFeq$a;;lD7nc~f$qY9w>(fQ@A|!!(3K)h(`XfMmsyst1UR}~ z2L&TSozYvfidS;eySwGXau84Bq_s@bm0uK{;oDA@eVEPSz_9`})Cl!%oxaMt@*Q7f z{Tn$8WwCtg>a@EIdU8~lt-Rps>gwh#jRM(HfV{)h!Z=Qs{rmf6U(Jy&xll|nm6WTP z*oveTaOj>Umec{@p*#Tn870)3;1H&{GDd{e3w8izTvB9u2Wz^xL)WsvIBd|mURl!{ zg@?`@bx`B80>|UxIeNQx2b(wb0>_V8M_vqqPPnJpZny0sbbUM2y~{C5B^gjs@osg) z;G=cTz(1b*)&!!cRj{ckghI+Gs{p6x=imI{n{WOommkl!>FCEl{em-Ep;Sxh z7l+nL?L0eN%1iXp5NRro@u$*NY_X&+GCRT-wL5+)H75Lq_u|Bbvd|}Dmr9<$~ zpHaL2KI{I~dN;57YbAI82St__^ zCnsm?vs44A;17IveVwFg_r|hi?3~2Nf#p`t3C-P*xrK;d2MLu8L2$HF3T)rp1cJ5k zHctk=pRygC;GHsFz6%?5nr@@j>aLr2m+2}_iq1vWe^ta0a6DbDRxQE#mfTvH^ll~K zz4~@nT-|r&d#8BSf3;o7%Srm*b+@tH=KhMhV&m%m)y+_tcbr^(chya6JuB)2-+Dmr zS48jPqUiSfS!cFGTzJy$cklbDvzumDr}qNhm>c$70d7PILjE?`J)c7YXIt90-nXk+ zkOtp=%Z(fbZ#c>giVJ+tL#K_&WY2LOQiA6} zchIcc?om-$oepV~RI;O!*(Yq9}p-~JG z6FaQ+m=5a?A+i@a3e~v3qr4o+Bd%Fx=d-c9!EkbH$)L0>)N_Dp3#aC4n5#TLKvIZh zc>d!b%;m@Z9%IZOH$5Km<-zFsGg^pcqu@s{-`WwTE!(47@(B2bYlPDG>D;QdH>BtE z6t-Wt-Y++=_fKEN5Kn~S%e$>j+eNwY*wnMJ3y5BnF$>y|MsAzL+q!ResB~avhw$#k z5ox{{R!(p(Wa{U9L0dGZnJ7br@VAY!)uBUUeg??hMSktqn+zSjAqTmoV^ zDl1p3C^pORqiLavTb89LH7K!r5Dn72-_71$G+K9qAdP|`xy$>nmaSE=ExH$-;?=8M zFm=#hM)5XHm#yWp+l{8Xcq;(C6`)LCy}~JKc7K0$Hw|JdekI@?-w9IR%g;uqbJ2bK zcDUPlLH}OhTEIK>;*QXG&+GDzjpBp1?f1J6#cBtv66XE1+{R9vY=xY6eFzvfvbzH; zMtT;|Tg@oIZ46ZzYPEvH##kNnXT9_)LqB2 zxq)ee09hLtjTM^w8G75$#%tepum&00jT`LC+a3JGPnvWu7I&=2Y}0|r0Ea+$zXJsp zgvMnyNjX*JG2pPpNE&Y3EPVRg-Ytn8GMv5MmlFOV8g_b=po z49wf~=ztmXmL=;p1YK#k>73WTV#C2JsiZkPcu<;%m(|rwwz3t)WT-h-Y7j*8%|&VD z6A&IYn~*$=l>|4=6nv{28LBNe$%TUx$Md0YI6VwPh0Z%Eqhw|-+R!J|eH}f7VfVs8Ly1n#21#q#8VsPD3GqBw9z&IzCxPQ!R~$tPRUXQ5Xt- z9dA2@lloC4r{Y`up9h5>xOtHdRs%!4I74nw}q<%+R=Ffg>t9o2owu+dp*;_4xb1) zwx`7oP(x<$?@_{LYAs^Mg@5aIJP^YRxMArBwpYO-WQefT!^iCVt(noGjR~R61VHYk z1D0xG%`S;AvYaSdVA)5WS>QEKy<_yAaTYnYhv3^oY);lYO^T(2;H=-z;XeeqZnt~L zPvP?m4`%`(V`2%1Haq8e4!~)tNgNER%#Y1r^A<7VHEw^BV!!_W_4nUH{oZ^(`bJo| z#)Z54oiPHQ1{(`;FSMR;a`|Mn>n>%L{w7qdJlvC}C%gFZqY+i)F*fPPk55k@pW@fM z)6@9z^y&0t-#Wk5<4WxoJ#1w>VY$BvX$hg>OjSY7%PoyP<`lx$X{=8x^hC9iGH096 z-7tw)m4Y&?nlOh(F$a1pId2>X7t%1;EK7Zw6ZQg|b~Z$f42%50{VVlc6HFkM_-Gr2 zV>45~AS9NKX`diQgi3H5H}-T&_g<1;xn3BEWY-Y+Vj_Y3+1(^iX%Ittp`ca=jB z;C+@34E2s+_HMP3L3Fm|PGxeJo<;BCNboy4!_*QN-tq)s4Y~Vdy^gX}AbA=Mrn{*C z`AsJOnS}|1FA%zFIr1G51ogE;@D>(-e}8w~`PLfk8vdx$2u6eZ`>tyx-(AJKnKi%Y zXo$BnYW?5Dy36uyC!U^k`~78Vjl7QB>*m${eKbn5rsKv@D-gclx;nkfd~bT<&A#7! zJDhooUOTv2!i47zin=4vJ)ED9I-On7?e^tyMt&fudVO}%x_Y|L1jtY1F|M+$j{p*v zVXx3XJawDIWZpAp(OVFlXERW5lif|eUGZ)U0a)@;CC5yDSWk|oky>O~bvl?zh@sXX zE7~j79v+1jHVu5k8D0T39E3x_cO{Awl^c@_wT?45a0tB`-jrNr6q7jHDH}3j`xc5_ zV6(o&@4NwrILWuXGt@mzkaB_eT+QyBjW#TZ(6%P0@h2!T<-O=>xAuuYbJ;Kj*Z9ZHJl4)Si63y8&0zP6%lfJK~l z%WMDxp*M4!QFPTUf{yJ4Eg|xGFmtAZ`-eb&m;`Bus3)@vWUmT*x{;rP`C@Bx=JdSL z>ygmzPS9B)@gs@l@YP=i^6vHYI=){5ys@YgXt@qG?`;xO%Jw{GAqS(LqvbmuwsX91 zwMUKS?s-*+Njw+4o+IIe2J)~+BRMR49`Lo4yvgD?y>zw4LH^m$m?&@vUlhQmKtiFT z4s`cmT&b~zp~kr<39O6AJ#Oa^e|%;}p@zUVMPzjXH9Ioxns$*vkZzI`=Y#k-rAp9f ztne#HRzL#1z#(KZ#NnnVh@N+IU>pz*Nm(``O<0={Dwn60f_U$mYg{Mtxm#m|soaF^ zwrg(5v=+6B@4r9)@#q5aWTVs8@!op+_)*dLX}76i&)xUkeexCI+xHE8hs{eGMJ%h@ z=8?;CKSTFssKRXVcAh%#@3p{U%)kfBo@{gX2>379+=7$^LjOn&7w0vT;lbK1CJ)+q;w36ff{X^CvMyd^CN0|)s z(xHum%7oiCR6dLt!lp{Iewk%A!niZ8W^#@RcAg_SC4=0aP1I^q>F!KD(PjIt5l_Ax z`u&TGIlnf{uAkR_bGAOca(98lmkSp?mfPws71Xj__13S;708_nu z892Rlnk@(3!m%C4w`tz6<$Epgf_!<0g`Gjx?dH%Xy`VeDJ!=tqf&9oiJvZ;a$^wre zC)O_avA2%$0x!6WBFmFgyWrixAz+@s%hyGxXWeHe)uh$Rauo*`(fC-!a^?G2gh4p1-lBv8}=$2+d zPw>yZ*!ZE}K){3J_d7w8+ zddIe(`T5N-pMbQEnO4%Yp{x73k2M_h1bYqikVERfib)-wQm#zhg^e^ zzs5XS5QgvCI`hP$`yc=C{PM^1wyW{7z0H2K-)*nBM!A_|6;ocT5l`k51K*pTf7$de z^9Or_UHbR$KR!K?eFvzS@jG(p?${i9c2My)!+8kT_c6WH7#6VaW`M7uekJq#PK9=M z)x!bqqGU~%{nb2Ep40HO28BE}o&*@Ic_u*JMuokTM&VD4%cPoU9!V1Pt(4J%Mm;gn zR|RPHzhGs&_oRo`9t$i6ml{UeQ!6hnLGere5cLNCB$hBiF;{s-RKh3Agvx%8o zfyFl-Ci)*!n|J!?|#{W-9*59dz3~+uQ#anHc{5CvI&%vq!pc=tfN*7aVLZ1Oki4= z=NaHyO(#(jB-=ENS&sWd!(sCl7MKQ} zop-w^I`^|z87jprsOyG|Te`^)dq%iIIHsMU}X#jTbv)T;bG?k-;DDP`fY zx)RA2Sw@BtW*roF?4rpF29jpuay-6EoMZI%hgh>2)7A$LKSTgG)>v#VX*TaBcRn-y zD6pH39h*XN$d*cGw6OoZrg^ouOy;haO*{;%4H+yoW|p|#8u#sOU_ANe=In(9JwDofPGJUb7AFx7h1J~u2j*@OP zG62C-0(mhIXcpp~3?ljjqgY7yyBLL%LcWtALbRZ~Cx|VF@GQ+@>$+jGD$Ce~3<8{> zaOimp%SsZ*5=uMp;*;s_WOovu#O#7Mgg%av77gX<&eOe4y3Da9Byex8NmIF2E@+oT z@Q7TIZU@^|3vZKjDTjjuO+C5rdpR-;fGGVeqHoN2BeLQdcX7lJFtn$C6>6rkz$Z062N$zLEn zx3z=8W8XXEbW^gx2tWC$_U5S1v1j3dh7$lhpf+oyWDPG$!mOzBy z?bYh0Kv{>o2azaE)z!IEsqYC`HtSq;2g3yRmy9vA{ouKB(&^BFft$kn-DFlZIc5l! zFK~6&RF-Ko!JDY(%4tA2uBjN$IM+Ij-As+O$-!NnTB1HUyseFo9E}GjIwDWLIe&K9 z_aHUHXwzm&%Y46tr2S!!BZ3^Z_wh%d`QG;SE!DVrTEG*8p0$TS0%N$`080l*A+$Pq zeNqS*PjtxXW8PTzv&k`V^Q8;1xJ)mFdf#Q)U0%p}2d-~kvNn=8flgDGL(4+7tXj=1 zDurfJjMEPU={Bpi%F=!^^s8oiwT~3Eq`bY+WzLH-`kQJvzsMx>rLKNZ!iQD7IGfmX zcVDBsGn7!8fR^E;VXBDf^JcYePlro7<|3Gh`Ws^RAn^;h{qwAKlVf5@ zXK6<6jWag+Il+#O9nLK$S>E3dqV)dsDnKQBlnem8{eG0hb3T5u&HAnAgL#%#KhY$Rq@yE?Q4*4eaEZwghsw23>QrA_-7v>}p*^cvQTf-I;%-+c3jA33wM+Vi$$?a!^A zIpYv6jhyeXMIYe%Xm23jvaaOA)h3+NYO)1<<17d1^-hwOo}T|G>aW#;K=V5; zb<#-V!%r?Ik&xrdi)!QMEscl#JdYC8z)hE$7TuV-GGjF_vWda^<`7~wh;n9FF`}k) zzrCc|FbbkwXHt^!3z)_M-0JpbldlRIaEml=EhA_7Doy23P%QgT-(97i zlgiO&xy74)|GwpXf6`(x8Ax}k)$S$!@)q=?mj?izG6Z_6@Rv1^{jT= zLWX~!H95ZPF;}9cj4Q+E7Va*H z)&x7xkZjL2%a$Iyzl2YFL>z9-3wIAy4o8@FGw5lNC1a*scn3}KquU$TZL^)@+6GzJ zk5C87kD+R?;1LyTY_dTM4MJh-rhyVD>K|9i$AQx`Zax>L!CuWaP4KK2u0hDBSWvqS z@r;7b;G%47mlONCc?#Qf$8&ZHtfy=a5vHk5Mr@?xxKJzC|0}hD?E6RI+?!Dd3n8*k z+Bmeip|y{9oBjTL!-?ca%d%bhpL1^6$oB%XkGLos`9F9A)+v?FGJ-@VnRU z0m&Bv>y*NvS#^T4u%~02M*2?E$l9$#ryQCYA!-X^{>FcWJa9$VG!DlTlpo z8!AQ+m70^dUMrvzd4tv#VZV=Ki4=>Wj|!FCJOm*0Z5d71=HTktzJP)^jA-=n>?Ik!56KihWPV4$gj7K9MX z^5loy4g7TAQkNIfoeQvL>A(k|qhLbYDCQ%+_~FLCvR-zF~MZH@l~In;Te_BPH{$n=Mo3{WDJ3Dd^nc%4Ev z+tq;1^a?gjuL5Z6kU1hSCIZWwRL>2FLs)Nbbm{V&A2+@8&2IO4AMZCffCf_8)iq8jO_VJ>XkVU3k4fyZp7c zW< zqUWNm$HxCvPmsOcE4||5l8hU_Vb$}XDO4z%A8M$SnPxT^@hzPE2C8_bEeVJ9cpX+0NWT*hZ(#Reo!$)w*U{a;hYK_- z2G-Q4alf;TN7mrRccPU5dgeDH$FbHeXVL2RTdn)kQ=!_aUu0KTH%a=`U*7kHfG_)r zWkpMY>DC<@3;cZ9KkX0hytV~;Jf8;w#Y=MQZcV=PTg$9}e-KSU z=)SsNCIvbE{nb^s7^X?O#Bt;Pv|9*=@E6|J+v0q2Ty(oZuP1mN$a#dHrhaIhlGcUblAcDOJT*aJ|{fgi|8L)w9%JXlz6qz&`}?ua8NcI$3r z=*|$u8o0Juc4X;-7M&?!N8$)dj&)OBZP|o0ADT9{ag?T0mH@Q!BUO^sT#Xf(nx-oO zRs1_f%3S(mbzApB?pg}=QhyF$s%FdM%O}Z&nwQWQ7|qf&zB+rXu8dl(Nq=Fd!$~LZ2Bn831|2Fsw)V!O;}Tv$ ztjcdT$?0hvpKdoj6-l^7`SGI$#>Sg4+^47gxh1sxlxA=iHpCnBpy4^&*y1s_f1hr? zz1vxQP60-x}$Y>lSh~sk#=+y}_A33LBb3q>roq`x;WyXAvk--DN z>GwB=?;91;aU{6VULW1Z6oUSnW#5(B{pZif-M?}%=j+cw_a`1f!@CdI{jY~GsuI0l zdpIqvL>qP!?t_K)!2nWqp)2S0U4UV_3EvI0KPMX&pckEb#V2i~%>n{63ywe~T z5-Z(uuGzIqB{3@e`=s9s*)#cHpDJED-vQZ5n@4mn#N&p8E2&Sa?Fp1;-(L zdji!ooMS2&kZlHPJ}^v}o;ue>%`c1NQHI8CdC#oUhy1BVErVS~R1vpB)yzq=867g_ z9Fq)|{tX6d`}tkr*G-+IAa!qiS;yE6Rc31QtK-JZeWjThSNnPV482{Z?lqf&M*w#| z7)NGffp8ojprG8k?9E{|2z}+yN8Dz;OkRPfjsi*DY=mMwij)?VDAQ4>_lI-=(@K** zy)p)+wtsyNYPw!7ZzJGc;eSf;!b4%4%iH9oGL;yR({y0jQa|}96br6$4 zIOA09q^imECwF(3e*W+v_?E-Jw;yiDMgH z23mahu*}gbSTZ8S(!Mn2xx=*Nir>(4|UGeHRiQgpx zeCv~BaB`9Wt5YNkYGZtK7QrVd^jpANcsDS65DhN#Zgd?D1}D?tW;=}`pA@4}oLa$+ zFm4~IsMibU`q~|&u00X>4&7*B4epbZ{(UYu=QvI<^pgI4Uog4Vzgo6Ni_vIgEnDB8 zqzfQ+yW71FET=?oYcxovv7q}x=U~5BH*h3oj(!;jt2Jv(p|Fdt}ylNYPlU2 zS-MSIErI&3fO$4yG(^U@V!YSLtn+igcdr*@*<@z5=jUi57ZTnU6hC*1ZJ?=wt{rjv zaTYYW=_uzE@}c7f_(9$ZXs3RZ;@dsncC2%SDQ`l_|uWmQZB-aqZ)QxNAlJuKe2)q27X<@?je z-R8Vk3$6HZYlX0@#C?9^DZw&*ovOZDv-Xdt?{Ns|e~_!?HOrUA1^e!QeB8f&`s#7_ z^wm?`N0=3i=@g*G+`nWQ?U%>9O zmxBSMlNW=Rt-*_JDhPgdh%@f!fe^}fM`gpUEJ+4vB3_>i`rTxG5^+PGt?>{} zzYp;MwXK% zu@jBv*VAOlzRA>?`_brHDD&0w>V8=-0#uzXy31G~yN%u)dzlHYI&I6_jey_T@_dxu z1uo}`qtSUBpcT9wXRlrn;78tF94C}a`mI*>*bTn-UcE{zD`_Qn|M$DAelEDZB>}(b zzUm6J%lBzVfO^EcWB!Oo7Bt_>(cxTh{oIP#Rp|xjj0^zYj%NpfI{?<$0nFzEzeq{L z{Gxj=zly*lebe&o26da`O4|rNO8HP$X7}e3um0{ zlE)koN3q&`vwwX5G=KeC5VpVH^w?w^?l%^O79Rw>Ei^;`=;wH_`Fs##c@gPA<3bXuM2bo|)B3wVHr;57HM)R>hl< zrSR>vwN1{Fv%wkS1e0YeS~Joc%zN!jRq#G>t~sORB^EM~-^n}I-ufDil?6=G(eAxEdgk^9!1M2yGz~WdcIC$uM>IRB25D{yIY9g3kHw(r&m|YJoiR+9(eP` z!trYht0xF;E%PE+w2=rE#pfe=d*9kcLCro*64h6p0`F;d(gkX z&w|nS-+#ZFudVuaVEORfe;Zq~KtUdcDt z%9{qhnYd~WKzM2V2;1cFcmwK!a6~4KA{VWFF5kP|JC~sujkh5J;&t zVH>=Bv){MdwJJXsFHOEh;5FP^Z3J{9BN0M7R(|#7ocL;{?)m)m(@{3y%N6n z?c0#ChqRXCOR7@;xJpvj1CBPj$?Fu*(;c3i=5c{TPG=Rpc@yrMQabbbAJNqH%=)F^ zIPm+mPB-OZjpU~Qc6is;fr4wI#f+GOW4Z!3gAKVSkAb4e9Y1uK-BgvuT3{^i=CnuV z%9oLeNbfgW8q~Bxvu|#8m>N0KWp6mWR0^LNPl*ui370wn?0PbgA1BGOM{|-}za`@R z=FR^iy89n&=6trU^1!=MoO4uI`OG4CWHhNv$OQEl^(kU zPtx?{U8?mt*C5$xE4e;H{wrg>Pe8EO(b;->J#~oRcMsj{I(oRfiMYBc~|3Uu|beiZ&&Q# z*~_b9d$&g8I@}mJ%XkI8ui|2I@h`uh#q)WXRr9(0{N-^!D?K`VWBlN9Lvwp7O#SL= zABOW;UtZurpuW2HguMvV#_6*WUd!{6i&yd48CEg-zl;BHwdsd5xh{+Z;o%Qi%5`pk zeU%E2I6p7X*6noO&L19LL~;;ZBZdXLKlx?@@V?$$gM70AGo{lz$#s@UKZ#~oCBW_^ zPK1*e^9Ec0%}#Fev)$ipQ1Wh3fI!YDGud14AJDO8{jifmbVrZ9@u^Q$f?RE>5^$8M zpE`u2ySBJ03tI(j`=(l$&;eK`EmuHA>YvUg@u1q(s9}2S%0XRYplvi+GfqEJPL`SK z9(edQW%3Y(4Q4Pz!+o>N^mP*5pR~#a{rJPcMtT@n63yuo#4M8^xi<1>kP2KK4b>i! zOKRbfEnXt5#eW<>#}qR1AMd{T;{AswTFV(Ez&!J$4$ZQnkzO^M-286QvGl*TUDHJO znRJeT=vRU7SKmMX=I-SY`+gb(oj1rEqw^UVFipKyLUYOtv3Q5H0OKk3_LLMzF z8H?@0EG_03^EJ&WFDS3LELh0lba~I{OJPXKX!%djOlCUdgu{D=WR%%k7yODh9GP-% zg_ss~0@glfbjott9Tggs^7enn=<-dcEe{;809^|13?&39>)qJa!(w@Ei> ztMmpNLE)>kpEuJiYcs5%;{q|`L}&vipO=>Mk5c0_1DEv%{(6*qnwfodb#+FLel|~% zT(G_$uXYz%KDfF`=g(fe&il{i>rI&FGYBI0{ao-Nk#~>^Klhp`%6Ojj=MOK=r|}iE z@3X-eOFCEH<_gY}63cxrH}fp-x7dd7^Vng`2~FHd6~Y{dZO1S#jc}HHe|#Oc$R3OH(b#2TbRaO5^R_lZgU@AfG8q4BPyU-l3J?qJyhj{+?)xW(0%K7 zF{^=X_#shA;f9b;Fo&3mm$Ced2wRqCC5_hH_!bb%?mt3r#97gzLipBlO3E^d`&f`C z2=V1mMMB@9B~2zIm%34|hY)oGo~r`^mFWzRh2}c#(S_wl~F#*WoIwFm$|q^{Rk*PHrf9jMH?Ff3_R4 z@4LG=9p@F-(g$%qpCjWW^jW4mC4CLSr zO+VWtv&|pmthoCye>MsS_>sTOXJL6JuOlZwzdwgoa-FQbo2r?PI3mwcezT3iyoG~r zAb3B$^wR6=^64>OuTv*t3*KS{9xXWuo!xBH#7EuaNj7f~nU%zYd@koixK=Mo5~i+& zjD-){m6@bEqb#9ru;_;U!WjToMe8V3!JCS4qc6pLxL#`d_MNkkK5BA29-sy~|twBkp}S;rmjqPL&1c%7~Q>wJIk;a6ij5+C*W@ zfW>y>L(>UDOJCtBl&Py57Zq#n>*#uAXERB{#WD&O8EUJ6Pc{bSqR-RI-t+Ox$H$j< z-!w0;Q_XP=35fuHbFY}6oGa>yo932+-zhZ}%{tVw&Ds=@v#0Ox9-qGd{%JgsGh*Vs z+)O?^ovBiS)5^XMz8rV>I^%1sX@mx*_TYX5uxT3k+t}X&C69k2-Sj z-7R@dfMA3w+3)u-r~teZ9T_B1*7@OmdrbZx=uErTxG-dZn;uO?1v=&;;?ua*$ zWk$J2a{}R0fm3p+uEA&BwxufU`bx9WoYlo2evu9cP49p!_mW><%n{~1w+a6q}qgj?# zo3#+=ekNB5nXvgLd%BXx#kItX!h>@#9t(IsdHC!4EdRrYHXY>YhUq404o~(vN3@{) zmc)a7g5NFqY~;dL(7T@t|1LsQ#iwPMX9C^1MHaDzA?X4{Q&-NQu_h_6h=U{@ltlC( zOk7e^h|NW6*P#w4x!g_%h`>WqJ5fUy{J0cfyZ*D9X;h&VH`s4_=-LqQmRfTOMYYz} z2H*dvlz2P|m7A8e7N7Zk$NKDDQ!0bN3z*OsiO&*u8kyMBDUhSC3t)yLOo`U;#J)CbNTxC2VxkDZ^iUY6{d^Hp-GyOS)i zayflM#{)Xj)x(ujReXTAJZ`Xi#i6zQ5ZuP{L$;?EQ?m%nS#ImA`V4ROdHQ-zTM`O4 zbq+0;tcC{!gKBd;$^9KD+d7k6DkGn&m4qS?aQvAol-IIiX2;^jpcI-9S%Qq|snr@& zLeXrj|3UaZiV*ydxV!&$64mGZ-GA<|```ZYxP0Lw!MpRBoS4*oB7dC>i^)lIqPTqs zq#6q8-u0lFJoI#B#~}Ljv~7#wesBKno7J#T@kCx$&~*~ic(S@#?U`wE-rS65)4kkX zT?~QH`y^g{5bPfBuTUyKfBj;56Tkl5v)_%q)z!rV3gDr9Y^&H4)}0DK3+*1n-ZuS! zxuxJ`JZ4L85(@PO|CW~tobS{0mf#KMod7t!GzVps{{_B*^aAo}DBOFDf+%@Gl8rct zluJ-NkqO66*V*Q3-N)N(LV20oH%hO(JHhw4JksoS=501l-W)_>;IVN*up5Mav)-hX z>uK_q8|3aJStGj@S%EQ6A#c0crX<(vJkN4L@g&~H0Cs_IrUXU>)ofdPN3e9DaU}{T zthNz2*OG?hwu}>M;(fC z+yy^`;>fgbeJ#J!tCg`chDkp2@+_2VC&#@h6GzeJvHgL!Z`g~5s}obnov0jy%jJR- z-%+PIgOTfCK_hYlo@zX8d~6>P#Y=6JfRIz3XijRN%`laa9riG+c>k*$g1^|^{Zsbt&*u{Nq0( zzx$_`;=AP>mM^sO55r(jh}=%`R%LtAE85=0MX%^;EBQ~=w#`r%bL6kFPALVfPxq5% za=H@E9m6;%PsH&}EUzIH{bt{b_i^k^&fC>WFg=FuJ)S??Ry+B~n~0rc>sLcZSCyFSCJVxFXV zA%B9ZN{S*+D%k7B0^wCY##&>)!C3JwZ^LBG2r2m|@Ava$bCr5mX(&&RWLvrC^G7tn8>`wEh#g1iOVP=_N{XGvW4e$KHS| z2Z#}7sy)L6Qa)4+0Ur+%L2`lgBF`fW5RFU50smrx2ELTWHDW`_JvwFZ?bj@Ix^tDqV}w1#tuv4uF3 zu&#Pb(w(p_nF;8;s==`tn3{i|X+#&3ckS${eFo~(54O+uL#-1hRH6(eS|bv7XfVwyFAbgud7AKlxW^gmv3Ps{GWjDuW$=&}k z-u>AWL6_fs=oc6L}h?l|#dCdb}?&n!Ie9-9@i= z=!<_dfjR;NAMV}IvZA|NKpT)fsrCSAKr;wA5ZgYwYu49q2=@(s4n0RJIb>x zZ?bUo;sssc(`lE*xe}s-&G>G9HY>8yOn2wm$5vAz;H7c?9Qr`UP3Ph zKJOEjig|)*Ld*sK@*)pgnm?*!oK{(0tp)DoR;?NT2mFjTvCniq-jeoC{_1Cu&~p?t zjQVMVJlLkmnkLbe>pp%=+etNG{J1diO?sDMJ-%pj`Hjj$O5XCph4z@l?)`RvkG(|7 zw|tPm?LAj%z_jI84!%A=9tsx7&)Bs6Hx4_(54U}otjktt zL?#`}TbCPTy+YmC_{5w@c{gH8)g3N?%;}-Y$~AQhP)IJ!XcT#5oeCtY_%zQ{DB;(u z)@gt`Ry4GcgW_5jSuOc{dB4D5f&u5Xjfjh@~Pha=WoCJ)?qi1n?{r09yL}TW4Ec@uy+^iT@dsxE*mBZ4m+pG zo8if%w;K*8ZPS}v4m;XCoD3)Dy@@WxBZKPZ2II>8X{9qvVcVy0c*{TW9sqv2UyUd8 zBD=pwm8G|eKitG{3*M~ur%4I{{3gz)OJU04!-ITF$19=T0^i#-sm8!p%pl9t6oPl0 zjN=VhHz~Xz_4X_lJT1~a6b6B8c>lIlvWK$+jy;GKg6~M>=Cgw2I0bUp#^si*VsxFw zTPFIY6{mNlyg(TAd|t34VGY52&4llZ9nuQ1IlsI1tQMSL-EO_JtLr~pUtPsHpD%J0 z=dj=`U1OOhPu8I_ZDHW?Ace*a4jzR2808BYW|0D>0}Lwpn^=aLlS+^dvOF;6-5G`{ zWheSu9oC6L9_g}GG;p@5>|3)=xi_O#i}J*+&)?Ttoe#hd--+NlMzlj9U^E|nYUJ`u z@?H!cBZN-%g$T-r@DX~Ci?s?d%Hl?SuA#@w+;h7mH!!|lb%T&wZ09SIbljA zb2>amnn=RERo$9lT@KZE8}q?z`E_EWKwqI2pHvh&$B8a0VQJKzrb55(xojGmbX41X znU^BehEN$=-l9PW4)jFNu)t)GBT_7YFkJgq>Vl}7o2bbq zT4aeISgfK_cD{9B5`VT>E*7)5OLQU6mWT=XZy#NLR_#{W{pBxdJ^T4l<&TJW=Mn^X zANfo^S&Bc_Oh~xpnPSLXs>}A+Cx|4$OC(-jP8!t1cQM{?CMZSgp@mo%;!Qa@jhSjv zA<|o(+>hg%n|NO}&1_cenG7S~Uf^n6_0alBS&}505Ky8n0dlwKzZa$*tv0KfqF9N>BR+72L-+_-t}JX27Ug#60Dn6 z4vp(8f$!@pCR3rLAwilqKWcdf+BQ{s;C7-<0LqgfAEOelz8|QRRANPqxq3Uo7CpcTh=w>07w#BY~saHZQVS49r^!OOFzS;J{lUBktVS9S!X8I7Y5z4 zi@*+SPD2&C-33u*xh(J{f^=hdl3Iv-efwc%^gEz~1sg)({{xfCFF$p6|H9kfjx+gDo(YR{+_dr^6uVXM{_3kw zM3c+T=PiGbM0I&0?7Cp4ple^SVP#Kns%R#clgV&*?;=g!oQ@~$i+4qExGM}pVEv6Y!~d# zp^0NB296iT_T}pYr3snv;xyiFw~$T1z`eNi&`&7<9(w~cfcs?{j+G$;W^;5==9}?k z$H>^-#rdm?hv(;gVPP49s9K@so6Q#6@mJo}Rm*8*PT3?^pI@KbIu)07z`k?(2=Aco zgn5@#qHaRgEu?#&%1fY2(w&BxxSw-vr}T}UC%Vz1oj1Bt0(xvPsp^0LdB)XBv+?=2 zDtWUuQU{lTjU?6179=)iOH>jMg*gF2G^SM$BwGTC^jE!}9oJfpCrL=*gb=XI4oTfd zXy@&oZY<2kyNPrWT?0A?SfeX@nz4 zGb8Go$omUzH8rCkqJdYL;f!1hfOL=4vlnR-7%VFDWfUx3atR@AW^Qu|LQx&**jJ?} z-^7%Xa9h^)eN?5yeM&CywXRLJ4s}7Z zlI}Qg5nhq8e*1~84Zz9U7mG+R9Lt^ThW_tdi2suUw*&7lKjPiLKF;JXKg#d!X!l>f z{quL<9f&uxs1Dfu+fVgwC=d)%NuiEj=?0o8NJzcWA zfovk!I)DB88NyjZZ=1*MhhYV?dykomDEvp>%K#Qc;q?f)8VCrYd7g#vVa~ST z&0Vps9m>o+BxMPFUtf=N_A#U&-Z}Ov^E?9gW;HU3ki#|1 zC=^rH4DT*Ns`Y}$;cYxffXWPib!_PBzcm3>xwu;*qRY@X0Chl$zo{b3Fw4#CfZ#Tysu)4g zp@Cw35`?GrUw8Q1}h75)MURk*R>Plrv*VtfMXr6kjM> zEp@!dK&Is=Qt3oNnpjRXT-TvGHQKFS+Vz7@b#1O;J3)%+kWxx@rr^Xh>yKX}C_Jp) z2oi9eguwy8?W&6kMPx-kdWFV=pJd(wWK@VUlFor-=H`z9(H|-jE{}A^9GbaN&%S8s zpj|hL@U`TaQ>P1#fn&PSmB#6O^CR=@d?sIhR`34JZ~o&Y@t@7_ zR=pd7w^O|TuM0E*cz?pXRq1v%lgrCSE#B=(dsz&J&7~pt&|HG;C0*Z_5P2IHNX5+V zVS8$X8wn@Py*j?*J!h6N;!ThyczUxh?kCOc6jeC_+tuoBIt5>bX!7EjkZ#z#SF8Nq z-wH9FzJ4+4T{Po#8=v2M&184c8yACtptE)r#OUcI%EBiO`VH9Mz<(0w)W5g-V&MA~ z2b=qSq8fL#&WnD^I!S@}q{y>2G5!whhK4Rcp3=*bLLi5T6 zg0%s9B$cM)V*%Xbp@F+>wTCpq-2@S2jLxtCV5LtLbXdZnYYqN~9 zIOsAVdck)Gp*+*^FhTi%-)tH(>B%W)QD!+VitGa98PMGOZ;?#?^bvj^HsZhhS>FBa zPwL&DsXTLGRNuO)_>OpgPBSr+V29l&#qh-PV1;3yn90N{bcRj)X4pHKut29dG!XOF zB0>1_;v#S7Q`Eg<-CZse$1(lU1m>IV3RIcu$%?2A$Q9XvKq zxWM;*BS4)B@h&PlK8pNI?yvG9!~ZGyHpG~%NAVlaB?EAHc`alR4p{3jV6Fj?wz4bPZ$eh1n6@ekhJdW}l?bsw^On1?awb|wc%h@ssE z#b>2Jd4feurk-p{JOCUZiF_cNvjJ%-uJ;8tHz@UbM2aaf8wuIidY6xpZ4ElI3uyN> z3X5SKrWIJ@$3r$A`+^E~3mh zv)V!+fxBT?KoSWgSVWzK!}QxkRae3_m0b`(zR^M`oZFs$DmX6?+a>W3}{mZQdldlKh-WMPO% z!39pU(NeE*-Yz&g?sqbkr9kp4z365J%Dv4^M9f|U^s}%TRLS`Azm$D{`Ps&tqY%OW zDDVChx{vhkKmYkVOe_EO2)q9Z-u=~&eI~kESvZ3?Q@n=-1@B8O9JV;BA*_Qv-L@=x zyU78#nH-3{OA_yDubdm3mBYQ+1yA=Zd*|eGzvo63BJ<{LwYtH&ybIOjUd8hLV zu4qKrj3XFJ;=$Rzm`~?ZjWt1hNKAvYl5PGg=LGa`5M$x$SjdU@^0&v=LiiInceuxF zaL*OTidGXWW9I#g5rt_*s~~siDWDjd^M*a2!9WmvP?jLj*mNJKUOHjz@Ex+ar?a+b zrsprtd+Z~oup-#qFPc`U_aFZ7m_jDOc8;)YirP?bFnSD&G)cY3mvVdDP&vWj5+-t& z-1!8HU~(o;JwBCq2vETC>GAQy_XsTAJU)6XTbJLlv>rUkt37(!u7zd!QjL4WKVLVw z4e(rJqGoyH_nn=Sx8`G0F6SI8hZHLATM}jjz2)*8h>&R#t6CI7(m*Wd13*5iwH!}C z$kwj=7}o;++Qb3{yjuUYO99_50J!|)9CT)|aH4ovtD>X(hEXRLb7mUpl|C;SY7O}& zRB&nrWUr}v9GwE)bqSe!BacN$d8Be}=W^y8 z6Kmsqa|@kPQm(SETS1C6w}tL%XhLV@*{z*Q8e`~oT)DC8R_{X&D|`p!swzc=CV&UF z`i}1^EhdWvp_;~%EIP^-kmEVb1HHV+Ot}xu1fpy>I&g5qad#b|i?D9dDdKkhT;m1d z@_wsRT|sa%2YkZ3^1!*o(-ASr@;<3XsrQ9iyE<5)p5P*8k=fqRf2DZRIRua8?oRFg zvBq$d8mqXGsbny6&rp!=&&u-kYys)kPh-zP%3(Zb+TV0Fb(@Viy) z2JvnthxHuzOVkkv46nvOZ=f~{&ol^BEv^YlD;?4$EC-i$Zp6G$-@DXq5*7Ly`dr}*tk*WOe6PHyAJl&d5N3>-X7 z`G;Q71!(Ia{zNeQnecMOzB=_X*J%hUQho#+~j zI{y^(IR~s0m>_O%yEXY*6>tqZG5EHwMa^r~fgw)==f9}wH?A#=PyWq5LGQ%xhyGd~ z=@8@X2sc+e%)?^Gh`P@?nxl?l9~j>!KQz@%@j3?trs`s|zW_mfOBbP-gc>@VsTTqX zdJBSp2{Vz2_j(4{I8PX!K!sqCIUh2OfsJO%w=k-Z8puNb((U|+6ws=R^= zicDn+ZU-#%tyw_gd>W26n$CK%_Se>paM6<85d>qI3g=Psd z-9#|>24--NGs|r}uePg75cLeOS(RQfEufZ+tK@E+j7iqzB`am$du{F&gy#BAx>EPx zK34Ef@rV9Aq1{`q#~{HkA$H4?Ow=ygl*D_>H;T6#knGseZ#h5)^1A}~E(czm=j*&_ z?#AQ17505MZ|2V!g3-@r^9h*6yjGwf5)TcNjw z_tMZCxLcOEz%@GooFKR5tu|P4Yp2#iE?bwc&BMUo8WeJIYml)`2?v`rn+QI^qE@PD z4IUj#EkEJjsfKp+QF$}!A7@Fa+aNThq~qR!9VIlt2%u~HVbCofIroU=BaOd2;Kw%eSxP`GxXw z9wbX+hk+e3I>Ixmy0FDW-eaW(8HlN_zbxr9q>2!ldz`s0{HnSz-BPzXf#B*uDNSHe zrNuYbzK`##X0MpdL(e+_K5c~V0tU@zNXH5XskK`Po6j@mlj*EEbTPJ(4KgWs*x*1R z{O}#^N37fd_12r^+%9dIM~;NK0D==@LYf5&6;MJ4)yfYbNG&pZmpVKpuzUY4n#pgD zwkm(wQsuYb{*2!JaZmi8zy0nzDBk}H)dWlN|EzlVS0D3k-Kp$ml_$l?eGkxlc``)2 z3AF7uN6R^a=R>Feo!wVJ=4HS>HP z3&myUR zev!)wl-{-No!sOHaQVB@8t6^8$t2&T@^I@s6lzZQ2}ST^vxzb+|G;CyWN%dKByxnT zH=AVh*eDc#xE>^mjdEHL(ZA@ultbgO_r(|A+&vN4OGHz%Pw|^?6yP@us|tehrJ%f= z0fWGK`yy2|=uN1Nof4pMZO$z`>{H)rB3g}WS*^8A*y!$3Aw6<&Qm{0$ zfWTHZZ~gE-Kb~3^uq(nT-tSVb+~qb`Hv((b4BXzl@$D#bTO)Gm13dCAtS~VIqRqkT zcI=E%5aHf`=xdK>=(1a=nNyUo>=5o`cBcR};EdMFz{HcKjnfRsLm`mZ16pVRpDN)Y zF6=e-Zw^s{+ zbWh*L4l0(Luh6J;cHAMVM>1!Y{3^|sG{L`pP5G2N_EG5U`n(+BMVMv)XBsyKNrkwL zX(gS4c5y;FE>C*@6}0;!clXE9-CzEPZ6==^Rk}En@8C4~?*9S2LA$%f%CCO=G?O>Q3GusVb|;h5(_v-IyAr&foUSa)yAU9+kUNFjDR?xa zVXH||V9#FJHxMYi6mlGgyAuEzUn5|48fsbhTjAX@DC%)!QF?|7`7q-fcdQ0lw@e%hf6BSzzVWhf|V&PIOd?58kI3BsT zaqXy+5CpxuzRi${PsXZs@guT5q(C3FOq@yDb!67G%w!8*igRaD&#B0~7Yk%Lg%&@c z;%f#Qw??vBerib0yo^Q*%I%}YNNevS&g4L(p_Fts37h$43#HS2KC&JPT?ZuKdu0DA zoVhlJr7mI3@*=ph$$2`Y<)-WzH77mm6pGA6#9<9{`Z2a(C?{8BNr zUDJAl?ve#YpdizIOUhH~0+I{S|Kd?)=k5LlEAij{4WCJ;nf&EPeU;F=zx(#j$JkBc z{c-uiWmlbpop^b2c!CjSfu(o>=#ysRJSM80Q0pdmx4n1o8eOZTYSL>a2hZS8IQOI) z78NTP_8eUjV^5oA-o*PALSe@Z0wCwv&0KJL*9!YiX!E;S-Ha;?9>>*v8W-HCX|t25>~%kSJ{&*0nbcUVd^usk8ViaIZ? zT_!U_sm3q7F6&^)y8hUBLOHp%@gM~1>@71?Y2*VhFSYQiG|fBk2fmMDG?MSs+8L-) zC%X1c^Mj5<4+&4T)mM`L+ede_G|$l5TfcT0;ZRT9iNo2ZPBgpCQgajP8jyyW`&RX! z6I+!~)p{dXlxR(4Tj%V>5JSU18~&59W68(FSXG@?z9*;Ty0U9Idc$m3WCvf03N~o6_WpCR`^(SROn#}}{q5iM zcmL(beU;s?@;h2h{>=is|EhZTZ$BfbzAbcj(fx6UDtt&iB$^kL}ob!P_l+Vxenve zvQV4hgy131E@st7y_RsQaM2#SEn&9<9)%;_GEw!zw_}6>Sm$4d{<%`;h{{n?TitT+asm+9b}rts9Po~6_72Wq`}&5y4YFHHPvMoEh4#| zcRF>(avS(G-p-(BFEW+R6{Rs5Ay#6Z*SDRNOqX2<-YA!0F(hNOmm`>@XmavN z>6wFW2iikA1&45*^xEOj=_Qwf)WhyJd2>2xf#^D|95;<)-771qWVFeCIHY)j;uz7ae#SI!*63g#v%0@{H}>LkylW=a*z>$mQAEqx}%;w6x z*T{ffCwZS)CzHFoP(E~QR1&*m7FpsnkYiLj)yZ{Fj@bbOR^GS1beQd@x}UNNv1 zFg~<)F4*BAfMae8x3Nt`KU@w7$TRB$citKwSFoW2GSN!~HB$u4T}%!&W})`Pbts(a zH9qc20!Yzvhnyo!z0$Q7{TkFA$icM?Yctdr7};#iXC_a}n};)FiBVt<=_s=e)4meW zOl{(9fXFOyRttiSkg}6KaJukvIfMI-Iy+p6eGAE&Jp=p4{59(gANmHg6t!+ACiq#T{sKcPmWbU|Vo;(&)J znP%WNCnH>=%$5sGE{We6H7gr`nw8P5KFMFRdwgl{XNdA@Xw|2VviSRrgJ1rHyZgx8 z{R{N&Z$Cr2kM!1(m)5-fB1*7J}wlIjmu@ zr*hW;yeCj|-&9sy`R2`}nzR~6<*LtUG`YFqQaqO9R{(Ev?|pnahh3i>TL3+-KEw?Q zclL4iyJzz|aB^?89|OGe$*gJP%{EOZz1d_oZ{o>rwu4|XPHj5}n>}TzC`^$WYId?` zc@9PJiYZUAs>+Ffi^2RrXm>^6RL!|$ddWsL?Ho(;&3vxAmVj_9S;jiT6t11kQF5c` zT~R&}_Kk<}u2U3NdUHYVS1%r3z2biSC*y4mh13)tV8bSVAThW?emlg@IV`mi=vZXWrP@JDP)ZXD*=&%1VHx zBcyq`l#s}>ish_uMiWi0@)0{u<;2>1D23?Q!Fn~BWVWCVqO}fsffaTcX6EiQvq==F zOP^|6%>{jzOKjs=b={aLFt9jWyRKL)bq8c&!6~6LnK)~Gfrro+tMYxHE#C@&FSC61 z_Wpi(FDKaF%f3IScK@onv%lrKMr!$)ve7D@qVTTU% zlgWX0zqxELNxUzqcu(41ubm9L{v31+81F7FnhL}l|BVH{kx5les#9c|>?=gU((H|C zrn>dVX zVnG4ZsdCgRK=tOL4kwrdS%Jnez12R-(5}1^@vjM05Y9daFk?DJl zj>BRbGv51d-OguCo~)^P#}#{VP{D)8*=(|@_vAf&{qX8R!26>4z9RKbtOU;6{czIg>5x_(2mkdRuNo|~vL5%SWy!)=vIjiT8-$8EV? zW28Xztsi#HXxde&H3H<`Gr{cmNcWca)whSyd=lFytQpfC>VPtf2-UaFF=&ktfw6E# zv+#C1V3u{q#lh}w1^LF7Gpp) z=RAAZV!-2J#K>G6B$-2ftp_@`WJgw=#uZLCHNZ}+7K$ci7cRwBOyBmhc)BK?^;M#bI@1CTN>LweYB=d&8oa+>*k#C(wjIfD z%A)(^3yqpx-e=M5?SiBmS3UQCr+9K4A^4-poG*X#%QWv_8fS8(cmG9MH;A{>yZ_H$ zf7>lqo_tb!W+~o+*hn-%s7ZU$pcTG#>NWu!Pt*N9q1B}6H9Z?u4o|Cg+IGXr)ufpW z1+pjP;5Vl?H{%JUlgUbcVNqWx3|n9vnZJntozU66-+#DS_4oY|EPAW)>PnEmDSEr} z=4yY}Oy`p#t*UWvw>zaNPwjiUR4Mo==#Xl~OqHuO#4q<_knt+4pm*nRePfD=AlMvb zXjk5V$*UW0gK=Uk%zKRz->QW6EpNzr2TeGM$>0I(P`d?(^9&(`&{eP+DWp1G%VTV4 z<>q`d-(00grrI@mg;+sSba`RHr5*VY)-k$-)39I}TcXW5y1krgx6T@x3h8Y6MD671 z@rk@z$TXyCpU#tu$0xz`Z@yRfz7|$Zq2-&&HLc*hVRWgq%CYZ3s00*QSG9?}w&|jZ zfi*Ueqt;#dmVeth7#t6;b&sCB%Agy2_$4A?v8EZg=u>@BNwT->jX&nUydjtf(cV|pu$mNYQJo6+-WQX-ydW=xv*vjb%ZtZV-aHfVZu54+eM(UB)y=rY znohdf@8fZ?+g&_7|Ci>Uu)Gc zXPV{X_uqW+P4DH)m(Wn2KRx+LD!)6%zDcOxgM@Q*S#q1_oBT-)DC+w@qx-GyMwe$= zU+$Q)t|{saE()A($*E=7%?G)2W_vvwMDJAc!pPxufr5U^K-SmDLK` z`WId|&{dzs-1|>fyML*>`zOM?Kb};66eEbvv+q>!{`M2>{_3mG1)7+>yFhq%@3Pkj zXzQ?2;JbA`6Gy*E#EIz5?&6j4ZmK4eH{;Xe+prn}ri7pi*DU0}n+lnNdqjB8nqtB0s>AyJVt_O!wt(Rwa#6Tojz}Q)wB<~?Z6wU zuMkB-RO85df^HJwZ3;L_@Te*m$5M5=h=#FLkV>j|{) z@2}<8O)cURf$zJE_b{elZAYOfaO~T&1iQp1O-$e(88KmlK%0=%2d8#$0XQ?mtAA%8u5|1Guq7lHRLv3GZICJw#-tRb-9 zf_fig_aA=}yPe>Da&mupk1&&yUPIZtom@7;y^EnR^4<_m6D8qD6D+FUt6i^gu_kig zk-?ii@tS8+wD(OR*e$n-fcH(j7x)+FS#xm_6THz#44e0rM=#-a zwd?IJ+TJ+cdskO%*onvIyUH8HD-V?mP$MW=b0vppDL^-X;hWtu(8T3|#!0f@GS>u8 z7En);w5pOmG>Q#7Yvc~hx3FP6;F>(tmx_SD+3q)6*3_qn5rkU8mU);2!KP!y?l{$8 zS=Hb{oss0)PMpzuv&R0tdwxwU4-uh~W_cn%y8IZz84?CVnh2B7=kiWSL;B!)0}%e^ z2l?*{Q%?jSYJ=}||4rM#ebTH5>;9hs-S_nq4v@4e(n6soW#MsHedle6cesvLJg>Cs_7C_`I;J{ z>YJ5NO~`If-nBd)4Dq#7!x0Zf_aFrd!WSd+A}!~M7N&bI4@C}U(m-Qmhpt?(ckO9f zD`yFMx<9_4GCW#DN2z_0MS&Q&(+h1`x7{*m#N~6M@q&q}s>uWzHm+H&k?#F3U%&0l z(l?#nF1oTE^QLR*&aZ^;pGfZh`MQN) zD|dHsCMKFN&g9#VHIqM@&*Zm1-p#SnGbVToYWI*R*lXJ1*$w zrSfhez{1X*W-_i0(Sj9rcyer7PT=we^~OyI_$qJqtD74XF;oSH$un3^s(AWhTJ6X4 z>Fd1*hafWrSNjk9ySRQxs|vz{ zmgs1eyfE48$sxex3wi=+**5q-yV`($zoK{oaR4$n3@T-LcKvcf_`YVENgcSYOV3Yq zNkWYAb8wV`I}!@R{1mb?&H16&LjApMw%S+?mvDuzx$&!sv-Dxani$D&Sg7+ z-hI-bO}F>12O2&(eM7xlxp(iPxcL1=<=}c!v0SHB4&F|hrfqs~mz-94W!NpZ>a>|P zrwA{pisf{+&!jZ^`h*_*6Y3F?TP$RI$6t%^{L9j}=b| zcAp`#M1Ypl%xVp!?zDBobHVrooSk7)^3Zw42g1S*9|o(Q*m8%w?wB@R+kGTgsfhIR6oRAZc*n9f zQN*emxNoVNg>#T`L%y^;eqLLbom5_bir(6w5Zd)PA3z&iLgyJ#1p`F>whoRxjCQ1a z3g5R*oDV`=Q9-)VfAw~&HS49ETHNYkB|9=zYil>)YKeU=*3YYjX@MqFX(K&MIT1rT zm|Uf9Wo4=CQNtFbt$~{s4I_7A`Lk-1w;aQ6liwm&qeGv}LZR&K@-4UU^>ril-O+gx zIN@fgeB8`|dOWyr!f2t=1onkyB(=8LILhV%+I`DS83|+q)bSyYp4ooT97sN2!qGhhErdQBra(S?L_by)TPK(Z8GHj;9suJGb6Yv(Q zK5qrUds9Ivc(?b}L=Zg3@UnrsyVwg{<8~jmNF}uw5^k z2{ekIz8ME=Yw&@Og^+!FFrT=^p~GO6kyVt(al{P>-#DrmrbGpvnh8pmVRTmmI}Tl+Xo63AQ5`2${J$qJY>w6dL~B-Sk>TyWpaL8HZ<<4XF}c=`No@@d><{ zYEP6=ve}$lm9Cclt%~*Z;^54o9Wc@c)2_P|y9r%1R$$$4&X)Mg#FL*?yFXs4{PNdt z#Q){z^zJ{K+>Q2}fB2EV`=cQ~+ z4juDudc&rfqQ7xcP4M#hq!rpe>p?6TSGu)RjdLO7^LbJ2t86-_Q82FBVztNKWz`Bv zUwJqC$`j%Z<4L@V$Ho10HW6YiKsC8%sL8p!=Z9Ap7w_L+T+9u66euz& zAdYXl>=U0eO!bzzm&rYe^7Co?5%+F&hewMRvas)lm`>RaT-+2P!5t84U(_r>{qRk+ zuQh_nM0zHnmS@b=vn`awxAc|-vFre7c>vSNk$yd3*&U7pL>F?JsT^N*)-L`-_ZAmg z=@=~+IwIV)UNA1y`;GXR+cVjly5 zd(;p6+U78FQ%6b>+`kVro6jxrckmr)42{bQuT2&j=@2u*CZ`??O?UN75|Uav*=s{!`u>E-aUvkVqJA>{9NyJl!g_oQfs!?wkm zCB~Wv4uq3XkQ#pppbIWnD;NcvCM)uNRm?O45ogo7 ziyK`G0*C89BLaotR~3_|@*>%%MKf;-N+`m!VI{Psd*R%J#0#^;+v*Mv*f1kjp?Ys{ zm;5^O3Y?%%SsI)hcr0fK&4MWjGmYIWu|!``U#>}V+tTTWYr49#lvz|j{-74-hBZr_2c<+bzjSK1AgLNVEbJA(!3-W@ zMexV9mf+rfzOma2VLk~cWnagObQ5wRrtSzfFAPjtwP(r8Z_O@Px&?U*FaaHk$=Kv^ z$t~#rEPXoejCMK%==roq5`LkM?djuGQ5zqS@QU^F@)% z_zLwJ#zDG?)4^ef6H7!RJzPc>c*PYVQgMAg(DYk@?osASBoxRkXNq~PhT=yp65R>! z0>}v7_b~aXAN<{*-446|-C_5!(d6>56@QdQb#iil!p318O5%1x7)Pnu zo72fLb`M(t?-twfL$i3F4toeTf$)vOvo~)}hfPs6vv%HVdQIE5)%bMM^E96qSMkHE z_kz_IyNicubAIsv;{EF3q1au>S>4-B1<&6-Jgno*CNIW_AMwgKE(N~#EEyKy257?U zHWOaEq$~4)3lc0yDeTTVj+8{Mtm+s>@ zq~~VRrrsvM>*w>Pq2}F!dS~#w$VY<{C)Ua2AWk%>MK@a5{XR%k^-kQ9OH@C7_<=d! zh(HZDT&cWx+{o{P!S@D!z?OVFy)JR#Up_tdemI(SBBF{?baKYgrQO==K~S6cOG+yA zv$S*+EmqNMeB(KtLGNgWSqF8OHpk~JSnx<|0et)NsR)L=b?BWM_g2l+H*!q_HtI34 zXz9AvNwPy_+p3P}%=GrQK4er;6vu-6z(D#I>!9*1kegyki3U^<@`2F7!9X?G&=$T+ z1r~Lf<06C)Rni|Gb|O2i@reRxXmWgDRg??P373YLnX^zV)F&QhZ{NOtyHqO9l?Vc=T*<(gyc2(`&xXn>0i`A8n**=Te~oK-M~@S(vbqo|*msE{1>(g&`p z-U7L7!QM$D)UO$^La8V-2zQJ4(53C>Dmry(NbY{SwAG(Q=Yb4Dr?;`Rh=m(WwpqMg z-Y@W978F>UEaWRyKse3r6|NSV}JK=fBR{m$&XBeK8yl@n74<`TizGR$wz*-3WkJ<5pfn zSmv~d^JKhQ-R$?m+GB6hOnSQ)yWQJaj-tkWp7qfTxtq?XaeRMY^ccL|e+pTPU&Q6|UP z-M>6S@MrYyW4ZfC?>_c-|GQ?ue)ZMohLsMzhbJc|x)OhK`7vtSQst>a_v8q>cfD!* zJyWQJb`PsbufQ|KWHJ=EE(8rHMKJ*lpA_iM`94RyM~iLy$*QU1swy6e)&9ecVEK4g ztj^EFI4z2On(w!(Rh|_Ugqg|oe4js@&$6~!rQ2;I7d_Qvn9l^XoAYVg$iKzK#cX!* zuoLVS=KXHBJHG&S&(6>1&G~uOUwdgI#J{&gV#qp;y$zil*kaVZ$!(m1d$SIK@`vRK zT3`xREYTkCVT;FePQkp7GI%H*Ip&o40Lpj5!6wRrP5b89QvNO&OqIs~@AVoP;5k*3 zHA^j1I|m?~#Az9q=~fd4(~>(r+_!|)MCh*{t920KxBR%5$nAdgw1PGmJn@G5c)sBJ z$`7)zyyCsrzS6CF;5|Nmz#n)!5~a)3w%96OpNCeUXrefay7X=V$!Q*^A1fz}|E{g>nA*55%{xoCHv5H$F^?&Gi+ zXEzJSX%+1E`yAO-`=Z+K&L4WG*eZ{>WH&uO$D_^h3cLBdDf$y()`IEh^FA`~*IW2OQo%t%ZZFQqXf#XPj7vB0 z=J}-|G`-`3-rE?jLfzYo;l184z`MVR*Ya~wtu;?7O}DPtf$f>FjBvx9ns@#^n0K76 zoB4W8$(ufJgviqBl7jh1VZJY+nRtUuoD2qlYc07UrlWl_#gaF|NK_IJlY#dnl+m!k zXB>H{RSPi8tRt+%m1ox;UkOuxq<@rWSJ#iYU0-{p&W`Ft-l5!$N=`JporN?gfO95b z-lcBd@Z#MM-DPQTm=Jb8-k`oM>qF7IHMf|8((PO7on%YG;03+MNAO)Fwj1eeEw=ol z%RW}oB7_{LR=4gMK;v}|Y+dNH%CC|=y@P?z?&^V>1J%_nFTh$BBf#ZB(Elh8I3Nvo zCjp=xZ&fEiYE8d};3DuXf5E1r0kn|W%QLJ1sl!DdA+W^r$kc08GFl>_vPX5TP!q5+ zM@_Ttr1X%o3SyVCBiTE0d{gBkkaA8c7jFDWllj6e!vj=RxNvx94`Itd3qx2QHWq># zm~GuQh9bsn!GYh8`h8eWgwo@`5kD$j>4BdS{%%HUYXNhXx%_eaz#w!uOZ?HLgv-MU z*t+I&4AB%<6b9i@7Idya6`@>=x~f-t@h1my5>d{kkIepaQ`uUACkNO z^tpxjFMp}I`={;QA2$tu;t~8#p<8+PK{WY{W^&xUfW`QG+*M#`Y2fXUx&!aYadBm@ zH=hajo*?_R;%a=ao%D9Ys;Gv;RnZfc-GHC(1it%NZ#BL$p z?;ikfK#;#)Rew0eQ81nN=jZ1S=W}#w_GYu4+En`4eAGvfYaS1_9#D2K^cV#T+mzW= z(4T`+;5#i1it{|)%7?Uxv0qumdT-3Fdcj^O(oj;;B%yTF9XeiTRlT@w zq(!VujMG?L2)c9di-82xnnJ-DP&okvxs61K20?fA$*QzEAz$VCg)Z-*mr<82!Z2}h zeqC_(A%c+Dt#Nh6bIZd@eQgVO_(#zD!}zEgZIX28UxvEgPB0El>JHS1b|?bS{oux&giUA*C@F+L{Z#U^0kLO&{tK2)dh2< zy3RbFxeP;jFJ$5-pTG{T+KQt4GE-lTTkg-Orm)I0GD|iIx<+?LMx^;cvo-@qJb$dh zOn6EWXedmk<#cWl$K~AUqJ5pIEl_`?oI6RaD-6ovotZZBShiS@-5z5AoxoFm$;{_gM0-z_(@cYo>;bPJWo%{juln*#ee4HfUplTJLbSd+^`I@M%C z@Se|m&6`tH3v0b_?|#=J&7>-@9KRRz?)7%(=RM%o8ztbASl+g2cC(%QvznbZlX*UR z){n+$>MK2D2xyGrN97Ov_oIqeBuKF@`G=lwS8XQO_WUKQaWtx~p{ZBfCH zYg1(?6gCxjt1u^ZiQy^aj8rqItG05A3S*L7UC`~WX3d&f(54FB$XSk~Ymrv*MP!4# zN3@Qje_Zu2xZiBRq3E4T$YJjma8@E8I9?O8uHSLW-~%O?h1X4 zlj4Ss%FHHgC~w8wkAY9MlHt-n3^v^YW}VIQ5Apa2y>)@UtE)7h_nNv%pG6O)7N94t zvJFQI%QtzL&}ER#ml`L+eCo67vjOyL-+X{(N{5sqAEe43gER2vLr{lvu;_Wtmi$s0r+$2JnJ+H_3DQ1|FX6msqKRN>gR2PDU+Z24nj09{`fHQlsu=-7C8KlCI8^_9Z zp!!2Y$|%?fHZ>*F%~HhoQg*|SbQV|^%tE{P*!~u1Q<9Zf2O7~5=!Dr?Cjxk>yuZ~` zdBE;prg;B+n#s3E!^%(f?jLC;f3?oDALW^x=w6N?x2D0K^e%fUoLs7O;+iWjU4%EW zn99HN6~evmt9B1IK0lxC7+u{f3dQf!YJ#A_W+rc6HPhAUyq&(D zPtJGyaogO$DY&mzlS$RPxDXtE=^@mg zOj2;w8I*RDWh-q$P-)?ERLDoKR!}5OtNq^}*D9NmF$gELaC0Sqc=E2-$ME?RBHX3dw<@KwBc!6~H%GzHF-7^(QJX)GpbcRi&vkl4#>^Pgw5D@K8@xEHF|(Zu%9 z@H-3+70Skbb);$n3-ZI+n5L^fw(G7TSRn5JYA*f^1q$CsU1xv#^6%i?zxi38 z$wwZ+Bf0x%H|HNd@d%!L#Jdkkf&lG?i2X(gbz*UGIJYLK^p z_g*u+FJ{eY)tk4c`|)XfS`@n-x^{u!)dYdCryoGTb9qVCzNp5%$!PlG;o{=e!$nn` z?^ba&u8Q9D;{4sNsm6Em233v~8o=WAYL%w@{aDbOz%5Ul4hHgsP<)}^*&8{c2H2?o; zd%NDo(KJhtCMY0=6fH_1nI;@G1&UyY+_Ndk9yzAMhAxCiVGLw;)lGXc7o$OK*KO}b zFB&kAfyVyzea|`1OUaRuT{XSC&WK2dKP88B-iPNo9}Xiy)Bu+qe4_y^Zr08U&ZK;1L|-GF z;@~@XU&28NLq|}$z)>7n4OS%t+{Sfy?z+I^dxK{!D{N>==#;|E91sXpEU_A>k+IQ` zwZo)iW*kPrkKhdh6n1)WM+*H$00_hP?aPV_pwlC>;aCOooEOzrqfis1KX#Ap*p^z~ znebiff(2AK=57$+Gg3$l{MJvQHl5+@l3j2!uV%NHL@C=zqO+QbvO|pDfO$>cT!k`X z#Ttcb7J8aS;%p>#umxHI1z-xGq6x*Tmp9LTls2Zp$LS5saAAczi3Jc6-=oC7hF@bQ z45*1V1BR<&fmO(MBqU;30PezVt&M#}g^ljY&mvzFb+#C^c|IZOjd@#%ehMwTA#rcD zaEZL6h1loK&kO?;iu1Yy`^}+rC+2l#N3*6niz9X-Lr$8Q6<#5XcK>az#!!QYBcz$` zgEq>r;(i@qjz|RFtKge#_giPq-vr@;?cYr^8OHA4dg6V4_dol>%CGg^XTHjdGlR~> z@xl$=7uW9p*VhhjwVQ0;`}poR+LP;pdry13ZjQ?q5<%iO2W_s7xl%lZCgN|j+dS%be>x*6SJHSGS& ztE;P*<@#oI3pRX@Z(Wt~Y!UqNkIkQ+gM4 zYs}v^e%I^)uPrT`@+#TMM05aKb9D`eq4F}kFf0>8j=9*J=QDJlaeQY#FbQcPqQh_@ zt2pisyG(MBxBzgou!X`gCD!;F&fGhu6LzX0aFbhYl4*YukYZuiT30Lh1Q_ZN6yMl= zWP#Z`Jwxx0kTAk92c`pOL*03!JOM-bSA*e$<1y4H8DmtS;*aCCgYZP>Mp5#Iz~~lb z)S3?nFz(=%bM_9$8r~=B+q|V*a?T(S>~`dr9600k0m~sj%)py)ZikZmlJQsO@s$2y zh`wf-!C+4H;e_6LQ?RAjMB(IxarsmMUh51v%rsiQ;tlU?pcf^sL@Mqs)zAP5^p5J{#~5Mj$3x-`D%tySDh|BqK-=f>#Q%- zEUK*~u6we`q^9_o2q+%>m*1mI{^q)~f2Sq>D@**p{N+t;&Y%Cum!y ze7DWs@KUyXwYt8zt`GxzeD57OCNsG{P2Mfwx;d_oBVn}mm7}KW8~56F^w6$)#=#Q3 zN2BWgYTP#CasT{$gjBFqfE7MtJ};Z;d|xh~o94J5e|GTv3N_zy z`Q_NBvG)G4Z2%OlPJ#4 zY7L}335lN!?%`aL`ItT5VUt1pn@QYiMKn=low2}v25&|&W#52l>I}($gqf`0087qL z44NV|g6G}AC#h|ncf{8MRR_JhgKH-;aR<}0aZZp?C*eZi*HbTYv-erf z$>*k3mm=Kjkmm_)JFy+%#|eYDLupWyb~HGH(47<0_0B7lD1$a+7?rbP!iJ03qW7X0 zaSXD)tE>Vc!{8i!9!F8JnPS6WMwIsvo z*|NIoCU*BN&`LgniG8w#;?>&D~UG(m? ze*C_bGyeJr28E3G2n`$c&9K5fW(|+Wp;lp~h#^AkeEA;7XNB!8r z_jo+U_}!16$IZNLzZh3uHcgYx-7viWuNbAco&o24diLxub0d1hw7^0&Dm3v zvfdNC-6Xz;{1LCbjBg9HB$Tr}S_F&W<5B5U3`TjvOr0Wqo14p$;EirgIPlY_h0iug znOF63Ql|OrDFt%7={qJH?xt;V-g7c0AX3m&X$i1UbU)4D2dYyJ+T=(8;gQF1KxxL5 zR*v1B-^cj&cJ9Medt#Tx_&PcU0OQy()|q8;gwor^T0F{fo{<%dJCzZW`@lE!U1#|I zR&bD!h>5#dtt2Z25!p`PgyraAF(RO@*3&fP1YkFj<1#1<4A zYj*F{YiUBnP7xp$r{bq@aP;s7MMVi@cK=E^h-Rww(a({~Fg~wi*^sEIA=!;NoT9*v z;_yrSBC(_cLS@E0&D;!bI1P!Q`&~n_B3mbRp_d>}YA;R%kIs+6Qj<~!zzy)N1|M) z!~`ykAY<@~AeLsDq$p0Uo`tO+qsed(=#$NaE56;x9}(jd1ZjowgrT_FeT(xibhN0g zawCI$a%!QA{B;UXjcDL-6y;t(m8i=CA-C>W75h^88&XP}^A_sN?xKzDV0 zxb7>|SGJAcS8h>Y**5*sy>SgJpSMR$-rG3~(MFX+-~DxSJoddCsrS!6VGzXt{s0Y% z8=#NR%keM!DGJXRI5Vy<36ul?z>8)DO-xqq2D@LjJzEpJNmqUVQsK1b)yJe_&$ zt`E%@_rEVyKVCcVzKL^KEZvb%6vxSO>b}7|D39rw+H&^|m--*r6#lxJ?r*R1Y_(di zZ_39w3qE`ZEIbNI5-J#Zj376|! zPh!p{g!42&QniEd9X2~+x&az8!oZJ{g={{EJ4xh*9ldcdTJteQj`T;yVC>F1XvBb0 zqTqGk_^!%Z4V98jC5kp~#@`n`(Ax{XKYwn$Rfa63f9YzkMA00s%JxoGnP^L?j(ngyA4vCY>Ti3P=oixyEJt54H5Eu(RG zDzfNo;W&u7W3?&c-(^zxL|aD3!ne7Rbso2Ab!SXqY+-@1br%oy&*y>ar+N-Imz#jr zo(o*}xc_nZad%D9);Q!A-~DUs+)2!1JTvb5x6$4IYre{F$-7Tu_g}u50n73Q%Yaq+ z!W-;c9jmf3EdQ$n7z`C;RJ6H-tXU6)fwUa9$p*dn6w~94hIL{htYL4YR8A` z@pU_HN)X+n`NOust89Kt899;dTgJc z(tg}GUNK4Jk_-Y(bE>3Z^MRiJ79W67p6^v9=7lh0;lzi#TLnO&w|nqdg<`*Qxd zSWTDfc(PtikIj{PbyCLe9YF72dK?-1=`T}F;JN|LblSUDKfPNQboP{}cdrTBWOKxJC?>N&nBp;-SC-%D7NNDN{O$+7TTN`kQd|{I#o(b-1(v5xK z7bqj|GAT|nPS4cvb;|Z|fNyhQW-0odsCA>1Oh^qDDdWucc=72PKqWjO6P#mTP-FfX zIWf60<1rPldO)|0-%TU*j!jJxS&uJk+jwh2FTjfv3-Fd*$A?O1LRvw4%=vm}49@Ug zB##zDEe)HK)w)CWWJgW78SHDFBX~0)80d?yhwFkJ4WZtuR7-|}gG3S)uZ$#fjvHiN zOyGOHQ`QyLC^$QC4)Av9hdt!Q5`Trpk@XLwy%-o?DA+YA;!M|HMKrm)lSMsFRO)Ct zZ_(R?%Pi75(Nr3-R(|lcl+vfj#?MxRjR^sV@&h$6=yq6faG}zJ$TG?!Bj~8!_IN8K z_Dw}{{JTHyNTD!19Jd8F0?1mpb{GAIhb9hLOD{>1Q;BGI<|`nIXSnVPt(q0TQ1ifQ z4I6F99cCFe6%3^0N(Xl{cvE-wzd(2Y`LE@f{P|mB_ZfD(vHSl#&+q<by>dgaFD9`fpP=0?=M&-(T1WeoIo zzvox?x3_S$92{`Z-FUlNE*&Hus*m~2dQug|$F$!!Gt~5aY4w6Bw|5Y|o=hBs=hdoR zxmVXKk|g`-%M_3e#%3(?`)WFU(Hr-x>8hBl-!0cDv%k!X0=+%IUV{GK%_uxk5+ITM z5mmye5#zH*6srm4AAOb15fN99kAb^el;9w`)}cKO@aZgy%1k-1i0oz(IV%=UbF%T) znH9Klji_r=bLs2KKhOc8gnXS$*BGO91t04pC?m;? zG^T7iP6QHUfivm$>MZkQqy=%99L82k?zG613s@xbQOM66spp`;^n2I8iT8HsEf5X6 zNrX?Ig#J)Cl^z?LP6z}^ZS=R6v1Tp;*Y2kL+T2DoR))IO9MB8Y7)=}smJleD|F5&q zK2*apwcrN+nIOD23}!V%eYs<@coYr$fY8d2yFp_Juy+5n3L0lqM0X;Q9GL9P40^eX z?H@$h<>Dacg~c;z_~sEs)Z*~Mp4SYZB+OBEt_R@VmFMWyfSe~y@du#w?Nzman@ z`2UOU_E{!hrBPW1ti$gA`46_MBy@Z1{=-RTVo8DoaR=EK<1tp0Nb(+!#^dYp*q~by zZ#Q?Jtd^v^D~E*FOrjcU;yGWB`m1(3uNsHjsb|9RD*DVEem`svpVlRS{Gsg|#Oi&S z15{t0tHXTjKjFy@&&O)N+BXio`>IUSvVtYCLJe?$aKA-y@4k*qi&=AM`t@|xKbPww ze+t&{E`pX>1pzUevv=DVio02Rirnwp=?X6S)$P7Hj;|b81F>IT2G-uULF zxdvBLAiZ@xxygbL?!N#W$x^+Fc~-HqGS_sSy9b^d-L-2B<%GA4L7BfXk$2Vspn`ch&7p?t=zxDy_Re;6 zA~8t;7*|d;W|WhFEdgZ5b*7aa{Xca1#dbB{d5evX3;7ondxFoy6d87=IRJnpiagR+ z=@fZH`Wrp8oP@iG7$?rRCT}k0L|RaycWv=ivf9vpVZY=)XQw7h+`x(|L#lug|I?BKgl-Zp4= zDrIa+FRW@}qhd*=#A4SH5mvh)$#5bFXVHZ0n!LN6Y_&kz#9vV=8O59gL#*Y{+-JVw zT}%%&=k83S2z$1X6OLV_w1+f{Weh!cH#hhXsJs9A*!^45^0t@O-c_cwNx18Z^` zy0yBzAZz00P5h-*7OeY=dmVGPg;BNbo5B0KIv#s^;yrXbXl_Y+kE&%mx=zub;Qoq< z8!w~R2lv||`{{D+hSxGLmt!|%-|qMKO&O#m*oo$g`*x?7zFz{o z9eS_b(0&}X{hy8v$dZ>U{wSbDaY!ygd^w%o-Y(b2cW~n`k)LuuEoTU-`tad0&x6I& z?(*{K!vYbmu=BHm0qNgQDMQ3lh*faOkh1v9{hm?y{nRjDv1AG@i;_zR90xagr!~0m z%mKQCfydb)1XY&_oQd3+iL=lEn@=_ypEUF;txpIZ+HOYKP#FX$oVH_2;l{;f4d%j) zr!l42n4?WUEvQo6uJSu&(;@10KI?~?H+Hh)$${1byVmzgfoCDlL{zDLllG_e4-r$;6mk{_jgXjfJtd%>fFUdQ4Nw zW6#!wv;wKH*qYNsr6>%Xj5LRS<4FoH5==zD6dLLy`YP|_^pA~ykzX^mjNGX3c`h3h zlk-T4rF!Js)%clM$Q8}?%Epb&gXW<-@j+A`uunn278o3HRI-8#Bp!;9 zN|%yhi-|`>(qZ~OE2{htrJ#IxlfDvv6*jQUq_>0yLCU+21RI;YnSQcV_O{Evk{Xw)`G|N zdhM|GWqO2iZ?*qr|I2cEb^m|gU-fZ=F?fbJtkF4qBie9HE%TnUGFh?PoWHVQ}-=u*Osel>7e`myQ|ft-0#Z|kN<4}GW&6M8KkpCn#n%jWcgG2 zNQrm$h)8c@_fwDqyvyT}v`P@nK3BZw?BfA^v&9mvX?YfvQU+4#otqISE7XLW(VQ;a z4!zh-iy4cQ?lkV%sIA#q%>ry83oV{R3S&?xQk^I(FYdx2EVbi~4zd;|QK`$(o+mrS z_{Y+Z$K2@IVv#IN7aO<}z7z8*$29oFypG_|A17+b3BAZqd~$sEwir!L`IzK~yhT=E zY-uOMg6~bMrY9~e&MM}lti!^6#;*1xwC+3z9c*(k%yZ1<&m+^1o>Xbkf6U5|b2yEZ zwT<1iEf|N5rVZhBI2ea;sO~Ont~Ax&0e+?S8gQv-Z1s$PVO|)aO2Vp*u~<_}1a`&r z%nP_fpQz~FhjBE7JW1ay@J?)*xnZ3T*O*2}M<+(ypq9AZsTsM5?D|R@O`ZtdN#!v} z3oR_gKEmflt)fo7Z;7>~W|h}hODu1Z_MqTD{eM82{1&|b<-B{rB48ymfv=L_ z{g1!lyU!}m^jF50AWZP0M-pu7K>7XqV}EgMFTBtM(0%e%3cJz0(2l)I(BbvA`eocy z)$uT2Q{KIuAHj`a#0Fgg_8Y7TjL#rZShn!sUbbU5#uB^RV>PZ?huBrsHf}738n2nZ zKA`t(ixj_-j>@?M@nf9M8TiLlWqN4(chjXCiP5LyW^M{c9OO>FyWg*2(U@dzO8z(j z=`!%&TtCS^^VGIPs)5=4uY%P_C+?r8Cq{^k|KDnm(HGCnO<73V7 zT^$Z0W=)3oP=jBPCx^I}>V-?*6}1N%Cw2s4_S`>a7ta`xguRYba%f`h2+ zp5IpM%uC4{iB-x-@fQg6^#je%Cio$$n_;a;ctuAJgDy1N%ZG_&Aq3zS70&HKs6I=I z{5s#J!$0Bva^M}urSagGijy@*rZQ)t8=R@HVPK@ZOt9u#0oSujg`OCi*E^}@Gqv(` zJ1J6PdizZo zNS~q-Ssb6%oD_TmcC89oN}@!&OxWr-zL41}ez5b{@Vg=CR)H*3BSLL$B)D#yNo7#; zKu?nF^EaCtV)q^2xbYX6iL$!<0cFIESIX<(*Cz){6CQi%H;HdOFcrd+nS2U99cwL4R#MAL9HtP{7-)F{=aPQR-TFYZm%ve&B@z1sxiEkEMzg{j#v2>UYPxURxtqk>hJap;=h{+^0O5zj$RYOVkUzXSC_kiW z@0Qb-rn;is?-%}BuWpy?e$}IH4WX+LY9sb90B_N}nZTb{>$~-8TC65FWxs64>-0l9 zdKsr~lIJEn>CKa51O3@~vr#EWQysd9LR zO{;eSB)o7~b>JGmP~3otPv#(v(4o?(<8!9h%Rs;()Y;~I_HKaQwdLkzv3%*=m7X%L zWH)CogU^8S2`vzJ??~&D#0Y&>2T*y}DIA22nx4PTxWUXsHuG`>cNN{x{c2UKuvp(z zB#pXtb~Qs$5N5JtmY|U%J4pr|vR@LlFE3TbgX9y^@fgD;c$Xlu7Ci$l3UY38RpC$> zhHC}NAgS2VJGh_@Ez}loB*$TrXjIvg4Nt^x(#^s!yjoeIjVb@+3Po_BtsNC%E&|6&dAL(0&a*KXvn`XqEzyKM&gg4{FLa~NxcPZ$ zB|x%-B8{7|SG<~Ip8`$+Oxy%^rlT?YMD&L)581)Y0B{IORgLEUv2bG1XGxt&07|J=S)yM+{0e!-+;-w8TZxpFf!!{=j{iFTCdwzGzz=n{9*BM zI5eoNY|?Epb}-w|=WaMIzsv)N=k0Oa1dFFEeM}dx^QYh;$je#ENRyG`o{!}mYU;qj z_wCC|k+(G0lc`1`m7A1rk!d&{?~An0p!7Z-kMrE!&gZr~P2ld8{&~M#7saGlzD$d< zSoN!_EQ9^3{{?Ibh2=|!+b>g%-Y@&U=Si_F%jpVs&DCTwVJcwVGC_{bbcin8GquL zlp)++*N^cq!K>Idi+ma(G~Th|RflRXU3aRTJ<^nHWD5m^e$UzIzybDhB#eChV`s{9 z>CQodawW>!CG`q*bi?E3`kSa~V2bp~&w zZah!$#sU;LxnYp`CLvDCn$($J|I^QRH&zy*zD$nh7Q(U-HLp?!2EXEX@Az2IQv*^G z+EvxNgzeCd64718%g7xQxHdyNy;=M9!{~y)hTVU2ir_aif}S+N*!>TdMfH#WHV945 z)4Sh$6nC$VFRpuNyHPmoX6fU_`2Fz$YW4Y+OwQymm& zvW0Z8YM?ba%%So|niOFC0T7N=rUPyV!=?L}hiw^eoB1}SxZul|(tY5QL;vxy!T_5F zLHWFT2pl4oPr)lSg#z$nKbPY%9qp&9HC>YTzl^cFTq7*y#SQcT@0agh@(EfiaqHXW zcspGkdqeMX(4njg2hk41vwZ2kKrxvF<8k0d?{~{j)8!4&`(C3rz?;j=>DBbOrZMyC z$8}szCh_EBUBjf~3oya%ut628v|V&ESgJ)v8bTUvG7FXJG=@Y>9zmmU68q{BseZ{v(1^p=DW(X0 z#RB;ePa$$Pvq*{1TEZw<y_W!p?>)LZ~lmU5mK0NnCiH$<9+V=?a7Pj`a_;)AOI9 z<~eXV(=~wC*bG-HNEt~IZc0O?S0}o9p#fi~s{3MLY|Y1{gnj#^iq5o8j)sU4iAx=f{ zh*YZg7cInsM@D%MW4BL*^$PE6ZY#%#rW%kNHk!j|yM=wwq4zu;4GC3*@dLFdqx504 zY(S#85qwL~Ez8di*XQ$tgEr)NgCKF!cUewGPeJhTgzJFq(;}F+t8xDF96SYXt_>cU z*FUm}>{vC2^iVFBtMz))v{x_Rjoq~D#^qa}tUHPzW_kJXWfrf6olVp4ZTx0PM1e)D@q{ za^tu^4irof#XA#HTfc%7BVHaQFG^=^TZx7Lb*gsUS#OxC%(URw#G>h#Dw5D=C2>U= znKv`??g#VeBtv;l=;Kww(5m7=A_Jq`(<0#zEG$i=m`S{gALzHE9W$)O^onVxl?Nkw zmn@HO!29zt_VSn50KQWTn@ZI}H`WhpX;c(&ARCs4qlsFhsMp=RDnC64o+UZwwPIQ-dz}) zrVw-d48d5+k0rQv-a8vJ@3a7-);`p*i@V5gXi4LM(7_k-ZhIMJEr6GcL%JLbxuc{r zA*)S7L$#AO=gQvBM?-9W0^2`&i+W;pzdTv+Y1v@VA}VuZP3MjeCH)iZN zymqtq&+MJYy9?eLHS%ma1p}%aUiuqp$&*M#4JA7uL^53*B9+`)8@h~r)JPV?nDUHc zaFD7X1rZtMk%C*$TBK;%XcPR$<=wxh5%ltISabf#V>buyujg*V?-O~Vw&4r>*^i0Y zZlFG1RO%gmgWcEdn`Pzo=zuQyLv!%8!$(L5uiI5~JepcN9c_W;4zmw#uBJ}Vp?FHs zx0}83o^-o?O%CK#QR z2z|Teuw1PBpuNAUdN(Vt`rERYO%<9n}LW~WM41yUVb5NX6{2lQBC8ZFl;n4cN(9_Sh(wt{5keC0JMcHCyh!_L4s$DxT$5C9XK z+&&s4==Ds_AjGiPBA}k>=(FpLj&_~Uq%xr`a7FbX48~#br3yH(O(>$+TAQ(^<~dDg zRBVfgu=Dq-)`Avwp-4EC;3m_$Q`aVxQ&=&XS#h){p&~W*^_M6}C~O}o5qNA{6Lc%k$<`@88$=ynepnf7>FZG@(j<~@LLeVx$pdU;QOzo znf&?N@!dWI)~_mk=hS5))FPIu2ZkH`OYEm=rldmRz-Ju`c9~{k;YUoLlB$8cMa=PAVnb0GSmf6NznVd^ z;b23oLjeO$j3m|uv{UAHs2IJ>G#(24km(146%?brRSfb7QWAg;jG;+*R|}pZpR(G) zOCQc^t9*z;B_8_37fG)fN+|1I##C@=9m(jZjNFdU%#fHC99;nxv3m2b+gb4l0bU1PC51@2``NjX8DD7wG<`c z4wnWbXn57NqnR`6{E9UkL`h=83(Iois*%g!STV2^h5$mrG89(+z@W*f*d#+FlxgcM z>niaGu64Dxi1HVyE;v@H8s5kOgaf#$mi34>k+&9~n-w%HOhX(Noqi7*Me&(G-jZN9 zM$|`S6uVljNqjiCldE*I12bK+9iAg*57=el@Jxy$_9x%j*VNAnPpU5XkEy$VckK28 z?|)U}+28-e8Fv4jVfQ&xGUhMC^UB`QUsU^xF`Sj}&&uLY;Qf_IP|XVi-+hh1B^nb~ zEx7Ggg=i00RzlQGz&?yhIxRJg!_)&M;k+v6D+k4W)6Ua}z#%x%I|vrY{_FF0v~cG^ z-+rFA&rgdFk7b!RWs^3a-81RY0eJA39ue$4|EXaPmBVJFc(0J?U7*{coVVkv@$u!y z{r+XyqOsvvVn2x%wyRr6!+SKqH)S=wT>-$+meA&aZ-=t|%Ax#pxth8!v|0r%vcJnk zetUoW;c^JL(CY>-NrK4p;DG;?>K zYWJ=K1Fqb!#wv3x0+w_9EER}z-&hN~BkkI7{fdWYMxf9L5L~YF|ykl72=FzFfGmzR4864sOPC~3Csoqr4JjbMGebtpNUdo3L!%86LY!I z-Y;7}y_fn#>9!Hinn5`JTl6kt!Zujg&iBrfR?xX56MPrTJdG(B?6`dLk{5>B_U%Hy z<)z}pJ=2T0X22Y`uDbl-P)sd?25{O-p&WVg{7Yx~yIOlD`az@ENai11tT2pxr@|lR z6(Y*S>*70a@(*iYoI#2HuEYF@+>;r*-4sONS%3Gv+}FFj+=;g^vAj1J@`RbOFIuBG zWjsLi1lS%9x{Ab$3OA9(U8#Tp%z#z~GF(QCBn5QkXMnp;a_Q4zquJ7Ee_u)w|%;N=CO6&n`T2 z3VkB=;Y_{P-n>&TeAL-lRQO9;+bD^A3cd;6e=FbpMriU+fA)O$KM&abhBLAB*K?X% z1j@5l2?CsZ_UC}g9*-}6GU!GPgF$!u2ED6ul?hW#+GEu|kM~#2!|2#-AB^fg9Plcp zaHLYDTm9aq5DjkAG6k6;`9+&T^gSmP96SUM4#F1;R8(de&V>r#JujD)o4z0V=k@Yf zeV#Xm-2sbCH{6zPn4UL72vxswFLBWFMN7BBtcM8`bUmFd?cIG>4Ob!xx*>3XY$(6-&k=quMqqlkjwfqBG)t$x1 zN?}rCHqPXXj!8&!I^ts*sj)gDKs&~v7c43VDpLrz;El+cb<}%z+MJ3}A9}x)#}euA zLFN?m$Twh4^0SEVGK)SMSa-(M)Lsu64(1GBw1TuM?f^phd&1b{Dv_z4a64fIEq)`;)qYh!olxR;&J}4p|p5BawnD1}5CjLhqqsGiK~T zmJ$=Q7#4{o)P&OUpW1lLdC98-D=SsWBnRw7OHeDO6q@q~gml`Ui{ys(OQuob1Ssyr zmBco++rNrcwJFI;R{^L`X4jj!e2A$VmF@U^TD3>v+C`<@Fvspf)o1KZLcpDQcQ{;R zlI36}l*z0Uc1h<$3Oh5VWei{ozPYOW>(-oa@!ix2{;Sd5hTVfk&f1wetVY-Us;5Y>IX0ZNF@Cd);b5Lh z`vo*lNAqI7ojd5Rm`Vjyf7o(g=@5AV>ic-*Mz6GCc^cacKbPZlvG~w``r-I6f8FlV zr=Tb?eh29Rd%x35J6n_`}dS32V z6_fp{YLN~bOh3?1m+RH^)=lASm~vK2H>gjKA3x1M?2R`0Wp(f1`#X19#AHZj7^JPR z0X6X~BF^NGM;oTYca$?UkFTFUqnYPvW~6sY+~y01?^?sQxNgMQDYMFq-I-Ymm{Y~_ z7oU(SUUR5W&pLmRD|R?mD_N*KTMvCsl4n~*NQ`t(TNUq#Oab0${3Sw zD@ME`bw-G^j+-R5B&$%g5RkYg{}lR~WlIm_vB==?5W#{vTjgxr&1T+xL_s5^jP9i~ zk-Hm~^#jDJ^i;nozbCChyBUHFkbPx&t-46j!cIHN0R^cGx9clLHf<71w_-kRD6&KC zIUCD*O=8h6Y(X|!B~m9e)#i6hKVKmQ-ZZV}#pXU58liy?pNE6UqglQAgo-u-b6e|&ZHgvn1oxv9H)|9)s1 z9=MZX+y>piE1`O_2vU$sSj$eQ_D&)e$!JAT9fTU%FQw%hnwt?Rvbv`TmF1xG#aX4QLd| zwTa#CM%tHbk1J3p4!b9b`@)d3RO@%|CX04jF$er*fA!;c_bY_I%2~dW$vkhw3?jLTijsr*DD(P|nLj>tD8~NE(DJ;soun6DMF(s(VV0YwXnBw#8!u*y zR77Tu9MgeVg$=)^G2pS5Mdp*E4#2b%Lmg%Erq&X?w;}*zT`+Lm&Z0MPZ18P6z6Fi$CU*=%5sI4f zoDO`POvp;H=&y{^cjn2a)4!-C_1RuB8m8x1xdw#HWS~IQZxeUclqubb@hbx(4FkLh zNa)06WQ@8M3hqha?%{(n_OrfBmMTQv6n5z-CWcYBXTE$^*C$>j3#AE5;w(ms)Cz6z zxY8?pCCI6|A@r#z5nqimu0@IbUC4X688lXQH54kPa3D{9pYQ(d*!>%Cj&+`SzWeXr zgi%=t)%oE4-lQhuU*L>?|BTXjgm$}`dp{lb=Yid4e0Mvza}2$k(fP}vsiy51vJRw9 zRiL=HhxS0;Tio`RTgwNAn!q%_Ei3LVkJWg&a#L)N&_N8{4`oqd_QwA4FrTM~s;FQn z2M<1X;O$WNdEGxPJ}ew~SL3w2Nf%EynHt;6V+k_5;eTJK0POe6$>bwEH`7&|{ZA;^d7}0qgmj zcQ=#I!ThBi?XUX&f564FEYV?h$WrtQ9|Cu*fHiUOoji$v2a%bF4SQbbL_g&$=i|2)}AZ{i!c ztcNS>yn!zi_)F96ccKbunq|JJ-1`}#$R@`+Q>bd>t=8wIK0u$W&U_DAD44^_FyrkK ziK*aJ3NXY))9o1+K=1U#oP2Iia`D)3GL%x?@|n6JPh_AhZ4Ur*B`ikFNRrqb))}U} znnEn%B9JmZ+D>)JATM>uG+ibDaI7n$A;2o?ym?jP8!Obj^bCvlyW)mM?20#mBZ5-c za6~vwEECwz=qoa6LdhO^|Cs7U{6WBDzp>ijlL#rZ5F5%X#B&%#dn`YWl!P;? z#JM{lYlE6M{_B(MmPAO8tWYy{mz;RuZfLa87>p%MroD<$8fI2kIyi0gh1S3BJZ1c4 z7~3OD^LoO5<-}JmZ%zdZk=YD3s?p}1FdCg(Rt^Fibx{@;fLv&6{bsL!D%_FvbO^BW zDBeMV-tBm&?g~4ql;hJyk{AGKK$gEMd^q?keD_z&N~^0JIFogEhSzVQ6F`}5lR;(bu}1(%fk)mGoYZn51^cOOi{jq%z+bo*R26=v_}b+a{HiL$7+ zkeyh-AU>zuDt~bM&@f_ZyFH*;xbMrYoIAm&s^Fzen?pJ;`|41ZRogGu>+REgJRLjq zKDuf5_!NBjESg1CY`Cp$c`9zMNV z1;Fn`koNcYpMLoC!}k-g8F^L}Wf@lvQXf;$9gSyDh~DlkZQrjQcyADRfAjs?9S)!R z#lCvze|-7z$MJMo%7*MGFFXFUE3H<9I_a>L^LzTanf>~i765vu{KnU#3HOaH5bP=+A?B~)r_5xoE>P! zA}g3g`D;FPCH68CBT!Tq&jJ8C*%%=xrG`!LG?@&c;pUx>ed>5@s&UUkDQF_)c zIeWjJ(A#|<2_EfA!fR-D;aUDI;X66Gc+_91<1JL!A@;r}$|Wi)JC68e0DI9SR$7<3 z9N0F`(VN3^rp+5O{DG=FhonPxxICa<_-Ex5pia>_goahEGqoWdh;2oP@DnhJm(@@i zU=0gc3-f+h<{@E|F@vGiQSctj*l`TC4YCcBsPi{LazEADb-q`Eaz=MrT<#z{*R*R5 z&yw4Pg9R*BbV(=4KQ{}M5>&MB1C|NdMpt+eq)vQ zg&a6uqrzLn8%B|#wwxx2p#bsJ@D>$kyGBNqNUURzrz{*U!)#SzN#4AFj1+JW!Pq@+ zNCmlz3kJ3Gts+|Ra|uq2$$$Fu-xOzZ$}^$7+w0^cr3*n zq-RRoFe#sxyP0v0BejHimh9oll8*XdDV}((-dW^nrVx6pzGC*lD5{%0YBWS_niV_L z99A1*`b*cLb&6>$;99d}V@V+)2eQ~VSNbd|hZC2XSv8dPo#`YB?P;WeNsSN@kv6(> z=$)ST61SOs&0!mBe*Rid&4B|Mcog5UqJ-@v{s_$qM8camjPF)IuYTt3c9-6I8dIy& zS$Kej9EnreDcxJU#?HLz6x!G}AtSzf>!^xi;z7&ZdBPmsJ%y_5L;L5jQIT0I9V4=; zqNs4`UnyFQDkPv4y_CvtSM9DzeI{;XJu|Ax93Qie)RGgea8A+=4dS&iWg!(A;*qs9 zWJpe=?W_CTNn#NLp+k>Jr7Fu{u$mI_N-z4zDw?I zZs3HEhFWeN4=QZm$URn9Ul>c3uA$J=F1=a+%7(=8?MO|VF}|pn z1$%w{{+uuQ=_l+jzcqNf*A8#!lEFVYn)lDo&+BDte9GLXoACb!$^^Bvl;Y%Ji*&)Z ztj2wN1bXMC1OJA$ouFYGG1`gO{c_*To6@1T1JnjvyRt9K??0^{USFH78^0G<-&G&V z+aKOd%G^Df%f@}#vbb57`NyJX{*?b!9{Z|o=fMHX#5jL?oIQPbI#&IH=>7O^_3mBy znx^6GvEMHR?0kK6|NRi>DO<(+&1| ze`z}m)X`~=src7UWbengC<`KcOJkW3Vx-^ec#-z`Ok=z4dz7$f*}IScD> z;7lTGNw#!wP#$7BI)(}8S+6vJj!KZsKA7pG%H?KE3H1??RP)v}Q^rXdvr^I=>P#bv zL)9Y1GO>%Ho)kCu&rRW0=2P=Wonh0-CW??Lx}A)iILD0A;O0Q0Q#VArvtlzOXA>m( z$YJeGXca}BxA<1;@UBNv%6}wYzEg$?+ujp#hU+D4TEU~?02fp8DMo`EC%_7U& zVr!e{WRoe(D)^nU%HNIeJ_~^znit-1Ccg#m_ZNf0Lr9DX%PX#;tyetn5`WGIy zn9JRJ*Q*}by-2D0b3@j6Sw62CxF?tE=hlIETtB5{nU&>qKOcQ@Zv}kc-`*DA-xOKZ z_qZM}$Ir{@bP498SWU-dPQ-$PU2ao$o)MLQ*W8;t*AiY?8{9!%$?2eSWz6`3D zt6bon=Ve^N$nK!ED8PX?ZTj%Jlm-PDe(YE4n`1BVUKYhm5rBN*rV?y-*+AcoTq<`= zJjow_tQyp%xvARZh`H=Z5D&&VPm3I;%FH}Fn7OfH@?o(VMPgFIS*E^1pd$lZJ-jkY zlgcC`ut;NFxPvUf)q3YCboW%8(a?>tB05v7MVUFGxf3Nr-I*_>%alANfg1OMu{G?_ z3vG(K$c7_jNKxsWX%dWl0eK<^sLjX*8a^+U^2NB@tmbL{rWq|ZZ68i5trbI4+IYC` z2J$~T>y@-?7EY;a^N znsF`SX<|wE$hVMu$t*9NekpDaRN)(<-X;&J>ZcDCS-};4Qk6}%$~BJ-z7_PMvLhUX zY;ntA&P0P=R2al(fNLwS=)49+We{Oz318e~LeP?7)Q^$U!XIN6Cer8InpQKYvSf@H z^KGdK>x;dDUxpqXY8zf!;m4$hLu^T`QGz`0JClLq&lL+Zf$AG24jQ+8$K(ET{LEmp2d(~m^ zO}_hE5wLIgZn@$;-EF(dvkcg;x0Pr3?I8Ptm1pm%64WmrMMb{*`jkg?LhqlXGC4=@ zX1pIAyk7@ow%jnqdb)-i?Dbhw1YM`^j`$R!#bl9?SG$@vyBbc_#b* zF?gNN$NOnt(TOv6AeTAxF5Jl8jHf^R@O|*%kBc9E_~9ll9gMn9zpP{BZLi9tSWZ_} z1_q_^q&0juZThr*nq39}Q-{m#v7F?K#p1P$)8Ju_`m(@X633K~6TC|_4nKVeDA*=| zL)=&rzZ+~ckNtT1^0JC2%a{B7vZTy}7R%UuN(FwKfv_mlX^y-NC6$D!Y02GZJRv~# zX_g`umXdA+RncF`btT4KpA}2fFJCW)mEwuNh<%zL^~%(ECuhlW9w{kMGj|Qm=4x%Q zSPU8SBvR=tSBQ zOR-DPCCSvQwT zr$z+}=86?_TZdww$uF4Xq&8X3NmSD*OSmN z^H$+A9AYn54z-s{hu}AEz`mK_-RNnEd=yrp;O`>3xzkTViB@4uq6lA0r&Ofc_zY{! zLeg}rEb+|@L~ZHMdC%REvl@0pk)@)0!;v1)X5JB#7Tb8_{tW)TIFrA;;Y`l*OxS() zKcx};hrd4=E8i5w4+(;2@g^0Ql`Tpb`iuAHj0q#C0N!VW_W<6bsvWT<-ZwBb*G+}K z-l`dGw`Yi+jvO#k=$$@T3vp^Z3W#q9;1An}L*DKy4B-a~QQV0B`ugC|a|;Z2sCdW@ zZseW^EnPC@{MgRXWsE|x)D5)miQB$heLwk_r+>V87b{-1Igb0ho&vnr>m?*1aee^e zYJ+)74+K%6*?O@^A0NN};nQ^QPK86dSj_4m_%*l$8UBb~g%Z2a914{W3pWv$Sw?Q% zUcQvpP+uOG{bY&6syugR!ht@WG)GMizSC2%c!CWkpN;c&Hz7c3?Cg+d z2Q=vvai(~aR8}1^-x*z$W+m^anqYo+rulc+rc3)B?=s)$q&TAFqype@9Em%RJtHFI z-i6lE9r{{8qro|ysJ>-LTl3bmxahD%!IDi zn`yzZyWQo^*d`J%u`<4>^p7HQued>-0w7t8pcfgG{#r;5$&Oqqk^+w`Nb1fC)i%ix z59q6@3!9rE6A5vtMpop8VS=DWN|{=r7>p5BQQjaFR=M8_gOzLZCJ}|M!k^M$x+u83 za5E0bmCO#_%-3~-hv}rT_iES8hKYz=7jZ1N>@tc<;Z#!eAVYu=jN;7?!S8AW|MGjD zc-H2edvpHlzkOACcCzOfhL6WKYAcQkLEhKn{qnvq1N~qF>*(^glWERVF<2yfm5d$7bS#&ZLaH2U~=tYAd))qE?$RN{fX877XI*Nzt z3~dzUommpAjnvjw&u16Ee~pW6kDcz@qcoAGmBe;eqP4Bc9@PPuDl@K}!f;SCB37T! z)G_nIO2lY$JV)}r33<#*jD!ttJif?ebSOzv-z7-v z*{(D7oybldRI)(f)+3@&GKy}-xx7|UhEJ5mgk5MqL0w*`g+j;?6yS^R-a!mVf+Mq| zLdDG?*{ci;6iPd5EEI4u;5LV>JK`qW7Zh2pEq7~-B6klJw$JYvf`FXDSb}s4a#U`7 zsaHb_E0Zk4O2ynAbpXB#eFLgL1C@c*sqWpVZB-u28@V|XId#&SNY}jqw<8LqkSU*0 z-9VTFlS$(K!^C~Vd{_|D1?TkTyVcDd$s;PhW0nZJFCg{H zM!5}{84Hl7sPlsxAqgpU@NB5=4m;ms;ciD5S->EJ0U}8rwNK4V78?cU(EYdQyUBO^ zvD;(!-+hhU@88bd)R}PFet)by$p&tg=$JR2EXw@hVcw)}E@vwP(K~&BEgo?v!9!V9?io5ixQ|#Y`f|Qp zuSfC@V>wL<>fm!c)$DPz`IEEL)Ksc<7V}K zbu7X}zY~XOVld+g`1`Zmv5us3+#4S1PV97`)znr`_tX z!8LLix^M<_$836xX;dfwoYA8Lv_x_&2H1*2tnvgy8+(~Es|6^n?A(j%Eb2@-N6uVg z!=lRYR~*lsUH+&{hbln}NlfhDe6RwVvr^vfoj>T^D1J#z3DknS%bAW4_icCwvRE0E zj6q-yi%+-m@Rn>kt6O7sq#jatn_{(z21)8^Rcwz%k=7V@H!A@&AUUy^sfa6G0V>lC z3GxaoH}B;&8J$Q=2PwT;b((DJ5cGJbZt1S@}(U_Zz-joo67tFaB^MOnmp5k>A%;l3cv6 zE)f0d#%_vD-Vae!;JUBB4c=@$8=bKu+fjo=reCh`mt(v2NrMm4n2dny2l_2Zds9HT zeZUeEW_K7b^H((MY@2-hxOEfn;^ATO5V$wBZq6QknFs0ddF4K@Y@Uz3n{~@FY7pW* zdP;)@DC?kquBz33?H=)HJ?PuEM?LV>^yR8w1h@CM@3J%ic;_I>WA_`;C5=aLH!*)c z_DveFb`nvAbVl~e>Dr<9hhHy$y}U%h4L-e$-B%IO@*$W#qQs2aZK_a=LLqj45wYG^ z4xHvgUxS~Gbm-pPEx)F=fm)m~-5FQWArkp~W02*ZyQ!C{+mujyk%eHL zw*>D(E9ERy$|!~UJCpOU4UKyANWov3ANCb6t41;E@K~@Y61|9(n{L@7;h8yzv0qWe zgF03nm=$nzsOV%E3L0bB7S=H)b{B?nC>AkWO%utl2g+=>Q?XCyBUvK5O>CarkVfza zgr$*?KIu+pr=o9}G0;iEV<}h+aorTw=p%n^5nHV>Vih16)HI*qN0XSckQq}X)E#ga z6B6rG-N?fk^IvVyFp>W*3pcBa7n74nP#h<`>PliYdRr(MuRw=$O4nSWB!!APVYPF? ziXRw>#K3#B558@Q|3-fIS$wzcD$gQdy^+!{D2+B5kF}trH^+_9?Zx%Qet*8Kd{4sU zeOpyufp>d7QfK99Q;9#u`*n4_oIV4#=iZt_E4-Vw-RS(9HYWAv;7y%3D|8?L!F1|S zJ7rZv%9)#(yeP}6Oh-RmT~)!hUoTeb0or+pGR|S6+bMH^}UFnm&+=vA7?r9 zvitS^{(f05_v>;oUw>HzEBT!ql2kCmB~irI z4Zkz<5${~4vU+tX#{PSSXT!2c>(2kG<7NMvz7n`ocrGz}L!3BV+IQyix7pJ)Z46?q zXQ%#0UHz(hQ~hQKp%rED|8udZgt3eb=Nm5%bhk6n?b*>!dwOK( zfGFiUhPm`N~b5#8(~jp(IMG>|wvPaGg8lS#}J%R5A!rP4{~fZW|b3gkD5_1^L7R?3^*4t2>|#3!UpsOO4(34N!0#0lAaob&Fm zR7Y#@JJ@~JH2gK+O?~$n-F?ys4sJ@mGXCX4OgBdD%Aqz8dc5Di|7qY%Br$p49^apX zH@X(q$AeEcIT%2*iDBEfqix&65T8n2GSc!As*+c@Cdr-5%dPDznFl-HZkuE8Ap124 zUJ2|D1=EMcb_?&!wkg-;=(QT}pZj2u7k%YM^|IaHPY+K`T$X(~cX$Zwb_l+BUY4`G z$rtFRL4fw^YFgebZ_Cx~yJhMAejrdE`?3UoUB;TO%|+j|QjE0Y=LT*XMv?^cWaT47Ou7+pz zjM0M_zL^V7Eh4S=wO85+Xl+**QmkoR9GNmqvaZnff#HT(tO#6OH=N=XLyeFdyCf0O z#Av}#@)$A;;gE6LMMH~+{=Jj4)b7|$*18)mb8HXNMV3l)G99QHX{XKT&i1vy&dtX7 zhC-_odVFZbiHC}uLO=G{0*KvZ+@0mk;OI?mk{jjA;@5_Bx+;+GEY>zk))c4|s_87E zFwt6*i-^Qid@7RXBNREBcsG?R9V4@Fg}`*&h^vKq(462V7<%J|Zi>6r-CgjlRpoi< znK9#U_1$m5+oAOz&T1D7ybMikY?1Tbx~YBcChznCtI7wuE`#7< z@c=%%tT-1xk6~LJq5Njvl;i3CSR8_^sFQ~6xdPSZz^@Fn>PMed)7H5PH>s331bUxms3_i%SgNfbL&E zEK(3Jc=-ql+YSD~BhH)j5$6TR<}_~#3q$dNgeBed$Nss>;I70A%$nf54?yoMFDrN7 zkhe0!Y>s3>7%$!IhD<780sK0ldn2`Vrg?}v^GS+@&1?lOd0y9bZ;U%hbpBd5M7Hut zl$oZF2DHpug(Ghn7GB1d++;c4x^`qmAeT*9=(p}9V0WQ~MYBuTo~$&o>v)J2J>7*S zd?b?cvVx3*kA4Fe(^;jC4kSNKN2}wj8@=4mmY1qq=A4K z7bP;8Yt@^vfsG14i_ik$SoxuoRvv&H|!s&HMvplRBW@c&Dkpkz$Em@7R98KMv5%Kq{fN*>mhK>dqmGyZ0O~#%}T^d^64Dr|Usu^1i)z!EBXHaH$2szw%FphZT2#flukg&L#eK1uH=oN2!6ofH1qLn<8@QY< z->pkDAe4+aX_XGxj~iPyVgS$l0FIBD=OX}ZHFxi6m&@{T5zHKPU;g^x*I$9)d1Jy8 zhZ&dHWd_VGaTv^kN{8PK%oHYTDWz&DIo4xE`P}E}VFreU3rlDKXF&$HC3C6*1jf3X z|M-zb!_arLPA5}^Whes0q|=m``r_euFtO1l9iJo}e4=X0lALwOcUDxO&sOGiWW1@u zQ%$UEoQMTpS%rggBTNCVMg+(r)Obeb9KRxiTj9T_Gi6sHOS$8H>!|KirFg>lmL=D?Slh3NC%2h{#miu5Ne|Ez&wGb|A7;tQkAy%`P8D z7RzL5hqX4t78e3nkPYZNr5^J0l2cqvXa`3)yoiWlBNEfC@F^hJ`Biv^bnJrI%`SID z{~bq!jjt{B1djHImU|Xk-~hexg)at{SHL`>33Vg!M6ZSuU^=SKCh?>w{Q6m>I=GTJ zq%tRq%EB^XI&dNxqXgs3$U8-|NVt!mHRp1C)r}QKaAXhVnrA_rgt6F`@-ia$U3s@z zbN>7`i^}JjoJmdIgb8ZyrbZA&IuLsI7vueOf6-Syjmm?!`(M?*1@B|~6T<@s!uvs` z!p%?p^>zfgNn@pGerwr4e}WW21_=@`S;;VO(N{S~PkWE?lOLg)1_#^Qb{+)V02jrN z*l$+V@~W?@dE;hqK;YWp;(R@>DuH)B%SVfJ{u+>>pm3wiA7_ijBgWj|-McJx-->1N zP1AUd$#Goe2ZRSIwzZ*)9`s2$*SLIqF8ie$+T9gElg~iT27v7r0y=IYCdz= zo?=s(%b1gf%=3=a#>Hn~H-L9^(sLW(XccIlSBZz7%Wkms@Jqy=&WkLJduXKbRl35@ z_!QmL4OSlsvl0>#Hr+v~fk%5+@F7mtK=YQhl(TOPK~8iafko#FdXL z2M~J807C9#VkMcXj@i90uPvA`^AY7_=LOIbJ`%Jvfs1~^J-}Uo+8d%rc3Ores8?dI z(HN19=b|q_sI!ZnWA~1lncZcW88fG0K2%VY#e7AEn?TY4P5; zx~mzzIuPrL1?ecd%7D~Jn_?r@hXctb@j+G=z2bhh$sMm^CSYC?5=W5h$IJ^*KWC!U zlV@6y5eTDIM@BrqgC0D}m4O1~3%iSv@?FrsOBJGoF;>|vt}qf=Q>fZ4VSig3{LAlS zH+teZcmHpO-8Oh@UHOMMrW|!wdaDk7@DQ0iOS!!tzxN97VeTet^8PL3jXw`V_kw$I z_<5ZkTQBT3=pGC_IZ|Q!p2Cyd$PzbWYgJhSz7O-hor5Z2v^QEV$(b~LInT=yD#F?0 zAqN_lW#&G1`HVo=raJcS<+<<6JgZiPn`B{hEFYV`LUc)4P9|~s^cYYx?Z(>_%!R|h zy#3OgIx4xr%nvz}WS^e0{@J2mso2J#-Y-jlH;RDs#}6Ma%f)|Q0K0*?4nCOyh?V89 z0gaPD;;i|I8yo299Tz4Z&1!!eR0TYcfk`H50M&n(b%S z2+K?;=%Co9mqkT!9+^4#cC}Sg=V5HWr5%n=Z1oxIZOMTgy*ndTd<1<{gm&$_>_Rrp+mFzf8S@lSy(b;C+^1erTVCgKoG0>x zcWmvkRB%OPak<8EF!8~KWV9K|WMaoeD5wwVSiV_@$_k_`E)MO?!VkJ;OBkDpL#3(f zWv9*tWuS2Q79ABU`itfo`ePGsO;m_ZGNjb7oyPs!pf+fy$gSAt&qS6Trp;<+yiTEN z8?(;?svVRTY+LB!qVqN%M(*G~CniJGb0A@!?5f}oZ(XQUxgbz`PXfu90%>33#X++~ z39LMk!~F;sPCoGpO;YevP#d1Gcf*=blCv-&o5z)cDAqj*{_+jJTlw9_nVhiu@BZ!Y z{_uydoRz1VVIxqWD!JhAi+p$u)H5H*T?Y~9LgLU zNfs{9ibLjv`L2iNkSnR1-W)~>j-V0*Z-PFwV5{OY`g1^pSE!C8*U%`@d;U4i1Bc~f z2d9(Ijk_plpP$FiRXHiv%jK$yn>qJ_Ws_9%`LS`&rRRnlE)k@je9q8 zx6AS)DfRs0=l{k^9$YGXDK*xgP2f#?tjg@kom&<+TQ+%}KR%`*A`IOukC{8o4q=KO z2I)XD3-XLD63`&{?OxJfd#d1FWy7)8-X?=LesD;3mdWb7j3W!@SH3Jp4+CwYp|9}r z-a3M@RS~d~%Y(g|q- znCg3H#l}qIUutN zTarqB6eH#^W3D3$-m+N2@GSOfdM^=GzLlS9xFAWA;9q`YtbCi_{TpB9K$!@z1>J)0 zu^?G*dVc<8{2sfqGm)TQPM&P>0&nR9**APRAj})n_VIeOJx-VHxMaON{&s9B~ zKD@r-?T5o$F(>I<8%(U2s7Yz&oVqb~2Uu4k)Wl8IZZIvILsN}=2hzv+{EGwTEJx0X zo4oTDwxIE9+)m2L?d|e8f_0}UEBEgNyT;`sJwFKJtRJZoY#Sv6T?W5C&REs%g9d5R z$)C0ik>U~)WXG3QDY6#)y6(#u0vCtwXlXcRV796FcF@d9__PL)yN^Qh3HlbY)Xn`s zeE2Z)yjqQqU{Bi9_}y^wCSRVB94~=F`J+2-m`ddk$<1F%r^4zopSk~^vOgm(`%Zhw zF8(T2P<)8G7*DK8WS7Osu)kztRhA9H*vu1&+_1xtlE5dhMq-^~<$1vl!ZJ${Ed{A{+!3kC!`OaiNbZ1}Q}vx$ z$D-z4oh1ftxR6IS9vtZ#{ga!?72m}@6Bvd__fN-qF*Rj$*5ON~<&MV>o=3n(c3<*F z?8s)DD~$QFq2jD+MTN*o8~X0l*b>&21s?N=synS|AfM+JrI4*Qvnih|6iI71U{lh* z*_d(0-JOZZ@Z>Jy=D}*FW1mnZcaHQb5!EYRMHuO{V}lP(n6%I1%CX??$G2ZT!`n&o zXIy86jUEa=&@diDf_|6KH80thBw(5XBK7)3!C8=?f%jQorOn;{_-}vs9lm>DyvJNs zR&30XKYsknetah8R+-Klru%(cF~QrSs1Dbs^lpdFO|>2M(|zxz=mYbnpzKche)uWL zgfOHEoVI&{;Z0?krVkGf@J?>|PPQ~`gN2n7KLo*p!)WB19NO`CKR#Bk^YXa=@xDy! z<~S+cQ?+_t_5I30{LRg$PyY{HZ`<3pwQh?t1dRryC{Gh4W5Ho0NCdasle=U&uzh!> zr2>MhRRgQL`+SLOG`i~#oKF`Q5TNwp{`EV@7|*1ft{$h&i{r?)UIw2zp7HW_l+;}X zyLknZXMs$q)jC%k=V}-gD-69&!_e1ZG(*KfF*brk0KR`3uk(^n3em{;shgUQW*Ra} z1{L;{!0Niv#xh@#H$hzkwchaf__^z$R{a^+n9^VAsP!vLIeFmV>4$HK0}FU5tp;tv zz2|K0%5{+!8%R-hg{pHxjioakm-Gxx5ET=45*0sHVgeL~m%NgmNL~_%?Y@~LQFU6d zSCZ6q%0`jQ%rw%9?u#}5rmv>>kUMBvhfIH_sRo?4WyYFZB(qJZ3DNb%wN^q9Sm>m+ z>=V)n>aoJK6WhB;VFL^@1jLf~_D?Q9e0%hUotsQ*VRJ98ISs?2{I%erQKP*iAwh1F zB_Z%`nVLee0SsbqnVOn0vC5V#HTs`Zuo{NhI3YG9WRl zeo;yQ)ZI!4BtZ>tr8!e51TUz~qgc^KXEiY>VStCTluR@kSf(*8mx*lz8B&skY)I7U zFz`@evZ?hyAb&OMQ(RMUI7qkhpXQc+dlUX-!2@Ohj7zEslcXQ1c-Y$58k{vj%*Ni> zvV|8``~&b`t*!@&bsI0Um<$b%2y_?4!u=HaRLi9tX=af0zd|vNUI(YaK!N7)?qGGf zG_Q}PoM-ZCQU*@px72@`P2xcZWl4u@Yvb@;^&|So+zmQ=E_JlA-4a&MWZz75!%-oL z`uuK?CS*;B-F^4M|M?%M$@`=a9DI{$0&NN1IeWr1td&<+Pjpv8Bl!O6FTzYlAy%-j ztn7OjrdQK$bk;qMZh&)Rlb_IPLo@u{nd;6c?4FQ9ne5I?4hZ-jPuVtnhtZquXIg3c z;TsxnOx}KMoz#ob<81c0z5G1Bo**0h{QU8;ei{r$-P74D`r-Q@-d29*-j6)Mp4auL zs~fBr{rno2!)R4Bt7BA*YgY_c(Qy_Xk2C+?Jcy2O)pq z7=4j(c23f8}=3z(NQ1OSl!(Y07fG#sYEusdtaAeby!;v6RK)=mKQ9c3xw zRHQ~%WwMhx-mdW$L`l*N({{ttL7FKJo;(xE$*RocIvB)t#^_alJm8RX!F7=1JX^MrVqQqgE? zVt2jyO%5Nx>u(f<|H987@^}iYL4V%jo-~DgcJsnYU zawejLvp15wndUv-UTi(McSy%OSt}v+rXNTBX!u9@okC#m#@uFl^u8ZMO_)#jW8@3o zi#6Frv-|wuUxJ`d?(-4ga_50~HJ&`)JU*6+f?egg8~xA?22b_l&HnIfbo0Y)J@Vi^ z^&dtNcIRx!UIE3C4ah&`D@gvJ?K{p^!{HE0!ohxg+EGpsTgAA-wJsvLG$H1Bw?6uA zaZ~vTA4zn%3_<>KQp#dko`XWE!M5*8s~vVbe>o^L)t7j8o|+Dv)App`ClZk|$#)Hk z7(DI+ve)Z10LUq=h$AFkrOxoxaqJ70mh_~SP21PX5(~W4$EDxW;~D|2(vjj7T_M0K zC}cS-DdXT;mf56jSvP5J9TV(+o3C;z97+2Ml?;L`r4c1*=<7+9(9tqO10Mrn+r|>^ zvSr3>IBPpd!fdOmcaNheXYjZU<{Ojup?s``hgg9&EL@M95ObSm;!#pIdP!iy$(nLz z^$c@q7g7mh&H82yviv8~(=@U($+gfP75K!v&x0faef<|%HlcA0=6!uA{;01njoV;_ zXV4QYIDHf@~R#qYF6tU1TQCK#OY*(xN3vP zzbN`_iOA5K*iF9szy1${?mwGzY+E@9n2qiQ%-@1-q4!`rc(Z+Tc6HL3Fwx{sgZGGg zOY_6;uD;3e?zR_$!QQ|7>y{1cAI5dg_j$aYOzsZgqNxN2 zWdh%P6#4(*rk|8|Q9jN+W+Icd06XDls+-T(1mgPX`ulBt{fN@`A8xKacvr-}2WYH! zbyxZ!dj`er*a17nh#h7j(|oQf29D$8`27tVRyhV9<}@1GB7?4+!` zo+86AuSZ03Kg^>ag6QpcV?~h;D3uIZ9}z1sKcQ&L>#b`hN&*D56mE?(|yC_KjDAFEE3Q- zOnsup2J(1Q0AW1lfLbMLIs!B;<$LkqM@I@t)kf5gZ7^ENb%qU}7`8}TQW{643#0k` zU5DBT=h2(1Z;Fw0`UtVU*j8kr@{O&S!RJbo7RVioVIXX(7l`f31sjfs&&T>OZ!(S3 z{{AkcuE%d1(B){cw}T%)fH7XfjpX>j!kI3l`vY)oM%coSwSDeCQod$Uv32P9?_Tg4)A}8SvTOe9`fuvwe zT&R&EzVoc%XCD6@xMH)xf_6fA`aF{$H5vOc8uev&_=~&g7837!mI^~=f~{sQ%Ouv7i0Q5- zWqx-sHTUlRezLDUVvnXU;@sW)p?jCp86QRW(cJ;!Z_*cy>Lpjv;c>sc{QL=pW%*!x z`R>0z-~8~y+Ydi~xURBMb-wSA6tZ*vAMW zy3Ts$Ys2rZg93c#+zye3u3kVQ{*|>0Ur!YHn9aogZ?CUAI_5=l=jFo#?3wEo1HApz zz2hj4B_>qm{&pc=T#pu0p|^*4PT{DJFYxi;PKv_i4M5-jZe6fKXNQro+^F@?B_XfM znsOAatm)WVno_n3Do37any-v5ZSuMzCt-<-GzY4E@UJ*T{7W`SY>O>d8_F@;S6Ts} z8b^X_F(|;=5QlXttWobeP=L;oQ$tx|bG+GUBuC+Zg}t2`jOo+>X%yR;)s!zpZ-`C~ zOd2HbP0B-LtO2ZELQY5?JC(p$F;*=32@bz;V@14x|Da0NQ6{EDx(O>v);`DxiP4^! zPn;LSOkBo1*Rv*qm1|CZBalR~)|1Zqi;^V7jEFvt8IcR4d}|dnmM|jY5%;Mumo4MLa5@26Lplj)b1I(kXraUdXpWy4VZ#W z0sltMNq=N|US0lv8AZ%DfjW@6iC`0A3l@{Fl{0aMQiu&>v70zP1t4zhTa69J85h~w zBt9$><+-#{@o<-#rDRjgMWia?Y^i3>^cI~$$+?oJj3}?Fw%^S5$5V-Qf^VzcNQ{I) z9xRb7eK^<^wmf5-!1B?gT9S6cLKSmVtEe)}MY6m*wmT`dp-5V(`C%J1%O(B@Ou zi$zzKRaN`Zn97m|+h(FSjm!zUFbVAbe=IQl4d>B%)JY)d{6~oN_U8te?weh)&i$x? zjFWg*L~H0zD3_o^hifVA$v9)DieO7DT`53#+P+#J(Hu7FwZS*;jQF4`4+roV z=&hX}8vvwn7U-*mxIM)+o50*8-m$!TZO~Fl3X|HbYbZjqh1lfRyHCuRkf_lRnW+&- z1?dV#aRg(huK83Er@vwL#zAjF!61a+_|jVyql>v{Orb~`p>g6~q=jGwP{Nm2A0DgC z9P_o5Se=?eU1tu25t6iEiy2U^SB|HO`%hzkDg%6ug3CzFkJNRyY~pNZMFLHD`pb5 zvTmiVdW9-wgmWrr?6_iSHoC9_zL`GGlZgNAFg6PT82K!?2qZ1kSurDFVqrBpxG{-@ z=~sz`lW+-;NCT4^4bq=fQ&TBf`Wt457~h+Y5EiH0CX9!vcxd%c9g6CClJHkRl_|v$ zf&@?93kai9fcG~U-mhgQ?@y+9{&-J$$!H{h{CmqYL5KXG(_i0@f?DwFU^{+Inb53* zn3F*#D8IWu>kw{ow)4N6jHjH!a|U>G_^!wPSM&ns2N2-n$@XGR6y_2}~RbyZ#8oJX^~*uVYh?e+Jc_x1N3 zc#N*@rjzk_;^%L+EO@w%j@A%gtXIVfSbmJ=M#(Z|vo0aaArf32J`GY&OV3Kt|d}JOL^>Kw9;QwnsFz ztKAGwa~B5!Jn+I~Dw(|0D&*L;fkb~5T6jv3OGBD|(+3l^TB2INNtK55kj(TFP=DgY-{T^ZMWE~u^JHVqBx9^w2LWcyD@=8AYYe}10Z+weK^=>6Txb5kuUS^W!t z!ktHs5}CxZvf1!6N4lGM;Z345S4%Zbct+vI*%HYk$xxrb-z%G8p{EL#y#7*xNtejm zSDRU~q{S$LaI!k$>V}T_%9`tA8g`&R!2^+HcyL6@g-qHiL-rsqDq01lwt`3)z`%Kl zEEayagc1U`k&kRcqgYW$xP?nf^uPYs{}5;Lf2*+a{{?ct{Kub!Cja@q*O^!#Y!Ba8 zBM;kGZ{F;;Z+b!C`&WV9r*-ADqq=){HQk-DJ?C2pN78F|WkDyCo15L8K4y1TFZPq2 zZ1I$L=Vud&QF8Sy9LDwb;=*4&wih?`zP!_Hy;|p^dhJ0Ul?xsXM{w?}vByLnAKS`S zWB&or7Otboxc1|2<^RQOcJtHq4;MH4?-z^fuJ-3&lYQEOJLub72#yimH07pQ$zbS+wNKUz#_Tb$!C^ubIYp`az z$qGqTL)(((pwHJk2kHb-;(6(RS1;3i7yDTa`CW9A2A-t39H+zGSrxJZ9|l+cs`rJ<$!mZFAJvGe0#Ti<`h7Bors~ zwxA#p?DwEHyDIcmb%Of)SS9gQjb(kO-jVoKu}uiW+Jtpih+qnTqz{wld<|lb%RT?f zBB6V`z|JyfH2j1a-;Xe3vkRFsG7qtdva*?t-o&9hQEHqx4#(xRzazA7HCsLN{|wL3 z0BNP~G0O{p$r~jRCTZK>h%}-e97ezgrY+JYk6AUS>SZ*?J?x;TF6imE^sd;W)KGTK z5Z-DbT^cvFC3S+LM7dwuadPSl!M~{rjFUFB4!42NSJY3P$n z735)OFY{3Hymx$FVL;;BbM)fT`!YJV7FgTNpE)f(&q5yuet5|L_#E;5M}9l0?ZOqj z=Hl@DF={U6&G=7qe4ZDU$@r7yel)8S`ZJ6ygVo151W>?Modb_v!qxvSYR`x7RbT+ z6i5FRGGLkD{h!}>;=fHadGqGv)4A$-?>B?(%ge=_c!1@3TcA9ozl4OT_|CY zntLaHgd5D!lzNgoY$5Nun;QgB(Vc@a{C->`TF{T;ll#MdJegi>x8sY&hyBgs1~O?3 z-+pfG_NbHxLlGBi|KWc0X0^?lQ}QaB@Kx$>Z-pB6^BM%QpRW(s=ljp2@pf^OmS|J} znO+tpK$IkjSnk>UIQQrstx#`n~An#IaKWVc`Boe%G0fzP*KXZlTKBj#qtx*n~uCVzt+orOOLI6fg znn>wJN@xdz8ctP8=Yj>7~^QrO!a8d7=y1h zQLkkq2aja)iBTu^I9Vol!(gjQX-g;;sGu#urQT{VtKNX43p~^qSzB1bSi(eu)C49% zXbIc1${JU0%MtVD|oUcrHx3*c@m3OZ-(A0bXrS z9{VAE|MKO_r!SZL<8g?hdfwHIRGuyHFa(J4n=X#g^o5^eu$mWrLQh;gA0*eB)?Z8F zH@{Aa3e{ED!e(&GejPgmLJj^TutpAw>^(~+J)8vL3ElDxNx{w^SIK4AQsTl#51hlz zwvFP4C7T>d4~lY#UdWQ#hGwb`D#=7pML?}f&5ne0$J=g-J7Su8;{-H z>p+u#o4cX#9>@%T#c_JK3#&^0)+q4Zt}h%Ojjo>9yCA$CcP89s_rg6V>ZynJ!J^yc zJLvAPF0A&@T>!oBIbP>ehOYXLb?fNhf%)zZ+=kj8qhPc5So#S0UBn#Nn}?Z4;_Gg4 zU6l2h_QxrhlkpUt!SiS~9Igt@;eOTzr93P=W;YSg``4&ITN(V9oE}gRUk*#NVU7`Y z)zxmCuTdgT1>yC80>X)D2){~1*o`3tME|54KTtAQ((>bg+`0dxZj|mA*`51eQ4GI* zdaU)`B4QBE%yqNV#?r(0rgTd3jyEN>q8=Wag_v3 zdb~kHdmIRF?EUP^*VNl&fzswIovP_0Y^8jmbS#uCw31Zo8?u;=BkLvU9m{tW6NFq|iY72NI*F9Y&Qx-vB!qNl zYe9bD%cXc`eC{L#P^O_eo}ueFqA9Y|kgN%K5;_uV&d?;f9V zpQPC+YmSG@-}Ti1OcE9X?*?q&8FnnrfkZloz_jmVa=I#b8_!r zQ}+iZ!}<^L6Ss%H1ss%jyNO~3B|*8%*Ua)>-A5DQ8DMjg*MM$6B%|jYmUGR?cW`8s zV^jj?bz0s0^nDHZKBv+;Wy&0QZ!Q**kZSXWcX&A29(tH-x6}`D29r;tHje z(a=xlt6@Ei@{q^Pss^N3xq9qCYWp+A^$os-z?^(F6yHDXS@d4k=csIWr00IkIeMqa zL7gDhqs5bl;RkoSXNrpfI7soe|H{DX?P3H|38{;nlZB4&aFV)#!I0y^nS6__UV+j` z+tAX`ZxyY+p;eJfVu6IzvxczMw)ZP@OQ>Ojn@`IaQO$~Sx!blshHIs0f(9d0!+I6?4KbhPA*Axh=^cAxsaYIY95#L2~a&j(!HB zw~Ez)_COe!&?O2Z`P49;F|`2`T4Kuu(87!2lODZwCy>~Q#R{c;Z;=%Z+kr$vb`c`2 zm4o`}8#qVOq+#b=SRq@|cdG&hegyt=R%<3Kb&|ob4y~otGFa{tYwl9aYpTB9Sab|~ zLiq;ArHW?ab`#d3P;}$=v!VuEcH%sU&o{(CTiHZ~`L7V`nBA zHXUNm(%L2}eZ^#ib{$Twu{^weMOg3hA+a3-u(i8nN@(Mx;Y#7SW=%_*+8ByqS-F_j z>)5t`D)2#4h%N8cc#vB7YeK&!Fx2v)=s2g4FbT8wMglr!lK{Jil=|6g&|1H7YrpOL z*_-7$IW#8?qtN|`)v9HTD?HgVm@cI4lvF3mISpyCq2mitOqPMGuby238_GV!H)Tm| z!*OAON`3jVHF!!yt>g?!3!RKccu`9&X#UxLpIS8b5po9MtiyXsMMQ}OgU4z;6W!6$wEJg_!;vZO6Y ze-UsQ8J)tz_a9#d9Y^rrC(rF|rf2W)h@1F>Z(pLJ)xRq*QrSA<&is#zmR>Vq>C4N+ zVW+D2US^@Pf$Y397tc}#ONa=UMmzfFgD5v#K`H1aZX?U94Pw)n!3+{|O0$alJA%;U z&oYzur}ne=uSt`zti+E2%Fm|n&n$xK{q*XuChx%|^?_Gc=Fi!gLNK^>cDu>l1hmOy zCp+a`n96C_VOQnh-jYpVnuPRZd@=BUJNXKtgdIDPu^@NRJ@FkCmiL%sN3QWN!0Eob z_`b@=<8lY6_t?6gMVQeM!B_f;bU3cvxSmAg@kKXAD}#qfOymfaC9z@QQcokqZ0~A^ z`Wq^#qhf_BGt^YB^61xy%*l}R_fX34dAXN89{&@;r-OQ3j{NAo=r}8PH{CSsE^BoU z*KCfr{UzikVoLm+zaw=|3+FCDx4a*nN1*B+VFAJgtIQjOkT=C@UF;gA2|AD9aLPCM z6Ki!E$p}=a4K6h#!x2W?UZ$5?a!A|f#v60O5aQsf=~srzL=FDKS34xWi^AuG&NX1o zsWvn0zp_47_T;fVk>J4)?IiSTNq>uzp`IjMFXG-bZC}=Avw20tBQ>y5_N+F2!Tp@H z3(npL<($BdJ1JL9sBpHmpE=$Gm=dd0jQ(84lCb209tIVngbeYgqm3=`{DHfFH>Cs4&zR9D9Z)S#9 z=a3?4Y2*R?SPowN+vU68|9JdZ#3~e06D96w1c#1}wu{;$yX!iL@;nlb_unW( zo@nsQVUizufLyPNXf~hEAtvO;6374>CTQaqDUeylL}n-rFxGdJrtwD|Es6COW z4HI_^t)SVOohVUNI!SzI%kN+eH1fn!^-oHWpw8x;N&K{tJ4BZ#(b^d{`j^V4ahB*u z1~|4=PRe>KcCZ?6un94qebiv`>e>*rXmq1XXvf)kW9^i2=*Nt;0W`C;&^z9=$*axP z2IH%Ym_dfl?P$9Y?=9e-Ou(zH3P2M0W@mx2(6`AOGVI`=hD7~_P%hr3DNpRO^ z1n4v3BUQVeNJ^e6ey=yJhqxE3OEbX-l$ecjZC#dxN>6%bVVU1Z3Bw&U`X5YTDA}55 z5kO69TgG0PZASvLtTyDv*dnX|YV)2rXYFm0kEExChe5Y`3izO_%n?s2m{0u7NI72G z_mqjK2)W);@PB}GnhOp8Vl0O9j~_p>C44KOB`=ip$RKu1u$HU9Zem3{lOUG}^e*pzvq0R7lf+>Fb5tlz$``bCD z@0X9yl%CA(q7y3s7wij34jgF#;L4vTJIFLIJ`zc+FmztN*uGX#`R))0(Aoorq`{@X zvg1BnYO90Gdc)Tx?vf_$ooe#kwlTe6JTUrCIvjHD$fEx+?EcRlxnI9YX>#@cm4oul z)pqbYM{qQK^XJJMsokT&<>yZ@P+q-C@J0c{H{>^q79>7l5wU8CA@SaIR0xj!7=#qq zdsPpgEe6|*>zmrYyy|+o^W!!n1<89y$T{&pp}U5SHhy@{CpQ=0|MdOM_M+QQ_mjgJ z?HJHzkLwcp?G+r9c{ybDfqaf-H@Mz54Vx%kxBpfaGS2V7YDe_Y%-A6uts-J9LKqku zTVU)4b%N)}JQ^*g;Q|l>RLOUM!P$*!L$%H968c6U`H@C7g`JNR%N^-@V zsXlo*HFvrx+7jEr1Q(@t#PTmP3pfl0KMqnZ ztV&}s?ab76t*PEjl1G{_VFZQ=y*J`dSj%hXLiNNrrV+9%C&?Cj4c>W=-V6b)|_z}luElPi_eoAwT#wx7GXoE-e;=>3S*IUKyFqrC_3KM&r1+}>|Le;y3B->ACJ zemU{pr`6@XX->qKhzREza||Yh{Wu)1>DalSTyL+Z_1Qh%Gaikx=Zt2kt~?-OkkfZ` z=MiuM)z`??)y+>oU4Q@iW-+b1o6*_9-|k^D&R2f&E*U(9Q5-Q-gUgcP*d7nJi^1m+ z+7aN2nJlKS@q4E29krKQg`Qa04QZS$U7fX() z{&=%18k3i>jsd!F$8EV}!jc!TsgO;QE_hwyw4VUu-USnf2tbP*P89OmhJe`EQa;5H zE4gyfrd+sCtqmlK*tm&&DSEGl}_$U6BDM6{#MIRGgA#mD-K(!VMdx7FAil z6Sdy5SQ)Afqdmy&(pTtQxafHqvBMJ(DIT&<>Sv+9SrY z?=&VS2sTH3s~hV>ZF_iFx*iKs^-KRUsW(NxrJkl@c7^KM}u8 zLLhBw>9)-MU`T4{^|kO=$e5S9!qV(He%t3&d;?boF$Dzel)q*u30+=WQ4 z5|7`Idm=TQK~=X**~XKoxeWahmf*!xnW1;&C+~m!J-q!m|M*NdrUzG$9WV2tpOU|D zr^!i`H;6kU;s(`k0NL_#9HwclBV&Z=`x39? z`NuiAKE`cUNfTT2><0FAH2NshHAzqsnsBKI;+nq})Rk6CV0YZGz=I|6W)28N#Z-Q0 zVF5}>mU6EuRE%H^uQQXKlMvP!r|14F`5B4iGyz2?oyq&xvv>EV7YPRD$Br%?h)ggovs4G@eZSv7 zPNrjw;)i@cVn(e0KQdMvDW(5`)_Dxy z!(19}{1e@z2XMTy*HMW?a(H#tIRZ^oq2o419$Slm6ojb~;Te&UWfpIuDup<;`N*B*F9Z`l8~f!u2<3E$eMn_0}P7MU4~z$J`DXnGq+~d&PT0El9QZq#Oo; zxYAK6wQJ1r*r>^us$Vryh87AbDEjc$Ce=3pC}=Ez15LV{O>3FqGoA^wFTrV^ETF^(Q)mHUF1>1L;YE#UiHb!ExAzi8_{jhz7-U_&oVTaBSppu>qMJ9YvUfS;oc~ zoLwA6mtVfT19kEe9l3^_Q!bCD3iAI|;=*DNI+X1hlc0;su5 z`E|-)Jz(!hmB5yhAMOtKhx^GrdeFvrWnJA9t0y1{THIR>@G6GT|~gG0?#BzT#1UJu5v zlS%dq2vYouYu6OA|IFqdz4PH}hSaM0k$cPttoN_u#bR-N(~Zj=O8yD7CK(a(?+aQ3U_(74hZBj8#)DG``Ob}UhElpdd zt&r_us~3f8yy5J^qc@VhsTd@BkB5!9m{{YOs?iryFhs=i-=!fGlwUy1yHM_G3*;uA zimqum{@d1)H8c8h)pYN;j|?r)_=jaWGILPV+ae_nqVzg+Dq1Fr|3sEJW#e`dtJ9ue zzWzde$E~Gmq*hHpafU8Z_$q^_o@WXYS(ZY@bZXY*hG22?TV+aaRBa?oss5YUFbReU z+-iXfQ+jJBl`K0|psMudiX{KF|CVj zKYaf&IpWIKGBThTBJ-+y_s5sXQA*S%1|V+crAZUtO`juFs}Z8pSHi(}gXcNyuLh!I zq8P{kYYk+u%OtjqXRJgwMKD;82IV^0ZH0ssT6MYdX&fDAtVg4MQ>+WeX^Y4yo9D6av=G|yA`2I8AK7G0vdGN0GIly}|-q)PI3qO0W(2#TNrcqa; z@bYo8{q)awmq_-8>TU-+eO{9O{wg{H?K#kk>~`n?=H7EYUxRcp!keW#!{IzSu73SE zTXb~}ex&wOc&{AnC-Cm6E@jUVpnS=hDr%2Q^Og~;;NEYsUxvj`QlKz&^wC_!b2sc z8g|=_C{c5Mlf^~4Wvr-ZqjT94Vm=!qTr5>e`olDcoYPQGVzLs&KAk+CeU1fZTj}MP zuib1;-g(QJlSYDSS*BZne#lbOu(TTcgx=DeOlDnedW{i>!elvxLw*%yBTgFpMjezCb2U4)VO&T8y{FS8*+oO37_YMd#9B zx6vCenynabXSK{8CY#m-GYr#H2@dUpne`^7!Kg`76&n*0*076%;kT%Uu#7RgjWsb^ z)(p>BT;<|%AwfiWvR&RY3n@$)(#x(oQyCG$6WKkPM6S);^Bm|s861B6`;X6u1OIeP zM~M?Y59UqU!#58*a95^DL?+vh*+cLYJpWJ&RLqZuLo^?%4poH^&HV6357Wn}z5NaP znYdk1IB0tF{qry$7O{xM+b|B`MpH%sGL2TY-qem;>JRcSLD?*saRSdxtGzBRbFl@% zK|I1&WE<*TabaHEE|n#YOJ`NtOH@xoypnD`a(@7Pf1v*U8~6?={{B^#;1y~sudW8~ ztt|dMNR#R4-y%)0s~m_dx$28^{t~|LjPfu9(*25w(q_?-Q7j^5oi_I$!7>I$Wb%{fnSdC{PF8}u#d)DWWj#^^yS^BQH>ge zn<-S{fNzi8Ww|OI8TL9m=HFv{eZ-4)>Y={!Xi%)+SEODqFCAHpXf?Oy+UEZj=P86Ew$P2)LaUB(S#7)MZqIRa}*)wYpLGy48O+ zYNyG`P)V0z(if+j!=yhx2cVR_!72JQmVaCF!^T;pl)5Hur7mxuDde~s?CT4ZV%3Bt zs(zoQeHKdaF=G8MeMBG6uLPx5D?}0X>Pv$#NL?!y!c6=ouw3s~D6}N!9nf3sb<36$ zS}aNRvl9SYq$KXIBNFB4(vz`$@u3LP#9Qu+qwMUab`q0ohW|slX;Ng<{h$bJ^rTTTR-3 zmekpwaG|NB09Wz4U41QPm^+8K*{G7&siI()>bYQq)a@cBoN z*UvAPfbWl!m#-ebe>^_;r^-t3?NK!ne9w&!0|690W3Tz$&X^iq{!_r(E zg(fa!;!Tlp;$L`~C@`1l)s}M4gtceF2(6TXIsok3YJuQfR;ban$+J+)hPDqM&NGbN zKyLpB{~&#cdcu2P#K}mbcYyCV19Ms;Nf73o|BXy=aQQR}=zYpHxw|5G-<`b@bf2Ml zSUfly&(6;3$@F^BDevU&e%ygL!P*kk_k^0c$=6Bu`Q7Jkx4j(P>^#OZc#1aq6?TVQ zR^q2e;P-yCz21Jly!?c>FQ4;SeN%NeRe8p_s@~^l?OoN=$zbHCHlK}dZt9tTpdfLq~;vj$~(z3lKi;`h#9DzGZ03I)UoApEOPx_{dXz3~;X#L^>n-av*z&cx5$r2#Y| z1vm0Z0E4)GW2l97F#@{@URB*!K7|n@2?H|83AL}A%`)!eO;U^ZP&s(W@lNTE*@P%0 zViQ%IAhY%qThr7Xm3CxN))u$$7dXZ>|G8Tpa3buf8vg2xdRnb_7f%!?tU zHdda@+*sY$6#UpuqSZngZjJtXDMPz z(^*$QO2(hNSU{t+v#=6nZh};cW=qlus!`6cuJ(KqWg+y1PgD|Y*lip=T>tCibN52{ zK6)7cmxuGne=6g?pW*BQeAmZRjYa+*jh?5Nr!QB}Lq5x}l+fpfIi}!6T$LESJ~nfR z10&4q-@S{XY`MH$AkKSuJU%}kj|W^QeqTk5!wE!L!c<)8&@1gFSTmZj$(JY;{Us`KUThYWR_ znMd--p!4cQHu;K-`YXna>TmApAS z_}X&pFX@DtPN6b6yBl9mb6GFhUP*+G^87H`ZoAQCx6Ai8ln8=7$!XN_12l(jM7sK) zrn~xSwEgr+=zV!PczGIiXmPg&`pL9Ih~RWOan~!%?jF2}-%l8iA0J0mRgX$#{N>0S zK^MZ4jlG7y9=}V@*t20Vo2|KhTuCYz&1ttpYPVwxW$G})BWWe?2DR}g^{Z9rs8E9r zOV5yl($%u>@WZD6_QqkHq=}!rOMlZWix=UINLYrN#G2ydzjk!w3AV)z%b!OEHDTms zmAp!8?F|(ipEP*8G&D{208ZON-zum~WoDQ-#Dy!AKZMR&4wbOJW!_XJ$dg2cJ?J(P zrdA)>pv5KFIkox3VUq2eq{f-tsv=G6?`gRfG@1H_FKxIRP4s1DyqTqjQ*TW2+@trm zv-e}&uv?J-2Kp3*D`}Zx^`-y!8aGGE{iqd@|3~YZ_5~r z74PDl1(26KN+cub1*r=}9ivf4)Mf}RWxcaQyDd~3i(f(6y3PH4eVJO|;w&-Ya7+U^ z+STRjGiu*SZo+@<|LKFXisaTJt$4w-M~$ATgx6iiuSR=OK46s!MEj>xX31hnzqH)g zU@ocCD6x(!#)ChKTp35falP17xNceP0~F7$K<(93O?%bP)R9Y4#%N{ zD9O^2cN#3HheOBDt6DpJBaOd;Hb;*0zki+cRDojm77v#jetZP3KhDVsV*1UjYMy#O z6zAM*A6bh_KsV~=kW8hBtnjKHF- z?;;SE_xEQ9Li7G<^t8SF^!f7h7ytj|b}-m(Z_<%Ofs@HEe){enfs4+KRvv0?^d4Vd zTu=S)ANO5#bG>kkXN}nM4$sV}W9Ne0mwqhnFf>Es!SIxle^?>6IGUq&XP(z1KMxmv zKF`NF9q!~v#!u77@zhY+EIRez$;mdFTY(NLE5BM;%h&o9VKNnavY&qS@5c@l1;oRs zWOz}|kc+&5-eeO?^AQL8q7-hNAGsmai?gO`u&PEJ9#1h#y{Flq{L;`U6&ss~bc2Z+ts<0rc-gloS`iKCJYsaNo(vPU{qL?L!gJP9sZJV5$ z7{b!4=>w?<)H>6{oul{I{0#fjMjF~aCkfO;dR-rw?Hy+C{IM=^fM_TP5p%;A{g6NZ z9RJLcT%tEtePn`d)7lyd#lU_=blK;|{7t5to*vNgO(;)mCB&|lffxxo>dLNyER@0R zF;m)u_Je$QB1?3M;hiA;htOQ#9xl{Le z_kz9lu@c5X^mF?tys@g9H6&GW!AN{-Ndzbog7u^TFN0D2deW}a4-HSCWK7_{e&`4T7uLd3Yg z`W4TzT^{w!gC4v9s~sN?pwS;u(Z)+kYH?|qjBB{YWoV8_i;Zn@%yFYuCqlB>AJXs_ ziPaYsDV2pdhb0!FjO!eT6KYOixWY9$%akcWZXY}254UfzvsAo5MwvX|d(`vYr%4+# z^|tHYzh?|A!TT>blQ-Sf+12)a@KRp&vp2&8&k(h``zLg7+Ou zhEW8mf=X;N$9pU;5$Sz**zKlWjgrfI1qEX6Ugxy!KqmMI#^BLkNj$I)K7GEvxqP{} z*s?XbD#slr;nlj}XoUd5308&}uOA;Lewcl_=oVA3=KJmC<#sXh&)HIu;F$6u3K{ID z)06(Bo^~B#T0P#T?m5E8BJ%qPvEUp|ooZCOaUop`H(RvY}SXksy)C3j@{cyjbmfS3rTbOp(zAm{Djq+CgKk{VAN ztGk{5iY>|tHRd31bEh(kG_z{4<5S`m4b?u_!Ob%*tV_hJ-lnFAsh2 zbsV(yX}AG<(5*a=f}oJ=j@u~2)#$=xY2s<0@RDI7H~g~uUCw$L_gP}&AN*yERJ}G0 zplDY*cp9HEYY&efKmPiUzyIT-AHxrr$DbSj1s?0)(Y!MseuV4t%WN33x{fQM_eTbG zM~!wT+L|=;)!=1+JhEIl<8yP!B=KfAmrWC@6i0h~g!iLf6Sx2SAxc{-@rV_mxj7}A zw;@J8iTma`%Dm!@CE!Bj)E0bZYsV5pqY0*JsCMZhiFf{`wrTM1VO7AEKclCEi40Y| z!CD>L(Da-e%eNoY8NJL>5B9f!Z|jN=lsDIqZ%!!QgZH1u?z3rk)$PL64R7V{?AuhT zU7sU(*2kG(w4R)?BK~ZW)0Km6ot^a%AMP0(c!pscjRSXg2SD`MxV!0gxrMx9GQL|= zSh&8+4`{U#jBD#bL)SuHSdq;F&pz!T6c z4K1}AF5?bb+g=jBHSJm{fHt0)NDu;roHMb;ZxG&%wb`ior?pUUHSeaOcp)?dNKP2{ zGin_A(h}?4F?o6{gNk`XD5OvfbLD665>Grs?{e~3TRWxG?v&q7VVm2S{okz^UbC{Q zaZ*=4-KvuJ2yu={UH%owkP}_Tobml;*x!&mGKacx9uTs?F=-3{UjCK3h8uoDveA+u z@-CG~K>kF)D+AkFQZ@1Wkrb8*rE%WvX#Rlo$g~V!I&3RI;$KH?wdnIF)>MkZ$D4dy7LdX=Rf|-Pv7`T z=Z8Y*4r1YKzA%0bEShe+9pxjB*q5I#UM|6!__t4& z-SrKeHU2+H>q-y4tZvWC@#JxmcNdpWH8KgO1Mn@~C@spW+C$ai0eKb}>AW`gC5K{+ z&wi>WU+tn5>K9hCBhpX&2>x+ambgdJYoVk!U8#mdjy9#aH?FYuev4wqw@oJ zLGcOJm=5_<0Pj&Zq7y!)>>K+}|GNSoftGlduN13djka^TbNu{mJIk0k94?6Qv>?Idr4?<@4JF+_snS?i8c(t3O*|T$4a+j`v$t~X*D9_Vf00+_A*i_XzXFl zB=CDloiXh?vB#E-n6zo^vX?D0D;K7A5M>UOw(#T09jnb_Dcb<<4rkI&Z5nW|SGUW) z=2%)9MEcp6sQzFGPkubc{#TlJ{{G{yA3uUT8TxNjuK3?CS>o{S@Jzj_|2)x(a_!&$ zu%PZJ4f4{&1=r;>Eyv=Nqv+jt@6ZK7_27Vkw0Irh_W$^Tpe$ymJV*532yn4%-o$~k z+wkcQ=48X*0mUOjI#}pPSl}t_jH%}HG^0PEp%frx-$QCv99%G6b;}2?N!3T)nsZIl z5e++8b)J35&Skyu510Qd58vK7>Qp7yIudmBq@GKQma_qsyo z?(Xaxvc&k3o&G?Rq~3jhw`2PPSd+VZlnyZNl|}OYUDIhd*pKhTtH{7}*X6VOh}y!4 z0Vnqu!1MidG=2K~`O@Q@NAFp*{q*JYXVNAfyDu(1cz>v_5ds^{R_n-PzN#H^wB7iD z`{}x#PA22W8sPoq^ER57W!2R%#77Og9WY@Nb~}yV>RmwfaJ^!bRLNl1dgYPZqjx#` z=;v)zp_LfMBRDG8(QHkFJ}(BN#eO=)?dVcKmIUS;@%ho(^_xjVu#mHdhB3(@Ov!Tz zyc}+Z>Z){ zHYXi^ZNs{77Rv%`hlTzn0zmk(;;o0oLE6}r+tx0K-X)tE=-cw+TQO9&e<(MI6+=xV z+mQC(Y?72WP93=ax`DQRWpip7qOBrHT4^3kZ>i*Q9O6S&Lu*mvnAT!{L3VvaE1N4> zTV{l^6%136Y3ooq-c`v!w+QuSjDDh>yun9O_pKum{3De%V|-#XDtn7{Raq)vOT_{D zbcNXntrka}?iG7Fmd4Xs{z9dPwGu_f;Ss8H3Wh4};xd%AI|ZkZYeFvw@=S)jdy9D3 z#Dwqp5FMEF=YRe9ckthS9)IS^>G{yxYJTsYqqI`_#dELXreOPV&X!=fR2c#**QL|6 zi}TTN_T^RHcN8(L+u-|@8-9#PTXT)eu^_=%z)YW3I~Ke(vL2&8Aq_DuddTBGP{3KZ zGLA+Z!euWeXF}~bY_I+ytC(k-Rw3u!pK4S?)D7yhpAKHHtW?moNgt8;qd+e7bei~#Q)mX;o;4*=`?yRn<( zK<|5y+0)7R<kll`EE*mFMVtaK(^wzhl~V z-tEJ@{8a+JMU5B|TnW0W_M`C3qjz1eo>v~vJ!+#CbB1`@oB)o7pPk$7)@wIFu^Ctx z&f#B4i%f4ihZ4)N`6B(YsWqWl6&&X756g%E1VuTqiphuxEM0{$Kil=!tCNaPS~1 zvx0$69c5x^3E*s_h3Qt)u?aK#vUar;>-FARG89#kBu-;zmmCk-E=R7qB=LzoW3NCe0dGu&p_Ep$;+$iNI8w^8sA8X6I)ThrTVX(6Gk9 z)VM_HqlmLqVr&IVg3=WwN6Cgtg!o*7adF9BCs~hphhotPo#2s?^228j;Pa1jkKxa} z)(@Y*8u0!xIL<<7SbU5wfBz%Aar(}dbV0&i)f~G&;JQ=-BLlpK$7!(V{P7Y!7nTVe zm&ZdWig-7OkYtsmDCF}OC+hFz-xd9DNj(-jm6G%)oNq+YB}>&yDdio{pf;mx$71QT z)c7Xz%WqWWvrHk0R}ye+WmeMRXXh!j-uT)7;T8|0i-6603lAJ@FW=Cc1H67Sng*fC zH{d_NS)et z+kbxd&+YaJ1q}B)E;46#Q8dlh$P;Ac8S3I^6Zj3slRDkG(ZzN(Yf>EH}vEyR=ZOa z;_A+VU*+Ga$NR+y91JvqwTF0Aqg5XJ-A%{OxL#xA=lq?^mlLS%d@=AC9sD?4Vot%4 zl&&60)$LR-@1Ij1?x76KoAr=WxJQ443cB*)ficc3ATBp9E}4!YaiF8P)xS9TtSp%j zom72VUm60d0vVF^1vdacg$Bwd9>SJFD`j9aZE}po7U+paNedKJ3i?rWbdZRc!8i!L zL;kFwq@unqHibvqzS1Lx-ZAj(o3`Ja%H+dO%^*R8K+B2}t3u8K*|E@dZQ{^cuQq1l z1uErP%}}CNhv==yp`W45MmrTa6NSreh~BYe;6W@&Yk1SDcu?+Y^K|&hw^bF7!fTt2 zof^Pg=&lHtL!NTvXOFFoQYI@5%zPvmQI{kZhAXIJQ<6u8j59NLkO0g^)o2t8H;Q9r z@HBiqGGk?O$D?cwseTDwhco6~L?-D%wnsY#djLq)}2?#i~a+19$+D z#W58@#Lp>fIMw?=zecL;WhQnVhXmfq$LD|i{m18sd(s9SRv&--`#;E?_?s%84}(iT zYQ0R3^G%;++#C;+{_XKF8pg&G1ey~;G7Y-4P_6R1bO7-kueYXD+sD;O!gm2j?T*f+1mT~{u zXba2o#MDu#cqnz7STB|(PcYeebqnA8ZH8oY@F@OU^Jx9PlQAALyMg~BdeElt-y3Sb zpH7M0_<1xPV@VlusCKVulB;i6Zx79obWgOsl)-W`$@9@@w7|#b_uxe))4hlHt_H6% z^VnVPyXp3FdwD&bjOsJQzbeUlc7N6lV0A=Myhrc*sHD#8a5#*Tw0zjUTnwW1U9=dl zrhX8o;$(Y?@%#FwKL1dH1|j)8fz|P$-d7hFi*7LWlQ*6Wp9kB)bo4ZM8Z7pYn59_- zjER|yhX2F}j2bVd7?sI;5Wx2fS7M)-CjR9=Ty+by#MjlLD-}lQ|BKe;m^(|1-AXFV z^8yhlq)e;{!v7Yv@U<*Cqj7zG#HevtwZ^VJg>mB?zXdAE00whN`QIE^OZ0N^tKW#^nkz)YIABzp| z;H;QGA7{to^L!Xv(~Qe6vK_}7AdnKY z!QnM@mH5Y^h%@Uq!Nz2hs5y|u^-IQBoipkrJLe7)!6&yLZVBIS_I~nydNTkn`-%I_ zbP9XrNdewZ-uqw9UMswNp8Fok2%_>g{0R`6fv{|2@Nx&UC)MQOAVan+M-cRE^`tY`{A8S9e z`jMIC44A%g<;cr!0J$|h?X=JPe{_v}@Ll~_`T_jLgLmpi)gE{a=>ijJz~TDA=Y}Z5b}&(h2^;m(l3 zrW@lQ%(U$+pxR0EKo3Ch$Lmz97~)p)3cmE{;8qP8onGvkyx?Wgw;eSV_v@kMD z)ArS(3y-vp83f(T;V+_&4!a2_-WZQn^eY(e=jUTI zoJT_MkHd}Ow||I{>{)D*SNnD%Y2p8BL&+W^4hf=5>HF2WTtq_&Lir^%g-RrFSGdL> zPW_{c6;U~i{JFc)hE`jnkY;PQjML(hCyOk_l_I0cog4U!cNTWNi3OYc`;)#Wjo&d} z2`McJsy~T!-bDt3N{Lej!zLM}{<_`Ne;enwx0(MB5Pp06mMWCDw;w>ByqUgv@xwO* zP2MohB*;##ro?NB3D3xKU+u2W{`@wbZU@^}6*`k0V0=P3HzQ!7ErHUT;_fr?5zvt2 zNse|I9Clqa`uw>o%k-hU zSl!KLcir~I2`TgbP=lbG$52tB&UZ0P52BjX2@)@aawo$Iv zsx>2nO#+39ueh~tPb%iC2kf$}(vke|W8t=2uYu?;$AU5~*AY4xO8@>8#l)z1D^sQ* z6>R--szPBMg9%eZtALcdE_7|#%o_%xkY{EDO00j>hLGq)-8pjTkV@@mDV~rU9@vHG zA(YiD`Re}->Jy7))85N`8_bSYrIe}opo35zom1U54yg<>O>O8^f|V65V07c$*@Shc z@;8M;v5pcOU1eg1B7*$@o56c#al?cvp!WfqZ|c1@6~?gX4MRDjvre@KjE@_S-W$=M zTmo*$r3Za;D=tCBa4xVdjl!adtO=>(*JYlJdE%hYgu+lc!7#cM86~M%ceq)0+#1v4 zs3=%6BN+=SEOkXGBK(OD?2=*dQ?-aHglH0{hDaoA;(#xl;5*AlXf}zS@ZBHQ(5nTz`SlAqb z@2|!*9s8LqykO$Qu^!Jqho9OsM6)fH7(%k%5ybn~KbRTsv#i}%oEeXYyz1ax)K-yy zNo|EwLER%r_g?`#Tp4Ym1+8ES;QNDz@9g%6AKt$G@b-tly}kWggjMDHK8@=A^nJg_ z#K`>~u_eInD;v819lLkCvniUrM$`Tse#)NYcRQsBlKe*D8QLnT`reu51b;^25@Mt- zJc>eJGE(s{g@L2}Xp*n*cNgDxV|1Y8D|{&N^`@TO{BSgW4G;jaW2+ih2G zw-=u;FE6hb^-WcMKn-tovseKA?+@y&?4G*CE~>hh&!0YB4!X|I|BJ!X=<(t4*VUuH z@$;Jx9&M-Fx=`vMVh23}Bd2PBvHR;-_-%^6vL5+)zD9e3+e2@{RBjq}_!Ge&eG90l zw`h}b=|)d`+HX*~GphGfNW9D3rRZbG;e$tv3Fm82-qZ*1rxL~SFm09CSQ5h>yM+nf z$cJ~WCB-s1qr!`GMEf0=P|Vy8tyQTNHQ8&y+KL0~!k7H*Z&@mZU>h1`JTB1Wg}yZKg&L({4xMnkdX1x7F$ZT z5#k%WK&gekL98GRNdEH<3&rm#Q9XQRNvld6vZoSa_(cJs0P@Ouqs^{e~ns|7T1-7(3}saTIYE&@S|swq*BhuZQqv>+Ah>e#}$Gf z0@>%F!LW(##3PW23E$uohP(=K8`nphg+pI(Txr+Wv<p}d7Xs{jhncgStCSSte zoc(fk1uaTHdGG#I7%#Hqmz(S9oq|m~Hs6yiVRNP4cSZ`^k_JJ49P&Gw zFzMT$TMoH=Fdpf~i~aQJx|>cQ%q_u$myeUjy1Tjg>FrN%AGc!<-udLbsy*NhzP$T% zF|D^AyDxsbIj^e^H-7Ry2Y7!tzu8a5he&aM8+Un8rOn{em(Or%c0liXvU+%Yz?Gp| zy#48?qTXI~Q31AM-Alib{k@nfwqzPike#31Ywj66D%a&MH;wm9qjnxPmYBLrkR)r` zecTA`mQ(U3{`Y$i-u}4ZUx;XM@Dsh%#BhJ++F^RI-T~2bFy44Bu9!JVd4S$u5kO!K$~b|R&% zgLR`yt5xb&qL+6X&isfI;cGj#P73CqBxYk}%>%cisyAwp7n_{h*8DA;w?}=q7)XYS@@&Xp4DJcx*!ttuSQ>9b~9G*8o((vq0Ov0Jsjk? zKgXAVwWrprpuD8j4_;HdtC+|`c?Q0`qL@Ep0LR-uew;tA;zSthXw_6q%*F^SU6o@E z02v@OwCT~H#h{oVJx`vN{uw7yN_Jl^Y$2?K22o@q5M3aS{z_c(oJGX=+1bBlmZPk4 z4cjf*GFXX>Q$rEH$t7NF3|=Q~h$lIB%xM@XlD490( zc zDepr*mD=Jta^JB7-kRa>4tICs3DhRcDcN36C-sz^FuHXjdMj6vAGY_~i)%6{U?vem zvc6kAez>`L`_tbZ$`6n09s1#;J1YCepSIQZ;_~~;i$!;igux03?!mkA7`~XoZVBCp z+ih}xDk{_Mr%Qii7Rq!a-uQ`OOjL2AorEV(u8(nPQ2}g=^s3`rzeArf<+~&NLk)sg~Zvi3c%7@ zPHftSL_EIwoyKv|<|*NjP>9!_J88sW;!yx$Q%G;JQ9=`kapL_(s=-ty&E&Vv4+$i^ z^T`2Q%lxsnh}y6(wHiezbyakXhzqv~@)I1jrD$ojOVo^tYgCr;rHHKc7Uh#_P=kG% zc1%WG&~Qp1C6_Pk){<7cM|eS)`r1-4=onf^^@wdY*plElw|mrejmhJA*PyG|$}uu3 ztNTl~*neu3t3)R$Tqp|T^GRFLo?@-=mBQHx-wZePw^te2vtx`j z7MASo@4kol0SqxB6I1JT(&G&`5>I*TGfj&j;wS#)-{$ipc<5|ttQHLCd~`P9nu@D& z;h1}6S1LR(*j5)@Q=%nUjC{qO5K!-Ft4>d}C>La}aBNK~)x!Cgnrc=3i1D=4!U9(| zgrv0I(mz7mc683nhNz>~qW1@7o_ffcs_{TF`fY8zlH7u4H<37S!FlGY;n9w<#3d zO~ShJr1PfN(o8!!SQB-c(X?}>Uif?1E63w*FdbZ9-`x1|`{F6@-{`!&kMizf0dfVU z@H>CVeaxeKk8U?_|Ms`HkHpK`58mb7>@H%wYjwW;e6hIMcME@{c=X`CxW4eViX5>LuKOf(w!)8q_7m&S8~>7qLc^kCg<2~ zxJ|F6#J@YjqH9#9MU}Ax8Cp}eX)ilrJxedwtA6`UyRMq%xyFAQ9<4XARW~Z3yNyG* zH`{NRb}TNuuZ5yPS|!DS7j4tNp-e1fXruRs!A--Rz0yv^I`S|;*3TrebdqptX7-hw zIW|RG(5UJW<1jw8+DziL(gs_++!Rgd#3c1%4m_m>WI*qd=v`7ch>Stk29=BLIaTJ9 zDujw0PI~I7+#rh=1P`Wuklfm^wo+o!cjz{ShG!1xt+Pv#)b2_*Y2u*oiIEFy<(HD5 zarxLNcNPoM4Ig$9rZKxI8HZ97f!omG!Qx{r{2*hesDcXUo7%)7o>8obv(`9_$xEV! zQ=^O>n~-#ugk&itpDcA5NYpNrWLXFwwwH8;lC4O*{v2hQ1?Lpw39cwAN(PirHQ!)lv~R ze0tfw2j6jPZFb`F{1{QOHdGaOv_OeNgg0N`YMRu@5>tRT<0fx$J=zpu_@G(IH0JCf z4OQJ$aGNguKk}#L!aw2#T|BsDt`sVz8e}xaW(Xf_DCEEOrYPs>R24JB z`~9DNl~-4zr|tH7&+&WwN@n7*dp~_0ZUPBl-eWi1@%hQMlUsKs!21sL$Ozo_;SMQ+ z`_6;w08xHtcjJ0DD)W_$m%BUVRz;&J6kYk5zfySIt@n7};rzqj-u~@oF!pd7J?zi@ z)OxqRM;_~}{7`Kd-JOi(Ro?q0?`)O?fQUvlEhRO9x(h{II z;QEdc-VuXhS#egE!gl}r@gBta9!+of1(P>os$8RR!-7SYEWY2B(4M&d4T3=xG3>M< z1aq>nb{D}naU8>x4c@Al)gF>p|LnJ=@ukk=w{vxs21SPTd~rgy)4jde+R#5{=xvL) zRIH1wj5OJ*B8SVpO>DA6#b#j9m`UW;Dor%A*b!MdAzZ`p!8m#P0G;KxwKhi!nv`k6 z@`5I|$Q4@~4VysGV;4vaRLguK$qH7XNp{WIThh~#QB_3mID~3*A%Gx0ee%pMX3FT= zi0tKcW8>6-82)K&p)Nc>fCT`l+-wwnj)w(zV5J&i=q{9JBvv3+vK50rB$?EoAzdNq zPJ^YnG!u(~b}slrDYFQcR2|uqBvc|KI`m}Zdr7iWFYoOBZ2KY(h1#0NL*Mc;V|-*E zhZ7DCr zH|3}eS+_|AbCM+gKU?qG+cuJQ3ljv535udsB1pzUA6kS=2vHD>BnOs($fE{4Zp|3z z!91Vr4m!g83;{}j_piUT*4jm9o^#Y4$MHoMirlqp?RDASu@x`ac9S#+3H^Z|x7()a z7VFS-B6wzd+TJva<8l!eh>m6_7sX+hgd$8USPc5$Y;s4LdDk5f#8B)O%cdyCrd!svCWK{QUdxzrTdN0Mw05-3hEVH^7RNzquI!f&(5tSx(uQ z1L-C`kiB!);U6nRlP0T^7PagB(W!bBClodEVL*$ zJ*k!KR-z4%1}RU<(r9HwytRano^sq!ougQv$q=QIfI!Ls$ujKQ5ihSYjp)n07yX`n zc(2{HfOEJGmLT`_3|H$F2jK;L<$3l7B=`0Z>c%spX^Q@#C7RcM=)xj z2t8vg8;dj4JVd`_z`BPW^KrAWHGzJ+q0cD)J1b%x?S z|36csc>ha0lcjsTx4>Mgr% z*UXlaFUuvcaQvB_0D9BN`v60en=SJaLg!5b=5BX-+Wm9<*X7I0GyeTd3#iZz-x028 zLKk_BEyWDL$IC}B2ft1xqeb1+&y&fj9?cB;4z=@f<;t?DYyair`u?e@s>$ci%cszI zpNj43^Y5QuK3|0|j>ofy55;oj3CI`8j&*of7R}n~_iRoV!q9@RrkYJYJUm$au427^ z(AYBk4`⁣#s^ODxxpPBQTW*SO*>;k~b412cZs`CT9IwwU#qnk>2Fx=_!e|k3w@V zqlq`I4wAK2f844BGa*rSRSdRl>ghCh#upX`z!@okf_f)Qrrt&2MXcV@x4u`x`#v?} zYA@AUYPhwT@>!xw7NvYyI?#1Zi;pOh_NPdD7Uy0GUkpq{tWAo)3rXX}R3fXuEZW;N!j4&!e#> zOI-UI)HyE*oy%UXFqw6a9bZJ*YJ#hIszJj`D#3z zNigXs>*9AAYKr2ykpp5sq+Mo84s}XxhtmgZ7P-ZPvUy{v0U-G_+Ah2kgn}(3I0<_!;W} zpKMO39*a<&hawJxShP%=8U-9I6lCtWa5DP_K@Q1)QPa0DB^5F#LC1E|;qXVHGOl*>f`<_~zy=q2lra zWZbUXp5eFt>Gk~2r_m!Pn97I`AGZ%h7d~^>DBi`rJC0x$JGlz=`{U#BY1f3t8@rcL z$JU$qHj8psG}CZMSJzL?)9GoV;$1bfZvETGmu2J2uo^UgGw!dmLum5ZMw9r5;tck; z)bqN-P>@#*eNDjjK5)jVUYxiKBH$CY-?4ZTHbL$waV+zG%)DuplX#*mm&_)($MYXG0COqr84~@1Z zePm_yE@psaJO$B)?&DxS#tZibdAx~yjH+1M6@$b!^N| z>)#S4#Tsta<=e{e7CE6BA0;rP3v$P<-W&dcfWINS1adMk55-ZT`yRL0J~z=!I=Dt* zPY)ho`{oIt2ux{E)se&ZY9HMOoqe#ahR#AWN$izALklKx=h?w_{L_To!n?;%+#TCsd8@r=6*v~ zdUne_O*+_O#?TNgoQ|esq`ja41|}unavd6(+H=_ISU=IKrv{qqGHL~-w5_?+_fAxg z&?B2WamG*vozFbaLh*Rco>%Z(1|-AT$cDw6Eqv?MTW2*+pHhpL5v!;qiU#MNf+AjN zG`1jAo~7J7(4ug24NMB<`?kJzp+8-_alN{|zP+s(S)BYAYNEI^Q3Q#4cW>hOQ2+Ej za7_S{5F)u_*Nr&KgQX9XaMDeIigX7Oyl3mh{BVK(w_wOH)6g!~%g6PiqYa@XJfRpD zhYEJEcd$0O>AIOhzt5i%^v0*;(<@VOcBtO4BuVb73a)%jDBivVQ+#!GHCl$^{c^Q@ z8oyhWmy5bA>dA7^#pb&?9(Psa-D>i2iR!)nxCq6&>K0coliz;(ZQVQ+OgaP1Ja(Zs z{$OKE71>a}tJTpeH-$Iz?rC;hbq^X@9tP_$FHc`V+(iOweByFNp*CYUSJ zS`Jcl<3~Gs>ZjqcS+H0vYoRmVTH}pDMY(%xvE%LV3x;VnrQRP zLcm{^YM%RAlSXC{Jg~=)jw^Ap*a}`r&5VkzAxBIslf2Mm_hydb;injDd7{k;`QE7B zCOfryP1R~0(RhBEDtKE@iQ z4mq6D_cSZqc!F&2U*Hxf4Pm#|!Hz*@LhjOy2PBx8i+aPOt}RCu7aN`)OP$tmH7{#xt?9*lx)Y3|~Xu zz^teWAQGYLMjTluqW4Ke!ceoP;b*!#Wa+>_5GLQroys>XVYf;{{r>D>G6Z`Z1 z_fM}k$*F+*6yq0?0%>Dy5nhx7PCkA7comBG%gbclTsO;)??PW*U9LtS9~a$Qy5!oU zcu!V~V^v=_;|85~_xI)I!6 zdnPkj2SMef%=a^?7aeIwY&VEZ)~1_aac*GxoVf^XGjU8bF~{^6%SRlT8rZ-YaiQ2?}}6W^Hg}K}p_| z&LaFieM5}WXe_ud>6tQ2Bs{~LEnd0AhDG_muD4LTo&gE82psND_qeCI;{LKVA{rSH zN-Src&G=keNO%RHmPHWfIVlUyF{$@^&B zp5{i+;i5;zG|)DfEo>P2Ro{ls9J=Gwr9H5xo~L# zb%Il%AO#80Dqt?Zm^3DGa9o`s+Dxst<8IGEYU!zUsu(7Uk}AqLw?D0jGYmQ6F36d! zgb0Jyw`dwe>IgLR4&%!@e1Hg5-oW%=Ml2ltz3BrcA~{0}Jp*1D+#uI3m|yW>H@RjzuHC((R><97*P;7{qH;c+vvgYlpI!Vn;=N^K zeP@J{J8=aIGpi~PJABuL^2@RwZcQk>7hThxz!gLshE@ciRKV zd3UpBx|o?i?8AXX@2Bp#cwD@G`ZWKh+ws$vjIGrFZ^nWeNRD)Ysl5q6!qGo_HtGXtrR|N$f#}yOx?-yy0!*n;X*Rb2w$YJ* zoa*1$Etw*3au5q^0?OLi^kl`OwH*d60Q9v5>KSLF*c#PlbQ}~8^s;hDsqxZ0hK~{h zTR9Ih`^8YZiB5%Pp~ff@fq~>Lru0(F5zJ8H0FpkU35W?#_u@WT^&bAn047r|Qjf;i z8M*%w)?(rCVNQzGn@SwMl-wNPscs4nUz1(H5ki{Y$0R&lySJNbwCgPMVHG6=&NRL7 zt7D{HI(Fal(fk)tyMHLn?leI{6}W<)ItBhzxF6dT-~8 zW78cFB)?_$LMYxh)5UUeI3RPNfUn;SwjmVgz~>JYe^xb44~ z5tOr;M_BJURP^(GSd6Y$A75TV@BK1rn&bS05`TU@SIdvf)%ErAIP36F@JP?eZg)N> zWzkL_7rRsS^!zgU>un7J|yz|R=5sqvYKYKh+*;b z(8!TMxL8%@a8i_qGNC;c=awwqjf!_;PT^QR;060|Kr0aLnG_?B&0W}Ujh*pEm{+OJ zhAIH2hdCmIv=mk6Evpk6Qqk-^RPR5Y?JhvUeanys*cRG^M)ar{9w{TcL1-~_+|pxY zE@}>yP!p>U(E*KpG6eiFBm$*P`(IXL%Yn}M`SLx*(YNf($qyc2DC9;j5 zr0+?a#=OB;zYR}`BQ2&gGU76Ri6^>b*dAS`%N2}PnaAL%fKpzTNrO%=vo*;gemvn4 zo5&expHbeKW)_3|^ZtMePm)Ro`KBV+Q(eLlJ7=v&K7q{Hok^wPjzu!IfLIxI!37(5 zcTL}pl>6^m7(&gd1pPL0vKmu6VI0Q{rlsYKk#cs5a8mX6;sbGszX#(I+I7Q2d}^)- zEeMCMt>j>pNfuAaK4^%WETYh8vHS31P`nWhSKo?D;`IwMergpwAX9qQNMR+0D?vCz zR{186#w(7i6BaaCW`*;#=OdF?AL^dikaBJ)!Mulg8>YZcQ$$()gg4(XZ0U1)8RBE+ z>vZxfUW!9vtZum|moe-;qwgy>TAb0;8@hja8kzy+Z$x^hvJ>YV1qd{ffi)KGC$V3q z)qw{Su-;e-Lv(A=EE;DE;Xc-Riu=P4-!g^-p0ezpEFh!hY%7^hL-)P-msRio%h1F= z9-{dDFsJNYGfKAOmDvk2_KZDw=(WKH2WK0|NYRXri_vNhCZPe{;fIdP$8hxk%NDY{ z^YyeVWCvTIpRKyZ?~~%gzkkZVV9fNVo144BcOGK(tt)CX?lOd_NwCKK&kq zXpi?`u}~yh=#mepvrWB#Lse+!)qV^AMg(T)zeyRCQ`G@xS0s%O#d`+Gn?5OjtftPF zVFd~08pLilo#IVvlz~&nyu+~BYl)AvUVvw-uhW)Qnq;CLsT`8LmrN#9Zw$rrsWao{ zZ1CU5$=dL~6ogJ_wrU$MDUT zj8#$d11j{I3r zmN>UajU(ht#VYSveJjp$1&Ul0=Z&<&pRn!6a&30LZ7YbCfYy zxDjL_pUx7aDe{CK6IHcJHNb3{F`UUMJj;ZUll~Ch3^LA4DMN>|$%bRoJ(a2&130k- z#geNzs;sT&-h0txV9(=?3zA2)EENYP;$WEti((Cu-8#TS54S^&YQ-U4To-d$W3@>K?n9%gfa9-3qlkr(IS!uOaHs%`n*F9k^pMH+Vc1w&r!N-7o<^ zU7+BvdQiUW{N9;cmP`Ki%Nyby5tGBk;o^TK#2=7O8H)BVv#zilOH<|`B%VAJHrD`C z?wZhuhw=?keE8>Lw3v?`58xJVlbg_scOaT1^En74oNb1m2Ghb#k-$?V$*h}o&GmXc zS{y%|zy0Og*LVw`C!Y#*O^49_Ca>q?w;w;gRp;wI3E9X%rN?6RqjwecV%6_8&fq8_4*DO z!sx@RiiWSDY(LH30_dMtp1EoXyJ|2_5U454d)mY#hFMj)=V^Gk4@fu*ck8G1GwjW> zW-#cks`SvB9zHb$#q{s2(n_%;U4j}pxmd7zd+8Ozn?HrU#anW`n69z4w#}bBePZ;a z%PpqMydN~rV)bTSLYh=bKPd(K34Ej%xWdz{#}Uv$C7|{`1321Z=A zY5V4|CmC}u#|jriBtt8dMz8L@Sl?o&_r{Yq&!^sWufRm7nIrL0YZGA+v#xa{KiD39 z7*K;vUha)4sRE6Ie2K13p$r^cx2?+!8G{fKD|?@7Q`9qEz%r3IlA}+z^qknmXRMAG zjHC4fCbB_jj%<>gW#(?wh;l0;=Mec$$qXx+k!5;J#_)L*Szz0oC#J??VO}3G4FDQ_ zCaW^z){7ON4ZiG|wWWZRTb@b?Jb>{vd+@wY!Nqe^M|?Xx8oc^?^|MsK3d>S4#hn8` z*40xi&qSBs}B19@kBN&v|F+ z5>ZTkff)X052~MT8d=V^{8(7srX=S=E+=bhRfyYpL0p1y(c z;_~Bfzb)T|#vQk-cYkdFxp$B6ACsy1q$`kcBBhS#VX0TZH>xhx*rqMC+Nbc9 zn8iRAmY64Q81jkp7t6QTb{&m4;KXPHt-&dVOYAhf4YW8VbsBr3bjwYoAMA>AOLkFR zkbjAw!jvR2Yr0dlUo7Et@}ND7#%6+pJfnE2EmZ1wYBF?R8oOlAi!7D*&whwdjwzEW z`bL#AOy9k?X8aZ;4XZ4?einOwSaQ7@wP3ukDs z7=NR7x9N}!s*IhM1|xz;u*bmBvt?&L(BAu&yCkh1vVlb+Oe-tD-f(9UX{23ssz7_r zZIN@4$D|~d?<~fl5sMJ40w?sId2B7M$9x)H6r71@d!gy{5d+Fn3z;FUe3SdsEQUi- zNyW^;_-r8RJL7q?1x5MZ+{y%9Y|fn2LC9LXDSEjONCKW)5SvmEqS+bTwVcA@3<+e% zfiY>za~x+$Lq1-4{koF~)tR#YW81GCeQ4h}p~wKdXA0$h4fa6rIsA?<`8W$2h` zSZ`2aZ=F%UrwJLVvNvt0wmh6m^`zn6Zh$qB%iu_YB*VgC*Bpkqga9 z0jTK)V9(yRROy~m>e@eVJcUObc!E4QcA@_!K!2YQ^gdk7-Wu-1U=zqMY!M27FsNB+p>f!*w4VZ%mnw#8#>wR%I8?6@e*?jSMF$XWD0&X&&Ek?(|++@c( zewUo?l3n3l!vW)bF=QI?-jb!EAqvsmP$a%BTr`r)Tf+Vf+lC)CyqgCy;AR~c{J7l)79il(nq@|rCbi= zZIy$X+{HhZPZaAEguP)9TRhFmff+_TfrB(GsF{uM*nIbI2?rVk*yE~8l;NQ9VVpWz zNBb^pBrf|*z6IXOc*cRIeEoD}Mh9CWX+)^qIJ7^@h!LsFQhA$U4!yU2c3&v#gPN zHj_)oVBL-`wBESBkE%xGDM9wAp57^>gW`JjtRNCvW}hq@t=WL?#f(|P;h(}SF`NSM zNXD{@_sRpCq6c}-bmpkfi4*LM1|-8K!N@GKz)U^vNBnl&56@4-xp!;k? zN3Y&lXcf)~w-OszfQhC?F2B9UkSwt(eHdny;0&t6?u>SFHw(r67m6uOW_cm}8eUY} zqC??EfQ};Ji%`F3p}2*fe6$F4`>sM3+8x0Mas;bRKL`Fcp~z&L+&tXvpquHM(PX{+ z?c-!IdR)xj%J)D1{*Qlz^43lNA-W7^_^5Js)5oD9)#ESP*Xvmt;)p7Ci`QviYgtPI!sVW3s z%8sg#+3S5JAMfIMVePm2ZzRLdR}B)*JQybQlMThYo;LEfn&I3y__81qwGMwm@y-Z! z%N|xAsO1pr1b}4Gnk$3?eZfD=YkA{gBt(&)@J6RR7f7j5Y>hXoA&&wMB65#dHczWs|D6e^ayCM|2mpAhOcSlrNBnZepyijFX zZnT`JQpwErm26n7Ns0l=Npz<$qE83R#Fl|9E@O-*R$iHt>#3j}m4VRVtR9~@c?Rx% z!W!Jk-&;z53Rik1<)o4aw)A=#i|55?iCm6HkvXRqM+iiPf~yVZX!thXp3BQp(@S3N z3l&@5Zy0+T99AZ~88>bSWL;_gMNzg*k}eKX_W3kNiX zDJeiCG`&JTw5iug(t2<6H!~K4A2k`;l(N$;D>rTrpM9;_rPfGG(cuo1<4+k<^a z*gc!#-n|G*O5(F^NIxio&6zP~prO%cs5ebmaAt-r2Hq<>DNw+3QN6-OhgH?1z2>U6 zstwBbnM{9j1W`aEM?l>RdMUl!1zCZ0CCCWEX>YN~(2d6nH1zpn3ZTK3@))>+C)4&V z5frY0^?e)K@C42Gzb+2{kAY=`x2GM+fd{iPIfQy0zHz`;5C9*2sScb<7Bq&vn9q-g z?eTFmgH`qpGRqx&yos5F0v>+wp`Z`cX$#@|%?)UV&FnZ|gqk{;JkK8IOorTjGVtWX zhldZZp9*&0fDaGF>(h_-^Y8CjzOR>|^?tlsRF9L#_@#L&;?t9em`%H7oKg)r}0sL4DWh%$Mo)K)hctZaNzxyDU1Z;DDI zdedf#Gq;!rHbB;>eP#M45CqQA@~qX6vhC%B!C&((!ro-$IzQkh=1f%^F`Ohcjxxh1 zo_fO6;1zG^iKi>4qm(4o5Qo6W-lXyP_5AtS(a|Z*hUl2CWHOMdI=trqZp@}XH_t)NMb*+XdwxHpPG_=Mr7#^< zQv5m@gTU7Im*vk*f-?oVtEZXzoc0pSL0uC?$28FI_m>jEmYm3E^^_)w>ftRDi2j24 zCXMR}Nk65T90K~s71!@eMmRx*iil&fEThmNyulh&6XufDfcWBgE@7uZs07PMkN8b$ zD}lB^w4^O2lczl?x*Ff4(&MP9#>LqCnpP(ERZ^aCGUN&qq&lINIuolbe014;|1yvS z|5qKqxHFH}y9;0^Kt~P-)@pnPr>VmXkoH}1Ivp6F1MDR9?Z?OU^UKQuej&T9_1J() zh`MY62ZvI4mxN0SBAuIUGMgQj%h_W2+i%O`vw>NPo@KAlv)>(S%a(c|w|3v}P3zx?IT(Wl+hysGZUV=@Y#0di2nDQM+KcZR9= z%ZpFymzU-B6N-1YUA%w)`3e@Zq2xETA-e>u zdTSJ}s6(EmHDx#C%DNcwq${1w1PZz(N6E}rR?rDgc0jN?4r=P_oiFHWkFK^$}62kjoPg+Bmfab;HHZ zk+0ecna;SQ!5VqV{}D|pb7Uokly(wpu7E`|#}j~n(|GFAvEvj*&Bj(%`JiIuIU2U! z+Ta%&P27bWGDlN6b)kC?)t3V!u2jnP24OyHIa6sdm?Tdu{8b9u#QWYVBopPj1v@bJ zv=;ks$=An8lZ5X2{pr&g zx6pjACdh9fOpQOu8O`_A>u$XQWU@=f>tmIis@dalJ9_y%S=CLwT91#YpiL;^RpqPQ z!ywry3L2X{z=yk7j2h7gnLDosm@gOg{75zCVzD^VSGMzInXOjOn{1jPXt+=WL*{29 zAh|brjvDUFh$flpZRQ3u!KQT_aB?Ue2uhk2b|2g12%S(cVW~WvJ5rX^mTF2;o6e>J zeaIuRLRoJV)E1fDsf*5mLS*w8WS&V;m~S!@r3emZ9SgtC-W%E0iq<(PTSvPOkjGh@6miD-SDTO(508jgu_3%?^d^ zvEHI}xKcWE(oW5|T$?1*&1jdSDWH?bA6>37C`M!5TMMjAf{Af^B`?R&9wYyw#?4N2z2P- zNYZHp>eP)Z!=lwr$Z17Fv;(I}`M%ASaE4b2xVmSaMw-I8ic1D&31*^;BP|z5kibi4 z7PX9dD*LtsD5FCP`clT9@=*U^g-CM@9GIYyTVQQI9y=l`GoJVfK}Vx~e4%J&6rxVI;`2O{>2#wTEqgq8;4!td)Z>w5e&V_-oNI`4#*R6Axc zY(v>zO;P*r9$J*|WP7un9UoWS>dPbc*HS|6%Y(=)T{dUz2hd_7hc= zTqdvVzP~4rpI=6wUl?=w1nB$y{P^|i>g(}*UWabFUJWpH_uBmk&H4PbEY>g3SJubs zbXq*FUVeXh`TTWJ*SD+n{nNPdK(DJ^dvIRnuN55xA8tO-Kae{Em{&#H@9(oGPA?I| z08Zh2v0AY6o^{m}0rb-%rM|K({Gke`-T}5$2l-14xQ1ci2JT6wqnSr<#-4WbrfFpL zHv9dI9Rx10HWfTU|0x23B(L~hoLLv8b+YIgLKn1=6dKB?Cg|L#k7+d=byk|J4wGcw zo9c02rUPx)z>+++qS0%J;Z$DC=TiP`uA=LnVu3wT;+VAt5=0+Gp{d{qmgi_Sq6ROn zXtGM=F^P&zvp4-?)S+S*QtKd`0ogi2`n8i`M2cvcZJWjfQ2vO(SqZ-5c-S=US~bj? zPqX0Ou=((EXq;y#Je;Cac?=Rn7ATSPAdv<>n0B+SDae6oXmqYh`+>-v8fTa?R}`zr zO0G0U#uQLb%SEffxY{vYCM9<31X#N?B0<<*v19GUy6;6nVT@P|$TLnj&$O_P)p-_u zbj>_!I5NU@Hjb*vsF=@e;ZjyBAZOHkdzp;vS@?RuJAvi z=*o=0EDZ{z^lC365PD*Uf0oh9b8&-h{Q2ztuQnR zzkmL?e0+SFjLy68r9Xd=I{4?+ zDY+kC*X+K(qd87qp#u7Lb6!kB@lM?s3sETkldI9_Ybd znr>rxqdr?WeAHH^1I3~rR3fRE7luk>8W_%BpZyUNkxy6+vrT(7Fl!k@ybu-RDr|r#|jnu6q@di`IhXxoy`DL zOH4UL&xQ4BcmgdaM z{e`m{D0ZERPlls_q39*=B(FCXEF+u4eX0ZsN!D`?2FWldPA?9J1V+j1Q)9k>8&K$E|a5FhcR zZV+;jq>_{E)=>+W(e&JW)1@NwoQve5@ zKYensTEQ^zC(gIp@X)Cu5uVyfat9fE#tbw{*Wl6(^HL4Ko6@> zthdSI90ss=Q}9$m`R=-Ay<9a+m=CwRu3L>3i(~Ut>`w62CQc!XktAXF{o&WY|Lt#o z`};pWo&NlM{&Y^=KmDvhBF(u&`JO$!yiDrD;_7O0Jf2TKe&Tn3J@3Mmx;#dM60*Pl zJf2tK7reiJV%FyTafBUp)41`vUN7t9LxpmBpAhygkp)33Z+IFOjIsoWFg(58Y{}Tm zX7&X3Ajv260zV#&=Iygk@{^KL@l`k{pzA58VWlraFU~hJ5A^wS)(cDjWRrNa%iMNA{LvMti_F^AYQD;Q}rKLG4LsaYhc5e5i$% zP0?C=c9H%kB8pkW_HS_wnPsU_p&?o?qGxpC0rV`rY_D<|tgylN%op=I(OG?>BVH`r z#23v+1-`C|Drhxq)xNuz3|@?w{Et`)xI2A2TGA3pC zWEK`C6@Co0G)O7aAlfVxYFT_!RbR_pt0f35{iS6NX^BInr}C0ZK)*Lp zZKe!N0($_YO3GYlb6f*XXa8N+T2g9djP>fE*@JUS(R-?7N`_IAq6sbsMLXhM>jME5 zj+i~a<#VsilAP6gQa_x8{b*xAZp4Wceh*YjnCXK5nzhWZPuZA@We5QhWHoGh1`g*xst?KLC$;nDVJGZy>IKR%v_cTCArjwbe;xA@LV|xQ9 z=|};*s9-H97{z2d7vhV|JR*m~kDM^zJU|K=E)p^W!OtoVg)G0rPfcb3ND%dYliY1* z#}(s;L-B5=V0y#;t$6}bgw9aNC{D;qL3=Ln&lPOdY`(2vVe{`GOMAsrfZqtl3{Kr{)H@8S+gZ>mjS#HuGC7$O!Ksl4Dgsd@D_bF z3GMCaHv=y9w?l%MWa!~{FA;{m2N$B1Sqtt2FAj1L znd&+-(vG1u1GiFYYoS2&h2h~<-PHs#8^EbHayc9k6_~H1SxhZZm}LxaPit(pf$o~w)V^^Wv@(kdu$5oEM-4| zrSLX1%#e3d2nxng-&z_(&y&sN`_j{UH&pQ2NCh~R6orjv3y7rVpYZARb$xxiW|G0Z zqeE4Fd!4UtLtRIRSa^TaG?6JReZ6P%@K*sZ?~WEG_`fR(BcL4AcWVZ@4duD(E<*KA zPDePy0#5-v!swiBsK1BMcHeb(=+BSyyNm5{)l9?P&7M}P1%^nWcpukNIUXBS>kf#7 zyu2Ckz6<4Zw|gCkgC9P;f_aj>mb;ysRet7Ik2`kX-_P~>aN{2r^Z9b}gzo##(eC{E z#76tIo=lcT4C&6vd$#1E5yM8L>uz3Olk@BAdDoqG=j42Xdw5aO-NZ(fsMvx|^at{t zqVmjQI6Q#;jl#{TB|z}GuI&24IB1CT8TS~EL%^Gm>YQ*Mt&wN)|n^;o3FdG$aLE~*i&6VAjItyw` zFE2TZit)&5fNdfb9&a4&Q*b}tD$Q!aM4ih1gpZ+md&LOQw@a?MT=ux!q4mzyR1*ov zHBl2z66r5k7ibtomb0-0Zt#xx!hv%QxloW8s+x;|2a_0tx{a+S4(Zq+iI zGhNf~cc2fdQf9q+m~yD`0uAi5@xFJUa;Ppi4$@0}6NsUff;^ zF0Z8qowBwY#5XWfZ0Vzp{f7t}aQ33>l)@P{j8Vq_eP%JrQaH+#0nNXIOsdYpebXO{ zo-})kddar}h@`C)9uY;H3c8ev=Q?|?3AA`FrjjFtuDc~Hk1XUB?hud%gXt*r-}lOD zLkvpys!X1#zAQJV%dxef?#%T;JY0Np-?gxCXCw&HkIm^1oy| zm@Rg+fQ177gs3vb#iIoWmI80V&|x3$PIpBUn(feNZy|Iqwn-?~)0sS}P8e5K7OHbd zw$1#wJ{}k7NvEUr9AnE+>K5yF>rg<$XHP;)Y+QMB0~@P^{OaQ7jd}8SF;9|LADZ7; z77F~P_dP za+?VS@n*vLX1Z#PyiV~9Dcxb2XPg$#FGhLsSrE513q#ViqbS{?T;1T*?4m<8lP61S z^Kf-s0`E>u^Vv#BNAHcCG!I;gEb3mDl`S)t^8)m@hZ~8L4$?&(VqDfTqs5c#ND`db z>7ja8@P<7h*AfX0U09*p)Rs8FvljA`ieeHrzd#)bswmQ3@ipRo#Nja!ZARP3>Q4d} z8j_bWjgxLACW*usO8ac@nWgJ8Wy>MIuq}I$Xt;UsW>Qc`=BLUx+HfEpX2%!%*i0_8 zEO&^W(NGh|f6w-wUZ^J2i|e*1NqD}OFmIA2qBEL3xcgH2z&ei}A+~VTnPPktY1+q3 z_!bTJzNdyfSE8efp&Cp%Qns?7CJYWk$%oaSq(S+H2t40s3-b|=umta zE!%RY6Jc9HQ!#Ykn?Hy~mO32;3JS|3)RX4|0b7}pqo;vN3WChuUSP_6IF@YX?(`Nr z1xinuZnCg-LpTp|8RXXwBh}mMTJz8FGRLUhx8$00Wp~Lz#@$921oY8CS&7#A03UCS zEAQ?)`o9*e?F`K6y3k$2lDk1}{PuJ=TO5$XaKrvQITXx0E4t=*9Ia4W7Yk&jg<{_< zP`lr)pWwARZ#p&Gr%f7S=#AHynkY`-3p#4QY)fFr1+cl{Bq6 zWYguD@hWoOrj?S1kRXDR<_pEo)Y*r{_Tmvx3aRJ^jJz-7!EM|)}@= z@A36|A!5ks_4wys{__8Qe@&8V5t^HB_jxjDBoZIygI#x&O6lS>M*q3 zg@HMtj_>s3Si8ewlkBQyxxn=DyGi3wy{jD{UdVKaZx_C{;pCzG3FRJaPNJcpc)mPK zOT{}H?K&0vJIX}Z(aIlUDEVgSsU2!IL@U}hJ+Em~m_|rie+|AQ49?ELKC=4ZDUTCzD&Ul3LG{j9fQ_Qwx-kv%QX`+!_2qd(r26*b{p2h ziIqGchAhi$=)kSUNm`$_WsGceh_&o08_QIH>_YF&QEczCr~qQ5LT@o+Y|NQ8pRrqw zF5mXz?7*3URGLLXI3@c4O`sqVY+?#MaeaoVvx0wUd*I&u7x@a+;~9h0mfyEAH6e7_ zVzs32fWmnRIU@t!Sk!1mXf`ap#5~yC_nfu$_7-FF0$&co5|`!>hDy!7M=M$=GvMWN z&Ym4Gu1r}p?`AH%zcU@%rqk!Zi__jxr7tM0-+<@*PF1qc*-APbxt!e&S#n7>NX5) zP8pj3&nl8NiBzZTb_C&vd)h>HKYFQY{YSk4S)~pSxaX!AQb?G|U{p%xduX{C{t4%= z+f7FInAL5qg)iHi4%7(#txd69Z#-1Qsi9_%YjC~cDM-3a=qFY{`jB}^{De_{;eAY^ zx^gQ`yjb1R)=)C8lD{rnA-C{DMIDQ*y=1!_~z~3P3A-5rkqsw3a@$0Yu3ElVS zoAcpNR5R~)p$aE+c%B@S-T6F!LG}LpdAS2-a+M@!!^Owbr(FV$OLs%b&bRZwcTL!r zOpd2h@_KxK{QiDE`tjq(*Y3yHZ{f~fZ9G#is3p{IIXnXu^k8v_)-_m%;||r+v=zRq~D%kVVkchEG09s zlLnAFPG-|3z92CJ*Y0CBQI@|YH=D3LReV5dD~`hL1V&p{BHdrMkAc;ag3lM>^X(0|f*Nqn7@l*u3k~@6 zxR}zA>e$TJ>*ezJy%~L;^KNH_jVVFO)8rEWZklkl9jifg3F6?dAJ}~tuDSQK>ci>V z`}ZUX{&@fX>vo_6!oO{m|+E8I~2T)bA!PgkqQ3P}&A z&sSI9zQ4aZUAKYcFReSz=_h@fX?5K!>Tkp&SMfos18LN zUWqS5{co`blojFP5`DOA`#oFSH*;9e6Gp5-(E+20MeoxX${S-3;+#v(R3?XPx<50` zg`Ky!eJbItTh+Zudj<(i{KPs!^M>Ng-9@$_1z*wLr;JW3F#%ovQ)UyMzmZJhm`t6c zmlh;CGNnWfSo2Nb9a};htvY67>4YcKKxN$+*Ot3h|C}}+w;*q^0+a^fN=DgO$v=Bn*3)qX{EfdE!{#Q{e26SII&?*HF_vdmjH2*uxW<9 zU<~#mt!UxYUP(N5GST%3&2Kh+Ydv9F#@82KQJWgs1j?4)yb86aDx=9b``#=~4co%9 zZ(Ai)JgLnz8-YR*1Zf#t!k~qI*32S-O%)m$Vkarduc3j>rV19K_z|JN7;ysrhVCns zNf~LjT7frSBpQ04^|sf`Ym`U!C~w(=IfJQsOEYfOPDFGZ`-hA{q@kfkPYvE*Mz){d zJZJK_2wUow`$hmmec8J*RfrTQFNmS58KkzU6)Gew%*i+&r&y-3eMTN)e@Q$~5k4DC z6WT0pmTFiGjO%r1yI0G4yuM!Fu9nNynu!jH4KBlfQ-0*w@{Z{X-32M%1xJ>cUnZx} z#7>__$ZA|X7TsZ+91pDO+q-VHo+rsR6gGKz7qhOg&*sx38}HflI3K@TuEy@^@ntj$ zHT#5Kn}0MUObCBdwo^6J8p53aR$T)7_Kk-slEpaQzMU4T-jn0*{Fcx2zB@0*$=C4h z1ZipX8ayS{bn>}@-^x={ov;4APnEbQoT(PAs<&YI zuv6Go#|6y>8&L(Dt}4r_*j2uGU<4Zf_V5!fN?G`^5pGShZuqy43%sFwyvk||7mI2< z8~j`AYkjgb-W0@FY1F!>O#72g2JVEdJeYa~=)8G{n8PL8c<(Hx-Vk`YA)B_D{WJai zdL!cYvXWLELQiVOAubwS3kmgfM%EomPZOF5-&%KMwNTtSc zsW4IBN42HxM1C4v(kv!7=k9QIP39-!-E6(_F?0`2YjPz678pv1OGn(1oM5<*B1})_%`q7!=`syU(IpCX?exzc&jQ<6pO?5RWc1!}bS$ zS9<_5m*&^yvb`z<3cUWuvmEQ}3V<@!Y;we5COOH*o+hiip zAeXY2u%wNqPQvAF+Cqp0m^C@@gwQY~iF1&ox8I#BZ&^QD@{fULTG`9@`q)t+{N$sIr!6$?2u9LH}dV zQv%a&bwAw95%Nb@o?FZ-nxuZ=XA->>td3$}0 zz{NCS6;byZ}ap0>OT4UXDHttScBn5N9St!`Q?ww z-98E0o(q4m`J6r3tzm+Nf@#t~*N#}QTU=--fOh?D)STr{tpAr~vwUURTQM*_r@ z?!%5wBB|xKXVQXYN=VDp$@hCr^DPWD&i{Dv(SO9$D(c_WWRzrVQ-r#1%Jeo0-3Na(h zaky|vc*I&lA&=1|@DsRIJ=LDF46EL>LWL1Ys-i;W1h>wuM+Kxud2dP`*Soj@>6ry? z$@6=WOsJ*of!yxV8&Zc@LLS&}BH1%#EE^3=N@c;JDv}IIy}5;NK%Gs4k`mu4%Qog? zI=vB^E$-v&7;8CWe1IgRdqovp+HXm|W@se@&u}s%6_A8Kn673Z;A814 zc~HaZi)yKt-)qJqotP`p^1$}SJu{CjEN$Vm-FrXHs%*s!mtoqGj!36k4WOpxlk&Z9tilGt=Ze6!3gqud#mRDCMD$BW^yq z8+=Wm%;~@vEU2z5wh&cXXvp`l+cA0L;C zm{Qyw9=7zW!sjz&tIy`$;;~skez@xRjh$lSiJ0s#G7OzbIz%KZ>ENrkl3 zJMjtOa^4uiiOG8`MGWb@C3Z2J&8aEn;=v0VohcMIWFZdW z^vWh;gV?6x+sL{Je25*yW`_zIhssD@otECQ*U`!Y?C|iQHo{;C}!Tw z4vWWiGl1PY@i=bqp%76pk=D|>^1<)>KV}%4z%aH71@k)mEOO(|U}`6?pI+xzqusW7 ze7u@8>+$Xk8D(-l{}Y%|U7c^L?-*Ue@cX7&)nLg@msR)s?=N+@mk&3upFVy1clba2 z{hE}l)F#fU*n1}h_$DM0hUy(^cy<3o&;*q4?;x9m!d{kz0*0Mq^)3k=6f&cT**Ur* z28F!)iSw;_Ab|@{4hE~Y4f+RZ9-UPgC4T#iNDsMOIg{^j%0Z`Mvd4_yL9{WCKKrcR z%D=?6GtV{1Hm^Ng6UN^ni$d7y%VYT_qRL%7^Tt8OrXM!^_!O2lyd(m;Ot8_s z+}de5(OZu#&8R^kwB7P?*qP#0=egx_*&s1KpKJ(3hX!RxVh+m~riW;}FHyX~afj*Raoy(45nDFe8kchMp3GKj^lm zxkd$K1}Y)b66k@Qq+%p);I%~1s22`PJA+uK&D$jURysG#y4lXRjDX^C>){xTlc<-) zFua`PrXouzZVGdY?908GsX=Gv1S#+=qO_-_4G$;~XTwiZIeah{JEV%>}Ek`yPURg!uFP0od6mYwz8+Y550=ZooV`Q^(x z)aUu(uB#A8Fr}0+w4N8uDpc*~B`6r(U13f41CkiFq2kROdc$@|?wz5_4t=Un?;--; zH>}{HQEJeKQ>=dTAsWUm&d^_mKR3tFeZMwScNkYUHx*t^{dKZB-LF?4*W<+%0*4<@ zi+AhhDYVDCe})C?-MT)mEKZn)-%pD*{fg@QCMghT8P<=`%74H*B2-(Bg3#|Ha@ap; zglPoAgg;Zk;RKEMcZxYXj})}9L4g{+g2^m&^1vhxRBXlMvwfs1U(r47yZo?fNwzIot0N#FZ@><{5EZ3Z=13~qs5Gs+5YAZ+yVY;QAi*^}nkCVCH>UQ9z&w~=oLStJ`y`|yqsT+F%)fG1rS3e@2+n~%Ef@ylw8LO7p>HvV`#q8uLA;kyO( zId>H_Ii1;hC*e!Ly&q2D7cRgi3|~5NAh;85Qte{#PIfcY=c;O+k}9!4o1|i?4CNcl z61)BQ3!;j{mD${X*wyQBn=Fs(^}CN>R+GustB;|8FSpHVIr%u5tjG1c)oR@&J1gIG zm6|t;17p823Qj$Iq%ioo0B2+4@y@tQ4ZTDu?&@(X+X3^+2SJhnE$n+o(*mxE_%hH4MTA% z75dN`#E>sJuvE0piEdSzT4vc0RfICx3*%H1YA&1@Wn#|(55>!U44O>sKuF*SQU{kb zASZjY!KG5p6j8rdhyf5YN!emVwTJoPMlUcy?A-IC`V;WkUn(x%ML)l5F4$Jv{{P{})r{e#2>rv!?(Ysl{){f>*ei7!<{m1slTH`GTXojCKD z zrimD`++0(dY{+FL)kDfe0(CFBggJA|E$U{IDS5fqxR9Kh{oVwXbOwN2!A zs{&CenbGDHQ$@_WT88dW<(Uew;PR?*aqjkJ+toAW2t?;LHF_i8W`Y8#3}{id;WEH3 zoSu20gago_5F9aLsf(%9jC8>2;6=X#E`Xd!Im`4A+#7hpvZ_e*C#YXuI-)bFvusr6P z{6&+XVK7-LfHhnMo`9nQr1#O{3#W08q>2nkBl-%CD+so@s;y{2o3?dUaS_AZ)Lr&H zU@aQBUwWtfI12*GO@XY(p(O-}K*;v&6?aUMIQ??C($ioKuSF6jKZ;=Tk5Pi`ioI__#ogr?5Vh@!5Q}Tu$cv4ajqdk0hu0Vts&jRRTRFZi}mr zD=08;w#8`|U7!kL+zDBOl>|F%x{C&GBT?#@B!@%t=`}g+PPpwL&wPE|&3q`}<0iD; zO@e?%ne1sbrbsZ>$QcNSz_>FvHJL&gv*|TQUE1T zzlVzuGW^hOKRhT;9$v8(B|FK((4RjP9Sy3!12%aA&L6(py0R?7sau6ztE496dRJcY z)v-eVB!g76snPUeeV2?k6WWnygTr8C30v|)?OYV8@7t-1xyH0$%H{FhTY`8l#YvkE zRK8}T6A9j3Z$2<@S;I;xXvqYW;IeHi{5bus*@@HWiA}6j z zM}3dvch6X1oRy)Ksr38>Bq@ZA&P_}}9&CAJ!W#Ei#yn5`=DFT%_<&$zrc5!$S;Vc5 zH;h=PAQnU_)Byj5a$40c<|4tk5#2)QO<>D5&Cq*80f}`Fy>lwmU2ILzxx-pZK0CkD zGw1@B0a!3?e45-gA(P&dpIf?oiVK7Ik%P&RL0NRAqoiNdoZj}MI_K!l!<^NO#%Szr zQU&+$h)~)|lC7^p%e~KeLFGi-zl zBMu*C3ouP4pXcnei@OJ?Ekhw6Et(F=y~SzHsP#FfnWyc|&CPshv5VbXnhqN8=r0J- zd`CXD%woa#*frJp_4N~S(LV9-^A3Ze`@&rx>-F->@=GY*%XgE>R|Uq0+hVas;~lE^ zb>qkN^>{rJ^o?MJ@L@5z3LR_3IccI=O*~sgyU^6qH}@6j+oBAXw2M{oM(d4KV)WiV zH1H1(Z7BH#ggGqT*ctPDtYUah6u)~#!duHBm4lrM#%f^0Nda&!9+|e@@_+ComUwba zq{-o8oLW+*83IaM<}_Di70(9Zml6-OAShV$pEJDRj*kUx9iTrUo2-qHx6fQT>_7JAhY*Fc_xJq zs7Z<1%}brrLLx&tY(4zGqst8VZA_Eni{S_sFEbz_7i6Ive-6c)FxhmMRWG77#YzB>Fcvo)e zXJ)o1T1-;L`Gz$w=BEmi7pW2XzkBPdb5(bQKzc&@#?{P8P7>!{@<`>XIqpGt?gB?g zRv1XyVs&dxYbE5$YZo;_G`#Yhzd|_!oN*%+MJRSvYul#qn&Gxf>;$?RfY6F}uX|a{ z(~(3{QoJu{aWCoYT)REvh+VybK_KvzUL37FCFXuvhOVaq5xgWJg@#u6eXnyhYp`Lw zt-0oyT46))MaL;5EDkfNcW(1Ex9L^R6f2wiZ*oF7CDxwIB2jI_>XH+>X(ls-@;$q| z_~oMe9&WSc$58RWAUr6VpqMq&i@Vd^1@g|ei{;~TbajRDPHsu4@(gH<%% zyB!;Gu}%tg=MM!NZ`hl_Q;-08_y&U1XiUX+JKa~dUG?Go@kT~=X^bBpW|luyato&M zrgb;h5)zuTi11-##j$l%#4`dOzygg&1&ESFW(FR%BFKP0BEIT7V-%a>xV$+OGH+{}nqgStwwUA=OfL2c0$Z&Vo4BuyK);4%gNzZbLoC3wcth)y zrQ?hNs7MEjV06gV=3<(C|H8>NP@Le3sL zBNAhWTagygK$!HN@bB=%_g8s`U+JSg&9wNY zvKA)M(Ai##X_Ylyj#CR%l^)E6x55J?;m{I-me%CCY`^jHmFt>`3Qp=FiPIYbF=AN) z0E0n0UfJcIKvVCK=^0vOj1fTy#9*nU$O?=a3irWV>049M&^D1{s6AuISSZ0~7jNQ6v!7oiQ2QGMnelDXb8RuQ0QLmPd*+nVx<$ z9J}-4DPtlPWIJG(ps8-U=9f@&zklzV`MclNP+Asu2(;V+w=Nc|#T=YLB<74(%f}h) zP$;^DFL+ijj$JXEHsJ#j)}I%%u6vqw$Mtx3T8!pH!%Yfaa`VBg1zF8GsoZI*xl=u_ z`17dq57i-*@PlvMtZF=tF3i50<>bq9QG;eOUbA|KKa=&bUZEXdj~$A4?Z)+Fazxk7 z?i=-cv1sMuy@O*Qk&&X}L+uJB>F9ycd5eppbm9YzsTj!+n(wOQk^>tmPz2M12i<#r zFawX?;)h!?1$mwd6qGoAfWV`1N7T~vLzv5(r7J}Tob&Z@3dpw2lk-fT9crLAhM43* zQI;5m*lls1&*X*-CM(m|d+I5gsuOA@#^lq}(o%4VDfRnW*d3(P=S zRY819iBX;ySmGQ=a?vZDxodffchX*}QerYO8qz^RDRiFOx!T!$5Jha?TFNtF1=?h_ zj4~G=LNo|T05+V;;$?!iA;5@s>m-p#*@K#pTZS249^ZYh{5CEdIBHnj%nyJgZnW;X z(e@lwr7YyGku*IOm6}@fO)cKHIo=WmuQQXd_id=)+?NodAR84WsufjTgcRSBk;{3e zSE#~9Ap0CV{F%7xhP&f>? z8W!&y3J3Fu&#d_Y2dbB=b5hWT3YyC8zh?jHzAJ9v*i2_A)uAwNcXu?Q>XxI`YJCS? z{Cv4ujykF<`C-=0vZisc@rE@@ahNZj=TBXCaRK5j3h`hii2t@|!FQc6tOY0CyP{Q< z+VX^0NO2zx#yT6X_@0-wf zyU=>Se4fnJdWVnQ4A^&xkz^67_s)VV^;j?nc=7Rwt$c)pDIsSC~@gq zBPwAL;%HKCSM2@FHjBvz-0an)@6}AW(ZoKBMr;&};XrIQF&j*xPcp-6&fqd_OaFhW z-o3SrWZfQaiW(+VyQNCgt=RnNNJxdShp=rq*oG~gKH%-6Gl6}`{%bsDV)n-nD1rB@ zzqQtSO3wCVa`8o%zC88Rde+5>hsE$^P+9`(B&MlS+>4&$X54?Fo0)L$SOb=*S;bq# zcVb(Hb&2>TS2xdG2IXAh)DQBdz!4;6Hh2C&<+$re6S>}?eIGG1tue`G)ofvpix#*w zJ#!dxZAB$VGJKNDt!^IV$K!=_0meoI>QKwTKy;c>LWyy6fID#XTPH>X3Dh=oc2DBw zz$CWXa*Kg0>2igUaFu)S<$U?e^6dXmxF2%^dvi1UW&ir_3b;43;sJ^`)%@!E>v=BTS4#~#@0vL*y)Q!duwKs=#y`2sjrVLG*N@9$XRon;<|MC8@pUpnLL-D?Ochj+W zhv`)=-npn7@npULw6k7^d2X6fxtmn<<=F$LjfKArnHg%CuNdZV=&dLbl*&XC=IgdJ81^R44%QwSlK8+FT(I|U$HBG}S}^k76*d@A{TIiOhG%0utdX#k{zc!8BS;cF zIf2sYu)0nrci@&oC4M_42&hoGfvN-;Vc$rNHC$FmKz7xW^N1Ei1y zH5Ye4GayE`kxEiIATXbIq4@`Ju%8~XVq(Bp=2*uJjH{Z7m!;yba ztRq8_WCjF3DWcYt96wA){n84 zgf*YT6x$+#GE@%V7!Xo~(47f&md;au8Cy<>fZVtAD(Bg%drV!xYeaJdwjox`Hg5rY zKM9tI;!|s>*|{srKP(x62WW!UIWG&Fj~_|m7T+I(6DggNcrY6(fMrNL4ccN44ym31 zjoMTjrx!`{^Yz8q#rNgea=t$Q<8l2uhcIV$^T(N72M_nT+UEMbUq9xiJO6+7w7fdI zncsoReMfhbT&ZW>!)&qW?hqY+zgr=ZD#nYYN#DzS66`_JzCkqE!bE5emNk3x)#`GU ztM}zm%1gM#s&-e^^Vd&bF}+-E#R%z|VLQtW_G}7W&ZL_C_BeZ(-n_d46a4Dx>fLnu z5T-Y|DSuo~!}TkJ;OEPyLzQdr`r1b(pvlf#y+7+UpO0>_#$DX)E-z8TIrUT^!wd#U z%q=c)IYZO+M({3^%ILc2#Vg^2#uS$Vg=NcMn-vc$7YJqEoL-}OTJjR-j*RwIVA}?< zPx?^8)MV7;3_6fbqz}oAV}p3#?kCT}U@2=3icHpb8P};ojqG69q`bk-76IT*ZfEf# z#Ymj*0cDlrI%%-A*?TkM=B!Rmhq1`NlNm=DU?DELB-O!Nx@|8B(IBXJAn7DZvBJuG z!hyuW4B=``)Vq_(H}R8Py+@HTIH@Dq+h%Rz$$Rq)WZN7pcfB?K94ad6wsboqQS3NQ zWa-W10M5BizAnrIl}|t_F$YdDLg>ij2oAHDCIoL}Fv3-0(&ieIH)nq61`B~k|Jq8G zRreP`glwaOl4|5e`ISnsG>}%PfvIBy-V#+GY`raGR1e-Hc(`(_)+? zk4Bwvb`0ccD)|}onW66^E(zIFMcSj|R)D-`)00bx*(pYpa9uIyxBLlACo!rY6mEoa z8>tg;leUjzxL{<}sEI;qv5TO4K}#ci$YqFv`=P9b(X4QR8)}FBFqqvH+nWFL*}v)l?# zb1`o2*gdbR>GHfETrR^0QB8`C35)r*vvxc;*WG;9SvHz*X0_>C*~U@|`SsJMIkyVZXkyyO!`aLKN*33l{CI>cDU!@_jq0u5yHW3rJ>Zz+ z71cUR{vuW(PZm-t-wa)xsrMBf%bMD6$fnU&X zq$L*Kf9YX=oi{PN2{s1kp`lPriU{$}DerRPKg#gjgW zJrzO`8QYozMNck_wca+NO^7&SwlU8LIb(Hx1$`~%>m>AfJ2tk#{JLmL*3&+aXA;O2 zI|R-ERzRu0DDel`vuwQb5zIHi16%Z=O){il_0B6q-s4qg>-qn!U;g;xY(KwPF3+xR z{`Nmt@6R}r{N;jz99D182QO~c>oZVJu5F09qdsT8zIwl&Kh5ULi(eqOT;1I-9?veW zLNTRM_;6`&i(bdtag*l=e9r$`G+P1|`eJU$bJaeaQ?m2z@Ch04xz(TbH<0DL14Zy= z+I1-2SEu4V?H>B`&wu3N4f*Pg<;*YV3(g(aUl=;6*kMpdwkNxlRx{0&L_E9PdAF$9 zb7OkX7F9I>>)y2;-AwZK5K+Wt#c^T;0#b=q)Xc{_NbO*G?6tYAn(<$+B=(bet0tV} z3xIbeq?mvMhv{?rc$z;k~SGEF5Dcjf_pPp4gM`rje*4OjRUP+pi|ui6zlp8 zDIumpiApu(;9aU2j@Jh5H;vq=aGrdBQsE+B|5kv?=!zAW>44ru+sTTO7Plasf3Gl> zXbSTv&0vZ}Uhj*}UzI%it2JA1gvyKTo%d--B~D{{i&p3A!B!odJ4=yJ2Aa7l4iuuQ zd_#F|ffH!GTUktlE?p38u0K)cRY5fJ{9~=14J1?s8d{MU!X^zMcuS9~{Kc`Py4PC9 zdkn>9684Y@7-W%7I-e|Gd&%?&eo}z~l*;wO$}CUA6YAz6mu&~5aQT`PZy%%-2Npd9 z*>;QT#10b$j8SjOEM>qb;Aox^TX!R?i>F-)qv*8?($gF5Fm#f5!&2Fb`{ZqAVkDs2 zbM9bCQhoX<+n&vAE&tqnxlq2yMEbhl)VJ5TF#160D&F}9B`)6zc~^uJIMO&VSe$%5 zkTvB~9vY-v8odIGNNDsMk_~BTNU%Pob~2)c_f*jLsO}MDx1KiZ0KwyzjYldbmez@P zrh-Kmukoe8L-yQ!c<{i$K3dQyuQ8th*V>i?@7MaHg&39n4c0qF^S}GkhUl0 z@(s=jJiZB8z)LXZmb>W+QogE=pFVwBn&k2oj#6FhhBl~p-@LoNnIgXD?^iePSiEm; zKE8YRbaQ?cI+r&!;r(ydXW)B(r)GX}*j9_DZWgz@b`M@4#+EDiQ0=x=OO<8ALQYff z6)EMSMBq@Q&|GjvX2DQd)J@vfX3*;KL6Skj8ABPotGV>MSC zRlSK3(PvMiRFZPY@HVZdf=*O&sD`a4Hg`TP@Xn&o_1QX@agLZT+Vj%XVH7lwblDqm z1@ZzwkgR7&P9Iyk%#EDmsnD|F9+|BriH8i2;E1deQ6ASo64hCL$6(ERI(dZKY|bwH zLSzH>$m-7Sd(g<%?r)p#vHfFHgJ_*bLrXEf7YC_z%wj5;;Vpg!)3sK|&H7{|wlLAg zX^2)6MjCN|MrsxDW`!ybDZ10h0P7?5j{^%OI`d(oK>^N>pm3ynVR00VgiZQ{$(TjW zmrDwC1I2%mrc1Hx*LcE!u;qp?5#csRb_lgG)4d>`!WDM3tD&~!BeS{z|HM0!RVg8v zLrv4p$eobL0}TRz77rw^j~tYR4W~P{OJq_U>}k1ibZ~9brQ%Zo(`fR9U5ThMLSz`q zW^Q1ETwTmx6AJS*)IA|54!3PO4MlHmI(xGSMxM_GxkudD^K z)NR{Pd4V=0;NTX^Ybe#M-W(V&JcBy0zTzOr8G(lN{tKRq*vv?7ujd=XiIt*xl0ejC zeo%yq3fCJrsnZEX!>qi*AU=R`^v% z@>&v6mVAJ~O$nMhI9EM>{`@5u=J|AaPd(1r%SA55doa20mRDzIch$wk9jPg~TFSNQe* z>gw;}P&W1UgMyZChEMY|(n}S{a+hSdOXH7!PSn-0O;Vkm8a33(0^Chc1byr%$BPe7*xX%JJ$s6 zoAk6v1|*^eArW$vMOlgSjMT&@g!!hLb{pvXL@$iy+RCJbQ}XCrEL7cJ-*TK8YK})I zC~6x|FplGtp)6a5+0^EbrG}F`HTnz#_=eH90_;vPc0lf6-`C0nW-#N2G;)n(q9rsJ zy$C4S1#CSjUSKSL;1MZaAADW9Kdx;@3IK_ua*Lu6<`$R|{w@?@*f8xp*&`HoROca=~6M zuCABAG>iTGVsThii@U}A?0T`jo}WCsQ3sniXG>es<5yKx)bmQ0H;+O71`amqr9JVt8CGS3d?0+XFeyo1KxxPC8{Q0-ve*631A0PWI%k*<~_4xk% z)tM1b7OUsOD;9yp^W}tAC5Cwm^xo0So0vD2no08nTN9B5=N(MD+lCQ38d#3)4oZ2W zt_nS2j5rw`ayAa4H<$ql@m)1V+DDS-$B@bs4Ui?AF5X^RNc%ZO<4|Bj*$U&l`5h*% zHXjoX+l`rIuydiWdEPpd>X>z)sk~hY?KSRmV1i*PHltGeDD2_XC6hK-!pyB}?`iqu zk}I)ZCoPCG{&e~0sh&G+EX1-QCZdIffKp6Wha4lvcMa8HSjdRxwir0Dl$(mQM_dz~c`ZxS1n$>3Vo*7NF(}oOx^Z%Ui*qc|_|c{e z*m3|!VW*8ocqCbRP^=fHy0`(Qz{oc^JY^YB!&Q>A6Sl_)t&C%VyCZB?9mglwpfd&n zk|B)WCTs^OGvvrqBuvL)Nxou(%mV$UhsU5;cgV^V&SmbTHTQtE*^{w}<|HN{h6k4p z)-IqV;Ka!-H@Er_CPiMbno(~I6XBZ7kQsvrO{9a?G(SpPpmuffwv?Yd$f;3xNg*Zd zeNgF=21Zz?z#qNNg}dHhO3)HK)X0eziTMo>Q*ko9B$X-P@OcH61lIc`m6~2hPioL) z5+Uu`c#Uw0m2hV(>ov@uK>o;AWgRJ%q*gfZwAx&;Y3oQeRG8$mnim|nskDO*?3h}z zag%!p^~c+3eH$K>_Ji%uG!)&GlYt!AlYx=*a@pWU8?RMtb7s5Y(#48e-OLuK+Q=J* zbxC(OUt>(!+}#_~J?b+|_;QhKtQ?C$oquYZ zJ6MY20g9lj-gc;%rmkEa-=sSE3tcBW6nrx}WH=6f_{NX(Z{I%rilq5)adY$W<|cQb zzaJL}W;j0_Z$AI?pMT`yeUv*UAj{^7&7u6qCern|T?yV&EA@t42;`s1bgnhW%9 z+gAVau_F9V*ksocHUZ|nT*9H;#fGpqaP7Rz?#5js+yv|=G~AtK=R_F|X}Te@_M6pd z3DMzY8Vjcm#FVa3!F7J5Ni0DpKrZC57bJxiQcB{~?+uAjtX6t!y*2!j5tSjxu6S;hClPy%)K|2#`JSj# zVI~5;@kYFndIciJO-Xr>oIk}@$%W1Wkr~rv$pfKhtR;M^)O(ZiJ)3bTYl{V0e_X2C zR)SWm<`950l#>}1UPHymlj8(qPbLJ7h^4fEy#Zd6EIyu+n~hP)p1d_(NXzzgFtq+; z*<@04FpyhW%eDrqn85l*g{yLC!;T1QIzl7+Jf*-Sx>Cyt?f%FuFYp!98nS;MfOh| zJmZ=fki9O#cumeXUc;#IHGEiWj0-)(rcIato0b}I5BPj=8uTXp%B2(e?MMq!zTOvN zl|3kRpvz)x0fjtaC#!%`@&W+CZY4ku$q<{8sS|0}V_btcnIu2%@)Pe8c}9$(&u3h0 z7e?^p_t%U3i#Ti&<_GXhS`G|29r?G zZBfyX-`yc?=liG2{IR;c{IvK1!`P~t^&k6w`f+;PenUO}YkBU?ugNdH^ft18qV=i`H4XKal9Dl9 z8*idO?3(4ReHutQ|D`W8(Ih8k#b{Gb6p8B60-RoU#)L{IHzn55;C(R#cgz)#YCb4% zmLXTg^okW-8NU=13)-+4Vez)W!PEDp60@7+0Y$`w$+& zW{p-1E+jG#pt%%pQugB5VjE$DRgOe3Ho?R(hEqth(@vx0NE2@1a8f0nEJE(XEcr$| z0Yx&o*cBj7dvw=Mgz>V`Cl3*HL#I@mU^7a_rBh@=_@wr>HsXg=PG#X*pE&sp`EW&r z2@-03{ZVQ2VnI-yz#};*;4^=%7d&Ip88|N^ap_GjpoXb5^86*MTj)rt4Gpt`O(kX` z-I7nm9CbR=^icK+Fp+V*MS%2-b?~z2j!qO2vhLtE!$YwN2Ib`&3Z44Ub+9ReA`HIWW(fH~Xo=wXbTq?o zBFtj-p<{2}Gf(^5`XT=vEjw)4!3?AnbFksL*$m}(O>0>KCk`8sTU-&V|MwsN^^gDk?@tG0 zT{cxao!)%>7{c~=_N&VG_P5{OzkfV`IX^!?s}|qvv(HsC>#x_GTppfZfx>+F_Ca6T zo~&uNG>8RmvLo+%*O6)h)cgB<(FpNwbGh4gxx^q=$HlfGjO>T1?Zn%|$YQUV3ma?8 zN)YUQO4BJ71=TBBHreqnw2_qQb6Y5|_qTi#9Gldq^HkIX? z$>=T8E(X5#(KzFpHCQn5gsa5pq9L&O0jOYVqa(>PWYnbC zc6rsOtswXsXuiKlWu^SNz>Bx%xKS2pBv@_){88(YPKhDrf1g`-Z^IUg{Q<`&4jKh` z1+l@^kaC@th9J12iH18)j}*}z3BU{Sp0uG)t?XlD6VXzJ-$@#sZ=;@Gj&$7RfxwbI zqMmxxY~pu4;chyN?MX*r&XVJSX$KF#oY5lJEccGK4%sTBnp(z}z`IIj~p z3LAhnbPLVz=C(EqB=jrhcU$}mAI%&r@A=|s`HK7k z6z$jb>!MpQw}t^!i^VUCN#HsPuXo{ z9JK{&oKX%~0`|>UmG6J#^8JthM$-K8m>YBEF3+ab;)50HsCT+ENFG<`!#GH({m)YSf z_fI^L;OxBw1^;k$P|8FJ>ZDzYd8R6xKAo(j#T@p&2pwel$Bxt?#b#8%E7u=qQhynd z4Dz+*rwH9pTaDfuHYd0q*@7QR^{zu1lbUHByD6Iy@D9Zdns1MYwx4O?Eg^^~f-R9F z*Mdqmp;H>wbC^|)^ajy_Bu}VNY#=>HbAzlBy(yqoT>SXv>~K!pV?tF9ZvulaT?AWO(94L{}#8`7;{d0~YU{8P9v7$3b2> zwJ*pUmpxymrDnA$3KfONy-_d`et`CsB=>=joGUgHrzoP}$d(HNhlHF=YFUshE<{W8 z0Fj=vmYUCt*=v6>`U{5w9?2<_dX<}%1Ub@#!)fL7fn((3NIylOJWP#+fPy|0bzYYv z91(-`%sO1)Yx6ie+J(~?UsZvYgJdZnKGluN?F6F6VJZ1TWES_{?8dl6DJnL#uBP?| z6U%#&16Qm2=B~P{U=52td@;)-5wzjVJeizh_u%x>PjMvV5l^}3Qt zx5kc2vLwD;1UqIZQhHvL><&Q6s%wg4D}I(d6n$%F-S_3??(*N4N}7M33{x_^uYLy{ z^5GlH_v6b;ZoSVI%g@WhkH22Ne^dGHX5so3sS1nZ;z$1G!}IESkxToB>iM{;S`%Bg zv_D}6aWhvI1HyFX`EJXt_CQj~p0O@1BQ4RZH4tLK-iEEWvvFmT@P;*$zEmb)Hxfvs zbV0e|eLrKgd^(Zak{N=Rf|itCtg~ea@rEkX?Sat+imnn-&xAr6T$ZFA_HUqYNK>hu zyk%di^_KaQZVftSIJO@oOPGQmbv~S|V-0qfV>M~PG5~dIp1iz6h?kD#yF-a9_sPiG zS~~2SRmLq42YLLR99$Fq6b(~{n!lLtex1?&*U!=7-;<20yW3^$zM)clI6uPW61Fu)_EP+(4 zXfUaFT3V)%NoX;~UW8DZ%PO1&Riz8P=8H1FgIzDBFRsWd!9j10UBuHQ6L_riV3~4e z$96w-Z3V-uda(Ap;CdwuV>Fppfi<{c8d$&F>1t4DDtC_9XKo~1f5T#!=#H153|=p3 z1DJgvYljQuMZr1Nn-MpRv}z*e+H;xvd;lRkA5?CIU`l>_T{F3dPbXhbIp+8IB?2rK z#VBu@f|*YR&2Sli!I8M5ETK;t4)u8Ekk8}=r{=9R&-tt%6|<#ZLBI-+qnkGm$QT~P zQ~?|rAlmdAICEn2KslC~z5=Q5P2IlfBY=3iT{5yyadJd(z(f(`hRYz;8=PU@fO#dt zT}9(6Ip)_TDJnPM8@#=`Vl1&b?kbn><(ia1wBrE5=dZ8O8s0%2kJ=4G!3CZ0*^TGo z{qCk~siJI{yFf%_RTZZ`kOe^s+)|moEiCY@;P8f~C(S%o1uy}eV#IK1cP=fe7$5%z z_I-SA+uL`4|NHyD&z_fm{rcneh2{I~@%)d^kIR=2pJ&zC_vh-HAtc@W8Z*dTzQ5u5gB4dO+{Y&oG_7V~*Dgj=2rA`^<+Vl93uX|zroM9Md5KIDw1$8Bt_PCH0x z8BBMn36l{|l6lwJN3k8zDyL|)LL4XbE-pw3>EYhN8`n-r?ciQ(2Y~GZ?&@1a>okXw zYl%%Erj{}3>A2H(uJqeVU>?n!1UzBPye5hZW)!%SCHYCt4;9XYmergCaM+kcT`@L$ zC`re?y+|2G+3H2s3u^zwXoK{JRY)Uo=usINAT5m+dP(Xa{ihsVSx|yE3`0|U&!aII z?QoRwA|so9u=>a1I&cQ#1*nrs-W8?^=J zPHgEIklTn3BTgUlqAiZEb|b*40Ug<(lH4*xok6>$EeBX(gzG%}bEvC?s!2?RJGmZ^ zbgV2%ac--&LDcU|_Y+#T(x% zL)d)LHp6~bwR?oc@AFwexkmMl*s20Fq1>7F4&H`&W=3TpmQjN$%VRK|p`3cf>eeJt zXrCPUQYb72v3>>cnlesgKMbvJZo?q+YmJ=V{AGnBTRubTc@sy$(6kzMiZ)^0rm{{` z9PXoiFlw8S7pDk7fXH;*NXB2R4apl6UC21#kEn*Xl;#zTOP$=c_N=CPW zF(*!rPH96bOc}A3SRKUaOq|;9mXl1K1f>OWhhZCqQRV}ZZDOeoBHWo<81r}7uuC8- z7@W+Wz^r@2#MLgc;s7+2*BLC5P#SC~q83w4A^f*w9y(}QH1m?6nHOpt3KlOd(66cH zoCG4_F}5^0>uYkx0p!_s!=*xIqo7EyZ7_Q)z&%d%qd^HAES_p!YSk?#);{+O5hKLh zM4DqTI9d+kdt6biouW}!dmK&sQ!81yMs5#W3L`H>FjxNk^Y#nKgNXaZnvkzN@VkL7 z&};;P-yo54lw~_x8pP_5FYoxokfiCp8kt#q5r!g<9?@wB*d^ox)(80@GZ|X9KyKJ4 z0by$-2C}OMj+Fl&Kp!&(8C<5=Zm6~^WpyCCl9oCI#sanfxnjFXn>6OdN$bTvX)Rx( zM&L&MaU&9tX2iDBuIt=!H$=Mc_WS*!xxZe^=LG#YjH+@O2da|W?>!hNY|ZbQ#q4o? z_1o3e&Fu9_hJtX(mSOi+5juoEG@evzUCCdtF=|SsF9KEBFZMUx%+pmg8OEY7aT-Zt=L z@#*;)Y?Z%WKdtzBcSvPuTf8=8Fg(qT=Dp2*cm5hW@`3(Sks+43`*vguHq5s|-@SM7 zBwS#riprL^5F3L)Vme9tXrHQL&#Z)!Oz8^&p!BNpyRu|qQ`2DM4eTsNZr9_? z%UP>c!$ggMutv%Msa*$ax^=<5iA+7ij`Wtz@8-7m+LXZftM%-T`F7E-@C|T_fhCai!ws7dGE?a~Jjm*Tin)B3 z;INa4*it%+J|#|&yhAQJmf%QV!rtV0eS{-bULV>)ifdHmsX8kyJ?aBO{@b*7w@6V*yucvIw{DQ75|VIe02Sfdpd zxSQsG3NKq3YYmG8@c|9fZH_i;MyX76sM$8GMgU%o!Ge1Cd+{P54;-e29s zZa$5Rw&|tFBHUpz|n!#LJNjDS9p`2dEqszgjP@cstf=|4yj57=e>FWvq_^NR+6;V0>nCyF>;JQ4GcBn%fF4D73@laB>Yd|8anF*y#%i zr=~Czg}V_R^Y?v}JsLt8ZZ`_Q;pEJW;NLBk)qka@^9zlOtJl+@YOJYgyk9GBtn(GnDCg4P>0wTcbJd z=hBHZG$7#0DhA36R66(Hz)#>}a({;eH0aqDa5<^&?mLVQUuUzY=BMD{W?NF@6;z4A zWLz|>ZGOCx!9ZBV90secG8#z!&cE%`}V&+3u)~Cwv&9>b6qdnQF+GG&A3kJ)pwI1t!C##MW7vHOQ|* zrCZZM%jOk_Dk*bY@N~YcE~pp|&OAnn%}*%2G1=qs@v-k7Tczd@rYOR7#)0RXR{)IC znJ9FWy~c<&hNe+T+;u&Rmve1@3+ta?vDjw6;*nGhheBOGy_R!N1LppwDbbQ0*Ka|mBtC6cbp9juD9KaxGaOrXeVrl<>ZKJjn_h^-Dq!h z{8^Jaszt|6f8gpx=W~SEv}VQtZDXv1+(?R!l{T*s@Zfdv1ksb1mMlWrv>?@%9dz3t9tgAY|B$QiB;oek>8oa1R8iA7nN;C{IkDc)14NDzlEjj{Li7+oA#ZkrQI9 zjZerf#q}F0a2zK?JRmlVqtFqB6|>L82nO}^BxXQ-&XpCXwcp$V%>$P^-wiBsszYJ`90-IiSKh;x7*J-0+Fnz%RK_kaK6AK-nHdGavL z{rAK6=|?WmUys7RpJ%T(>sf4Oud&N@`6%$@Qxj+X8u}Z|E)U=SqkMxSDCWs_FblSUc;m3NAz?=%y`hn=jV(^C&Y6rsP6JtzZ9rnV z;kfZ5P5R^@E88GeJ?t(mC9O8GtSrGL>eg1AByw^@;t)<9cj++`tC~1j5(J_0viAmZ zn`BTc9$xT9dc)mWldHy2xMp8f{fz z_~oFRj!}yiJ_mr4c1Q>@vhX?EPUt&Ec77oI&|R3?Z$u79*;|VRBAGvtyTJyRgC){K ztOy>`Sh9IIZ_Zub1Ui%gg{#}FRvP~v}0ZekXVyot74{2dFMfHCs7lo$;$#?J3+q6 zWKLd~=xyxURV*Bpy7W;eMQVgSW8X)1@DaY+V3*hh>FGh0TUib=nQKU;XFhYSf73HL zNTXUP>MP_0LtHuLHEiVEGS^yITG7;<9+nXDJ9E6z-bmUo-0T|!ZtxaOVN;h~Oc~7U z!U_pCE8s4{C~g9XW+KRr1$&c9l%8msBf#hT1Ic~&_xEsM(x4Ie$G*DHU%r#Fr)lQP zU3(`(@9uT_I$O-<7A>|th2*S=k8DLP5vbBN`i&V3avvl$#qbqLd-7-ZNMfigYUen= zhrUPG#q2_sCr|Uk^Wo*g zj~_oiyzpzEs$Df%ef{*DpZvI5Jk7Vy$NVVp9BhG^w7a~X?3AyE?qb(~;O%Uf6kPGr z@BIlGwuu})J80!m2Qxc~lB}C7r=+3zVrxLs*(s#K}%-mI8E$;VFfO2fLn z+)i{=ChIjAt)t*!zPuoKtC)$ZFJ(KP+pehzmTaBbNc)Y#34Q9ju#tHm% zL{kg1lG4eJffx|Kp^S4;Hffej4yB87G66;r4CCg8BN(^Oi_%PpDJWRCbf0{z>uU@v zbH^>8lY`Vc3;=T)fdM5cjW{42fD@zRE=ZxlCVKZG<*>H#)M8&ld% zER-#sxFh~z>YJoYv`C1#wOB&tAhDN||3H-6cNj(GAvrd)%XBS^m# zaLT*~4w@xAwLl12%MuqSnD6Bt6W|v`;gK1%F=R;N-lQc+3uA6W(M;r*wdqT=BMt5& zb5RqWc=8i$Xn-D)(E}8oDOdE3m(X{!fzD==8)=SH03_xMyr;gd)nKA+4T2Cj2O$^m zB=L0mTR0m&M7Vj!)G8rV@z7x+Ya4VEv;_qmO5WcPx?yI63N&ko#p$t8NlK5(i#ZiM z`P?hfM;5`- zOO6&B%669X{fyN+w>VEvPaVJ2f`^f7V39gabE^NS%_WCnTjCffOc&n5)?3aeh(*YC zHg=TkZ>xN;nK6G-UH)(BzCS%o!^3n7DEr5^Z{I#cOZnp)NrDd?p?3SYGVD7)#(KS& zV|Y2A=URVQEEZy(9KJ%P^L$)vkH_k8teX7)`S(xH$Eqb^aJS1#OUtV-?}>6rk6jng zcFXF&8#-7F7NVRl-7-yXU;>X@ycd0sLch6P^-ZP!bMK(S}Nb#YH_R z_%TI3fx2;B|K?Is5O8izhhR~SLlh~=*o*=~$xXoXsz3H}DV3&P0l>Jw)S5-%AtDz} zKi<|(KoMu=DB)fyR-ue8Y3E6u@TNC-L2fTc`*3u*wOtve7(e7-oB zJ40Hoz-h|SORr^+7^*C_M7WIwQCosBa&nMb8?;?P7IEPmAmTXI~gShyxkp!qOPw-%NJo4Zr?p|xyoY05_9qeSO@i@CR?T3M* zt6)->N=L!K@HQaTL+Ht3O41YHc97NwQrgfGJaA6t%nSZDMNfo8(`NA{~1XVLHj-RCW@@pIsnh$evqu74NL@kc4>W| zn*qFwVWxNmVl0zUQQHv3^O_t>%T1@=M1UV|RGwm1>>Ed3wUEtCV3mulz&KzJ&JcPp z>l$rjaYkV&Ro!jxk#W{ULDnqbpkSd8-&c}cE|>pz_WAs7wOza}%(q)8H3KS-#6niv zt}$F>OIIo-6chJet=OsWau;v7Ny%i`mb8T2`p)*S^vivBCmeqF{2!`IVBgOV57Vp1 z!{NivMufkfAGZ$=4RssMemLG2?7O>OKhg69l7BSo&z}yUpd6oBz7HQ>p1;22mY$zq zSFhXW?ck6ezuU(SD}O@i9{2gIc8m{fL8W6_p?T94S*7h7HI`&rjHWh4B;q(tB%?`I z--@i!#IQ^`1KSUYG_0VQG$aniEyERFh8)}3mx{P14D>|%7BSiAYe9{9?X{&AT7upf ztIQyThR{9t#NL^IQj~F$5dq*UG@O8Yq9Ynyh9HVsv9a)G;*3kqZteuc)Ie}G;9ed- zfKG(mdTIqvJ^_lLsZVr`w9%!DMds=n!3>6+959tp?=9&%sm5+H8e7k4b4=mYz&V{< zr7cSi&2}n8Yix5y<75w%+n|E;`x)KX4kDnS!126rH6bHi1aitrZ4=>XjfBf3oPs^c z_ZgV?Qgco^fjJ7#bl%^`_V<=htXU85X(!l9^{tHE$SU{jzxlMST2}9b&d8w1n~474o|sNAV?hVAGj04HO{-Q*M(;pn0aq7 z&}cC9AbIB<))<8E^fONiB|4cn)#4o{Q0H1=N=wI2K3i)J_jTT&Z7BU56lhq(){%!r zF{nw~vk_BpaHH~uqDBtAAI92-HFZTe8{^0d&L7*RI-pf%3}kb^0?Rw!AoJzp=kq^4 zFPn?m)w>vO?eF!rjGvuHL!x z-ZA;+Q&C<1`x4BPzkq#To&WLv`{DfO>iyTtu>$zQ2>I3OlepcVj#UNGrMM^C3itYo zJ}EC>FPZam{PtmW{BV9eJRP17KhDm6yi}LW+-bor30;HWoP8UUoCVPjdF9EHJQ1x^ zPGUxxc-~?XcwyD)CvFI7e3C~bsRj*(DCB1FuKMD>hkH)jq(Uha16&zv1=Ce3BADln zok|U_%G?`b(>|WU(X5;Ywk$Qp*&vJbbdI1+ltnp2(wK`_$j}|Rhl=Y0BC64BIJPvM zVC0TK#AIW8Z)i74;h3i|Q>}AiLmB0oI~2=WZU?Xu#Z=~j?qtcz`>9kGlv;mvO{ort zmQABxWAS9xrD9wd!Nd~A0k;q4=`1g;wu>Wcy&tWa1$@M2Xlw_=tHHh=RK!x8Q1zld zbY!4++i**CI7XBU}OK>fElkTS^=-u33ZKPH+3O*^v48{dkt&_+v zP*}ByTIM6!a1^=C%4@PShFq939H(fp&BwmC-4_kkOkRME0P8ngoe~8rj@q7(+wbcQ z&0*0v0KBdl3a6|!@h0=b4Jf)?j*WQ3`&D|mU& z&#qq=ca74_l!ddH&p|)Ahn4Jd`Tx%U_0P|bv)SwGJRTM= zXJ=Adq84MN;r8FiAK{5P< zEb8K*8jL^Wdv7=jNg1_BgXYgEjdZZU2VQFKRJ<)Z(i~Jvw2tf%f^I!$L~yfdqg>d_ ziqbr+Xylf}(bX)q%u`giOID@ifOHqc@0bNawQrhBiaNRcY>YJ16Md{L--P?UT8v(H zxJj0+UJfK`!IU(?02p6<5KG8HFw|aqj(pF*zv((sP8P=cM!@ClC;ok4>~1o{C}xV~ zI}ZCNJ*W~)S{_4owc=qboXbK0*d#LkS2B6RAd^8^Y0R{={kc;pK+E~kY0dNb;fKUR zGRUM5sCKZVVc;_iQN*gjPTm+Pa%km`3{I|05zdjCgp7uoSk*FSyceUysFLz_A6iRD z<_hA>BUXi85L=4L?EY9Zk~8xW&7Pe&9FEbC+*v?<3I7jU7TFt)Ein)}0dfneL1n9Lt(Ezwam~-QJ{AXY%GryrlbphlRTfH6B~TFrb>wgEt=GxL5b_84->15F z^+1!}n3v;`c2r#WdZkjPFPzr!t@Iekvhg)mjQK2rxiZN|b&&h(;3)zgxEZFH2L~#6 zY-uJfJTvkwllKYN*VlEAAv~$Cq^=b2ev0hLE}3uv&quZ2jK%nf;;T^!;G~v_nmW{q zogm8XlPe7T4OvoY(vJQVe^Tvf5wTbpecRFt$PcuUWz#IL-o1Z(UCf@g%~EM+P03p@ z<{(>f1dTyOK?}jA2;^6&!&{3+(||K}dv)ro)z?e3-rJ(qL~t-__wKHtmVNj2KZt|C zz7IFAkDouEpKV!;KS{QO5Vb0A9FEO!tX{r-`yfR8+spB3Dd@X7F2B7j7vEog5NcV? zAjVuA4%kgP3fT?p+=L~n1i4qh|Nv$w-GD-g8#VDQxA(e0WwM01iViDu; zj!{U!GU!)=bqAAIN!>+&sf|oI3}$~#_Mcr#ZUCx?${S3hOT-UG<#kUg0Fx}epgOw5 zS{x~$sL{z4gwNH}+XdPkLF=&aLw>KTjTuDpJ*?vMGW-S4kFd(tBbO4vm)vOJE}AHu zl;B1HCr}RCf(R$H#o{f++c}avN{M^TbByRh*yHkU$V)*?U(l~lr-1}`%nx)3$eaor zXng4?!FL7IglV{~4bXOK6_}7g?GY-u$JnI4-LMHl1y2g74ZhNNF?ZW{)ty1r7D1Em zjk_H{@x%X256EHI$~e%7ewuI6U8*zX4#u4Od9}50%gdD@lkFSGEi0-m$D-h?d}Yif zzt$8*CY)QV7J|t9pRn)Ao9ePUK7Rh!zdk?yadk7DwcC}+cB&?q?Y~}f|9uH;yL^18 zx~0N)4g^j9#ps?7i{}MZI#1Q}`Hv4ThY#n~`G@t7v+qC7o^$uzIObM*U?&|o-%-#h zT@ci6Qc6RK0nsg@2lQYnq%CFS6e~fiymBZxNoCl$M-j)_-m>78+O2vSWUAsyfUC%f zE)-WP^2!VG#mX%B#z;hvKZd9Fp_fAr#w?qYrF2r?Y>dQ2D_KnvdoKb_Nn13kU?^EM zC6ZHbq(n!gG9ZPsGbdO5$yZLH4TEt=PVz&p8mj8PF1Cgow$`LR;sBDaTKS04bT+T`{q;tEF6ys? z!dE@#x`^!6B@J6{Q^EDzbr`TBT2K#G6RuOT>WPoc0vjLPN>r!`2Fj~oJ5CZ)i|7TO z>pHz5T3Ll(GgCP)V;ksp;ARsy%Co|P1xHp)AaZlf?i;-JL~)d?&rG%xm9LU-uG`yd zreM8=^7j6q9WM3XLcKjR} z4d%L#YD1@++@5ZCr_hyzdn3;S$tS8KKxjsd{Z(J zn}$4*CW?UZ(}>cW12g+*^1P!4ioq^{7~gokux)qd>zYE@UmLzG_=V=LUaDg`Ym>(< zkOq8Yj;gik60JIxmEja;qh-VJnpif`0_HbFGK8RSHletf$_G#Axmx)#8r`*4R-XYH z1>_MI43-ZAl{!g)5glHW5og3-puJ{Y7q1uMvYxX_Fyd5(*>*FGCa9fd&s{5+*QnwI z89e{Q0|Tso|H{gJu-?0)Sf16}5+N7?QMj@&e5L0UyTKUDpAmZ+dcchM+F-DFYs5Y^ zuww3}K|Z5Efzfd*sL^~HDe?;%fN}Nn(%TRWY6B4vT8+?XmO!Uip7fj@MWHjq4Hbfe z3A0GZwH>ooC;MoBA+e1SL=fpNYY@e(zo{VJ47HrAv&^0D!7V^+VI+QQ)kjxw{ z5h_x8&?!}CwAjhKXyJ0z;h}hS9HfR(Ha2i(SX7~1b1CI}S zh-h%``%SGo2C-}&{A`|k&uDoz<^-6D@oY9Gtpv#gd$2*r z+E`y6z_|4^d8xU+%~jl~y~m;hTJGi}7C*Yn<|U8{O3j`L(~P2aa!-UtK55;C;-9cP z{Rxnx$Fn|6ELM&yW6uFqa@Bnp=~tF9{TJbB^UqR15bf=2;2P<{Fet3p>ixSNRIke2rRAK(eP@8v%~ z{C0J9)kE!`@7?3!>}6d&SKapbbhbF|y5sQ`koXzHjhDyStYoECpnd=KzOv~g$t;etCFj!g%@9?a+lm=w3(3F-LklVE z*l=S>3lwy=DOok8W_u{Ye8tzg6Fa;wm=P!J0qF_$dvBF!C@A zbl5{?d~JQAi~*!RQ?>M##v;>D>gqL`HD?z_$}?QY@NYmTPu(aHpP4u2g@pi7K(4>u zidc~*%s?S9f}jn~2FWBG4PkC4rnZ@g?43@C4Z{#AHRpuq&)rg8+#E@5_vz#oh>#z6q^ihA@Kya73v8Dx(T7;n29B$m(xL>` zM#7g9hE$?-0N`dTXyNq8?9wm*%E^ISFXfQc$dSn#^j2XII*?H6=B)#^A44=#8Yc6S zWP{mR&&>cDeab&^srRUXNV}*_gRr4Xb}rx7w}0MJ4A$3XcFmDHq^q~N2;Xi(OofX@ zmlk}>z)PBVOn#ZSw;Ocq8^ZR9 zI4Z4&E{DXzNP4d$&4mMHZZIh^q$fp~!P z_%S^ADR}mgI7d{jbP2mfQO4iNns>F_jp1c7(8oRZ`6DkE{O)Ml!{;6$Om%rLBQ}>u z*Lq(8Xg;tiFW3_=7TxmvY;jkuzE<;_d~;N)-s;tlA`2=t9x@rB*TPA5_{Q11+TN+! z%Xx6Mx)j&DbnqzJ`v4FnKi;Jjn=1v<=f1m%dxGox=A^o0+Rpa>%iZ_;_blEh?nCTW z&(EJeJ=0HR^?bRFPut_OK0e`NyPj)wId6`~3O2X7VsCTxUNA?et)4$UUsiaC%lx?JKI(rDT4phj~G}Bq2rBk651J4G5(GqOTZ^>JTyqQ)JBv?aS zo-F08r=7LUMo$TnntO-3{wd?qd_7bYsOY1=VA9wQFOqv~Y_$m{f;nP&H~HqAjIPW; zHPg3n34j@52ase{lO5RSho~dFQ#F@0{KG+rpb8ln4CIk=Tvk2tGTS!$5r)Z#7O^qeY2q)wjD6%>6#--=878X|TL9G(Ug3&Tbi~Ny>gp!lu8QWGO0eupN zBTlaUW687OPjV(21SBZ<8vKH&f=Fcwe3xX8rHcd-4kSL}QbIUFEZKFs9PoAk*QB9% zop8g}Du4~UbHQeyjn_6M<~0s41tH#0K}Jw*+?#VLmfAQ07ljY)RUOfYa7+rPJcwoT z&x1s`(Fs$?0f2g3iILuf+PHw)H=)x@P4{|#iZ;XgItK9wDPIDQJJEq*vk|<=N6Ovq zfY(G%UFT^pQr`kpQrI5DG6!kq5lKYG6HW;(!+h)IhW-nl8ADe$?k0YdIL?O23H@zB zv+={2|LqB&OZCa@OY||hI6UN=V;ZK2kiV%1gZpE zR(DUc3zg=rCFG#eN;z5hB?=lQhQ8evx2pZVD#OS^{g#h+E5?e@?p&w2T$mY3A%MS) zMTvbc6^(Ow`TRY1-`iZg;|}7ShzcGb@N`WltCmRiV16}E4=rEr%z}!+`-YS3Gm1Dm z?*`$OT|Plo)o$CNYj*_e0i2*^Y9h_Z^4bZlAhk6y1`D0EmN*sTJENXZ@)FIk!xF2| zya)M)ILk$)(@*r~+y|=Q`nvZvj0^(AOFo*nfxa5=@)vIv@w7rDW$~b)WCR#F0JzXM zl&?`*X{FGx=-e^s+7Se?R#I7zf5-%Iw6x_E6-F$VkM}}w6ibd zM<8}AE0Q|Et2GMz4)WoNWVreg8Km_`#sa*Z;R_8PCoA~%=KZTos)&0NILX!f$p#N* zENke84@FSJ02x+|wk10#$i5mURAhd-5Vo4ClJY@pL7NTI#!L!2=9?M1Js4WG4C$mL zBpXusZ=-zz?lMw3>A-bxtyi+7+2@K%;H`WU&F(G3I8r3Wq}ve|;SnXsAaa~W5qm^) z2K<1qo0`dCh!G=o1lx@X1t4TzM;Zpwc7w^kqoyI!M&+YY6P{59wlx@7aX6*S3maPZ zjSXG_QuE{OMuc+4?r2s=I*=%3XNcDkE1LSeSxsVH4Uf*&B1ghUEmDf&H-MstT-=>HA*~9h}fVNe@LDy7w+tYlrlxXQEg>2KsyD?H=-sA4= z8>G`|np5D;cDvt;OPK$4Nw<^SywjU?2gC8*Zu|8uY5p6M=08{4*{p-OpXGXw#Ik%x zc0}D#&b!%b%)fyp^xvgCl&AAz%Yh zMpoQoa<_p(M)L@mgTPdk9E@n(6dfre9xEM$xQ+;0qVG+xG9+@Cai_B1lj6{^NhN=W z-`T1~+ra2_l*etpgs%~;(^R20jJ-3fh*TIL>#U{mytc{yrnE&@c;!gyiFxix@h23YoBlV`Kj z@>VdNPA|82RFDHY$*&8JzcA&NlPwFN%D)n*qiia%#MRgk>TtWss7(-i{3zz0PjAZh z+M7KMLn?T_#b@FGR!)>rV7DlfwTcPLH|+K#%Xjk0MDi%-pr$?NYLZ`)NK~~9Spa?E z8r*O-9oZiRUJMfBpe7q1s@KL15Z};mVjB~6tfPob#aD}y-qh29f|e|~Gl+0BKq&{P zuAzNR1ZWibFt0dnLK_0~DF}Io=`xp0cw&;W2hajOURXcTFcZ&@Or2(M7FsJT5!3MS z06I#TJ~)ghv5SO-7U#%db;5Ou|DxR%WYr)U!A2(nVJE3KuNT-(DFqwqG5FfnX#)25 zsNK#uGQbnY{iz-5p2l9J;r70Tw|VZn@2ko}&;WQZmy7$u&ENiZ^X}b4SJH*IimL3$ zG$H)mbd^crQKU@?Zz{|Dxo%$c^jlh&=(DTpEd|Y7PzaM4*HC;HRA)$gFiLH9m(OQ^ z{rvIrd?|HKM@PaigA4a8G&@x8T(YV7iFk}S>mFtu9jo%katTL4%qwT}j%1kuviq z8*K|HP_C|3Xe-%H;k~j79S3LGfyMGA88!>MgYn{>X(K**f`73*6Y~V8&Avn#yNX<_`A#+V~j4 z!N7KB10p~u4%P$~$lz%?s_~>~C6?HO){yz_QMR)--5aPsv}6Ns=W&2}^f-cRILHkg z<*9It31JPIhiv)_x>!dFI?+KR8fF5oTGxuV4yrP|)q9#73`_zGoWb-U-?1E*iLWM* zxk}{6iBi-X+kT)Wnk;Gwbc?RzSRt5p?nd(<8)MmXScoQicZT*l^C~OUq};yBGF_Kt zzDQ;@Q4I1|qz{%?6QwG-q^5jUMv(@!I7>c`4w?8!4Z$ON^bPoyG555^>DY^Nhov@O zS3Si%19d+fY_v}4g9KZk&zXn{!(2+Kv9Myv?3Mn;fTeRAQd5r{BrM8%2W*ge=Oa&N zGE72GCZM#=DCQ3j`MBpQ9;Ub9!Puh!zrFJ1h@0h$9JQUfnAbE-%SE^5^+Anj*q{xd zk^C@DQcXrEdH+(?w{!$5=|@4WI@&ZW!kc<@P{prSh>mCNUayz)r@y_M_3wYXo-y}E z0QS#DuyBHn^SEf}dUAOz#F7fk5&a!@S8`5St#W-vkG)-eU1@5G8s2VAb>Hn9#!Oa6 zBILPkMk#J~MmF57J{=c7e;hv%s9~}0V(y~_p)?T%{2|7NT)F4dd3=Z=e>sHpD{D7; z?>WL45FNj&XiB9I6zp8brP2w#goL#@cl)Gs7;G8`Sgn+A&M&#sr@maq78bnVtX3zB zd^e~gP(COZRE0uvDCsO=yJ&3K$b#HegpsP(BFHmPZh2qMax6zHU)aB4~B zn(>r3fR~1J%3ULjLs3qtvW{L@Qb5+Xup9_NV)AR=!QHAADo-@aSoIs&t1~x&A!(6r zswCg3Vl(_WKM$-_s1fB9-Buoi42?lVLAnMIif1{`$2xzBX$DT$H3r#ufg{kHlNGIA zJM{IQ%_y$x4IpXmAn^H(Q88|zY!K6&jRpfc%_jv%62s3LuhaLV*$H#lNCzOjjGAc; zLyA3w9j=+5uP!Ass9tn0aBfhtrvP2T!N{$Bz$y&5|Dzyo7SKnAX$jH2$88c^F#i4e(fu zj;(ncsUrsoDDSNXm0~Peo>vGE$qBXv(&psr2cPF88?;-CrQ>}mS$ChqU%*YtvIl=yBr@u!4%HqSANZ-Tk!>Ude5ls5=KGs{6K zDWlQJg_|_Wx;zoXcg@|-k}WF;G^>VX)k5GajUe*}G&-MMvR=)I*F_!Ehc#AWtFlF=82bBgBtSNh^){g1)8#yUxYxQ$?EP`UypU9piIN@%X4 zCpps8;8L~|)@y-j5zP;Wy`LBAU0bww>Lu0K~oeUsiWQBqB|7 zi|lOP8s1Vf<$Qu2wqvlB`2oA4dQl2ZFpmypb1M9t`*^bo6gI;r0J<#`Z&_kE_|Z{| z4oV|zrqO)opCJ)5avHtC2{k{KLEcWFiyQMYQRj{l(2h2fg-8&_^jJ2>I2O0P0R(VG zt}}tvn-odf*kscL92Fz1nkky>L3-P80%}m8CA}pBk)4`|8zUafvVAB~ei9?lgT|Ru zrdBu_4YW8w4PVfN*GjvT^Z{Q)C5OS4aCotbI3xfm$tk#Obg0Io7pX^y)3lmOn_Ip@ zhS*@OC8MOv)sUXELdUqN;p8JazCq+4aZa1xXRfjjNYIJ-fWU15PPBFSc>6II^<3Ed z-=_neVq_3@o6ng!#=;-kO#-Lg)b*I#1?fX*$$^%t?IG^j%EBmcOPXq!22=yYN`P+^ zgrf3|s|92eNG|7VB<;*&GyB_3v%6b0o#EN^up()sGt=(I#5ye3ck+8Zu1df>3i>|s zJCRb1);-ta?kxsW{6d(=$`55{k67L9X&%c@bo@KHgJsf*zvY@ez|Lww0q^GMyz!%L z zr%sW*nN_CZEl&?@K}+!-$7B@jTAoqjZWH7v`txG7CKSbqo2H~zU_Z)Ks5$P04Knda z4(;1Pg8Wg*$6DVk7L)Q&a2Ja(Ol@iy$?F>`27j=Hr; z{Jp=vdc(aB2WTzHIf+S4S;>{LSEJl|1UsS%Qu7mOF*q=9xCI0|(!&lQI0=KTWQa7A zAZ?3s3T4?P3s)OR0*^}C0C*25-M2KW8ePE}N@Aq`!~{y#2|al?wsT4rj8Ix}C&v`U zY!bxaTI%FaTXVI`_dM}BdktK#u(ryhiY(;`i?+9HI2za@^Np%~CoZ!WM-xj?y&=6S zN?8kx8TxQU2>3AqnI7AcHl2#m2|cP9B&|@-*c&$s`Hq`hhjRno|A`8ITif_O)lw8~ z6sIE_aGT`jpRnGTcsgtgnp@ezj^2+e1@aUM*2U4uT!s zyDKZk^F7cH>#OBLmA|rQx6TIKepB^cS&uDitF5*6g=8XQT2$_RVV-nPghpCWS}?4H zt28nvIk(JzbX!2!@VP>j&)@nw>%xp(I9Y{VxL!WZnWK|`-*-qP-l6Z_M;bCno)cq3 zN8k+=UZ9fVVlG~%Wmc(cl&X8b=`ve$Jmp4NZBdP#+`XBDaw;0N^LZf^-d*vgr1o_LHj3F_QPdXYZeob%n94|mJ1{fsrW$B6(t?S2eLIpW zA_o+ZJjv`=l#7F7HS7)OcpPQhGZ2K$Zz8w3BgyI%T8(dma%A#qb(O`LHb?X%^XiE` zb&W_g>y74$;4nCO;EGh-PMO|XdQ5@zQZCj!jZ{vOaNoN+ae;{7sScA4Z-RlAo@%Mw zfydZOpG5K(4R?!U{$M^1SU9dxyom<_i;6Ty#`Z2B0iZ-=@fpTX72QS-Tbv;vmJ`Il z8!T_syN{3wfoE`gb9_OL?DVG9bi)8eZdwJL}U<$qe#{QhN2hQgJiL!{I#Bmo(W)h;N}I$KDYU8(XMEk zDWM4M`5f^nae!&#g|~s~-N+jD0Kp|LjakE>AqG@$fXitMo;P;_~)eS?9hK~2;MAC;_NzkS2TeHtgVJstYzSOAH zM_Rvf*;00xcut!hSb&vpN9ht6C&=uL;~?X6Gy~-DJ2pMof-uff^?L}t8%lz-rY;E) zs8JrMl%kq{0}J?u!kQ$1VSKt|O7kqxI}n>j92X|!gnsb1o*BS{QR!tHDB6Y;VRGmJ zca_fdx}gEYFjO8Bpbfxnm+y8u@c`j#;m4JW1d%%-M_5mUZiEf}Wx>Ix_HhE1)wJh$ zdy-$}Xw=DRK;?dT_;@o7YSonw8^Ub@N0HQV`TUZBsx`~9H<(kr31s(p2WI6hj!53k zA#t=^ah!SZ$g(xVg)`LL%~!LF^_SO0v${Vl+WGvKru4+7pI<3kxU%Zqu_~*O%i~qO z^!84Hm9l`fUuc+6)W85Wb{;p}Q{RVRLFq`GN98thIv?Ry8 z1<4x*g}HaGw%x-lcig$_?(iqK`Z$jlv&9pN_iWw>E5YRz3SCI0r8YyjliQR!bK%~OesxmglsFyM zJJb|`r52{+NjN!$^B9#@K3VdZ8pjl^jyWkaYf-p@WdsKb#arh}ki7_dt~PXjYU16+~8naK=TgKacn>tHyz8%<*+ z=1DEvE|kQP$Sq^w%_uR+0-o+E#yg_>2DUGHemY<9_7`ZaqMs&czddEE8`EO}L26rZ z**OZGw8m*tS~N#@BPh)gPANzXLdlMR1O_PkmPMXf% zwSw>E_adbN17|iOnkfB?jsJ}rK*{u4&t$}>g}Mpp#C!NtI6Ads}d`!HuNPfBJ!T0P+t z<1cz{7jp@(rw{#2$W?qGZEGN83CLuU@~^>Udt}7QUC=bQi2KM(lUcAMmWN=9pN!1; znoMjWw%Mp|ON(sle!d(kM5`Z|)IBuaygT`q9897!2U4N{VPV!($g9e3tIoU!q0>>% zUFMgk{=Kp^;%;xYuwS27D;dq=D`t8k_=JYBEZqWK@|SX9j${hvkGW}bx)xt1@f-Fi zhi%8goxl6x^?{z>2+SGcY|a4U*-XjtL)S+1-njf4)a?dD+<}4Y26u-t95f0=Ds(7s z>C@UXQaC=!@FSYxE9d*(m+Z7~GN_iBek$5RJwu6rjCQeehZ_Uu&C#?thJ~Q1A6>Da zj08<6Pj}4U9SuQAZ@-xjhMI9NuqRp`mAyhbZNNGLaspCy6#(aITVVj$wn5aJ(5v@} zBRxtWYOtj&$WF?5>XFz}!POm5m?WC{$wrlALB$`RHn&&M-8V3~t7Yk{q zKDkahX*uY(3M=T|;DgaOg!jmTgD!|F>AqCZZ3M+#ZX#h22IZZj1|w zq)O}|gtWBzD{~$Z!u6o5km8mPO>L6;2;#A_uFBsJAG6weRZ65=1hoTTGbE>V5% zgu!Z}R}R&K%qIv=wY7kqbn?y;9s0lcu5Va3>!*k;R9NjEY9>YP^>afbRtJVrV@z+d_UYL{rmzAa47I zY5$N*!vpDr8jtYO!vJDrgrIz47S@u5-??PM;c%F8$%)5>pU;mrg~l=;$FueNtp>Csm(Gz7T>BfXIv-?rug{gcx_BnZO?_Vxr2v`)QW{$fX`q z$=D6McIXP-ggkH1!uB0fkmIV;&=LnA<96+W_0V-y;( z*3q04ln~A?REfuOM3hKej+0Ts3?^(d%vI2dx*R$VQoceuH{3O)WmX|#vqs~%-iQC6 zsdHJ8BgwXQVA#m~k4QU?dw>SsDJqRZJyLl>6L2E&!9gUYQ4LEIJ%>R3^1rQbZ3|VY zTPZ0c`Zet`Aj{r=*&)@kb}7yIKSwAvh{qH~#3|?n`wI-h zrlF^5yi_=#+keaqj)941pwxrmYGX~WN5s>FJ28SJ5r#Cvyv(A(hTnoDqQU`%Ip`zw zUH&HMWXb)weaQJka>j++04{P;0(6<31v=NLcx3?Ns*RH1;HZ;=9U?*(&Gz&`nMK%T2H3 z*^xLZH{sy7@;YgDK8vI(Ghm1BZF*hp8z>p8@-m8-i4vY%}{!`p_E!;vhrTna^O zvS0QTwvclf8OkbwduXhk&kLQ|=76ynVDWM}B2$sRg3~xOWYW5~s1=%oy;nS7X)qw?qz;?Z39Tx^ip?JaU2hnBoJ*neie^G+Ew}6yOqXMrn<0 zf~-}hLD0%%L8qwT9OeU88a#jbypS?YsDZFj?Gqbri7RD==DE8 z#1A~#2ljq{P_-WhB=<+&aEv3Jwqr5;d&n#muA{{GDCU-H@{M?+)A{WsiaVf+VlV}v zoMOtkSe3J!MIR|w!QR&uwuydP#rwYW>Mdq?ukrfd)Ad&SFNt=}{g#xy*!c=>@_haH zuIVDKW9Re^qEhE`KZjZhl*|!v?$K8dzM2EkqaQcMCu}^FZCDDzadS}*sT>j6;nM21 zJHCb`_&@XIDY8@a;B}bD)*7BFzMg9)4_B&S*x0nW>f$u$GB3&ugc{>WcQRgp27+VH ztc*6An*z#63r|B>Stu+m;In$nY{vel4_LiuJkPMoip)4xRyT!3wYI2I$^_(8EQDUw zY6bVsamv-|9CqvxyB0Pjg0Q_lZM+8LMR8(Z70#e>Qs}-dc5-gH@XubK(bN4IL##tj*4^ zDi0O+!0@1@k+S`Z!H46pldbXkzJfs9*~&`)TkN#x(C36~OwT5a++ov`w{Or7H+vYR zSmdQT636UlBNkGxDzwCXLNdIE+Rwx$0C|)twSaXaOO%TQN|@f`RZ<`7kS=Y`r{;iF z_DZ~#?OYw`6kf9ywztwZxiZPiyWVLQ21p~N+Kuj~9N5JlcD>B$5$mmK@I=T5cz;oZ zZ(o_xR^xnPB!w@{^v5$SD7M67aM38oW+wB6Ps! zZRBomX>!wIjYodC8l_?nVsEQslZEMk^sW2Bc~mi1`Ch(|)qMs9IX@gusH~nao=KZm zb^{^tFC$ubfZXp=zR!_4ywvyQ45$0ki$;$xuJz8qMB?M_`;!3{CY;NNK2{%oUT)7f z?5|Y3#UYXM=XrU%1GU_5{S_$Qkivzlh>%ibb26XjrOxly-#&U^x!`Eh&)zb>rFSu> z6kpk^M1R8hZF8vvIH3*jAU$k8*w+Vfxo%4x=m`le%}PsnxfLMACQl}Bw~)aEu0#$=@M|}+@9@&!{QXMcbt4%B|`5@ z+1ZKqvN?>X6mXP!n3xLB(XR;bR|)GPe!~;+1JQ}w??btby3W~h5L#-cr@)&Ofxqq( zY?_zzL*0|S$=7aFVc($;ZeS;B9=4jt7+*k^CdAbi;l>K(3QIAeI|r%iJKN7Usr!C9HLuE#8fui)R7@Q+qJ&JCqd6 zY7#o;smx^^%7iToHK}m7q4?|+^azz-TN*y^ic>nA(b+GL)Bk-$w)4Z*u1MM)A#d8>h+{bY=j}fjn;?LH zBrrrFUq%#h{{aV83Q{>ep2^R{W8U7dvpW5Bq`khL??aoTe_1dP1UnH|(8J2=e^9%< zFaup~3zN-z@40*N?p3_^-YWF{ufJVC{{HmBIVZ+-pkLkEs>_kPPL3>d2TD0KKpp4dgjqJ-oDol=b zP*l{CBFi?5Yo$!4gP9yn>w;qBksemPNc&1_tUH7EJURWr22{Sw457KLXaPh+lF1<0 zwBD>*;vVo^5=(24>Pf3^FfL1HLDX1>R(H3~#;K3&*U_!0J6KI@b9>9fpxvmXViz=F zYFl7~O*Z%U5norumk7I2^@ipR`c3aG#^6|gatszS&*osk63G|+Zn{7{VJNrRKCoE8 zk7@7sou5M~qUnyHex6dWR#~js-c+*)byh;!MiB2ajQOa(;h*JJ2^EcuBHc?FDO&ksYQL%7G6R zWozNM((<=Q^;X#qmnz}jY;cmD220+*tqvy2Es~8UuwCtSb*Is8CfjzCXQ4Z{1&W+O zj>?8x-Rihmo1A(8?VQpe?HF^y)P<}!g+ai%C@pZ;4X8NT2d8bGUngLXA`9)>W}g&v zn!Q+N<8HXj6nlh*e_vRUfmRez0ZsfLMrQ|;bE4pdH6Ye>+|W#6CsF=*b2S|i*u}V< zu5bDAZNg5-9qOOu&)fDVvo^_((iR@N!ow4tn&p$-KSVPu+lbLzzE|?HTo63rxWIfwn|XJ6x*-2z&eNuc9k)>W=?Zm!$4i# z8=-hHh3Ee4zh9Er!B_xI=L`u_fomcAF}hZxf$omc^c z!<^otI{*D*#}rF8;fM#L8>r;(PbUlLWf=R{-+%oS*+d+YUYikEJ{M+{XSoNeP^)^s z$=+nS2LoIZoi9}H-hE3UFORD4xh$#^%UPzdZ!!}+$>(INRBy+d1W|&1(s^JtAc!?T z=qO0Pw_dYsmbwM?tgJ&Z)2v!#%N-=#=(ntt91+?fxX*2PhPqL8X=f&8s|g|?Ok0we zQM5HD%^UKtJGQM0YZ&c2Wet4HU95<2)gIFpX#T@uHW=;F&$tBu!lzn-69Eq4VvBcc zVKG~s%DL6?LnPb^?ky2{@6JBvRVnZGh-txh5o5-wa_V9GvuZxc(Vl{MNd@($rVQ(u z=~dA>G~MSPo>)2=jm(4M7y!MtR;(65b*Y#OArB_2W>jKpF`mKh+%Db;7{ul?%D@@o z9~@dBcNxVn7$cq_TQ4KPa6AxdKRo&HypT=Cy7TADTT0+ zEwYt0l$;Y0K9>B|u4ujc+}9jyww9`1(jlb}>Dz9+z+}KNP?pM|UnQUEv{b4e(l<*P zs(M#WD9iSyLEwck%Q5xZzpwrHDKVn203Z4#3&^gn=%OHtBvNPJ107_SAZnOP0Nus@ znbizfT~F1vkOu$y$M~080xTPad>%OE$Ia09ol^9Q(TZ7GqyL^5J8RR2$}$8Yq76>M z!`v8*Y~5oE^_Sx+LtlCS*nf?*%hN+#De{QveP_uhMGq&A`20^+2}V>VgG&qfpSSZc zrNZ9iE|)=n{|;yOi*OUCIP?|b)6ZVKe;OvIdN1$?g`eE|11j8aW|!wcy=lQK4_N-Z zy6${%@rI~E-+k`odY;dkQohaSbKht7+HZu}^U2j{07$EQZ3>nB^K5ovS7Rd=R$?Mm zVE7P@IwqzJZ>o_zX&dkqX}?n*F3;XsX1WV&)SN25GSDR=&9zpu78MjDwy_`aAsy^M7>>=m z#S$R?&>8(Y08a5%VWp9Ws-cnJTm#OSJb6ft#>$=(=O@`6m21Bh2uAzpqU|1B$jNUe zZ8SDa(+K&DsxsSKll^=m8~HG~fYkF1`&nWdHrG!NbOE@$_`t@n&>}tsZN7Hd19Q

L%2a<6JeA-G`p$kqIuU{I7rl>cmcBm9ZeH&%dv|zw+W#;( z6JMcN>}A)~WPdJz1o6F@=3%4Qck_7Q9wsMQqMK^i4p-&YM|__MOrinK_X`YV)-{lI zOjmqddh^J|tr#>fK3fc00Cyga1H;z}j9Vl2BM%Q-YPg2&QzMwY!0cn^qsi>PzP`S$ zjz{I4^;Sf7*AwpDAaKP@6ZsV|fW6=bzLoxCIEkybCkAN!%nn+yA!Miaw}6JRvBNSS z30f&G{gByf-M{YZhh5oex+o_sHTq(8$O=h#j>tC-jOsg(wO)vukak!3^_M!WrlQ@F zf{Xvv`)*|uL8-ziIoEKVQ3eKn-w>kAWx?vosfANw%xe+UOoQ0ZtlEpiqXp5AStzW;`m#!cSO-zubFceSHuMDP*QL=uEA8PrU&K-9=6}0 z-Rk0EH3I^+MP7%|$uJ`v2^;pr3Nwq1oBU57 z-t1+9d;vCNdraUwV571Z>v6#B$A6Ig1S=`|Td6YMd&Wkj#*zR^9S$G17j5JIWZgON zXaF>hF_z?^W-ui37(@Wsyl80f>O<<9T4R1JtMTZ)&o0|P7AIT&rdabS><0>}H6fgl zGH;q@@X=$=mFz^u#K@+v-u2FyfXLiyNDvcDKDw!)al*#KR#>qLKs0yG8tN9aB2&Gq z%b)$DT5+?5f>I7$D%LWIGOnD{MyZ6wS*U@c)AfplBdW%O*`;+pP-fB_Od;XOkyuPx zeICYT%{Etpj2)oZ%iHA`{jV;8Re1)ElJAXVHdL;|*n99p`3b<@vJvxgByGQ~N!@Fw z@KTgpYZ)95xlrxs6RaKsG=o_YMkXLocE#Mn!D_;Eye!HjYb+_ErKo(fKNMi~xrm+8AY8?$ybetP33mgm2G z`s*je5|K%I4ZarMnyNUAmA;_VNRHU>tHrcxC^CN)Z*B0;aJ3hhg6~2X`%zm!ybA*N zVEyGN7E=xsp#-L4d;kZl6oirZmyzYm_3iRoQ{?elPcw2C{P5~|sN2gnQWi21zIF%q zy9sWuCS=Xwk;YF#|A3ca3K@s<4phTy3X0-{Si-vb8fm>|ewQ&t6-=({*eXKwG&Fsy zQ6#E2LipYX%5#Vu*oyQahoIhLeA+*haxE-}MwUwsL(w+nG*}49-h;`m8wF(89QQOrjra+mZvwpN08E@)qiJS$~B)lCVJs@bq zTOyK6v38lgb!k`$C+iVpi{infP>}nGk?((hKK~;f{(gF7!`}xLWqE&4Pn4|CTj!yI zHx=b{`VYph=6^e*L4V%7TAU)E=YB_m35@dBU%jr=bU&@vtC0~I4PKq=^LCow)!uKx zAFsE6RPVBW5Yf9AZ*+S)u!2q`u+-`3x7hmz*+fOd#;7itQK%o>KFEMM*jcLFINuE7 z$Yk`yk3jKKop71LJIOJc%}u3t(+idsKKJR7 zrIKR?SR4xxZ95K=B^;_$6LT;bM02P)bZyz`EMpdF3x@uoJ~%@VfwsXE(*!F{_QinB zYN>V_t(ZHjq&bTPBv#GHCOX+0iWQDX$&1+^#SO4@YtrP0R7#h6Ld6D{weG6kFis4A z8$J1Wm1T99${0PuxHSh^twkFu2WU1LL?-Z@qIdvxSm7v}a_IB1u1>>5orj~SAYC_1 zJ`<=4Pidu(8FuJ1;e)|(ar5UPE|6RyV(f^w)VKR;+cpd9^n^-SfpIz!iIgJ^0gW9t z{xA|FK!*NS&UHf5*-e16sXaRwl4>DL;mED_9EnM`LZ&bZ7ywQrqCnIKF-W4+0C@v4xkXE!pTlB4;o$M#ng?^268?L6m} zSx5gEm;OyDfFwfAienS^T*piH83Anz{hsez(Tcq8ux&*6JMjCKFT{$!%c^Z!f2JzW z0&QaCo1Zr*Tbsi?XTUmNZ(^M46WBwAz6d2Y`ygeX^;`2*xeU77FDcv0;m9WIA7K&E zrekuFXWJNC+TJzvIlYPgP^7z&iMRP8=P`OTP=1#)3DoTu<0JMkxl@nB4E%28=7VlB zn?ruLM&5nI*>BIMkBWC7U zHO<`4GOz0|E4G#xtaUzZ+`}^U7LPj*+m2$(n@TXHO__3e2rfbAMy-ojN32IThRx2q z9btlbxOSJw{sm13j*03G3zm*E+cD5%m9PpWv7O%AEDeW^>qJFrz+`Lw;aid(P4Dm% zt#-(&p4b>tX_5Yr+2AToA>b2{1+)a{$`y?i7d&?=D%REE%!)2t!%J#qZ1zC;kv0T5 z)n$vh+l1F<@?Z`IOe!uG)m#{@f+PXsO!x#5K?`Cd`Sqq-F6_PCd;jp)rT5ERVh_Y3s|vNf%ll)G2um&QTI$^u%UD=9IyT%+jihUL{yZLI3^2)e*oTlmkBnw* zYb@T@Y!gn20v+au)gZbZv76bd>8CzqQs=TPSOW*DOe%5hQz~i+qG}G?#Y4VLmy>0P zDf0MC#&Ar9uD2}%``8&#?{y!RtQxwcDTnOQ96!tGbx3v;qq{4(i#c9w=`v>h3S`xa zQCK!Ck!|i3)}8qtzCAV@=})dUpx4tmTel%p17PSP2gD}P4-P?F-nGHdZ814tO32kr zn}h;#UEhlNB2{Fyz}%WVYy_`Kv8#2z|4Zd9Y!W)N8&>L@{0g!DCRpvJ{-D`| z5lyiVCgC{Tl|^yXeGm59OY((JvgS$WN%`_Rz)~(Kvu_i%{er(>zn|vOnal{YROxk- z+3xQSyV|Yx%a}y!51wL1z{0~L(Ac=G0|8Z*G5cJctmcaQUdhyf)9t{uUQfjm1Tc{z z{`B(qOaH;YKK1%-z#GI{ZT0p0Rh_qfSbh9kn1@rntK)Y1zt2l5AHEAV`S0~QGK5{c zFXtM%Hv+>?;tfjby_UtyWdqnHr0NwX@9-%aXaf2XC+t**qd7;|);~no5`7Vfh-E7e zSk}y_VKV63GrM}XN5DfKrKTAy)>=bY?N&msP2_t3>7hzvlxiq3SPu^RwF=Q&Z0k1} zeq|f`$he`=sj7i0R%jLzDcY}0WFg=xw#6?aImy>`%s0I+hy|_MzvVHlwcJnl;Un?J zBf6Q0NJk(Sb(siQ3lYWe{ffhUZfW}ybAa;NtG6XO(SncO`=a`?+2F~ehgC?C1EB@? zUMOcwdcv2s4z?F4ZtJ$fCea zO7fa5vTj@G_Zu~J1@{%pq~Ovb5zc|X`Qa3~%T|X;#F_yjdiBw7V(RF5b1WBTku(wO z=2>vAMhHxP31$TR&cXEVYs~7yiBq;AdVMafP;E=Y0iGRU;y-V)(=Co&v0hDDkRfF& z&z*%}tJaBQjV{EOj#Qd|p?s>^o5r7?v&rbIbv9BWsZ&XK(XvIDIpg{4#G!?O9(vp9s@w%>=anq#B|%(Hx>D9g)0 zz|WNG|6pDMY<)iuuWw80f1b|uc{z>TG;u`2#3X`vMrNAa1K)q?=RLuc4pU&uiTEBZ z0H6Nqzx{OeF4rd^B43v4dR_dw5yzu-L3I~)x0vK)_^9)~Dvja#Ttm)HA1yV5^u7oM zO(0z6Wn1i>$2`&&f)5y_dMi`HS1_<}2Mb#@Sf){qM^=;VxJO839vAV$z-d`P)Di+i za*YFFaR4d}a&w}tO+s~Vx#5k160N#(Rm_UA1$DAzp%Y?Lq#4SXnYWh%a2#GN$& zHUz|(Of@JUG}q{5cCYdj!K&|7!sO6xmA9PaYDvjs&qDLQp?=>3;{L_Y?sd0U;5$m5yFE^* zxb+-S@rW$1&r5Hi@1mj@idoz#_j3Eb;CJ=%>C?-guAIZn%JFByy;a)3T!onk^nQj5 z2x!7k^Nl83*~as`oCt06tpct_{Q6tKCW~&+{*7>=-nONm4qM})x=Hm62?|F-?)frW z?+Q1hMs^6s)wzzvfW$MGS_|s4_4P2D4WD`3h zx(;v&&PcQ9+h=u6k)sLQv7pid_coNmF3#(lS1wYLE~M00l>viVIan!sGqNca$EO$u zF#rQlyW^*c4h8}L_Ei-;=aIe%C9-b{4pmUfH|c#T+Wcm{uI$N$=bAu83Xfb3w+nn3 z%`f#(Ln244R=R$8*QMAN%Fa+>(E>3r97G6#ak^(QBiXu#X_%F1Gm&yw4qE2(DsITd z4&Eu27?Ket@HHd?96dAm<@@>iy32cTVnP~t%$96Am7Or$KjDX5`{pozfE5W^Vxn$6 zCbV#e9Vg*V$~+9S{uRE7m+qo5r-^0rMUtx0_ozN`S`7-vNN#4ARV)|w9f~_X3}Q~} zoRGCPB>aq$XH8?bU7}y#!dtEvVx)0$C|7lZs|h;U0i}va6OB}IiWOFbY+bTR;7Po9 zW&>0LJKm6M47zM=c}}<+dJ`C4h8 zi0sU=CY?v}9Fk$Wm?Zls+XhHnUM;F`b}Rt}XgR_s%ZTEtxI25OrvA|^!D))vv&o8g zKKVvMGcL~%KHP43zkT4s97sfVh!vX*elIzI46k#ysZ6gs4s=gzIG&Wx|M#nUqqXFJ zy?W!TO(?wN&FXp_Ix|7p(VXjIb8W%1s`B+=D30^f6a-0-l@f!9W~FO^7#wcZ;Wc4# zQZFXHH94JJr4`P zsC%((es5<3ad#=8?FG zX#WmOU_fuT$i^84@*uZ*Z5exSHdPua+ws5>gUMn?)BgLU$RfJkqRZ5BeVZ1b!_m<4 zRj*Ua>tt@L^LP+ru@%95R#X-1X^dRs-I(|5Yv~_kFTsG-rMfETuV~Gh2*%E+H}jk) z#hMiDJyxQJ%6iNd99gSp{t5wMO>b#Uj&MyZw_+;g?UNYV%-pqEfzhw&3*zUsnICpJ zR=FU7pvw3U;ID5$skZ#Sp>dJ|pa#y3VD z+eTl?GzxfYh<-P5qlA{zKeGa5mtMnQ~)aD#!K0|^IEX)@EtGfXp@DNz-@}!{5V};dkb6bS1>mLk?X$Z9_X+r7j=$1F@t0FSeRU!v19)E=i zW+$^y?5@0JQa8@Hi=I@OW(~hDb+Ov`&-7Hy#AuVBnK5o~H(}ao>l6OnIjqG2jKA(t z!o!z`CABZ?2iAHsIJMe4Eei+KbeNBo^_SD+B|%Y9p9!8OQXQt7_9+KsLtvvZ zT``e|SWUI4+MmIg5np|xco$4ioD&Zv3#ew|NCTs3Y5;j8Z)nHH9pJTUm#{#q#H?^9 z)U8euwrEp3KJ7;)<@f+d1t6o%25EY$02E!5Ou*G>_r7{n!?xPBS!d$|`wt!A{8`=l zp}Rs375JE zhfmwvCR%PkFMYK+Og2gqz&C4~)l{Rp?eBEcm|jL!p#jkLr++!xtPdZu3E#5PDyiAn zZ5Eo^#q?OnM)?#3Zw8q6bM)T5+P;m1;$EPy*Jq0_hZo`927%`Yt(4=S4Nrn2zKO^E zmufrRdq5~gLw^4CQ)Pc)5ZPPrFTHp_egD@V&oVh#*X!;6CaC0ef1~SOg2ghw)%Ulh z47p`lJ+O4~c5)?D!CtNVPmwcT2|=??P~GbA4>anHBab15G}k~iY}NcALZiLy%gXK6 zLiWYluP58=$5$SC#FSwS|I9c64*;e>3~kHUh~AAloF8^}^u%g>sNQOYoE_8r=u~kv z!kw;Yif-07L5m4oEIZ;cnv3vxR#!;ct^2R_y^&!cEFiY*EUmb-3R5k0=t#zkl`K1NWBG z$#2Ek0cKdIh^F&~X)_?xRHM-2NKgTbIf_vt!~#zL<^*LcI$-A~Z|FRTEC~}yI1+euFpWH!)NHRwt?#|i=`zHKWzHUoYceD(*cq4* zXOp)C?%Tm!Rfg-4Rp}*7)`9OACf2Yk+->z0)A~A819dH9>=9kNBsd9lVj8!~#$=M@ z1Tp%iS2Pz9_sGU#b!WoUn8Q}$8IE`5!YE%S6e3kfbo8SUFQ1}#=lb4af`|SNnaV?n*k9pR!!aZc z3E|N~rS1JqdQ|Y1hh`JeOVEJnN=lwasAXvBW6Fi)Yr?yuIsN0oD5N<!oN-`S4lYpzRL5+c9=;HihfUz2l6`}4TP9{>tk~hmZjbu+gRvc7}9t>UX9!X` ztw-)RQr$7|zF@xUv!E<_enO0pZEd1?9%+?dva)bDcjig%;6RUheu*YG8;Wh-9tB*+ z4rHc`D_x#ux%QhFIY9$rQS1W?mLP4QvHpS?pE?8Yn;op0#>ck9`^j@}1*XOjH~sl%FR@S4`oEt)-hTv9 z(75+``6$i_r5kcq7;FGNsNqdc;MCf-IfP9iv)9kW-WwS0OIvSdAjNHQ;MVZ7OIU8O zt5QP@;cdc0T)Pul9CA8 z2Z#$NW(&)&kyK2lx!YMm6o~??;HxCs&@{!nhPFZS^A?YYLxJp=MVJH7AUUNu=H1V+--b=7io1PLh+@gO&? zp4|xk6NUNP%C17AyETVnjlJTg=0!}WrbUDSIS^{y4^g96X~|2uY;+~NW+hi$m{*}B z*i5Q&&-0$OQXR8)y_gA^p0Jx7c8JEER}~4{)d-Keh#@Fa=WNG=zB+%J6UJ_!MdUPR z=W0lHI|0#2$v*YZK3#0mC0zXNBBZ1D(uc;82X@WOsQWEoDMbHg^3u2nyn0sUsT}R{ ziAR$R)22CwO5&vmkIX3P3Fw1|lyUe0vQuy=KCsM;}dK?!y+q$ zTT4Hu7uQ@btVYP>FXYU(iubeTNVwmEdxLo@!WmvpFJG3@(Ky5uP}`ql*+; z**P^cQC+w6fz*3WlM_^NdDOMYb)CZMM%vNMeedR22#XS822zkBsC{R0pw&i^HLN&V z@Q8R@(aR{&ayudkIA)nB+IjvGOAABR{gwHmM&s7he$wO7~n~}^< zZiOa^Hrx7*GOs7K#kZ!K2*sseX?x^_Z`e`kU^(PXjdNSG&96T6=B=rn*AlQ!1SrhA z>>wBIg4bO$u;E@PEV`~pgURUo@*bgbs{ehGB zwc#EUOQb$8KmYz|HRkztyIy~P`kjg8h|amI%YF;XD|DchbcRI(%SGp+T(K4W@ADNC zs*M?CarAqWwS3j#tL^XV8FqrO}f>Dw2cz35%_}Y z4Ap`RDO6yyj5Rr`y|3*8K)kONIwIRZ_2VSGX$Lpk*$RO*0(B0NQtz7Ch${FGv@J%( zZHm>fzth+J4_8Vl{k+$42%b7r6#bMI`Hj4~?whlUy+ zW+ejotztqd7lmjihG}FNC?YNG3*#zuUQYvNtzX~1^{!t1@2&{oy&(5ghFKd~v20)A z1?Vkprg|1oiw6Bqq`95#`%^4Fg!F zI@k?30gXM0rY;xuO0&H<4~-d+Enyxe;x|SPb4C=!?jmthso6f72iPFz@a2WIUvx^Q z-e(_bRTNf?U!&H>i*M6IvYW-a_lM8--R34sw9n{vz_L$D<2il$J7UgWBH>Jrd^4u< z*QXbh_UBQwqZPm3uOH=Xatgpjrh>Pp?@zz~e!a#}R8OHW`t$O3ew+JCgQSqnAWy+F z{@p6x7*j2aTJ3FqV@`2an}9Z+80?(S^OB2vPKaH&4)O^e_0`?B?<@1b5nkb@y-p9% z8_xD1W&H{-_6+o~Lwp#dKH@Uhh~kl36}Q~rR~fnV+>l$#ih%o^QrO4xVpxQ1L7TSj z-T~;26$BrNTw>Fbdn2^sV-mwkE(*o8?B=r$!2`1VG@QA~Z)_+!HfPreEwqqQeM#o3 zr&z3d0pa0_8#4fEsfFVl7V)NvPXh$X7(yi~p z|L2d8$>S{;xcB+XRe^VptoPQ!ngB-EPy%I2DRR}#Qb>E*39Hd{)+5woA5B8v_$gGda!U zv#3u784(0hbjnsUpw*wRVL~tgQmoRlOeo3t2wQ|QuHlFnoj5^YB|Nf#yx`WTMRZ0S zF=L{}Gcbd(s_h{RqIn=N5pKqmb57owmVev@R=DGNBDyDDEs-D0fV!Xi4`LKawWfQD z6D~)Ge%ki*Fd6Q9F`b^Tds)9tUd38?G8}H^FTS*PbBw%)1#fCTNhOWc@3mKFZ94Y& z>#9MoSVxxhN+K*DTbYxqY_G`aWgtc=FBo;sCskn;=TEIzx?5Y+1BN zC^H%a44vn>DKrC}t{Qjn>HSsj{m|V+e5&B7zWX)p-)rr5Of7uPCXFUFw>JG$XCsl@ zz)l>@L~2gjE8ofLqu*@)2aV4zC$!(x=4iNs@ppbPa&nH=`Vqu)KELz0Pd^2rpTcT( zHtV~W>gyK;5}yp3D4+87MRf1)*W39Vw&6IKD2InQ9Yfvc-iU7xSHa@q{YBayJWaOq z8FKPw%!GO_N{~&gxAg8p9r44Vjjwj2>KBv9{BwHHy;Vnyn~;zGb?0Y z8-Rlamd7z9rv)m6Zd1DI5nWU*o*JVEFEqW~)*MI*$fRpnQ1^leu zoBXL7j;_32Iu#EX8l(!$LJwO&R&zUMg%UJxRZKo}K$hm)#UTpO;?ne~`5S3;=wp@L zJRurvEyR|3r?vtJb(W)-=^3DHVCeQmm0mujYb1*;gE(*d`02GuH5=F_V!clVCP@;o5zRF*o&7pk*xV zy$F5FyYq6LeoVqDa*2!Qd@6!JpQqfStU5W)3Qw187nrrZxu3CDGg? zKGIGN)hS3))>XZ6lc)@Axm+$aFI7_x?cc=1mN1G!Adc(?`)u8XyG*MNqQo{61w88~ zsI=_MS!kT0BCf-ML*2?qU$&0faa!8E=|{6r@+61FcEt8qyE_y*TK_BR;fp9oxS}XW eR=nZ=FTeoM#=s~a2(do^00002sQ{JDj*`#lok+aQl$5ebdcT&O#!0_hK}?Sg7n^dlYmH- z5<>4Sp%c2?9X;nO_x|t0eY_7@$uHU2bM3v?8gtAs<_9GOX{w7iFM>cIDw!7&Dj?7W z7zjl6;7@Yk8_)b#5a8{Gi=>u|s=c|3yRnlQNX*p!mDz0>TVo3|6*FT~PsdI(Vc;MB zO7d!w!x7I?<>G&KA@O*;Y1#78;Ue&N;y!V$z$RPiQd3itvZB&hoVtC-=|+Fj;_)$s z{ueA3D;w1n4g!rI9zKrkn=KDGJ8O)b|5@syk~6yL=31!(0v#T9RviC)$o?=PHSYWO z@A4kSEyqVS_U_%0Ht)Jmtuh8G5k?@8^UKsBt>B9JxgW|_p^-nfP8MsAh!e#t$7aZ{ za%!(%YbbyMJ9>Qoh_+FA)3St{n;*>f=pJ27pFjRSzn}wB=T9BHi^$3SKAoYg)=oJ7 z+%w|J#d*BZd^(#mjNe{QTM3+2P^ghkidd5a_XijD(n)2M(VUDt;4F(@tTmjrYHP z?tzT|)vLK5$j(P=sp#6aU6*;RuDFZEsgAXeaXJ?gEg{m2hK(CSrIepA^Jjm%h{!KdI-5*#Xpe86V7?GAo5f~V-r1kRa2fcT&@7rHMpgxIj zi~U@IyH;|q;h){9L7>#^aRC*^7b(QH3h5j6=Rv8XQOFYTz?XW$7Te@S(6iFRT~_#Q zAJRGfVZTQZo{V(T{}`VgkIjkN6l*OW^FXtNZgtIX`kn*z*dx~$Tx$s44O&!L2c;i{ zC;aZe;=0V=1x1R|6fa0C_Ny$FN-yoC1z^tH+n*exnRofe%?R`QKd(({gPODnTeF8( zC+r^i*%V&i5JbWZl-{j8WQLq9FuWUy7{xj%Xu6QELe__GGOi&*>n~#P zKObPWTdk{C&Z?QMFFoC!02e!oDC88bP( z`=G<+iMFBnxpkU^LtcJWu^z z-<3ZZ=%Zp9)qiHTZFob^K28mW6;NWT-E)M9%Z21}&>Ii5^WOG%i5q4dzsx1}C5(de z2!8+zh#K7sJg}81ogNq19F0<~XmG56iq_+WlpL5&9)-eP+)G#Z>A+SRESVt#3r&>g zOhyh3bbP8@jif&r;Ow|gq|uUw9awqJWb@rdwS*D9#>2I%Mp0{wam8z%4F|IVvG2Rq za?T&AQ0Y>)knCi zQI$+NmPdoopP~-a$RU1CzjMdjozIa`Gi2LfUm-L*pYbez>01trKh8jyaXO)Oi&&MJ z9-t}8fy9#TR&o&BG|%)0oS`oMJqKqK)UOm=|AVcfkzl`o53o;0vYB1m6?o%SrTa2M zX#=Khj9;0uh7eqEz#LqE&4J&?KzJ(kAglKVEfX5sq}p?)$zXk8;(VAwq&ARsP={w7 zy^y)@CnmV?PqtySl)jBXE6*3~H24Z$1g;kCKyOl#aVC91#R_DNTZ_bBZFO%LYG>zV0ZmtNnn( zeg;bWZUB3LpqYLpoU#Oy0<-8Iv*#>?-VfLntz3Gp6fMJtS`R#0;K8l*-)&qdbG=3z zxn*H$<8@F9Ox369%kR0)Btww0KaUbuyrIY2el5idZ&KcQ#5pZy3}*X=G| z+c(MVdh8&O10UY;VbYy1OJ-ywfQ2V|xx3zr>|8pix&8|idm=bHKu`j!TI1N+oOBe?As(vkm%&Lw{vTjcoG z`sZ(>aGwq9cOr?;-@8{k#Hd$Alv|S?MpOx1$AQx!E@Ja#%!{oRz|Kz)$`3mhxO?do8BL@Cit0B z=mVcaWR@8+xwbY&DqaVERZ4E$AjxLdrv>{x*xzdRqq|}hOvU(eN*YH^>BlmaO9yC+ zHySYZU}J8DrNHY{ZstJ_E0Qandlp_>apzNEcrN#rFwCn{--7!gK1Hw$W;RutJCQuW z&+C4^%L&iuPwG~ZoIMph@p^j>?I8N1K`V-TBDT`G1N|10_}%GwJ=G6`t<+EKJ!SPW z;hyP`=j?3V8FOoo5iyu(YTblw9p86T_V?~oPMQid<;|7l!a}GGF$EQfel86wf7p|6 z-nzaA%5aY*<}on=ITny^$yG>v=I$RvRZf&CggG$^?XRtM3;QM77quJ#wSLp>?zuv- z_2@ny+Zn`&!)r2sj)wACEp{$rU@rIQw88rMR`X0aF7x0_k1pnll%c^shrpcJl^~Z( zOJ-KzR_$H|T_wJCqpmLVG$15U$L`jc8Vgx|rM0h(iA>UtmBGj(oVoX$Bm^gWJG%X4 zj<>8FT{&Rn6G(aR$x2bLpu*TNRLDuLo@>{%`JB&Xzwb(=fs3L?}ZotSk#p4O?NsF4QG$5#mpbQe5v}HHB>E2yNzZ$> z>l0%K8eIqFw#z`znEKN<ez*UW?EcOF!LEAu^)jMj2B`ZpTZ^D-pUz6m#2a3s64QiA%`-@4P=i#WM*$`XZ zz3gWKQXkWLpnEo>P;WJ4m!LxJFtnXFApjvX9+3XT+xM~-BbOXh8rzER%{>aBl*oZC zjzV*l)uX~-YB#cQ&-wD)8f=jRulD>vHkXN@>6@eCzDCG**BCW|r8PE`@oF{@RF<@2 zG%S&fT|;HxaD0DcAxzMg3ZJX6OHp8yS0(rwnN*)zz#W0GLE>|Aquw6w2yu|9jkksBjlhTU-=SdNxS*Q)emJ0nfzME zk>uED#nA!;ry+caQ_^l`Sgo)(viN;0G>9=pC;uFPJd~A^}t_qfpt(qy~ z^ul-jD`&!11(pj{vu|HAT)z zcYk?~knX+~-{*WUu;bF_Olec6Q_q#}4T^n-XLVe0w5|JPund;xE5 zC*4^O^Rj1X7&H+!5QFSRJ#_*T?9O_jE-iJk zcWqxER63R1zVOq!d!)O*A+kd0OJz?zrDBZrpreingl|HYmO=I=%pHvK8XPCIM$3Xg zq2-tlUop>ZD}#daW3T}h-pOjsZ2<$=OL_+je5?GiuOWI%7eNjyME;+$_f#_=@M&-3 zX*YHiK8Bve@kmoUb4hcT^%lk9tT_Pd{cY@#bA=K7v=`4e`00c@8=j}5u5d___?3UK z-}7rf4M{I|aW-Chc;b3%yXq~msZg8@q+^bpJ9he>KL&0ij2(Q)Vz-2xaC3mBgK^@A z0scY-8L;^z#Yd11AOp;WJY&!t2J)3d5aD-rdb9fm2IQ^3^Ukk&f(Ys^m%af4-RxK) zyxGqQeMTSy0k1yi^Z#2tU<4sej5Ll^p97UmLSLj*RDcVLDM6N@urLvVE##yD3`*rA zK07L_hHZ|$1^EyEN|dRmq{;>FSWQ^!oF9^dCp|j`vX`F0k%XP(%J7Z-wc4QL=DDBT zUtZ*Nlo>@l?SjJGG0Vfto8?W=TOVD7go<7AV2K4LP~IaWCO^gz7sk|=iOtm9z zo9}s_bWXn|=sV`1p#Kl@cC#XGbDGCcEf;Z$|6$wg78oI;q;yj|YS2 z`lN_Pj*r`S+X`%v(al-t@cWra9;0s^tM8K@?)#}KJFy}{e7Dv+5i+jw>tV2vSA{C! zCdO|We_VFUCopB5Pk4n4<(`UR^c{p2%nECtxLZeRimgy6Gu@C!ETIE#_R%~(G%!rA zNO$`P4((>r*6Nb67&ar}K0lir8PD@$osU7~Z+yHh$t>C7f9x@%3$6%=%b?o6lwPaE zP^{2shsrK7Hv)4BpudN3?x4Xc)`vh9a^{=>%ow<8&%v-IP)cV!G76=1cQ1!!>14bc zJA5Us8NyzZA?&wPZ8GR@HbY8Y{N&uOXG^*i`oc$tgr&+!^a&wJbAQ<|5~t8JDI3P8 zhCuhna^erIxSI1VIp|{gKAe9BABN7=!rXmiZwf)Yqc33R+IF`VGe$ID(se=i1Wb2B zmF(_AScV*{TWh=RSg_aVjdwrOlI9{(A~F_`fDCR=0-Mm%JXOsLrnQk>!#%8K@u;=HU?V zHgjpJK02B!rhUV`8l0Psfn9(n#ESGB^yV_VcBa2Yiy(ISJ+>WG7-EI2$6FIja~%RD z?M{s(vE>zDnYV=InpF5}pYjMD$EDuo^Sh3Sn|*c-DAGiHl3bkV)8x zO&g^k5Rd~h6m`eQ8>uM%4RMcP|AII`XW=9M!q6rtNtpp4o%ru@`XUwuuym^VU1Ae_ zNGcWh33x37(D~oT0mw-93m@OGcLOo)f5+6U{sUCj4nQmsfY>6)@A$TMkdvBgzvDMS zEk%D7AbNJko`HY0PNmxd*Y)VB&z;J2m$i`Ny@{67>4kc}m7=1Q{njXjWENaxDF3%Z ze82NZ_ko91h-SzRp(mjDTa}klQKcu*L1wi2Dr{&?F?5!kqKU5*6a4M-qqBvST0sC* zT|47pM^~<$>87k+@9{q?yTe}(0J18B8PAjv{2&h@YxtAddK9&^UVskI9ER>*dvdg0 z0)Kf4`9iTk^oPwZCD(Lp^7(bjh-^aq6NQqbx@C>)Ud zc8@{1CM(q>qlIWkKR1uAOrhXftsIbZtNkykBRbRq67w@xV1+`ax7JmMcJr2`^$lzEOKVOY*fF=g7af|X z&DH$zOFv_b1C&t#RPYg&H+I4K`B8=@YTQvhn1uG9n9R;INYeApcwR)E4$6rrhSnv9 zSMIZYFkNy>w}!A6%Kr#v9b$~R9W-ycy6_?i#=n$|TlqSBap>(QNK4_Ov&hAbO`@~5 zmaIf3WB9~;Fo(lLtaQg_^XO(das$3m_Aj*N+3`JyDLDo`em2|Au}oP+M?ed|}uzyHH$ zw_pRGZD!FiUpXm|q2oX0xKZa7N&m?E30W1C_@_>#6k-f^okMxs;bOjC)zshlz=DoV z)!hExYxpv&%GNqJe~22Vl9y{zL@lr6m!DrvhoBD%wZIw@+Qig@2&W(F7DyFu1&tqa zVVWl}9mni{ZRm~?sgONWXx19UsN(jba(*ds)@2kw;8;V9O z;Z+Bm-1hbHl(+ymG+> z_*HS_wh(ktQj_LF5D1h{sMeWzgw&V4ZKAV#lcC`w4!9b}c0U6KWviRnxYpo1`T!UU z*sEddl1^Nk3R{MiOA$$$1Hr6a&_rF0$GXI@B%0QJ{O-VtA)|}@gS_Nmx8=m?PaMaN z2OX=R#)85-^flDGAp_;^k2nB|Ai3k?tLzJ zpW#;-Yd33nRwF%owK;MiouG@t>Jnc50n#If52mC=NWQoQlQWp=N$HnGcLMythh{&Q zW?zS3EEzttp!~kWdSW?e#v%H7Ij%L0kVcLT&ax(4&MSl^%CZNc8S{2aY>+yATm7v9 zKmKGcD*bdZ!-4qjoRlTAFzm zxi2-_G2@l1X`IJMv&}GAlzVgP(pUj@2WNh)F?$H_yD(7KtsiCn;pUxs2pr@PYK@GD zAC@`fVRg&?gDu2|bMad{z_Q&ZdgaoldldC_wn+ax$`_{tYk1>)W69B)(aoe9F2%Cn1&uhLCHbOW zv`H~d!^YMl%=wYcjWL~8qFP`)tSYK2E9bkJyt!xMA3$wagJpj4)TPJT1)p=~HVMx@ zy1vi%YW(D2H@s)$>ei5erdTlQfKf15?OLC|Xg5ugN8OtZ#m%=lR?G;GV>mz z0n%-iBP4mY^DKJ2HcC8wZAV$Ib0+fQxXTn@%4nx*41jqy1N8q<2u+0jAXyOD zxelDT6>8oM>A1_gTDNy@1$AH8^--wa8c_zJIOQ0$rU$UHcvyk?kxPMkqpXAemP6x> zUs76_$V=c}0ckLm>;Jz*i(Jfb{~0)9P{k-gehviZz57qXRix$2F8T}J+3W7|Ex@=vV`U(XH61p`#n0usyng#3PGpQS6h|4Tyq%3BzyYLd8o_!QIClcG#3 zq3^2z-PbDZ)n^c>*{ZSLdWGn@eEn-8FXW^MBmF-JW=hB1ld}8~N!m<$Qtlcd7k-!? z@pq<6xXMI4P0f5To^thuwFAnq4*s_H9%!TusH+a=U6z`S%3itPoo1Ejw^W=7Ga0JG zKpCSzUxKlJ;8FurM}H>us%)EX59M(kZCj`G@NJ1~5qX#{oV-RRL`$-awJvXFo1^aY z3bsF>D#A#`*>^#ZrP9_y%P(Xt-g{q$+)NNxFWw2LfDJo25zP#|&K+mRDtkXBtD+-f zJ&T@|OIvLU<-oiKRie7WXbZ&Rt&knoYJ!Z1`E6-9@t~gE)ZM@g9tDe{9arr+A71gw zL{VMt(`p&Yy1nji>5&96LS}qu23JA+MmiDefO)}4DqI}l86U+}##$ftK0^j~ z^vh$pZ^5|>nRL#3fUFge$T*ToqPjZiBEgb*3nO#c7!0=xjCwY zC>iBJ1xYZi8>YzUg6VtM)*EM@u5AkRUC?ply;(7RIDJoikD;`%byT2q-}$jQAjXGs z1XuUs^bGZWY8F+BVW3b3L>J1qR;|LVNo2i`%!6fZ7Fk0Io|1vGV2>=3yQ>LRQ=}92 z9MHS#-Z0=RbL6+7?;N;#Y8>cnE|`aREG=1<_}{R%c?iLQq`_a_*Tldy_E@7?QW4LO z3|TJPJQ~_qraD*{77_Uj(i4K~Emk3-CK;WF!Zj+uK??s=9M*3w_-sN-*i<>CRfN~W zGp*48emb_2;y8?^trzji2GmoxE=_RhK}Xt-wAQ6FU&EJ28MCN(KJOF@O;4H5%v5#B41mV-NJb>;k{-gSS+a|1x@oxws5q3bS(4&A)?`s2j zz8K*B`Ghx9@BYoZePf}ZzMFtgiW>(s6yVb@>-8TQ1O!O`fa3pabU2S!z5w#S;N%6L zuD51Z0=@)Zy8r_IbHwlCu;c*l0cRmLMVkXLD}Tq#)jJ2&8c3m($p&E&$s=AIw5mmf z#PSd3iDqwit*T&~YX<-J2Z&V^#LYjMW_d6T_?GzV%eS%(=Pspjk@>>_bGD=Gueknc ztDiTMC2P2XcZmAe@XGdpzHZ`T<8q*51hEcYuR6oV5{@0H@MKMV#fVmd+lohJO#4KD z;-hA031Tm_^Usy1(<*IcF*->d+ z@ZzmhqsM+*>cWA&&tXUYQ*E)Oi)9O&cSljqZ#O)hPU8%`<;g5n;T{*xMi0Lp5pWTx zwHqAz!LS2fH5NtX_ajqE%XdT9U*Bgz@2_pH$*6qnm)78FxyprRlkse0T5xm)ME?CzB$RUQ3~c#I*`@e;X${ZIAueP_ zqr+UNvpHbPt>;ohZIF)Km;)?fb%2rKksM1mpT=|@t2{Y_eQlro^HSHTAK+a)C9y}s6+H_5+*+X2q2vl{Scw3pC6@HQyTeV(w z6|NNaIhje7MG;pb9lt>ld-2Z7rHsAT49vnCaRYACJQ}tTlqkEzi`6`*ZM#DIJlKmX zuOY+dC&mubH4Del*7JanvUj<3e(N$kbGtl(X;| zSoKdbfch58F=DPOj+lkffRe?hNy2Uf_uTUN#LYj5XqLOK z8Ulsxg#fj|dWJE>^IQ%A^5#-S0aX?ib$?|CAnGkX&aJE}yk0IYpceh7eG_LT5i%z3 zg&3@oUNtj_uQY~$a5(6v;xT0T!@PSD9cH2M&yjD+6rdum_ZVN4UWI(yZKy!(zSjBy zQ>EDtIH?k~4TZOzE@sL#P^~?3SqJNW;jhV_gEn0JFt?1GOOFB=;-Vh96>#t`dE^jT z^C;-NY7Bj@%@@HY-+kS5M_Ko%x1R^}nqeY8@NtEEQO~jQU^1jE0u$$xlFI#R^7HrL z8F&orVxx{B4^J@u{c0ln`m_`Jz62m~mz4yskD^$g4nWl`2Y(AF%j@U&9EUgJuW9Y} z)ZZ5I1?f4%wWhYG?Q-Q#8!%S$Cf!a!W9Gq!{{SG%XaJFv zNM9t5LJ!PzK+kOOZwxbS?cvkzD`da1v>T9-NuU04I7zDW-+J>e=mlvuLCruQ%iCWn z!IQa9&XogrTn>KL3v|Ey*Kz;!rx-!>tS*pDPs&m95$t(@Jx=2R_6Q(tK?zKrW@DbV z9PF$67pRXL{ym@b=e|~EW+vT8%1n14?3X#pH+&5li<#AQj{Y_d)1*HCCw|Lah30vi z1$BP#xGa6mhGVv9qIU6SGc(BlNrm*fhr9d&zP`boPn=PKsjYVWUITMD^SSTAl@)-Z zJi%4NC+Hn(k8CNNiZ{2a&4HjcOzaCUCyQ=(gF$6qV8e>+kO66)9Einx1w+F{LTy6X ze4SE^{o<|Cm+(=OqDo2PW==a!FDf~x=sHvek$vSbj$Z6uXKfweL+YpFFUQf{X(IxK zBH>6XW5-o3vm)Ri>|9?A@w1R|he@&Tx6oV)6UNt&l^0GpQzxlkD9RVXTT^-?=S7_% z!ccK{;KsTS^$lMvTEUPFd61S>lg59OY9J@wV_$;dO|LxzCCzLLfHnB|DC)gC@g&)JTTHm4 zTl@^&Do}lIA=jsMro;wW zb#F&yN>_`@^PtNJss*L^7=~6)?VBaXA^^Nv;fT|SL8`CeD{0P#fh;F(&`jQhsvOU|))C)wOv{A6Eiwsgmm}`hfOV*? zerofTaKBLR8Fc;n3hLoF1X&@i(>P)3uJ~f26fY*2%~xbsUseG=Zh3fLPSt#?mTcwa zEYHPfa9pcv%YT`fuTn4?gqfs~;MA|9guotFAKh}W^pz=oM9zv?LbF$3;`13Zx)rU` z$}4wS3Y_w6tJWlvxSa{D#J*bRaMZW7C#8r&-s@)YJ{2>w$2B`fA;Pn{eYkH2Sb#VH zhUN=saik3-w#H&qyb&QKs_vB5T8^lhdy%<*=Dmg>OjQB9f?$cHnZGPpH#exEYK^R% zxx4@FBhWA+^*Q5?-Z)zFz6{-9TprXZAIF?sTbF@&8VVMOUL}N=1%D3HG5L^Y4spF6 z^Qo%@F=rWIU5&0)3q83}?=P|*Ci2?T+j~5~rjgkiqG*&d!dN2BmSGJn z?u0P>S%FSEu-VFC&vmIdMG}w3MN7OCr8IV|#-Lv(bI3DzjNE-futbN!QB+yhlk!>7 zQ+N2)$Qoi6jyc~N>Ae?K-2=s^_vZ?R!2yChc>6yAyHRP+xN8pOTp$>0p0Tv|r~9cg z^Y-!eI0e}s<1YPiV#^(lkm@*@Zv*cr8G!{g2xYkh52W7LqvFFr?OPj02{%ShZ6^P8 zUIyP?3X|Wkk<2)L;&S%xX_0-rFjQA7w-nrq<+dN&D*WWo0UdHg>JXa8USBv_N#{$~ zEk!s+*Q$If2mi+K@ef}Wc6=bcpx)|PmA+)>J>NjPS$io6622^;IrzBH3RQ04EkPnQ z^rF@xw1UFc4Sj*h>`W5oP4-?A_eWA)AWyj8N01c#lDS z3&QE=KvPM4K9z}4JMP9VRM*^dpGeF#$h}={i5bc+R67Sq zDy4YGS6jtOW46Y|x%Y@z?O=mp)f-{Jce?^Lj|4RVAb$EC%A%JYxNEG==tOcV z=Zyn-6d!GjR$WVJBs&M625`R#daYV^R*m)Qfv}85C zgBtFhqx2JlYW719TvFX(22n#P^;Q=cHjbzvoB2wyLB@*t5nIXR2UmV60`%8XiRVBBF8c6i@%dfOW4 z463>WFXF#$;`M5z0`tviaNq@v4RUbcJ#~AAtPe>a&$T19xP%AQujgIgjLnLFQNsS* zr|hr?)gV0da8zC)2TZaSKZLw))TWH90NMm}Tn>cEQ$85uBpInl7qo~)4XWR> zx>#NHcO%MWIKTLI7;G|MuJh?Ho?2S8$ZcV`h{oi=p4Uz5v%vZ1nq5+Sn|@JcsZ7T6 zHs#XsygYFB875c2Y+AD<85L0dMjEROlsoRMd8ECvP!u-k9l+SR=xqKx89VQsnA6xn90&v@(nGl)-ZmGHK zp43*BaJLT}oIct&Qs1q@O#i#RBdQ#%`_?{Dc=uE=O+v{Yg8J0avAK$BC2Ah`4-fZ~TCXf+d(}U5Z&^g4nO5KRa-LgbHt(Fvazqm1a$t#Dg780b z#IGapOmgCmfzej`hD2}gtT^86<+CqvDI}36RKjcI%Dx%!v^56#YrAMdHAj|cda@i zn*vZ;Dq!X;ZFLn0?fLLebvXNjWUt#3oD$xP;_&YZI~^U*w0f&mqyvC;n|cHA%Z?1d zkhoG_Hz@vzdAnWpy(vCLTQGWJE{MdAp6yrzoeaUph3)?sV+4wNTNm_|)>>A8|AH)Y zUoAoCsbe8B`V(VBa{p-`hug@^F6JUl_RQO|Jhi zyei{gD-i?-+%15n{bNr7#{lURbqNOswva!LoMeOj-~2BkIjO6ls)zRPctC3bX_Jlu zRrx+?GSl?LCVNT}@cfSAFhMYOEBx?1>&(TE=F8?5W3v3u&!K?FCp41A7q0tZ%>qJm zW}x!3^ZsV{P^cQ+?NO{>kq z)VNTH{ldvTCW#3B%d4nvcj(>%8fZD2&+uwmzP6Fv(Lqco56k}aD)#mUjlC#Mnb4TH zy^9at*w@Q{l^oRf{oCBM>JBgQapu#Sx6xY@7qd;4db0{7;_V?8FQ6ruT35Ei_CHz7 z*o^3g^%n76b-P;S((kX;t(ihBgg>wUfOwFUw*HP?W^`!B?z#PdEdxL}6WHh>_TAEF zgsc72DlYwP&Yq}sgW2#pL&HUNhI`!L=-c^4;Hia#mgE$n#EWtids;)#vX`dE;DLAU z2HQGEBhy}O;URfC6WaF2U!N((JRhoiIq)Vgv>=?c1n+qpA(QIHr6$|*2(CnhUu=2~KXH8X(sVW?Z zz%iG@RLc=O1{O&F)uFQln5k8kXfN^aow|$=pDWXge--*$^D4es4~2yT5H&43I#-ae zylr??g;??7W$qqx;weg@9vNlku2;zI&VijH?WS3=62!x=0sq>bQx%vo0V_AmDI0Wu zIy}6GPd#Qi^cRX`!5(2Q<(#%D)pWyV+G{+jd6z81(X{2tsJ%^&4QxgJdKXBnqAzz5QPw CU}Lxd literal 0 HcmV?d00001 diff --git a/docs/SITL/assets/SITL-SBUS-FT232.png b/docs/SITL/assets/SITL-SBUS-FT232.png new file mode 100644 index 0000000000000000000000000000000000000000..cf7cc80e60ee2eeb561f5cb28760c48a9ff1c1c8 GIT binary patch literal 12444 zcma*N2UJtR*Dnf)f=X42bSa_;h!{!$Ly)d?5HLZS0*6R1A~h5n9RWcDA@mL+1W-_# z3Q|G>1i=8(dzBKTa}WRTd+*(M-@13btd(=l%$%9oXV0F!e|yi4GB(s0&CKcU3B1$$5-otubGFF?=yREN18hh9*-O^-*vMG98DeV9Rj>M z9BnLv!5Zo1vq#xw$!p)p2le@b&w(vAKPG+(ehM93CD%JUEz~l%$(Jy8HL< z)8^wp*;&_>5m>Bl(^y7H!@6$sZpr!c$7H8}>l?H-b(4$Rp~~+XdRDf_BO;U?>c0_a zeVP_ZZkQMu{oUNrrSbJKprg^jY;A0rhc%CmVZGD4uPLYb`TC9?jrMPD?k_GNOXeF6 z3CqN8iN{~u+}z3?0aYEB{QQE5clj}8Q_}iX!yo-N`;*@0e#JIr_|o`}%&iaY*89@v zss>Jnx$1<)tYViAwssCWUO5>%lzbaI80?NO%ZplGS@G4;nOHyGUBc`5pH~t zx=}fKJa@dbu|?f}74fh&%Ye|?IWW8czH67A_?w32M%7)-JNNyEmNTM4$rkmmGA=!4 zsDc_YG1rkVbIH9w9x+u|sp#~A(!l_kc(`mzrd@_jt%#m^z9=Fo<$2 z&)cOPn(4aS?LjmQ{oVK}Bye_<1ka>2@_6;A9{Q>gKL~O_!W6Cn^!SR^5aQ$6(juRM z%<9tT&;59^PGTt^3aE^B4yKX1) zmXU&r1rYkPtXM8M<}KLNoMU#i576C;DH6ck>pZJ z87)%5AW_7_J>dW)7%3MfK4}^wWA*MUf5vQ9{uPfT{ITot&0J6M({2?6u9S19v-Knv zw><|O&)22gSV}=-6OX&g7+}Lo=phH+l(X(!L{)jHWG2k2BXt1@3#skn$dboD?WEYu zEdFxedr}|pOQz>lQjH#rb?>=TYwRM$fD=!Gk5tdNN?HGFMtoWg$5%S#%K(3rcbn#- zAn}%%b|i&Ot`m{}t$1;UAnHo9av5vV7I-rk8{#;*T-|_+OZoTJb3iO9)qpJWG=aM@ z#YqO((yfyG0zV|@+MOi(w-`lqwjPecD zaXdC z#gI;2UPiR=6sM&;C1SUhle6cRJv+PIPUA7M3`AYp-%TU@X3$~2;U%}+Tg1hM%Cd)7 ze$Hd_vG24C$;cSxVYbk;7pLUwy%Ynvh0&yO4r>0Ow?K=xvl*QD{ar~D^61($m_stHeH zE!Gh&6i)0@NA^x=t`6Q$?VTb+Cx={b=)m-Y#L2JdRP357{s#0*U`nIM&uwwF^L3f2 zVSZ`Pvb!Brsb4~yOnE$SXMKIvEc`U%>Qy2QvS`Zi@nc1gQU3kKt?ljC>5U1>DfmBk zl)9=SHfRQz@0hLm)2ONN6L+Yvpn+%7kMpySPhlgfX*2lt>6jawRlT^%BWa!Oq-n7M z_iON{_*{9MEoFZzm0@2pq*)?PIY&*q##&HCPxF?kM@f{nK+s^Xv3QYODj;tl~lbi z+K6*dYLv}zo1VW@v%Y@dJXI8hPmM~r0X+p=cN81APDNDW(!SawZl~Su98eHX;1ajF z9lE8gh$}G?6fiQdg7Ot#@(qTo&=H$4h6qIsSu3kjT`kf32ri#=GgmkF&26UMs&(}^ zS9DsCjlT+NHdgmR6#Vne;kQ^>32dlb!1HoWaqr;aZ+lY1ZO<4Ruo;elcL!bYmQgmN zG{D{QWrMom?l;Dq(ybFFT$(>G0es1Wsi6hKsiB4j?u3M~{h@CNMTnJ0%B>ew=keuh zkO&A%()jY|pWT6Fp|NRXLTadmQf{cCxCe)LYCL-bHstr})J3&@`NAi}y^uyH?|*hf=4w&IG9tRWV=u_YauQW~AWZ zMK(!Dn`{L=s(0%A6{sE^fT_AHZH>HUzWA7h3aQ)~)Tj1taF8LU@#p}r$1{m9AtKTF zzLJo1l=WxN77LQ#%JkWLyS={>EQ6GW-ygW|0`=D9~) z=z#~5I_wR>a=QY(U2DyVTZ=%xe*MFOx4-nJs#+*k@Z^}f?##PEJ_jm8qhbceCCUSS zG!wC@>0)VBbw!H^^!>1>)J5&7S6ZYad7q`kY{1qgxNegXdnK=-?#;y8!}^;?g~i9N zHc}i!oSFQ^Lm(J$PGY>6gwJ$xgYHlFvJ|6xmEW^TUj*`O+WuAUQQ{sooFiT!S0rY? zJw)-c_#ZvAe()WQAGI8q#Flptc_~<7oAi%4LchummjWEHzR?4RDS1?!;piJ?Q_s{$ z^w8-NM|8Z0DX~ABCja@ej<{ul__0@lMO)wy?fq_tV+`HZlU10amZ~P?K6BHdyJ5RM z+5J8P<`>|{G(~%Mdf8}4o=w>Ej4c}-HXP!~mE^(4KKM5iLZ73^2=LOe`-Va2p&Hb;w`X_+*Ca4$*RBQ6sY4;*p2%kBjGh zEpUIxyOgGm^{H6y^!ABwOs9c^=p}5(l;@v?__~EOXqK^P=#Y6Q;z^nv201-!*5&X$ zM-u4l>S=1#X0SYi#UzMc;B=V~~kQ`#AD&afZqJ-ZVTIWZHf*20+s z4ufL=#tFq}3;ACptmK2Y5VV>Xjw3x5-w}@%tjf4QP?BawjUQ;+@w%p%4Y&s?h;HfX z8K9MtmwrL&f%-)R37e&zg>GYQCj}e4C@Vy3=RO!Vs*9ol8dkbX&}xZKz29s*371wY zhIS+-`3Qo{0*L-PY4hUva=YHf8v$yIPvd>G&)sV{j)gVMjxEHxJt;1-kXyo^?4rshDJ~TM)%9huv*g4X?@uEu@%};Q zUAh@u;3=LG7dZ7|mP(g8W8WYkK=ArbS zaQh`zN!C=GhQOMBA-N-Lo4^%6-p@HEu?aCTb2n^NKOOnsbw^RW{qCM#nRym^uzvWD zuKJ5gG!8b!inB$3w)=@tvR)-2_U=$yH!Y3arG~<4hqCO^#6&ZzLjRGyWedl`s2E-? zLcDZ2$)jAR0ogF!NjcpA$4R{AG;K$&<*w>#KSV) z^F4URf$r4QS{y2d#FgMCeM8l6VmY9zlczMtON(rx(&%eySL@qgNvi+DlwY1AQITS; z)P<6XZxBhUb-&~E^su#WvSgqOVNG77myPo}1B=PRHXz4_kYmal`oqWok6Wr>d*b3n_tB{Sy@&hHlY{h1-eBhY@L~Y5t%3da>*7_HE&5h)V0-8kCG-_-+PhqUxw)V{O4j!o9jJ0!`aebjckK7Xf zjd~7o>n^aJqDQq0l5tx!NKa}ya)S0=dQQWA1RbB4cD zc4mBpy0Ngp-Hfc|wH3*>?c|uB2~Du|?UksDD#@(U*h-OG8q=|pwX;K^wHC)w{8now z_+QjtoauA(REW594_>$S6xUktdh5U*H!EMvJ3$q%wkHq8i3&wnlg^`2bje%yt5InU z-8X`RdxN1$0b{SS^d*xOmN3@Gh=mUp*QvfZc?%1{AytNz?n{hAO5c9h5BPuH)7&oI z_SDwvz5)Sc6o+o(YRxJ3SZO)9>h8kC^ivgLU!H*4_c*+7K+9^z>Ieey>#HZY&^cM< zjmVLDAHZ?FgZOxA5(5pAQlBW>8ng|Cg&-@|65C6#upqw>;gE&C{5|T@Hnu#P> zlQ!F|73Xlc`C%H z(Q~8`DN(}l31Wtq>6kO{6P!RpR(d=i4%{>2ifeQ+(p>tDjbcMVh zJq#M$z#hPy4(rKxd4Yq?F>iSNzkSAd`~fUbc67y8J!EEFDOX4=v~uVe<#p741G`Q- zR=tHq@qL=k{NdGxR`ucL{;<}^&@{TA<|I#E+$=+KJestWO>&KC9iJwGM{E z!KP;&mKBHIh2IrQu!q`jjs9!EXH5<7gkpnd>tde8AF1DvI1ct@P@3niTC%tnxGnjG z-Zn|{n{YC=b@gPxV1?+RkzH$%-+Z5b6iyu^#+?JE6Mh%1#snRfb#hMK-uLv$=- zFPzd+#H0;@=lDaPTCYPGC^2YnzsR+7|C0!5ka%W)34eQU$v|X#-=q{gZEf;QQqaeBCe_Z;-gEpp6mV+Lni> zU%F1E9STol3LuL{CPb^tU-&W(oNJX`vE}ASktw3?m5hf(4hc!jjl+@ZcX~LX@+Yml zQ)RO+L}v7ra@RTH=jbWsd7(ou8vXuamA>lLz5ZyJyKcK@Y>rJc;+?tOi5M@HxSgp@o*oVPU; zuC$J?3w=31@Z;^C%6<~s^H7n2cxHld;T*7af$e7G0ms<~o8rh>g_q*S>Sfs842Sd& ze0vayk8Nhrlz`nwryDLYN8wR>dUlr#qB9MmbyE?f>PJ2{huz_jV<>)}!e5TnpZ+bA z-l6vTT{ObxvhqBSHCvu9^T$DmG*$U(g2J?j7%>&m+l_`#0-_4VSd%R|DmNW*`zONX zwYJ^_;R9OR7jREDx`WwGGr#YUqVFX){ENg-jpa_*kXUgtXngRS3ZdoPKWrZ}Wd)Ya zG)QMAVs*5t6&>}+1q~f8$g)Vi^*x@7mL<-TgZW^OAaYS=r8Eo_apTIx1pmr6!|8O_ zwUdhIw!F1fje~5=LWRd&L$Psxi!NpGrTV=aP31PwM*hgxU+Ko)un9ay7~HOK8XSEK zZ~(HOE^Hm)-*g$+XiYao3ld)}=QJ!_1+KV_3)AM_fa|{K;wcs3g{L1B^^WG1==s)q zN&h{D`=S#>QPblgg-Qm+x0MJ6<`CW2!R$v+jz$VnwK z=pr%^FB}Pk;Tb*sxUs@4MkHc5M3XV_3@GYL2nl8)TgwunIPckq^$!OD6Guz!%omk5 zy=~kJVHsMzyKsYj_u-3XpdwbHdi!1hIz2ycnhGh(^i3Eq9$>_$8wvs%j_a6+Baa%k zPbUmLiBQ7x@Q-6tw70(_(AC%Z!$)pPzIuk6t-gN|Ti3eCtzCBY9powmS#bZ!%5!|b ziw5a)U3lU@YxCh9xoCSDAlO1!R_H)`_Z~V`#-=A!sTQit0x93MGUgsnTSfyCX)nh3n)}F3o zPbbEn3qFaZl$+kEcP)e_Rc9G4UF1^72sf8F8CfKcvUtwJ^;|TXF^B)xz-v9a!9nCJ z#49++@GfoOt`LzaTzCP_r%DvzS~>@mYII=E5Whv5hXngr^NA2wBOpH}7AQ)duNd!; zz}2;b>4nvCVO!Nm`Wdw%?5~m{?y;7JxBU*7&!roeVhMC&QeTJ)S^ik*=bR=?4~*+; z+xnE_ill0SUj`71g0@372ViyCGDMra05z;UvB@*bM?T!-TwL%yWx;EJxqVt?L5+N$O0?*6y=X?_WE*Ak zw53mZl8=SiygjNbuy3f3svs>n^JcOdH@MBFw5beN8`aIyfD`FSTY@jnyE(7E&hc&| z)DUM1OyOoqW>kW%i{uaDwEFp*w1pm69yBu7QNyy>)ML-4i9cyS`@ND&4f4GEEYd8< zEHz#JPJ(=S`F&Xh&gejw1^yIW&si^Y*aongJ{E`RYt;5$dp-G$(%#;Fc=ZO@N-4SgK_F^-7F;hz$uzr|`-U-_M@=<9W(%Lrxi-xXX_WmD!a^!G zPifkd*50YHuwD*Xz3J`8=HnKtw4?}E6X^99xL>Cfi>=f2Zc}U^v5vC_*s{2|oate@ zge0!AumT~o3`Np>X@yQz7k@a|&m)rd*jR7D)z;XtPE@>I8f_0g&zq~}(;1kaQyovG z?&_iOtFLIT%1a;ivp=6cs19%Q{KML+Me28`35?Nax*;iu91iwXcpeq9Ie-cN+%YF5 z`_xY8uv**QSoX72veJ_VKcr>s*BN#ipktcwxC%J{`RF1Bw^-q=&qz%$4Rxz`DO|Ym zPoVDZZ&!+a@xG-vQ8)R6eOLbXk>^Zt5qMp%Sy_bimztYGVH1H0D5f)uenYqU@*CUM z)E_!WPAra2$=Ty)URzInr;Ox%={hqOptxukaK9Nb4fUatuft}8J?nrT%13gQ$&;xM zi@~|wUXQ}=-yJMY_kBsRYM>}XK}ZmCP#x{lrdwr@-`-}Zr&COEmd`hKtyVJp?aFK- zr(YjoYRC`OV*_vp)%0hTJ`*aM9t|rjSG&F)>VY)&&O+lVFx1#|-)!LQOj$){tu^^~ z`FCoIqZfpue9*8b%aK7E~P+&)ZG^4jqdMS7DnT2xFRuu9t};vmRVe1|m2%6;0rLFCedX(~|{UzSC?fe(%A**hTGkk5vzlZiYg{ zV4L%WzkEF2i^9`FmQq^>DxbBG9_H?2noz@|KMuOtwg~B&7ImuIzppI`52OCchnnp+ zypRp`xiqK3JY6W?$=7Svtjs$9*uKQ=fZXQC7oEYinUT{|PZE$I>8s|+r5T)US-Sf)j{wWQQXWgutGT7_Rl8XCh3oZ3NA z_b}YB^Mi)xi6U*3%ix#|s6~m7<(V&C3r_>=Q?6|A@?Igk2X@TF_FADjoIped7gj3) zKYma>YQGNSmVm}+9Aj8l+@A1mp%cz|rn(Xz((Oh>L6w7!L>CximX>EvQZ$mm;DG&?=x_G zWLVbW(u-Ha-sypuHMRXEu=X(QT>PLHnccid|7znX{rL_m#URI2n!iTXAJrO;_Hhagy?W)>KviH< zp`AD*)6_v&_(Aoac0_K6obIu9|vJYUVfhN@~RF3M#yHUe@pe%#N$?qCz171 zvr(z5_aOdMAnN?7>aFp?NG{+%GdK~0|Mo?nYC)(&`Pz*n6%vQGcpv~cK(Wa@sM|6B=!kO;4fK(#e^j1$z^PZrh%Rpz6rmaJyS5a zOPfa7=jf-WC9qzyAUXh5l=+j=4oUxzR|5)Hi+@V50&*Xj0a1aME4@whecj_>^H@@J zK&=w0gb^w)zc@7j#Pw8 zH!yvJcDZs=u5&U(aC0*{a(`;+ycPMyvG50reV+B`%pk79PkpM4bU>5*PvYZQIt>!0 zoRr8Zte&fh`o8R#TW!&BSRkHu=*=yY{M#&mM{K0(o_)SVht?@c7^@t-c{=2rYXl9{ z=O6i2VLbZj(674g;dCI?!=vO&o}0zMH=DT^Ru)_qeY!4UmCPx4)y-3R|0H_Ad6eK; ztq0Z8tTP4gQIF;^1L%)QnE_^G{gZB~cfLtW`te8Ow4`2nqt#+`@;y}4if9LKS-?e) z1DLz(W6VE0oRIS9wR@iYBGB^j)h=!CB%x)_nOtE)=+iDJs_%LIwdU@5LC1H!VH}Qc zJi9st{)>jjhNws>fM;w}|MCrO&(zo>h!B+@bb$uJg{CDoBTS(uknraJ10!Z_nHCOc zWI#N4aGt>WG0s2Dg;fEx%$E!(lgISo_8CGwI;3Sn4GiH}m)r*9bn{grCwI5=!Fa9c zJkPWkxl{ljW|1!;PjDIOxCAj^be3UW@k5GLBh$BeMk4wc@r{)8i zAQ(PYrSgTZ-1Dg=etFtnd#B3C>;J_>hpppy+SJTjvkd;5)>P`^C+3~-6M8u;#UG|mV21p>LnT?Kb6or*B-+eDB}`` zS&q|sp|k{ttIZ=W7pu2ma&byNZ7*W^y5GaiZ8b3vaJz5#(Gs*2g{nc3L4h{+v=jYw zZ8NV65UsVPuaX-s9B5f@?lf3x)54vHOwPzjk91odZpC~tjBmxdK5 zyYJ@XQhtF>-BXja?4NvVPME(zuA==mnb0p)q;lpe@up}t7HW6zwZ*u*dRK-bCERB= zSw9?aPlj;YvQbeZqa&P3J$aAc%oRIcWbhBv!F))i(_zVp5u9PolvUfU&HC+uD_{Lt7xRA)D{zXWejYin@W!iqcUNI)ya^z z>5(_LV%rkGp9Kk`LO|yt7k%O(E@D@~<1C`i@Is zu#VSn-?AX?K$X876yl~M#WMoc*><;~CReWCn?rM5FCe!G=?lQM#+6MQ#Cl{0whn!j z@(<_crVhTEZp`~-hmT8nVa?kD?#tn2ihhLL!KM&jixwW?wJxd1SD7EGIWFG6`X?6{ zyN;A^<%nIxRElqtuf9pf_Ql6+dUrg=8hSC)1K)oj?#?Y=D>V<%X54Rnk4Z}3+T+oP zEJ|#PRNh!&Xw*TF|DDH0%JE)JESy%0z-Q0Ka$w7T=T%?BR!**dw&}=8C{Qh`DyUdL z+|n1d5+{~ae|B&YFuV@c;|IzGc%=uu&Hnyf33Q3Mo0!#gO%a}Ju3({?RB}n$OsmMn zJG264V0~-xnT}zcTR2|KyDfKefQ9XLZ~?nxj(KUi6&Eo+c>k1#QD2}c!xD$|J*qrq zlw*a)1b$JugG+y|-RJjaGh!0TH(}znF!;teO5MbwDn1xI z1ljGESYgm0waXswDs}H@1o^Z>$@{41=jPB#o(i`Qfj%QXHixlAX){j+erz3mn<9Io z_Ze{Cu~GF;0g=sHQf(biS`e;O!u`kyh-S}!#|>PQensFPEMXGqg=JRn@7ksrRlq97 zI$1zVBeX@(T@)cR)RfA7!k}FY!T9Y#4+I9%mE)E4$M50o)i8*sLRd6a{12I&&6&Pg zU{&}W;^}u2hBpu?@oBqtY4hhU57>+41K^IW42stvHB&AJ&L)*vcv}?p5;7;fPJt3S zYi7_r!jgrGbv)+=0(FeXih)m)Hu~)-qVV_US4ZFrg}7ER1c*~V;aabp+-q=^%{$_t z!wh~`&({B#!>e8143eXh$8bvrva~ih!v61@?{j3%iyFr z1y{F&;<3~UoZGyn46=1(IK9A64P6bkmJ=yo#<+Axyy1I)nx2Il{1{4~MaT7T1&ayP zoB=qp4_g0?OW6c+fuKiYelY0QGZmwXHKO&y&yA%sq^5@tE|0IvS3PGOr8bpJn=t&< z)FeHcD|Ey*?5`Yt8H?<9AL~Qck-_usxp|ovH>+wZ^LquRvuxWxSlL|_32YOwKr`FG zA74ZH%soS~D?h8e$FT~N*6-k|e}0guLZP5p{X}vA*=haz4fKW=Zn}NB7j1B1tu@|u z?GU|j?RQiX4&^l?MWV)fYkR3QmC}7)zZl)^ynt|30@FMWTBYmRK>ca@`jm1}=I%Eh z4|}4uRL8bB;%4?29fdKCu``PR!z@93Ify)39)@k7M~G~YhrDaO1X`VZw+L-Uk{5sZ z%@$x96!x&fITe5(8rgkmNJ{&PEGIOk4oBHR&1C*zyfSnOknP8#(MbD0&YI5tY}i&~ z(%v2_AZLiKI8#f~I$&cyTlI$i1!B|Mrh>GN8? zu%{mzEC!QVD+5&dXm8&lM`X%5&2K+4xafjBwsH2H4aLTA0>vE)y<%wz!ti9#5>2gz zBhKtc%5GnycMaleoctfZa=kS$jjk8FiaLP&BuQRLsA&|HTjlbB#fSoVXAsUGnJy=1 zY~N0iP!1i<0iMXwH36k0$X)$|N`W&DQ;Kc(m za|Lsp2=d?$v|mAd6kb9424%?CcWAgMQ{Vz1b(S$jpmlu*guZhix_WPO@&vZf~s)oLwkeiFoZ4|NvXL1GLs9tTkxo%@p69WdAKxm zQ-kCh68|!-rq=WXurcQWwdkP^LyvOkBQ)|O8)&N6$;c(p6^ekshtsPB?1o1*RcNrg z{iFT+@|wq(Gbdx%k|t9#x!Cn!G1j0F1>?x4SFgr0KKL)}r%@Nh2r4Tcx)TGscXDQh z6Jg&)u_q4VK`>=*u!pKxke~+-v-s|lqyir994f?3XD7;nO62_#MjpQ6@bd@ae(dJB z)GJWiWv24T<&*+d`nI^fWi&nEm%|H}0q#LtLFyCL({-WvvZ4)uUk!$^(_4iRrL zlB5_~=io^vWn&lc9yDh4zT>87Sn>iuGFk}_y>HqT>wwD4k!?w+e$yxa%I?vR@SzWdBtWGF^< z?T>#+RSVSdUWG(-G6uK&roVl48vOpKcdQ~L6Od1ZR4mPtAhYg@i+6~zd8)Sujm!(! zau!}_-nwk_DRtBi!=igTbFwBNXp^w9VzAk<_4UR^ap1Sphzni!wc6Ip{Fbg1C$4lf zTv5K)ai6tuPAMXD;3WhxuoT$l7?XeT))t}X7EIuc$ek4i$z6=%!@9T}(lv4B7DXGA zyXMnnK>Xb}SEE&l-bDZ1%NzVHMoR=tQvc7Q%wA@>4CClQQoDMwN{6r7y_AwSGxBm% z4)+=_9Tszls7KreS>#{|UrO#Tnw!S`_ZP7r@ZJb?5~Fq`EUt9(%LJMhY>Ug>+wxTl z1W}*W`!`ywaBkEELy4VRkS`S~xz^2b5-!bB8Bk0`(pUAH3Wvru-TYXurNvPn2_p zMB=Tia8QUrFW*AEAnt887>_n4jT}}lO4nuqrw@)$IxvV)N6Lai5BK)X>4 z82f%;7krWZBMv;wa1MOseUbeY_(*@^ae=$<4DmJ?G6f+mVZcbz<6)sIEimqS8HVoy zOFxPo*yzCGP1q8Zyr{@!acdv~gddkV!TrCeq(+FB1G{e*1FPsEbpz?UT81(wWzfq- zBO9__;KK2z7EdV7M_V{&ffzZss5maGA&RlF0hOG|bqJ>Nc)*^6Dk1{c^8cUAvY$pl zS$wr&ka>g<48Mbl`&tb;FT2Hn1$;%-gNX&q#Y>M?+Km92DP;#Q*Vj1@)))oOP8T{Z zIJf*qq3rFVVw^o9@N5Uwastwz?s>j|d3^#PZiCN9OFSSu*#5W3A9Mof`tUyBF=)gI zLz@G+_|AhXRf8+$LMr4HPxoB={YUNhZB_yw{DWs+{HOXhDgsn!!#WQC zf%I>)H|x43y0IoQ@OvKAPVsa4wNd@OKY>+S%=-&`#UYX1qBOvGtd=8IN6V*{Ze1$y zt+afuO%U!wkJVSM_e}~~$yqfsypH$>;Nd@E96VrX!91@q5zBRh5XDqD#Jr}SsM?09 z-ck_M7B}(aLJ@H?u|X5DOBe}RH+0)KOubjy=pZi$LR%;-%!A(KTJ(SpNlyBptY%#5 z8@2{netM&6vX8~ijey%Ou;Da=LKIBfK>Eo_d^|jL#|{p8lLHkkdjv2TpiNFXASD=L zCwLNP+7yP;#|Z=;W=Q}8MKg>`RbiF3GV|pi_^|8}ga)hK!`*L;F!!F;2`$2Q8Cmu3ZnIV}0@h z!p-QGhSJa9BHs^#md^waUUU^lTq#rt$rTmlge095RNeG|c5Q=d*dXRbN6hl$he(|vhMR{~=ARX% zXi{U@$q<-l!Y};J!#+b$9$~37V}V_f7H|9# zxZQti&rJnY;?|Nlegl6FZW_<>%|H`+`9341IE^mr$MEfQvvp}G?JvcpFiH-cKz?Qu z_A&0ltTj>wkSny;b{?1= zscz!WIL5-pf?}2Gvj@K&_<%b|VJoHitD`C-9$3HcrY{hPV|J&KM{3Zs&~EnJ@i~>2 zGqX2`4oIuZMuxqFUrE!RW{-n^osE#LNgB5=F3S6ff`brLe!4;t(jxstTzCxWAGor3 zioc^k6xzv2;OA(O-#K`LK{F&4R1)>IJ196I*J|I~_zldfe2!a@D{uKVR(kA7M&xkz zqFN#RR>nbs?bxwG!(v+8mz#xUPJ$QM^a-^{9o?s;P&<27F=5VrAyP%?t3S(kXVxh< z$aPKD4Rl#XsN-{mn@(V@so_ZU!Sa-1Swuf1^k8keL-N=6D0mbSQywuJi!zXDGHSG% z;vGc@M)q72b{_G)3P?Yu4210AY!e<6>srxodz3X)2rbbnhk8cdr7uV?ShmRY3c|G- zfxS_J^erl+frU!ax;n`9$YqH?cg%Ec3P||huDNVF7=b?prdxgp^3clds#2?#Do4S&U|(HiT(W9 zSmgS*(TN?ky)(G96nE~3$jChdJ`IRyIP5GstF;BfhjNWtd3Grpp=8ha7V?H$5j$1V zBy{IPJ!B8@k&zFpCM~v?aH(mo1 z!@hb13O-ht?(E)G<+`!bUQ4rZaB;1hq+?-5m1UweIdU*DwfRY0f_ar$fn{mINLgj8 z93tl(RF;bxFjmc$){#N&Z~S)nf$aEDoVhZrBUZfEJtGoR{Ufw4*Jyr@>tts>KmIhp z0a^7o>P=ef^s1aorWLtsn`cFqRhNVzk#{4r1!80fP`HuUAMQJ%(07vv|Mq^A1~XPKl|~^-{rY+pUM&A&P``JB=1I zERCM=ZO&}_tR}oO4Ldw-1}YbGxrUOM$y%xXSQT7CVmK5nL!N_I+2J1tx8 z9c!eVa%anG)uz)HLCWx_BC$R%GE|>1dW61R?ajpb4_qOfVL>tOfe?O-G?|&grN8P6 zKQ;MTq^qA)2j0q|b4S57hHsm1!8>O3yj2&)MLWWls}y~%6>B9cMBDtkDl82~s~qCG z>l;rn9Zaaayh=m%Lo}%Tatr_ZCN|8&6BeE_p|;k`--^+Ssrw)3rcmm(5#ggaYI*98 zlr{-^e3zu1>%`{_Goeeu0~`OeOiwosyCXq9=4-5u%4J1}M^w6QZPHhSZw^5xqdim8 z)VZ=xiY&n?iJj#>jZUGz8P5OJj-9ex}n(ZZ(cT4#KyO zt}iFR$^Mm=RqU4<4p%sPq!6~=8%%1QDbLpZ?rA1}oGg!*RnAVtTQ)*DS&JOTi3Lz) z_v>Mmk;x3u^kB`0WnI^~ah$ZJt=vqOjCq5_0Lvx6#XjoF(V)K|^%PcM{64GHGWVv( zo7?GII+HV&Llp#RCjo6w_7|xHuVan8_n%vxM(`|KMWNT-0B3QoUz>uq z7#o)=aTa{CFnvA)PTOpF0BB`&OBLgl2*Cz@Seiy?V)K7J5l;QVj)LbbbtcL$X0vH? zV<4{ni0{0HZu6>vbgmYr=C~4dd6P#|(20FTm-CCC4DpFl2^R7oBi4V;TyHN8NXZ<7B90{%P1l!i|n`^~DgSUUYyi{QY$~(kW zbP-%us|k(%@{{Mam?;nLNGgbBPP#OcXr9xQ8|^9j&5iv{+h;H}V*ufG*om$$tIMi> zwWcfQYDhGnX-Z^!h(7$bfQeXq@m2% literal 0 HcmV?d00001 diff --git a/src/main/CMakeLists.txt b/src/main/CMakeLists.txt index 317da760b6..66e671502a 100644 --- a/src/main/CMakeLists.txt +++ b/src/main/CMakeLists.txt @@ -210,6 +210,8 @@ main_sources(COMMON_SRC drivers/pitotmeter/pitotmeter_msp.h drivers/pitotmeter/pitotmeter_virtual.c drivers/pitotmeter/pitotmeter_virtual.h + drivers/pitotmeter/pitotmeter_fake.h + drivers/pitotmeter/pitotmeter_fake.c drivers/pwm_esc_detect.c drivers/pwm_esc_detect.h drivers/pwm_mapping.c @@ -493,6 +495,7 @@ main_sources(COMMON_SRC io/gps_ublox.c io/gps_nmea.c io/gps_msp.c + io/gps_fake.c io/gps_private.h io/ledstrip.c io/ledstrip.h @@ -544,6 +547,8 @@ main_sources(COMMON_SRC sensors/rangefinder.h sensors/opflow.c sensors/opflow.h + sensors/battery_sensor_fake.c + sensors/battery_sensor_fake.h telemetry/crsf.c telemetry/crsf.h diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index bcf47a3481..22e73298fd 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -1558,11 +1558,13 @@ static void loadMainState(timeUs_t currentTimeUs) blackboxCurrent->accADC[i] = lrintf(acc.accADCf[i] * acc.dev.acc_1G); blackboxCurrent->gyroRaw[i] = lrintf(gyro.gyroRaw[i]); +#ifdef USE_DYNAMIC_FILTERS for (uint8_t i = 0; i < DYN_NOTCH_PEAK_COUNT ; i++) { blackboxCurrent->gyroPeaksRoll[i] = dynamicGyroNotchState.frequency[FD_ROLL][i]; blackboxCurrent->gyroPeaksPitch[i] = dynamicGyroNotchState.frequency[FD_PITCH][i]; blackboxCurrent->gyroPeaksYaw[i] = dynamicGyroNotchState.frequency[FD_YAW][i]; } +#endif #ifdef USE_MAG blackboxCurrent->magADC[i] = mag.magADC[i]; diff --git a/src/main/build/atomic.h b/src/main/build/atomic.h index 53c165d3c6..80ec70f55d 100644 --- a/src/main/build/atomic.h +++ b/src/main/build/atomic.h @@ -17,7 +17,7 @@ #pragma once -#ifdef UNIT_TEST +#if defined(UNIT_TEST) || defined(SITL_BUILD) static inline void __set_BASEPRI(uint32_t basePri) {(void)basePri;} static inline void __set_BASEPRI_MAX(uint32_t basePri) {(void)basePri;} #endif // UNIT_TEST diff --git a/src/main/cms/cms.c b/src/main/cms/cms.c index 8341cda584..c4bae3a1f2 100644 --- a/src/main/cms/cms.c +++ b/src/main/cms/cms.c @@ -839,7 +839,11 @@ static void cmsTraverseGlobalExit(const CMS_Menu *pMenu) long cmsMenuExit(displayPort_t *pDisplay, const void *ptr) { - int exitType = (int)ptr; +#if defined(SITL_BUILD) + unsigned long exitType = (uintptr_t)ptr; +#else + int exitType = (int)ptr; +#endif switch (exitType) { case CMS_EXIT_SAVE: case CMS_EXIT_SAVEREBOOT: diff --git a/src/main/common/bitarray.c b/src/main/common/bitarray.c index a46a536e3d..07d175d515 100755 --- a/src/main/common/bitarray.c +++ b/src/main/common/bitarray.c @@ -55,7 +55,7 @@ __attribute__((always_inline)) static inline uint8_t __CTZ(uint32_t val) // rbit and then a clz, making it return 32 for zero on ARM. // For other architectures, explicitely implement the same // semantics. -#ifdef __arm__ +#if defined(__arm__) && !defined(SITL_BUILD) uint8_t zc; __asm__ volatile ("rbit %1, %1\n\t" "clz %0, %1" diff --git a/src/main/common/printf.c b/src/main/common/printf.c index 340847f568..5e72f726b0 100644 --- a/src/main/common/printf.c +++ b/src/main/common/printf.c @@ -48,6 +48,9 @@ #ifdef REQUIRE_PRINTF_LONG_SUPPORT #include "typeconversion.h" +#define MAX UINT64_MAX +#else +#define MAX UINT32_MAX #endif static serialPort_t *printfSerialPort; @@ -110,7 +113,7 @@ int tfp_nformat(void *putp, int size, void (*putf) (void *, char), const char *f int written = 0; char ch; - const void *end = size < 0 ? (void*)UINT32_MAX : ((char *)putp + size - 1); + const void *end = size < 0 ? (void*)MAX : ((char *)putp + size - 1); while ((ch = *(fmt++))) { if (ch != '%') { diff --git a/src/main/config/config_eeprom.c b/src/main/config/config_eeprom.c index 645398e8da..6d11c1804d 100755 --- a/src/main/config/config_eeprom.c +++ b/src/main/config/config_eeprom.c @@ -36,6 +36,10 @@ #include "fc/config.h" +#if defined(CONFIG_IN_FILE) + void config_streamer_impl_unlock(void); +#endif + static uint16_t eepromConfigSize; typedef enum { @@ -120,6 +124,8 @@ void initEEPROM(void) // Flash read failed - just die now failureMode(FAILURE_FLASH_READ_FAILED); } +#elif defined(CONFIG_IN_FILE) + config_streamer_impl_unlock(); #endif } diff --git a/src/main/config/config_streamer_file.c b/src/main/config/config_streamer_file.c new file mode 100644 index 0000000000..8fec837ce4 --- /dev/null +++ b/src/main/config/config_streamer_file.c @@ -0,0 +1,105 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include +#include "platform.h" +#include "drivers/system.h" +#include "config/config_streamer.h" +#include "common/utils.h" + +#if defined(CONFIG_IN_FILE) + +#include +#include + +#define FLASH_PAGE_SIZE (0x400) + +static FILE *eepromFd = NULL; + +static bool streamerLocked = true; + +void config_streamer_impl_unlock(void) +{ + if (eepromFd != NULL) { + fprintf(stderr, "[EEPROM] Unable to load %s\n", EEPROM_FILENAME); + return; + } + + // open or create + eepromFd = fopen(EEPROM_FILENAME,"r+"); + if (eepromFd != NULL) { + // obtain file size: + fseek(eepromFd , 0 , SEEK_END); + size_t size = ftell(eepromFd); + rewind(eepromFd); + + size_t n = fread(eepromData, 1, sizeof(eepromData), eepromFd); + if (n == size) { + printf("[EEPROM] Loaded '%s' (%ld of %ld bytes)\n", EEPROM_FILENAME, size, sizeof(eepromData)); + streamerLocked = false; + } else { + fprintf(stderr, "[EEPROM] Failed to load '%s'\n", EEPROM_FILENAME); + } + } else { + printf("[EEPROM] Created '%s', size = %ld\n", EEPROM_FILENAME, sizeof(eepromData)); + streamerLocked = false; + if ((eepromFd = fopen(EEPROM_FILENAME, "w+")) == NULL) { + fprintf(stderr, "[EEPROM] Failed to create '%s'\n", EEPROM_FILENAME); + streamerLocked = true; + } + if (fwrite(eepromData, sizeof(eepromData), 1, eepromFd) != 1) { + fprintf(stderr, "[EEPROM] Write failed: %s\n", strerror(errno)); + streamerLocked = true; + } + } + + +} + +void config_streamer_impl_lock(void) +{ + // flush & close + if (eepromFd != NULL) { + fseek(eepromFd, 0, SEEK_SET); + fwrite(eepromData, 1, sizeof(eepromData), eepromFd); + fclose(eepromFd); + eepromFd = NULL; + printf("[EEPROM] Saved '%s'\n", EEPROM_FILENAME); + streamerLocked = false; + } else { + fprintf(stderr, "[EEPROM] Unlock error\n"); + } +} + +int config_streamer_impl_write_word(config_streamer_t *c, config_streamer_buffer_align_type_t *buffer) +{ + if (streamerLocked) { + return -1; + } + + if ((c->address >= (uintptr_t)eepromData) && (c->address < (uintptr_t)ARRAYEND(eepromData))) { + *((uint32_t*)c->address) = *buffer; + printf("[EEPROM] Program word %p = %08x\n", (void*)c->address, *((uint32_t*)c->address)); + } else { + printf("[EEPROM] Program word %p out of range!\n", (void*)c->address); + } + + c->address += CONFIG_STREAMER_BUFFER_SIZE; + return 0; +} + +#endif \ No newline at end of file diff --git a/src/main/drivers/accgyro/accgyro.c b/src/main/drivers/accgyro/accgyro.c index 6ed99cba2f..4182e760b5 100644 --- a/src/main/drivers/accgyro/accgyro.c +++ b/src/main/drivers/accgyro/accgyro.c @@ -22,7 +22,10 @@ #include "platform.h" +#if !defined(SITL_BUILD) #include "build/atomic.h" +#endif + #include "build/build_config.h" #include "common/log.h" diff --git a/src/main/drivers/accgyro/accgyro_fake.c b/src/main/drivers/accgyro/accgyro_fake.c index 0cd9addfae..92be492f74 100644 --- a/src/main/drivers/accgyro/accgyro_fake.c +++ b/src/main/drivers/accgyro/accgyro_fake.c @@ -17,37 +17,74 @@ #include #include +#include #include "platform.h" #include "common/axis.h" #include "common/utils.h" +#include "fc/runtime_config.h" + #include "drivers/accgyro/accgyro.h" #include "drivers/accgyro/accgyro_fake.h" #ifdef USE_IMU_FAKE -static int16_t fakeGyroADC[XYZ_AXIS_COUNT]; +#if defined(SITL_BUILD) + +#define VOLATILE volatile + +static pthread_mutex_t gyroMutex; +static pthread_mutex_t accMutex; + +#define LOCK(mutex) (pthread_mutex_lock(mutex)) +#define UNLOCK(mutex) (pthread_mutex_unlock(mutex)) + +#define GYROLOCK (pthread_mutex_lock(&gyroMutex)) +#define GYROUNLOCK (pthread_mutex_unlock(&gyroMutex)) +#define ACCLOCK (pthread_mutex_lock(&accMutex)) +#define ACCUNLOCK (pthread_mutex_unlock(&accMutex)) + +#else +#define VOLATILE +#define GYROLOCK +#define GYROUNLOCK +#define ACCLOCK +#define ACCUNLOCK + +#endif + +static VOLATILE int16_t fakeGyroADC[XYZ_AXIS_COUNT]; static void fakeGyroInit(gyroDev_t *gyro) { UNUSED(gyro); + +#if defined(SITL_BUILD) + pthread_mutex_init(&gyroMutex, NULL); +#endif + + //ENABLE_STATE(ACCELEROMETER_CALIBRATED); } void fakeGyroSet(int16_t x, int16_t y, int16_t z) { + GYROLOCK; fakeGyroADC[X] = x; fakeGyroADC[Y] = y; fakeGyroADC[Z] = z; + GYROUNLOCK; } static bool fakeGyroRead(gyroDev_t *gyro) { + GYROLOCK; gyro->gyroADCRaw[X] = fakeGyroADC[X]; gyro->gyroADCRaw[Y] = fakeGyroADC[Y]; gyro->gyroADCRaw[Z] = fakeGyroADC[Z]; + GYROUNLOCK; return true; } @@ -70,34 +107,38 @@ bool fakeGyroDetect(gyroDev_t *gyro) gyro->intStatusFn = fakeGyroInitStatus; gyro->readFn = fakeGyroRead; gyro->temperatureFn = fakeGyroReadTemperature; - gyro->scale = 1.0f / 16.4f; + gyro->scale = 0.0625f; gyro->gyroAlign = 0; return true; } -#endif // USE_FAKE_GYRO - -#ifdef USE_FAKE_ACC - -static int16_t fakeAccData[XYZ_AXIS_COUNT]; +static VOLATILE int16_t fakeAccData[XYZ_AXIS_COUNT]; static void fakeAccInit(accDev_t *acc) { - UNUSED(acc); +#if defined(SITL_BUILD) + pthread_mutex_init(&accMutex, NULL); +#endif + + acc->acc_1G = 9806; } void fakeAccSet(int16_t x, int16_t y, int16_t z) -{ +{ + ACCLOCK; fakeAccData[X] = x; fakeAccData[Y] = y; fakeAccData[Z] = z; + ACCUNLOCK; } static bool fakeAccRead(accDev_t *acc) { + ACCLOCK; acc->ADCRaw[X] = fakeAccData[X]; acc->ADCRaw[Y] = fakeAccData[Y]; acc->ADCRaw[Z] = fakeAccData[Z]; + ACCUNLOCK; return true; } @@ -108,5 +149,5 @@ bool fakeAccDetect(accDev_t *acc) acc->accAlign = 0; return true; } -#endif // USE_FAKE_ACC +#endif diff --git a/src/main/drivers/accgyro/accgyro_mpu6500.c b/src/main/drivers/accgyro/accgyro_mpu6500.c old mode 100755 new mode 100644 diff --git a/src/main/drivers/accgyro/accgyro_mpu6500.h b/src/main/drivers/accgyro/accgyro_mpu6500.h old mode 100755 new mode 100644 diff --git a/src/main/drivers/accgyro/accgyro_mpu9250.c b/src/main/drivers/accgyro/accgyro_mpu9250.c old mode 100755 new mode 100644 diff --git a/src/main/drivers/accgyro/accgyro_mpu9250.h b/src/main/drivers/accgyro/accgyro_mpu9250.h old mode 100755 new mode 100644 diff --git a/src/main/drivers/adc.c b/src/main/drivers/adc.c index 573c1e69b7..eeb65acfab 100644 --- a/src/main/drivers/adc.c +++ b/src/main/drivers/adc.c @@ -25,9 +25,10 @@ #include "drivers/time.h" #include "common/utils.h" -#ifdef USE_ADC -#include "drivers/io.h" #include "drivers/adc.h" +#if defined(USE_ADC) && !defined(SITL_BUILD) +#include "drivers/io.h" + #include "drivers/adc_impl.h" #ifndef ADC_INSTANCE @@ -206,6 +207,18 @@ uint16_t adcGetChannel(uint8_t channel) #endif #else // USE_ADC + +bool adcIsFunctionAssigned(uint8_t function) +{ + UNUSED(function); + return false; +} + +void adcInit(drv_adc_config_t *init) +{ + UNUSED(init); +} + uint16_t adcGetChannel(uint8_t channel) { UNUSED(channel); diff --git a/src/main/drivers/barometer/barometer_fake.c b/src/main/drivers/barometer/barometer_fake.c index 939089c132..bcab0ce992 100644 --- a/src/main/drivers/barometer/barometer_fake.c +++ b/src/main/drivers/barometer/barometer_fake.c @@ -55,16 +55,16 @@ void fakeBaroSet(int32_t pressure, int32_t temperature) bool fakeBaroDetect(baroDev_t *baro) { - fakePressure = 101325; // pressure in Pa (0m MSL) - fakeTemperature = 2500; // temperature in 0.01 C = 25 deg + fakePressure = 0; // pressure in Pa (0m MSL) + fakeTemperature = 0; // temperature in 0.01 C = 25 deg // these are dummy as temperature is measured as part of pressure - baro->ut_delay = 10000; + baro->ut_delay = 0; baro->get_ut = fakeBaroStartGet; baro->start_ut = fakeBaroStartGet; // only _up part is executed, and gets both temperature and pressure - baro->up_delay = 10000; + baro->up_delay = 1000; baro->start_up = fakeBaroStartGet; baro->get_up = fakeBaroStartGet; baro->calculate = fakeBaroCalculate; diff --git a/src/main/drivers/bus.c b/src/main/drivers/bus.c old mode 100755 new mode 100644 index f06e847d57..3b003b8caf --- a/src/main/drivers/bus.c +++ b/src/main/drivers/bus.c @@ -66,10 +66,12 @@ static void busDevPreInit(const busDeviceDescriptor_t * descriptor) void busInit(void) { +#if !defined(SITL_BUILD) /* Pre-initialize bus devices */ for (const busDeviceDescriptor_t * descriptor = __busdev_registry_start; (descriptor) < __busdev_registry_end; descriptor++) { busDevPreInit(descriptor); } +#endif } #ifdef USE_I2C @@ -113,6 +115,11 @@ void busDeviceDeInit(busDevice_t * dev) busDevice_t * busDeviceInit(busType_e bus, devHardwareType_e hw, uint8_t tag, resourceOwner_e owner) { UNUSED(owner); +#if defined(SITL_BUILD) + UNUSED(bus); + UNUSED(hw); + UNUSED(tag); +#else for (const busDeviceDescriptor_t * descriptor = __busdev_registry_start; (descriptor) < __busdev_registry_end; descriptor++) { if (hw == descriptor->devHwType && (bus == descriptor->busType || bus == BUSTYPE_ANY) && (tag == descriptor->tag)) { @@ -163,12 +170,17 @@ busDevice_t * busDeviceInit(busType_e bus, devHardwareType_e hw, uint8_t tag, re } } } - +#endif return NULL; } busDevice_t * busDeviceOpen(busType_e bus, devHardwareType_e hw, uint8_t tag) { +#if defined(SITL_BUILD) + UNUSED(bus); + UNUSED(hw); + UNUSED(tag); +#else for (const busDeviceDescriptor_t * descriptor = __busdev_registry_start; (descriptor) < __busdev_registry_end; descriptor++) { if (hw == descriptor->devHwType && (bus == descriptor->busType || bus == BUSTYPE_ANY) && (tag == descriptor->tag)) { // Found a hardware descriptor. Now check if device context is valid @@ -178,7 +190,7 @@ busDevice_t * busDeviceOpen(busType_e bus, devHardwareType_e hw, uint8_t tag) } } } - +#endif return NULL; } @@ -258,6 +270,12 @@ bool busTransferMultiple(const busDevice_t * dev, busTransferDescriptor_t * dsc, bool busWriteBuf(const busDevice_t * dev, uint8_t reg, const uint8_t * data, uint8_t length) { +#if !defined(USE_SPI) && !defined(USE_I2C) + UNUSED(reg); + UNUSED(data); + UNUSED(length); +#endif + switch (dev->busType) { case BUSTYPE_SPI: #ifdef USE_SPI @@ -285,6 +303,11 @@ bool busWriteBuf(const busDevice_t * dev, uint8_t reg, const uint8_t * data, uin bool busWrite(const busDevice_t * dev, uint8_t reg, uint8_t data) { +#if !defined(USE_SPI) && !defined(USE_I2C) + UNUSED(reg); + UNUSED(data); +#endif + switch (dev->busType) { case BUSTYPE_SPI: #ifdef USE_SPI @@ -312,6 +335,11 @@ bool busWrite(const busDevice_t * dev, uint8_t reg, uint8_t data) bool busReadBuf(const busDevice_t * dev, uint8_t reg, uint8_t * data, uint8_t length) { +#if !defined(USE_SPI) && !defined(USE_I2C) + UNUSED(reg); + UNUSED(data); + UNUSED(length); +#endif switch (dev->busType) { case BUSTYPE_SPI: #ifdef USE_SPI @@ -339,6 +367,11 @@ bool busReadBuf(const busDevice_t * dev, uint8_t reg, uint8_t * data, uint8_t le bool busRead(const busDevice_t * dev, uint8_t reg, uint8_t * data) { +#if !defined(USE_SPI) && !defined(USE_I2C) + UNUSED(reg); + UNUSED(data); +#endif + switch (dev->busType) { case BUSTYPE_SPI: #ifdef USE_SPI diff --git a/src/main/drivers/bus.h b/src/main/drivers/bus.h old mode 100755 new mode 100644 diff --git a/src/main/drivers/bus_busdev_i2c.c b/src/main/drivers/bus_busdev_i2c.c old mode 100755 new mode 100644 diff --git a/src/main/drivers/bus_busdev_spi.c b/src/main/drivers/bus_busdev_spi.c old mode 100755 new mode 100644 diff --git a/src/main/drivers/compass/compass_ak8963.c b/src/main/drivers/compass/compass_ak8963.c old mode 100755 new mode 100644 diff --git a/src/main/drivers/compass/compass_ak8963.h b/src/main/drivers/compass/compass_ak8963.h old mode 100755 new mode 100644 diff --git a/src/main/drivers/compass/compass_mag3110.c b/src/main/drivers/compass/compass_mag3110.c old mode 100755 new mode 100644 diff --git a/src/main/drivers/compass/compass_mag3110.h b/src/main/drivers/compass/compass_mag3110.h old mode 100755 new mode 100644 diff --git a/src/main/drivers/compass/compass_mpu9250.c b/src/main/drivers/compass/compass_mpu9250.c old mode 100755 new mode 100644 diff --git a/src/main/drivers/compass/compass_mpu9250.h b/src/main/drivers/compass/compass_mpu9250.h old mode 100755 new mode 100644 diff --git a/src/main/drivers/compass/compass_qmc5883l.c b/src/main/drivers/compass/compass_qmc5883l.c old mode 100755 new mode 100644 diff --git a/src/main/drivers/compass/compass_qmc5883l.h b/src/main/drivers/compass/compass_qmc5883l.h old mode 100755 new mode 100644 diff --git a/src/main/drivers/display.c b/src/main/drivers/display.c index 28bbd88133..55e15ff043 100644 --- a/src/main/drivers/display.c +++ b/src/main/drivers/display.c @@ -179,7 +179,7 @@ int displayWriteChar(displayPort_t *instance, uint8_t x, uint8_t y, uint16_t c) } #ifdef USE_SIMULATOR - if (ARMING_FLAG(SIMULATOR_MODE)) { + if (ARMING_FLAG(SIMULATOR_MODE_HITL)) { //some FCs do not power max7456 from USB power //driver can not read font metadata //chip assumed to not support second bank of font diff --git a/src/main/drivers/exti.c b/src/main/drivers/exti.c index bc7b3400f6..27f2294065 100644 --- a/src/main/drivers/exti.c +++ b/src/main/drivers/exti.c @@ -4,6 +4,8 @@ #include "platform.h" +#if !defined(SITL_BUILD) + #include "build/assert.h" #include "drivers/exti.h" @@ -197,4 +199,6 @@ _EXTI_IRQ_HANDLER(EXTI2_TS_IRQHandler); _EXTI_IRQ_HANDLER(EXTI3_IRQHandler); _EXTI_IRQ_HANDLER(EXTI4_IRQHandler); _EXTI_IRQ_HANDLER(EXTI9_5_IRQHandler); -_EXTI_IRQ_HANDLER(EXTI15_10_IRQHandler); \ No newline at end of file +_EXTI_IRQ_HANDLER(EXTI15_10_IRQHandler); + +#endif diff --git a/src/main/drivers/io.c b/src/main/drivers/io.c index fe89596317..4a77d3a9f3 100644 --- a/src/main/drivers/io.c +++ b/src/main/drivers/io.c @@ -128,6 +128,8 @@ uint32_t IO_EXTI_Line(IO_t io) } #if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) return 1 << IO_GPIOPinIdx(io); +#elif defined (SITL_BUILD) + return 0; #else # error "Unknown target type" #endif @@ -334,8 +336,14 @@ void IOConfigGPIOAF(IO_t io, ioConfig_t cfg, uint8_t af) } #endif +#if DEFIO_PORT_USED_COUNT > 0 static const uint16_t ioDefUsedMask[DEFIO_PORT_USED_COUNT] = { DEFIO_PORT_USED_LIST }; static const uint8_t ioDefUsedOffset[DEFIO_PORT_USED_COUNT] = { DEFIO_PORT_OFFSET_LIST }; +#else +// Avoid -Wpedantic warning +static const uint16_t ioDefUsedMask[1] = {0}; +static const uint8_t ioDefUsedOffset[1] = {0}; +#endif ioRec_t ioRecs[DEFIO_IO_USED_COUNT]; // initialize all ioRec_t structures from ROM diff --git a/src/main/drivers/io.h b/src/main/drivers/io.h index 27c0b3827b..5b7025414a 100644 --- a/src/main/drivers/io.h +++ b/src/main/drivers/io.h @@ -70,7 +70,7 @@ #define IOCFG_IN_FLOATING IO_CONFIG(GPIO_Mode_IN, 0, 0, GPIO_PuPd_NOPULL) #define IOCFG_IPU_25 IO_CONFIG(GPIO_Mode_IN, GPIO_Speed_25MHz, 0, GPIO_PuPd_UP) -#elif defined(UNIT_TEST) +#elif defined(UNIT_TEST) || defined(SITL_BUILD) # define IOCFG_OUT_PP 0 # define IOCFG_OUT_OD 0 diff --git a/src/main/drivers/io_def_generated.h b/src/main/drivers/io_def_generated.h index a1f0fc3114..580837d73f 100644 --- a/src/main/drivers/io_def_generated.h +++ b/src/main/drivers/io_def_generated.h @@ -1134,7 +1134,9 @@ #endif #if !defined DEFIO_PORT_USED_LIST -# warning "No pins are defined. Maybe you forgot to define TARGET_IO_PORTx in target_io.h" +# if !defined DEFIO_NO_PORTS +# warning "No pins are defined. Maybe you forgot to define TARGET_IO_PORTx in target_io.h" +# endif # define DEFIO_PORT_USED_COUNT 0 # define DEFIO_PORT_USED_LIST /* empty */ # define DEFIO_PORT_OFFSET_LIST /* empty */ diff --git a/src/main/drivers/logging_codes.h b/src/main/drivers/logging_codes.h old mode 100755 new mode 100644 diff --git a/src/main/drivers/opflow/opflow.h b/src/main/drivers/opflow/opflow.h old mode 100755 new mode 100644 diff --git a/src/main/drivers/opflow/opflow_fake.c b/src/main/drivers/opflow/opflow_fake.c old mode 100755 new mode 100644 diff --git a/src/main/drivers/opflow/opflow_fake.h b/src/main/drivers/opflow/opflow_fake.h old mode 100755 new mode 100644 diff --git a/src/main/drivers/opflow/opflow_virtual.c b/src/main/drivers/opflow/opflow_virtual.c old mode 100755 new mode 100644 diff --git a/src/main/drivers/opflow/opflow_virtual.h b/src/main/drivers/opflow/opflow_virtual.h old mode 100755 new mode 100644 diff --git a/src/main/drivers/pitotmeter/pitotmeter_fake.c b/src/main/drivers/pitotmeter/pitotmeter_fake.c index 5d3c56c4e6..f913b76d09 100644 --- a/src/main/drivers/pitotmeter/pitotmeter_fake.c +++ b/src/main/drivers/pitotmeter/pitotmeter_fake.c @@ -24,21 +24,40 @@ #include "common/utils.h" -#include "pitotmeter.h" -#include "pitotmeter_fake.h" +#include "drivers/pitotmeter/pitotmeter.h" +#include "drivers/pitotmeter/pitotmeter_fake.h" #ifdef USE_PITOT_FAKE -static int32_t fakePressure; -static int32_t fakeTemperature; +static float fakePressure; +static float fakeTemperature; +static float fakeAirspeed; -static void fakePitotStart(pitotDev_t *pitot) +static bool fakePitotStart(pitotDev_t *pitot) { UNUSED(pitot); + return true; } -static void fakePitotRead(pitotDev_t *pitot) +void fakePitotSet(float pressure, float temperature) { - UNUSED(pitot); + fakePressure = pressure; + fakeTemperature = temperature; +} + +void fakePitotSetAirspeed(float airSpeed) +{ + fakeAirspeed = airSpeed; +} + +float fakePitotGetAirspeed(void) +{ + return fakeAirspeed; +} + +bool fakePitotRead(pitotDev_t *pitot) +{ + pitot->calculate(pitot, &fakePressure, &fakeTemperature); + return true; } static void fakePitotCalculate(pitotDev_t *pitot, float *pressure, float *temperature) diff --git a/src/main/drivers/pitotmeter/pitotmeter_fake.h b/src/main/drivers/pitotmeter/pitotmeter_fake.h index 3eeb4828c3..f9fa78fcd2 100644 --- a/src/main/drivers/pitotmeter/pitotmeter_fake.h +++ b/src/main/drivers/pitotmeter/pitotmeter_fake.h @@ -17,4 +17,10 @@ #pragma once +#include "drivers/pitotmeter/pitotmeter.h" + bool fakePitotDetect(pitotDev_t *pitot); +void fakePitotSetAirspeed(float airSpeed); +float fakePitotGetAirspeed(void); +void fakePitotSet(float pressure, float temperature); +bool fakePitotRead(pitotDev_t *pitot); diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index 1d3ab1b584..eb14d6772b 100644 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -21,6 +21,8 @@ #include "platform.h" +#if !defined(SITL_BUILD) + #include "build/debug.h" #include "common/log.h" #include "common/memory.h" @@ -396,3 +398,5 @@ bool pwmMotorAndServoInit(void) return (pwmInitError == PWM_INIT_ERROR_NONE); } + +#endif diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index 658c3f5cb5..beb7b8d178 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -22,6 +22,8 @@ #include "platform.h" +#if !defined(SITL_BUILD) + FILE_COMPILE_FOR_SPEED #include "build/debug.h" @@ -635,3 +637,5 @@ void beeperPwmInit(ioTag_t tag, uint16_t frequency) pwmOutConfigTimer(beeperPwm, tch, PWM_TIMER_HZ, 1000000 / beeperFrequency, (1000000 / beeperFrequency) / 2); } } + +#endif diff --git a/src/main/drivers/rangefinder/rangefinder_vl53l0x.c b/src/main/drivers/rangefinder/rangefinder_vl53l0x.c old mode 100755 new mode 100644 diff --git a/src/main/drivers/rangefinder/rangefinder_vl53l0x.h b/src/main/drivers/rangefinder/rangefinder_vl53l0x.h old mode 100755 new mode 100644 diff --git a/src/main/drivers/serial_tcp.c b/src/main/drivers/serial_tcp.c new file mode 100644 index 0000000000..88480748d4 --- /dev/null +++ b/src/main/drivers/serial_tcp.c @@ -0,0 +1,307 @@ +/* + * This file is part of INAV. + * + * INAV is free software. You can redistribute this software + * and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * INAV is distributed in the hope that they will be + * useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "platform.h" + +#if defined(SITL_BUILD) + +#include +#include + +#include "common/utils.h" + +#include "drivers/serial.h" +#include "drivers/serial_tcp.h" + +static const struct serialPortVTable tcpVTable[]; +static tcpPort_t tcpPorts[SERIAL_PORT_COUNT]; +static bool tcpThreadRunning = false; + +static void *tcpReceiveThread(void* arg) +{ + tcpPort_t *port = (tcpPort_t*)arg; + + while(tcpThreadRunning) { + if (tcpReceive(port) < 0) { + break; + } + } + + return NULL; +} + +static tcpPort_t *tcpReConfigure(tcpPort_t *port, uint32_t id) +{ + if (port->isInitalized){ + return port; + } + + if (pthread_mutex_init(&port->receiveMutex, NULL) != 0){ + return NULL; + } + + port->socketFd = socket(AF_INET, SOCK_STREAM, IPPROTO_TCP); + if (port->socketFd < 0) { + fprintf(stderr, "[SOCKET] Unable to create tcp socket\n"); + return NULL; + } + + int one = 1; + int err = 0; + err = setsockopt(port->socketFd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one)); + err = fcntl(port->socketFd, F_SETFL, fcntl(port->socketFd, F_GETFL, 0) | O_NONBLOCK); + + if (err < 0){ + fprintf(stderr, "[SOCKET] Unable to set socket options\n"); + return NULL; + } + + uint16_t tcpPort = BASE_IP_ADDRESS + id - 1; + port->sockAddress.sin_family = AF_INET; + port->sockAddress.sin_port = htons(tcpPort); + port->sockAddress.sin_addr.s_addr = INADDR_ANY; + port->isClientConnected = false; + port->id = id; + + if (bind(port->socketFd, (struct sockaddr*)&port->sockAddress, sizeof(port->sockAddress)) < 0) { + fprintf(stderr, "[SOCKET] Unable to bind socket\n"); + return NULL; + } + + if (listen(port->socketFd, 100) < 0) { + fprintf(stderr, "[SOCKET] Unable to listen.\n"); + return NULL; + } + + fprintf(stderr, "[SOCKET] Bind TCP port %d to UART%d\n", tcpPort, id); + + return port; +} + +static char *tcpGetAddressString(struct sockaddr *addr) +{ + return inet_ntoa(((struct sockaddr_in *)addr)->sin_addr); +} + +int tcpReceive(tcpPort_t *port) +{ + if (!port->isClientConnected) { + + fd_set fds; + + FD_ZERO(&fds); + FD_SET(port->socketFd, &fds); + + if (select(port->socketFd + 1, &fds, NULL, NULL, NULL) < 0) { + fprintf(stderr, "[SOCKET] Unable to wait for connection.\n"); + return -1; + } + + socklen_t addrLen = sizeof(port->sockAddress); + port->clientSocketFd = accept(port->socketFd, &port->clientAddress, &addrLen); + if (port->clientSocketFd < 1) { + fprintf(stderr, "[SOCKET] Can't accept connection.\n"); + return -1; + } + + fprintf(stderr, "[SOCKET] %s connected to UART%d\n", tcpGetAddressString(&port->clientAddress), port->id); + port->isClientConnected = true; + } + + uint8_t buffer[TCP_BUFFER_SIZE]; + ssize_t recvSize = recv(port->clientSocketFd, buffer, TCP_BUFFER_SIZE, 0); + + // Disconnect + if (port->isClientConnected && recvSize == 0) + { + fprintf(stderr, "[SOCKET] %s disconnected from UART%d\n", tcpGetAddressString(&port->clientAddress), port->id); + close(port->clientSocketFd); + memset(&port->clientAddress, 0, sizeof(port->clientAddress)); + port->isClientConnected = false; + + return 0; + } + + for (ssize_t i = 0; i < recvSize; i++) { + + if (port->serialPort.rxCallback) { + port->serialPort.rxCallback((uint16_t)buffer[i], port->serialPort.rxCallbackData); + } else { + pthread_mutex_lock(&port->receiveMutex); + port->serialPort.rxBuffer[port->serialPort.rxBufferHead] = buffer[i]; + port->serialPort.rxBufferHead = (port->serialPort.rxBufferHead + 1) % port->serialPort.rxBufferSize; + pthread_mutex_unlock(&port->receiveMutex); + } + } + + if (recvSize < 0) { + recvSize = 0; + } + + return (int)recvSize; +} + +serialPort_t *tcpOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, void *rxCallbackData, uint32_t baudRate, portMode_t mode, portOptions_t options) +{ + tcpPort_t *port = NULL; + +#if defined(USE_UART1) || defined(USE_UART2) || defined(USE_UART3) || defined(USE_UART4) || defined(USE_UART5) || defined(USE_UART6) || defined(USE_UART7) || defined(USE_UART8) + uint32_t id = (uintptr_t)USARTx; + if (id < SERIAL_PORT_COUNT) { + port = tcpReConfigure(&tcpPorts[id], id); + } +#endif + + if (port == NULL) { + return NULL; + + } + + port->serialPort.vTable = tcpVTable; + port->serialPort.rxCallback = callback; + port->serialPort.rxCallbackData = rxCallbackData; + port->serialPort.rxBufferHead = port->serialPort.rxBufferTail = 0; + port->serialPort.rxBufferSize = TCP_BUFFER_SIZE; + port->serialPort.rxBuffer = port->rxBuffer; + port->serialPort.mode = mode; + port->serialPort.baudRate = baudRate; + port->serialPort.options = options; + + int err = pthread_create(&port->receiveThread, NULL, tcpReceiveThread, (void*)port); + if (err < 0){ + fprintf(stderr, "[SOCKET] Unable to create receive thread for UART%d\n", id); + return NULL; + } + tcpThreadRunning = true; + + return (serialPort_t*)port; +} + +uint8_t tcpRead(serialPort_t *instance) +{ + uint8_t ch; + tcpPort_t *port = (tcpPort_t*)instance; + pthread_mutex_lock(&port->receiveMutex); + + ch = port->serialPort.rxBuffer[port->serialPort.rxBufferTail]; + port->serialPort.rxBufferTail = (port->serialPort.rxBufferTail + 1) % port->serialPort.rxBufferSize; + + pthread_mutex_unlock(&port->receiveMutex); + + return ch; +} + +void tcpWritBuf(serialPort_t *instance, const void *data, int count) +{ + tcpPort_t *port = (tcpPort_t*)instance; + + if (!port->isClientConnected) { + return; + } + + send(port->clientSocketFd, data, count, 0); +} + +void tcpWrite(serialPort_t *instance, uint8_t ch) +{ + tcpWritBuf(instance, (void*)&ch, 1); +} + +uint32_t tcpTotalRxBytesWaiting(const serialPort_t *instance) +{ + tcpPort_t *port = (tcpPort_t*)instance; + uint32_t count; + + pthread_mutex_lock(&port->receiveMutex); + + if (port->serialPort.rxBufferHead >= port->serialPort.rxBufferTail) { + count = port->serialPort.rxBufferHead - port->serialPort.rxBufferTail; + } else { + count = port->serialPort.rxBufferSize + port->serialPort.rxBufferHead - port->serialPort.rxBufferTail; + } + + pthread_mutex_unlock(&port->receiveMutex); + + return count; +} + +uint32_t tcpTotalTxBytesFree(const serialPort_t *instance) +{ + tcpPort_t *port = (tcpPort_t*)instance; + + if (port->isClientConnected) { + return TCP_MAX_PACKET_SIZE; + } else { + return 0; + } +} + +bool isTcpTransmitBufferEmpty(const serialPort_t *instance) +{ + UNUSED(instance); + + return true; +} + +bool tcpIsConnected(const serialPort_t *instance) +{ + return ((tcpPort_t*)instance)->isClientConnected; +} + +void tcpSetBaudRate(serialPort_t *instance, uint32_t baudRate) +{ + UNUSED(instance); + UNUSED(baudRate); +} + + +void tcpSetMode(serialPort_t *instance, portMode_t mode) +{ + UNUSED(instance); + UNUSED(mode); +} + +static const struct serialPortVTable tcpVTable[] = { + { + .serialWrite = tcpWrite, + .serialTotalRxWaiting = tcpTotalRxBytesWaiting, + .serialTotalTxFree = tcpTotalTxBytesFree, + .serialRead = tcpRead, + .serialSetBaudRate = tcpSetBaudRate, + .isSerialTransmitBufferEmpty = isTcpTransmitBufferEmpty, + .setMode = tcpSetMode, + .isConnected = tcpIsConnected, + .writeBuf = tcpWritBuf, + .beginWrite = NULL, + .endWrite = NULL, + .isIdle = NULL, + } +}; + +#endif diff --git a/src/main/drivers/serial_tcp.h b/src/main/drivers/serial_tcp.h new file mode 100644 index 0000000000..a73e797379 --- /dev/null +++ b/src/main/drivers/serial_tcp.h @@ -0,0 +1,51 @@ +/* + * This file is part of INAV. + * + * INAV is free software. You can redistribute this software + * and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * INAV is distributed in the hope that they will be + * useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#pragma once + +#include +#include + +#define BASE_IP_ADDRESS 5760 +#define TCP_BUFFER_SIZE 2048 +#define TCP_MAX_PACKET_SIZE 65535 + +typedef struct +{ + serialPort_t serialPort; + + uint8_t rxBuffer[TCP_BUFFER_SIZE]; + + uint8_t id; + bool isInitalized; + pthread_mutex_t receiveMutex; + pthread_t receiveThread; + int socketFd; + int clientSocketFd; + struct sockaddr_in sockAddress; + struct sockaddr clientAddress; + bool isClientConnected; +} tcpPort_t; + + +serialPort_t *tcpOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, void *rxCallbackData, uint32_t baudRate, portMode_t mode, portOptions_t options); + +void tcpSend(tcpPort_t *port); +int tcpReceive(tcpPort_t *port); diff --git a/src/main/drivers/sound_beeper.c b/src/main/drivers/sound_beeper.c index bb089b4cb9..6577b26d5a 100644 --- a/src/main/drivers/sound_beeper.c +++ b/src/main/drivers/sound_beeper.c @@ -47,7 +47,7 @@ void systemBeep(bool onoff) #else #ifdef USE_SIMULATOR - if (ARMING_FLAG(SIMULATOR_MODE)) { + if (ARMING_FLAG(SIMULATOR_MODE_HITL)) { if (SIMULATOR_HAS_OPTION(HITL_MUTE_BEEPER)) { onoff = false; } diff --git a/src/main/drivers/stack_check.c b/src/main/drivers/stack_check.c index bf4a561ddc..f86d82d38e 100644 --- a/src/main/drivers/stack_check.c +++ b/src/main/drivers/stack_check.c @@ -77,6 +77,8 @@ uint32_t stackUsedSize(void) } #endif +#if !defined(SITL_BUILD) + uint32_t stackTotalSize(void) { return (uint32_t)&_Min_Stack_Size; @@ -86,3 +88,5 @@ uint32_t stackHighMem(void) { return (uint32_t)&_estack; } + +#endif diff --git a/src/main/drivers/stack_check.h b/src/main/drivers/stack_check.h old mode 100755 new mode 100644 diff --git a/src/main/drivers/timer.c b/src/main/drivers/timer.c old mode 100755 new mode 100644 diff --git a/src/main/drivers/timer.h b/src/main/drivers/timer.h index d1cc3cc16e..9f2612e72a 100644 --- a/src/main/drivers/timer.h +++ b/src/main/drivers/timer.h @@ -39,6 +39,11 @@ typedef uint32_t timCCR_t; typedef uint32_t timCCER_t; typedef uint32_t timSR_t; typedef uint32_t timCNT_t; +#elif defined(SITL_BUILD) +typedef uint32_t timCCR_t; +typedef uint32_t timCCER_t; +typedef uint32_t timSR_t; +typedef uint32_t timCNT_t; #else #error "Unknown CPU defined" #endif @@ -49,6 +54,8 @@ typedef uint32_t timCNT_t; #define HARDWARE_TIMER_DEFINITION_COUNT 14 #elif defined(STM32H7) #define HARDWARE_TIMER_DEFINITION_COUNT 14 +#elif defined(SITL_BUILD) +#define HARDWARE_TIMER_DEFINITION_COUNT 0 #else #error "Unknown CPU defined" #endif diff --git a/src/main/drivers/timer_def.h b/src/main/drivers/timer_def.h index e8c8afad27..7fcb152610 100644 --- a/src/main/drivers/timer_def.h +++ b/src/main/drivers/timer_def.h @@ -82,6 +82,7 @@ #include "timer_def_stm32f7xx.h" #elif defined(STM32H7) #include "timer_def_stm32h7xx.h" +#elif defined(SITL_BUILD) #else #error "Unknown CPU defined" #endif diff --git a/src/main/drivers/usb_msc.c b/src/main/drivers/usb_msc.c index 3b3904dd91..7004e7efde 100644 --- a/src/main/drivers/usb_msc.c +++ b/src/main/drivers/usb_msc.c @@ -21,7 +21,11 @@ #include "drivers/persistent.h" #include +#ifdef USE_USB_MSC + bool mscCheckBoot(void) { return (persistentObjectRead(PERSISTENT_OBJECT_RESET_REASON) == RESET_MSC_REQUEST); } + +#endif \ No newline at end of file diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index e1633983b0..297d6e6506 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -3307,6 +3307,7 @@ static void cliStatus(char *cmdline) } cliPrintLinefeed(); +#if !defined(SITL_BUILD) cliPrintLine("STM32 system clocks:"); #if defined(USE_HAL_DRIVER) cliPrintLinef(" SYSCLK = %d MHz", HAL_RCC_GetSysClockFreq() / 1000000); @@ -3320,6 +3321,7 @@ static void cliStatus(char *cmdline) cliPrintLinef(" HCLK = %d MHz", clocks.HCLK_Frequency / 1000000); cliPrintLinef(" PCLK1 = %d MHz", clocks.PCLK1_Frequency / 1000000); cliPrintLinef(" PCLK2 = %d MHz", clocks.PCLK2_Frequency / 1000000); +#endif #endif cliPrintLinef("Sensor status: GYRO=%s, ACC=%s, MAG=%s, BARO=%s, RANGEFINDER=%s, OPFLOW=%s, GPS=%s", @@ -3349,18 +3351,19 @@ static void cliStatus(char *cmdline) #endif #ifdef USE_I2C const uint16_t i2cErrorCounter = i2cGetErrorCounter(); -#else +#elif !defined(SITL_BUILD) const uint16_t i2cErrorCounter = 0; #endif #ifdef STACK_CHECK cliPrintf("Stack used: %d, ", stackUsedSize()); #endif +#if !defined(SITL_BUILD) cliPrintLinef("Stack size: %d, Stack address: 0x%x, Heap available: %d", stackTotalSize(), stackHighMem(), memGetAvailableBytes()); cliPrintLinef("I2C Errors: %d, config size: %d, max available config: %d", i2cErrorCounter, getEEPROMConfigSize(), &__config_end - &__config_start); - -#ifdef USE_ADC +#endif +#if defined(USE_ADC) && !defined(SITL_BUILD) static char * adcFunctions[] = { "BATTERY", "RSSI", "CURRENT", "AIRSPEED" }; cliPrintLine("ADC channel usage:"); for (int i = 0; i < ADC_FUNCTION_COUNT; i++) { @@ -3515,7 +3518,7 @@ static void cliResource(char *cmdline) { UNUSED(cmdline); cliPrintLinef("IO:\r\n----------------------"); - for (unsigned i = 0; i < DEFIO_IO_USED_COUNT; i++) { + for (int i = 0; i < DEFIO_IO_USED_COUNT; i++) { const char* owner; owner = ownerNames[ioRecs[i].owner]; diff --git a/src/main/fc/config.c b/src/main/fc/config.c index 3c6a09c688..aaef4a75a0 100755 --- a/src/main/fc/config.c +++ b/src/main/fc/config.c @@ -159,12 +159,16 @@ void validateNavConfig(void) // Stubs to handle target-specific configs __attribute__((weak)) void validateAndFixTargetConfig(void) { +#if !defined(SITL_BUILD) __NOP(); +#endif } __attribute__((weak)) void targetConfiguration(void) { +#if !defined(SITL_BUILD) __NOP(); +#endif } #ifdef SWAP_SERIAL_PORT_0_AND_1_DEFAULTS diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index 729439aa5a..620ec5203b 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -827,6 +827,7 @@ static float calculateThrottleTiltCompensationFactor(uint8_t throttleTiltCompens void taskMainPidLoop(timeUs_t currentTimeUs) { + cycleTime = getTaskDeltaTime(TASK_SELF); dT = (float)cycleTime * 0.000001f; @@ -842,11 +843,19 @@ void taskMainPidLoop(timeUs_t currentTimeUs) processDelayedSave(); } +#if defined(SITL_BUILD) + if (lockMainPID()) { +#endif + gyroFilter(); imuUpdateAccelerometer(); imuUpdateAttitude(currentTimeUs); +#if defined(SITL_BUILD) + } +#endif + processPilotAndFailSafeActions(dT); updateArmingStatus(); @@ -902,8 +911,8 @@ void taskMainPidLoop(timeUs_t currentTimeUs) //Servos should be filtered or written only when mixer is using servos or special feaures are enabled -#ifdef USE_SMULATOR - if (!ARMING_FLAG(SIMULATOR_MODE)) { +#ifdef USE_SIMULATOR + if (!ARMING_FLAG(SIMULATOR_MODE_HITL)) { if (isServoOutputEnabled()) { writeServos(); } diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c index a8ab8146d2..8153a9ff9c 100644 --- a/src/main/fc/fc_init.c +++ b/src/main/fc/fc_init.c @@ -199,7 +199,9 @@ void init(void) // Initialize system and CPU clocks to their initial values systemInit(); +#if !defined(SITL_BUILD) __enable_irq(); +#endif // initialize IO (needed for all IO operations) IOInitGlobal(); @@ -246,8 +248,9 @@ void init(void) latchActiveFeatures(); ledInit(false); - +#if !defined(SITL_BUILD) EXTIInit(); +#endif #ifdef USE_SPEKTRUM_BIND if (rxConfig()->receiverType == RX_TYPE_SERIAL) { @@ -309,7 +312,7 @@ void init(void) if (!STATE(ALTITUDE_CONTROL)) { featureClear(FEATURE_AIRMODE); } - +#if !defined(SITL_BUILD) // Initialize motor and servo outpus if (pwmMotorAndServoInit()) { DISABLE_ARMING_FLAG(ARMING_DISABLED_PWM_OUTPUT_ERROR); @@ -317,7 +320,9 @@ void init(void) else { ENABLE_ARMING_FLAG(ARMING_DISABLED_PWM_OUTPUT_ERROR); } - +#else + DISABLE_ARMING_FLAG(ARMING_DISABLED_PWM_OUTPUT_ERROR); +#endif systemState |= SYSTEM_STATE_MOTORS_READY; #ifdef USE_ESC_SENSOR @@ -700,8 +705,10 @@ void init(void) powerLimiterInit(); #endif +#if !defined(SITL_BUILD) // Considering that the persistent reset reason is only used during init persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_NONE); +#endif systemState |= SYSTEM_STATE_READY; } diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index ee5c8f0397..84a3aede8c 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -46,6 +46,11 @@ #include "drivers/compass/compass_msp.h" #include "drivers/barometer/barometer_msp.h" #include "drivers/pitotmeter/pitotmeter_msp.h" +#include "drivers/accgyro/accgyro_fake.h" +#include "drivers/barometer/barometer_fake.h" +#include "drivers/compass/compass_fake.h" +#include "sensors/battery_sensor_fake.h" +#include "drivers/pitotmeter/pitotmeter_fake.h" #include "drivers/bus_i2c.h" #include "drivers/display.h" #include "drivers/flash.h" @@ -1389,6 +1394,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF break; case MSP_VTX_CONFIG: +#ifdef USE_VTX_CONTROL { vtxDevice_t *vtxDevice = vtxCommonDevice(); if (vtxDevice) { @@ -1415,6 +1421,9 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU8(dst, VTXDEV_UNKNOWN); // no VTX configured } } +#else + sbufWriteU8(dst, VTXDEV_UNKNOWN); // no VTX configured +#endif break; case MSP_NAME: @@ -2443,6 +2452,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) break; #endif // USE_OSD +#ifdef USE_VTX_CONTROL case MSP_SET_VTX_CONFIG: if (dataSize >= 2) { vtxDevice_t *vtxDevice = vtxCommonDevice(); @@ -2476,6 +2486,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) return MSP_RESULT_ERROR; } break; +#endif #ifdef USE_FLASHFS case MSP_DATAFLASH_ERASE: @@ -3444,8 +3455,8 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu if (!SIMULATOR_HAS_OPTION(HITL_ENABLE)) { - if (ARMING_FLAG(SIMULATOR_MODE)) { // Just once - DISABLE_ARMING_FLAG(SIMULATOR_MODE); + if (ARMING_FLAG(SIMULATOR_MODE_HITL)) { // Just once + DISABLE_ARMING_FLAG(SIMULATOR_MODE_HITL); #ifdef USE_BARO baroStartCalibration(); @@ -3458,9 +3469,9 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu // Review: Many states were affected. Reboot? disarm(DISARM_SWITCH); // Disarm to prevent motor output!!! - } + } } else if (!areSensorsCalibrating()) { - if (!ARMING_FLAG(SIMULATOR_MODE)) { // Just once + if (!ARMING_FLAG(SIMULATOR_MODE_HITL)) { // Just once #ifdef USE_BARO baroStartCalibration(); #endif @@ -3475,7 +3486,7 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu mag.magADC[Z] = 0; } #endif - ENABLE_ARMING_FLAG(SIMULATOR_MODE); + ENABLE_ARMING_FLAG(SIMULATOR_MODE_HITL); LOG_DEBUG(SYSTEM, "Simulator enabled"); } @@ -3552,9 +3563,9 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu } if (SIMULATOR_HAS_OPTION(HITL_EXT_BATTERY_VOLTAGE)) { - simulatorData.vbat = sbufReadU8(src); + fakeBattSensorSetVbat(sbufReadU8(src) * 10); } else { - simulatorData.vbat = (uint8_t)(SIMULATOR_FULL_BATTERY * 10.0f); + fakeBattSensorSetVbat((uint16_t)(SIMULATOR_FULL_BATTERY * 10.0f)); } if (SIMULATOR_HAS_OPTION(HITL_AIRSPEED)) { diff --git a/src/main/fc/fc_tasks.c b/src/main/fc/fc_tasks.c index 0e0b8c5432..1830c49e79 100755 --- a/src/main/fc/fc_tasks.c +++ b/src/main/fc/fc_tasks.c @@ -306,7 +306,7 @@ void taskUpdateAux(timeUs_t currentTimeUs) updatePIDCoefficients(); dynamicLpfGyroTask(); #ifdef USE_SIMULATOR - if (!ARMING_FLAG(SIMULATOR_MODE)) { + if (!ARMING_FLAG(SIMULATOR_MODE_HITL)) { updateFixedWingLevelTrim(currentTimeUs); } #else diff --git a/src/main/fc/runtime_config.h b/src/main/fc/runtime_config.h index 9333fd62c1..a4e613ed72 100644 --- a/src/main/fc/runtime_config.h +++ b/src/main/fc/runtime_config.h @@ -21,7 +21,8 @@ typedef enum { ARMED = (1 << 2), WAS_EVER_ARMED = (1 << 3), - SIMULATOR_MODE = (1 << 4), + SIMULATOR_MODE_HITL = (1 << 4), + SIMULATOR_MODE_SITL = (1 << 5), ARMING_DISABLED_FAILSAFE_SYSTEM = (1 << 7), ARMING_DISABLED_NOT_LEVEL = (1 << 8), diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index ee5d5b2fa5..08c64e5088 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -35,16 +35,16 @@ tables: - name: failsafe_procedure values: ["LAND", "DROP", "RTH", "NONE"] - name: current_sensor - values: ["NONE", "ADC", "VIRTUAL", "ESC"] + values: ["NONE", "ADC", "VIRTUAL", "FAKE", "ESC"] enum: currentSensor_e - name: voltage_sensor - values: ["NONE", "ADC", "ESC"] + values: ["NONE", "ADC", "ESC", "FAKE"] enum: voltageSensor_e - name: imu_inertia_comp_method values: ["VELNED", "TURNRATE","ADAPTIVE"] enum: imu_inertia_comp_method_e - name: gps_provider - values: ["NMEA", "UBLOX", "UBLOX7", "MSP"] + values: ["NMEA", "UBLOX", "UBLOX7", "MSP", "FAKE"] enum: gpsProvider_e - name: gps_sbas_mode values: ["AUTO", "EGNOS", "WAAS", "MSAS", "GAGAN", "NONE"] diff --git a/src/main/fc/settings_generated.c b/src/main/fc/settings_generated.c new file mode 100644 index 0000000000..da2700a955 --- /dev/null +++ b/src/main/fc/settings_generated.c @@ -0,0 +1,1697 @@ +// This file has been automatically generated by utils/settings.rb +// Don't make any modifications to it. They will be lost. + +#include "platform.h" +#include "config/parameter_group_ids.h" +#include "fc/settings.h" +#include "sensors/gyro.h" +#include "fc/config.h" +#include "sensors/acceleration.h" +#include "sensors/rangefinder.h" +#include "sensors/opflow.h" +#include "sensors/compass.h" +#include "sensors/barometer.h" +#include "sensors/pitotmeter.h" +#include "rx/rx.h" +#include "rx/spektrum.h" +#include "blackbox/blackbox.h" +#include "flight/mixer.h" +#include "flight/failsafe.h" +#include "sensors/boardalignment.h" +#include "sensors/battery_config_structs.h" +#include "sensors/battery_config_structs.h" +#include "flight/servos.h" +#include "fc/controlrate_profile_config_struct.h" +#include "io/serial.h" +#include "flight/imu.h" +#include "config/general_settings.h" +#include "fc/rc_controls.h" +#include "flight/pid.h" +#include "navigation/navigation.h" +#include "io/osd.h" +#include "drivers/osd.h" +#include "io/osd_common.h" +#include "fc/config.h" +#include "fc/rc_modes.h" +#include "fc/stats.h" +#include "common/time.h" +#include "drivers/display.h" +#include "common/log.h" +#include "io/smartport_master.h" +#include "io/osd_dji_hd.h" +#include "fc/config.h" +#include "flight/power_limits.h" +#pragma GCC diagnostic ignored "-Wunused-const-variable" +const pgn_t settingsPgn[] = { + PG_GYRO_CONFIG, + PG_ADC_CHANNEL_CONFIG, + PG_ACCELEROMETER_CONFIG, + PG_RANGEFINDER_CONFIG, + PG_OPFLOW_CONFIG, + PG_COMPASS_CONFIG, + PG_BAROMETER_CONFIG, + PG_PITOTMETER_CONFIG, + PG_RX_CONFIG, + PG_BLACKBOX_CONFIG, + PG_MOTOR_CONFIG, + PG_FAILSAFE_CONFIG, + PG_BOARD_ALIGNMENT, + PG_BATTERY_METERS_CONFIG, + PG_BATTERY_PROFILES, + PG_MIXER_CONFIG, + PG_REVERSIBLE_MOTORS_CONFIG, + PG_SERVO_CONFIG, + PG_CONTROL_RATE_PROFILES, + PG_SERIAL_CONFIG, + PG_IMU_CONFIG, + PG_ARMING_CONFIG, + PG_GENERAL_SETTINGS, + PG_GPS_CONFIG, + PG_RC_CONTROLS_CONFIG, + PG_PID_PROFILE, + PG_PID_AUTOTUNE_CONFIG, + PG_POSITION_ESTIMATION_CONFIG, + PG_NAV_CONFIG, + PG_OSD_CONFIG, + PG_OSD_COMMON_CONFIG, + PG_SYSTEM_CONFIG, + PG_MODE_ACTIVATION_OPERATOR_CONFIG, + PG_STATS_CONFIG, + PG_TIME_CONFIG, + PG_DISPLAY_CONFIG, + PG_LOG_CONFIG, + PG_SMARTPORT_MASTER_CONFIG, + PG_DJI_OSD_CONFIG, + PG_BEEPER_CONFIG, + PG_POWER_LIMITS_CONFIG, +}; +const uint8_t settingsPgnCounts[] = { + 16, + 4, + 11, + 2, + 3, + 13, + 2, + 3, + 18, + 3, + 5, + 12, + 3, + 10, + 28, + 5, + 3, + 7, + 22, + 1, + 9, + 4, + 1, + 7, + 8, + 90, + 3, + 23, + 89, + 84, + 1, + 3, + 1, + 4, + 2, + 1, + 2, + 2, + 7, + 3, + 3, +}; +static const uint8_t settingNamesWords[] = { + 0x70,0x6c, /* "nav" */ + 0x3,0x5c, /* "fw" */ + 0xf,0x99, /* "osd" */ + 0x0,0xd1, /* "mc" */ + 0x82,0x41,0xa1, /* "rate" */ + 0x40,0xd0,0xe0, /* "max" */ + 0x10, /* "p" */ + 0x6,0x43,0x70, /* "yaw" */ + 0x25,0xc1,0xb0, /* "inav" */ + 0x1a,0x97, /* "min" */ + 0x2,0x9,0xa0,0xd0, /* "pitch" */ + 0x0,0xb0,0x32,0x68, /* "alarm" */ + 0x18,0x96,0xa6,0x80, /* "limit" */ + 0x64,0xc, /* "lpf" */ + 0xd, /* "z" */ + 0x1,0x81,0xab,0x86,0x80, /* "launch" */ + 0x10, /* "d" */ + 0x12,0x7b,0x18, /* "roll" */ + 0x3,0x5,0x2c,0x98,0x4c,0x50, /* "failsafe" */ + 0x1e,0x13, /* "gps" */ + 0x2,0x34, /* "hz" */ + 0x4, /* "i" */ + 0x82,0xf,0x98, /* "pos" */ + 0x2,0xe3,0xb0,0xa0, /* "angle" */ + 0xa2,0x5a,0x50, /* "time" */ + 0x5c, /* "w" */ + 0x18,0xc8, /* "xy" */ + 0x25,0x44, /* "rth" */ + 0x0,0x85,0x9,0x4,0x17,0x10, /* "deadband" */ + 0x7,0xcc,0x9e, /* "gyro" */ + 0x9,0xdd,0x34,0x1a, /* "switch" */ + 0x1,0x4c,0xc0,0xa0, /* "type" */ + 0x21,0x58,0x1c, /* "delay" */ + 0x81,0x2d,0xa8, /* "imu" */ + 0x1a,0x13, /* "mag" */ + 0x82,0x53,0x9a, /* "rssi" */ + 0x41,0x38,0x14,0xa4, /* "speed" */ + 0x5,0x11,0x27,0xd2,0x8c,0x28, /* "throttle" */ + 0x2,0x31, /* "acc" */ + 0x80,0x28,0x48, /* "ahi" */ + 0x2,0xc4,0x9d,0xc0, /* "align" */ + 0x1a,0x2,0xe7,0x15,0x80, /* "channel" */ + 0x1d,0x65,0x22,0xba,0x80, /* "current" */ + 0x61,0x6c,0x56, /* "level" */ + 0x2,0x88,0x90, /* "thr" */ + 0x3,0x5a,0x3c, /* "auto" */ + 0x9,0x71,0x12,0x30,0xd1,0xf2, /* "indicator" */ + 0x3,0x42,0xea,0x85,0x80, /* "manual" */ + 0x6b,0xc8,0x50, /* "mode" */ + 0x4c,0xb2,0xb3, /* "servo" */ + 0xc1,0x42,0xb6,0x0, /* "temp" */ + 0xb0, /* "v" */ + 0x2,0xca,0x26,0x95,0x21, /* "altitude" */ + 0x40,0x20,0xc9,0xe0, /* "baro" */ + 0x14,0x82,0xb4,0xb8,0xe0, /* "braking" */ + 0x2e,0x20,0xf0, /* "expo" */ + 0x20,0x32,0x25,0xc3,0x22, /* "hardware" */ + 0x81,0xaf,0xa3,0xe4, /* "motor" */ + 0x9,0xc, /* "rc" */ + 0x14,0x44,0x8b,0x34,0x3d,0x84, /* "threshold" */ + 0x5,0x84,0x1a, /* "vbat" */ + 0x2,0xc5,0x60, /* "vel" */ + 0x2c,0xf6,0x50,0x27,0x28, /* "voltage" */ + 0x5,0x59,0x4e,0x80, /* "burst" */ + 0x22,0x67,0x40,0xb8,0x65, /* "distance" */ + 0x1,0x32,0xe0,0xb5,0x23,0x98, /* "dynamics" */ + 0x11,0x52, /* "hud" */ + 0x1,0x81,0x71, /* "land" */ + 0x0,0xf3,0x1a,0x65,0xa0, /* "offset" */ + 0x20,0xfb,0x96,0x40, /* "power" */ + 0x9d,0x3,0x49, /* "stats" */ + 0x82,0xb3,0x28, /* "use" */ + 0x2f,0x0, /* "wp" */ + 0x5,0x94, /* "alt" */ + 0x0,0x9e,0xf9,0xd0, /* "boost" */ + 0x3,0x62,0x5a,0x20, /* "climb" */ + 0xd,0xee,0xa4,0x9e,0xc0, /* "control" */ + 0x11,0x49, /* "dji" */ + 0x1,0x32,0xe0, /* "dyn" */ + 0x19,0x2c,0xa1,0x64, /* "filter" */ + 0x7,0x5,0xa5, /* "name" */ + 0x4,0xc6,0x16,0x14, /* "scale" */ + 0x13,0x49,0xa,0x20,0xc8, /* "sidebar" */ + 0x13,0x7d,0x64,0x32, /* "source" */ + 0x82,0x89,0x69,0x5f,0x5a, /* "timeout" */ + 0x3,0x0, /* "x" */ + 0xc8, /* "y" */ + 0x34,0x59,0x3c, /* "zero" */ + 0x1b,0x20, /* "3d" */ + 0x2,0x41, /* "adc" */ + 0x80,0x29,0x94,0xe0,0x52,0x90, /* "airspeed" */ + 0x2,0xd,0x28,0x59,0x64, /* "battery" */ + 0x3,0xb,0x4b,0x20, /* "camera" */ + 0x80,0x61,0x80,0x46,0x9a,0x64, /* "capacity" */ + 0x3,0x20, /* "cd" */ + 0x6,0x56,0x30, /* "cell" */ + 0x3,0x2b,0xa8,0x59, /* "center" */ + 0x0,0x6f,0x6c, /* "comp" */ + 0x0,0x39,0x55,0x33,0x28, /* "cruise" */ + 0x7,0x5a,0x3c,0xc6, /* "cutoff" */ + 0x1,0x6,0xd0, /* "dcm" */ + 0x11,0x33,0xc,0x9a, /* "disarm" */ + 0x2,0x50,0xb2,0x68, /* "dterm" */ + 0xa,0xe2, /* "end" */ + 0x0,0xb3,0x18, /* "esc" */ + 0xc,0x60, /* "ff" */ + 0x24,0x8c,0x28, /* "idle" */ + 0x13,0x42,0xc9,0xa0, /* "iterm" */ + 0x69,0x68,0x59, /* "meter" */ + 0x2,0x17,0x68, /* "pwm" */ + 0x2a,0xe4,0xd0, /* "unit" */ + 0x1,0x18,0xca,0xc0, /* "accel" */ + 0x4,0x63,0x38,0x52,0xe0, /* "accgain" */ + 0x4,0x63,0xd1,0x64,0xf0, /* "acczero" */ + 0x5,0xd4,0x49,0xe4,0x1b,0x26,0x99, /* "antigravity" */ + 0x0,0x6b,0x47,0xd2,0xae,0x28, /* "autotune" */ + 0x4,0x17,0x2c, /* "bank" */ + 0x2,0x29,0x60,0x59, /* "beeper" */ + 0x0,0x4c,0x8,0xd6,0x27,0xe0, /* "blackbox" */ + 0x2,0x78,0x64,0x40, /* "board" */ + 0xc,0x2c, /* "cal" */ + 0x1,0x4,0xd0, /* "dbm" */ + 0x10,0xb4,0x28,0xe8, /* "detect" */ + 0x2,0xb8,0xb2,0x3e, /* "energy" */ + 0x40,0x82,0x1c, /* "hdg" */ + 0x8,0x28,0x48,0x97,0x1c, /* "heading" */ + 0x8,0x7b,0x8, /* "hold" */ + 0x4,0xba,0xc5,0x95,0xa,0x40, /* "inverted" */ + 0x30,0x2e,0x22,0x5c,0x70, /* "landing" */ + 0x34,0x27,0x38,0x52,0xe0, /* "maggain" */ + 0x34,0x27,0xd1,0x64,0xf0, /* "magzero" */ + 0x34,0x29,0x70, /* "main" */ + 0x1a,0x19,0x1d,0x2e, /* "margin" */ + 0x3,0xe0,0x66,0x3e,0xe0, /* "opflow" */ + 0x82,0x68,0x34,0x72,0x88,0x90, /* "pitch2thr" */ + 0x20,0x9a,0x3e,0x80, /* "pitot" */ + 0x84,0x8a,0x44,0x8e,0x8f,0x90, /* "predictor" */ + 0x26,0x39,0x3d,0x8c, /* "scroll" */ + 0x4,0xca,0xe9,0xa6,0x89,0xb2,0x69,0x90, /* "sensitivity" */ + 0x4c,0xb2,0x48,0x59,0x2c, /* "serialrx" */ + 0x2,0x6c,0x7d,0xc8,0xfb,0xb8, /* "slowdown" */ + 0x13,0x6a,0x68,0x80, /* "smith" */ + 0x4e,0xb2,0x30,0x46,0x50, /* "surface" */ + 0x51,0xf4,0xb, /* "total" */ + 0x1,0x48,0x4, /* "tpa" */ + 0x17,0x2a,0x4e,0x8a, /* "weight" */ + 0x0,0x22,0x7c,0xa8, /* "abort" */ + 0x0,0xa6,0x4d,0x79,0xa, /* "airmode" */ + 0x1,0x6,0x80, /* "bat" */ + 0x10,0x6a,0x40, /* "baud" */ + 0xd,0x5,0x1a, /* "check" */ + 0xc0,0x37,0xba,0x80, /* "cont" */ + 0x1b,0xe5,0x22,0x8e,0x89,0x7b, /* "correction" */ + 0x80,0x44,0xc8,0xa3,0xa2,0x5e,0xe0, /* "direction" */ + 0x11,0x33,0x80, /* "disp" */ + 0x8,0x99,0xd0, /* "dist" */ + 0x4,0x4d,0x8a, /* "dive" */ + 0x2,0x4d,0xf,0xa0, /* "dshot" */ + 0xb,0xb, /* "epv" */ + 0x0,0xc1,0x1d,0x1f,0x20, /* "factor" */ + 0x18,0x2c,0x61,0x1f,0x77, /* "falldown" */ + 0x0,0xc9,0x94,0xe8, /* "first" */ + 0x3,0x31,0xf7, /* "flow" */ + 0x1,0x9f,0x60, /* "fov" */ + 0x1c,0x29,0x70, /* "gain" */ + 0xf,0x20,0xd9,0x34,0xc8, /* "gravity" */ + 0x10, /* "h" */ + 0x4,0x5,0x86,0x25,0x60,0xc2,0xe0, /* "halfduplex" */ + 0x8,0x2a,0x4e,0x8a, /* "height" */ + 0x1,0xf,0x69, /* "home" */ + 0x40,0x93,0xb9,0xf2,0x28, /* "ignore" */ + 0x12,0xe1,0xb1,0x2e,0xd,0x12,0xf7, /* "inclination" */ + 0x1,0x2e,0xa1,0x65,0x60,0xb0, /* "interval" */ + 0xb,0x48, /* "ki" */ + 0x17,0x0, /* "kp" */ + 0x31,0xe7, /* "log" */ + 0x3,0x1e,0x9a,0x16,0x40, /* "loiter" */ + 0x63,0xee, /* "low" */ + 0x6,0x40,0xdc, /* "lpf2" */ + 0x3,0x43,0x3a,0x16,0x40, /* "master" */ + 0x68,0x70,0x16,0x50, /* "maxalt" */ + 0xd,0x4b,0x82,0xca, /* "minalt" */ + 0x1,0xa9,0x9c,0xd2,0xf7, /* "mission" */ + 0x1,0xaf,0x21,0x58, /* "model" */ + 0x7,0x3e,0x83,0x40, /* "notch" */ + 0x1e,0xe2, /* "one" */ + 0x82,0x1,0x70, /* "pan" */ + 0x20,0x90, /* "pi" */ + 0x41,0x24,0x9d,0x5a, /* "pidsum" */ + 0x8,0x49,0xe3,0x29,0x2b,0x22, /* "procedure" */ + 0x82,0x12,0x7d,0x1e,0x37,0xb0, /* "protocol" */ + 0x10,0x93,0xec,0x92,0x16,0x40, /* "provider" */ + 0x90,0x48,0x9a,0xcc, /* "radius" */ + 0x12,0xb,0x8e,0x53,0x25,0xc4,0x2c, /* "rangefinder" */ + 0x81,0x22,0xb0,0x38, /* "relax" */ + 0x4,0x8b,0x30, /* "res" */ + 0x48,0xb3,0x2d, /* "reset" */ + 0x1,0x2c, /* "rx" */ + 0x2,0x61,0x31,0x50,0xf6,0x94, /* "safehome" */ + 0x13,0x68,0x65,0x48,0x3e,0x54, /* "smartport" */ + 0x4,0xda,0xf7,0xd1,0x9,0x71, /* "smoothing" */ + 0xc1,0x39,0x61,0x9c, /* "srxl2" */ + 0x4,0xe8,0x91,0xac, /* "stick" */ + 0x13,0xa6,0x58,0x50, /* "style" */ + 0x51,0x12,0x29, /* "three" */ + 0x41,0x44,0x49,0xf7, /* "throw" */ + 0x5,0x1e,0xc2,0xc8,0x2e,0x19, /* "tolerance" */ + 0x41,0x49,0x4,0x6b,0x10,0x46,0xb0, /* "trackback" */ + 0x52,0xef, /* "two" */ + 0x5,0x34, /* "tz" */ + 0xa,0xc2,0x89,0x65, /* "uptilt" */ + 0x1,0x59,0x94,0x60, /* "usec" */ + 0xb4,0xe0,0x40, /* "vspd" */ + 0x5c,0x32,0x72,0x5c,0x70, /* "warning" */ + 0x4,0x63,0x2b,0xb,0x20,0xd1,0xf2, /* "accelerator" */ + 0x0,0x48,0xaa,0xce,0x8d,0x2b,0xa8, /* "adjustment" */ + 0x0,0x91,0x55,0x9d,0x1a,0x57,0x52,0x60, /* "adjustments" */ + 0xb,0x18,0xfb, /* "allow" */ + 0x80,0x30,0x83,0x12,0x52, /* "applied" */ + 0x0,0x32,0x93,0xef,0x30, /* "arrows" */ + 0x6,0x94,0x70, /* "attn" */ + 0x3,0x5a,0x3d,0xa1,0xa2,0x46, /* "automatic" */ + 0x0,0xd6,0x8f,0xa4,0x92,0xd0, /* "autotrim" */ + 0x9,0x21,0x98, /* "bias" */ + 0x4,0xf9,0x10,0xb2,0x29, /* "bordered" */ + 0x0,0x29,0x14,0x2b,0x83,0xd2,0xea, /* "breakpoint" */ + 0x0,0x61,0x62,0x45,0x20,0xd1,0x2f,0x70, /* "calibration" */ + 0x6,0x56,0x32,0x60, /* "cells" */ + 0x1a,0x3,0x20,0x8e,0x85,0x90, /* "character" */ + 0x6,0xd9,0xcc, /* "cmss" */ + 0x3,0x7b,0x5a,0x17,0x10, /* "command" */ + 0x3,0x7b,0x8c,0x93, /* "config" */ + 0x80,0x6f,0x74,0xe8,0x17,0x50, /* "constant" */ + 0x3,0x7b,0xa9,0x27,0xb2,0x41,0xa1, /* "controlrate" */ + 0x40,0x37,0xbe,0x44,0x4b,0x83,0x42, /* "coordinate" */ + 0x80,0x72,0x4d,0x12,0x30,0xb0, /* "critical" */ + 0x3,0x93,0xe7,0x34,0x5,0x32,0x98, /* "crosshairs" */ + 0x7,0x59,0x58,0xa0, /* "curve" */ + 0x27,0x44,0xf7,0xce,0x9d,0x3e,0x64,0xfe,0x90,0xac,0xa0,0x7a,0xc8,0x1b,0xa8,0xd0, /* "d_boost_gyro_delta_lpf_hz" */ + 0x9,0xd1,0x3d,0xf3,0xa7,0x5a,0x1c,0x74,0x34,0xe8,0x46,0x32,0xb0,0xb2,0xd,0x12,0xf7, /* "d_boost_max_at_acceleration" */ + 0x0,0x85,0x15,0x4e, /* "debug" */ + 0x2,0x14,0x65,0x61,0x64,0x1a,0x25,0xee, /* "deceleration" */ + 0x1,0xa,0x34,0xb4,0x2c,0x98, /* "decimals" */ + 0x8,0x51,0xb0, /* "decl" */ + 0x4,0x28,0xd8,0x97,0x6,0x89,0x7b, /* "declination" */ + 0x80,0x42,0x98,0x35,0x65,0x26, /* "defaults" */ + 0x2,0x14,0xcc,0x28,0xe8,0x97,0xb8, /* "deflection" */ + 0x4,0x29,0xe4,0x52,0xcc, /* "degrees" */ + 0x4,0x2b,0x9e,0xd0, /* "denom" */ + 0x10,0xb6,0x48,0xca, /* "device" */ + 0x2,0x24,0xe9,0xa4, /* "digits" */ + 0xc0,0x44,0xcc,0xae,0x38,0x4e,0x50, /* "disengage" */ + 0x11,0x33,0x83,0x3,0x9e,0x99,0xf2,0x19,0x7b,0x3b,0xf4,0x4c,0x4b,0x96, /* "display_force_sw_blink" */ + 0x2,0x29,0x3d,0x1b,0xba,0x16,0x50,0xb2,0x70,0x68,0x97,0x1f,0xa4,0xac,0x83,0x44,0xbd,0xc0, /* "dji_cn_alternating_duration" */ + 0x22,0x93,0xda,0xcc,0xbd,0x70,0x5a,0x5e,0x99,0xf2,0xeb,0x4b,0x39,0x84,0xe5,0x98, /* "dji_use_name_for_messages" */ + 0x8,0xfb,0xb8, /* "down" */ + 0x4,0x9d, /* "dst" */ + 0x0,0x56,0x96,0x47, /* "emerg" */ + 0x1,0x5c,0x11,0x30,0xa4, /* "enabled" */ + 0x1,0x5c,0x67,0xc8,0x65, /* "enforce" */ + 0x1,0x60,0x80, /* "eph" */ + 0x18,0x33,0xa0, /* "fast" */ + 0xc,0x9c,0x14,0x9d,0xba,0x5c,0x7e,0x86,0xb4,0x7f,0x43,0x26, /* "fixed_wing_auto_arm" */ + 0x80,0xcc,0xc,0xb,0x27,0xb8, /* "flaperon" */ + 0x6,0x60,0x61,0x30, /* "flaps" */ + 0x19,0xf2,0x19, /* "force" */ + 0x40,0x68,0x58, /* "fpv" */ + 0x6,0xbf,0x53,0x42,0xc9,0xbd,0x62,0x5a,0x9a,0x76,0x74,0x48,0xd7,0xd8,0x3e,0x69,0xa2,0x5e,0xe0, /* "fw_iterm_limit_stick_position" */ + 0x1a,0xfd,0xa5,0x64,0xee,0x86,0x73,0x4c,0xe9,0xd8,0x26,0x83,0x47,0x4e,0x14,0xb8, /* "fw_turn_assist_pitch_gain" */ + 0x6,0xbf,0x69,0x59,0x3b,0xa1,0x9c,0xd3,0x3a,0x77,0x21,0xbf,0x4e,0x14,0xb8, /* "fw_turn_assist_yaw_gain" */ + 0x6,0xbf,0x72,0x1b,0xf5,0x34,0x2c,0x9b,0xd3,0x48,0xa5,0xd1,0x7a,0x20,0xb9,0x7d,0xb,0x8e,0xc2, /* "fw_yaw_iterm_freeze_bank_angle" */ + 0x80,0xe1,0x62,0x58,0x57, /* "galileo" */ + 0x80,0xe6,0x7c,0x86,0x50, /* "gforce" */ + 0x1e,0x49,0x20, /* "grid" */ + 0xf,0x99,0x3f,0xa1,0x75,0x13,0xd0,0xb1,0x21,0x9a,0x5c,0x7e,0xb2,0x6,0xea,0x34, /* "gyro_anti_aliasing_lpf_hz" */ + 0x3,0xe6,0x4f,0xe8,0x5d,0x44,0xf4,0x2c,0x48,0x66,0x97,0x1f,0xac,0x81,0xbb,0x4c,0xc0,0xa0, /* "gyro_anti_aliasing_lpf_type" */ + 0x40,0x66, /* "has" */ + 0x4,0x24,0xe8, /* "high" */ + 0x2,0x1e,0xd2,0xc1,0xe9,0x75, /* "homepoint" */ + 0x0,0x87,0xb5,0x2e,0x38, /* "homing" */ + 0x10,0xf9,0x27,0x4f,0x70, /* "horizon" */ + 0x10,0xf9,0x27,0x4f,0x75,0x2,0xc0, /* "horizontal" */ + 0x21,0xf6,0x2c, /* "hover" */ + 0x80,0x92, /* "id" */ + 0x1,0x2e,0xd,0xba,0x16,0x31,0xf7,0xe9,0xa,0x12,0x76,0x45,0x1a,0xde,0xe4,0xb8,0xe0, /* "inav_allow_dead_reckoning" */ + 0x4b,0x88,0x5c, /* "index" */ + 0x1,0x2e,0x2c,0xa8,0x90, /* "inertia" */ + 0x81,0x2e,0x4d, /* "init" */ + 0x0,0x97,0x4c, /* "ins" */ + 0xb,0x4b,0x18, /* "kill" */ + 0x6,0x4,0x45,0x60, /* "label" */ + 0x18,0x1c,0xbe,0xb4, /* "layout" */ + 0x3,0xa,0x6a, /* "left" */ + 0x1,0x89,0x72, /* "link" */ + 0xc0,0xc7,0xbe,0x14,0x4b,0x4a, /* "looptime" */ + 0x6,0x94,0x89,0xb, /* "median" */ + 0x80,0xd2,0xce,0x61,0x39, /* "message" */ + 0x40,0xd2,0xd1,0xf,0x20, /* "method" */ + 0x1a,0x92, /* "mid" */ + 0x1,0xa9,0x63,0x12, /* "milli" */ + 0x6,0xa7,0x0, /* "mix" */ + 0x6b,0xc8,0x5e,0xc8,0x2e,0x39,0x7a,0xc7,0x9d,0x23,0xeb,0xe0,0x59,0x6,0x8f,0x90, /* "mode_range_logic_operator" */ + 0x1a,0xf9,0x3d,0xc0, /* "moron" */ + 0x70,0x6d,0xd2,0xe2,0x92,0xf,0x43,0x26,0xa5,0xc7,0xec,0xc2,0x62,0xd3,0x20, /* "nav_extra_arming_safety" */ + 0x70,0x6d,0xd3,0x5f,0xa1,0x63,0x1f,0x7e,0xb4,0x2e,0xa8,0x59,0xda,0x22,0x5d,0x4b,0x87,0x22,0x86,0x65, /* "nav_fw_allow_manual_thr_increase" */ + 0x3,0x83,0x6e,0x9a,0xfd,0x83,0xe7,0xd4,0x10,0xfd,0x82,0x49,0x3a,0xb7,0xac,0x4b,0x53,0x40, /* "nav_fw_pos_hdg_pidsum_limit" */ + 0x38,0x36,0xe9,0xaf,0xd9,0xbc,0x32,0x4b,0x8f,0xd6,0xbe,0x8f,0x97,0x67,0x47,0xc0, /* "nav_fw_soaring_motor_stop" */ + 0xe,0xd,0xba,0x6b,0xf6,0xf0,0xed,0x24,0x11,0xad,0x2e,0x3f,0x42,0x31,0xd6,0x41,0x1e, /* "nav_fw_wp_tracking_accuracy" */ + 0x40,0xe0,0xdb,0xa6,0xbf,0x6f,0xe,0xd2,0x41,0x1a,0xd2,0xe3,0xf5,0xa1,0xc7,0x42,0xe3,0xb0,0xa0, /* "nav_fw_wp_tracking_max_angle" */ + 0x70,0x6d,0xd3,0x5f,0xb7,0x87,0x69,0x59,0x3b,0xb3,0x6b,0xdf,0x44,0x25,0xc7, /* "nav_fw_wp_turn_smoothing" */ + 0x3,0x83,0x6e,0xb4,0x38,0xed,0xb,0x29,0x5,0x2e,0xe9,0x9e,0xc6,0x3e,0xfd,0xb,0x28, /* "nav_max_terrain_follow_alt" */ + 0x7,0x6,0xdd,0x68,0xfa,0x29,0x5,0x69,0x71,0xfa,0x27,0xbe,0x74,0xe9,0x13,0x32,0xb8,0xe1,0x39,0x7b,0x38,0x14,0xa4, /* "nav_mc_braking_boost_disengage_speed" */ + 0x3,0x83,0x6e,0xb4,0x7d,0xb1,0x59,0xdc,0x67,0xa4,0xa1,0x64,0xde,0x86,0x94,0x2b,0xaa,0x1a,0x25,0xee, /* "nav_mc_vel_xy_dterm_attenuation" */ + 0x3,0x83,0x6e,0xb4,0x7d,0xb1,0x59,0xdc,0x67,0xa4,0xa1,0x64,0xde,0x86,0x94,0x2b,0xaa,0x1a,0x25,0xee,0xe9,0x5c,0x40, /* "nav_mc_vel_xy_dterm_attenuation_end" */ + 0x38,0x36,0xeb,0x47,0xdb,0x15,0x9d,0xc6,0x7a,0x4a,0x16,0x4d,0xe8,0x69,0x42,0xba,0xa1,0xa2,0x5e,0xee,0xce,0x81,0x95, /* "nav_mc_vel_xy_dterm_attenuation_start" */ + 0x0,0xe0,0xdb,0xad,0x1f,0x6c,0x56,0x77,0x19,0xe9,0x28,0x59,0x37,0xac,0x81,0xba,0x8d, /* "nav_mc_vel_xy_dterm_lpf_hz" */ + 0x1,0xc1,0xb7,0x5a,0x99,0xcd,0x2f,0x77,0x60,0xc0,0xb9,0xc5,0x97,0x64,0x59,0x96,0x80, /* "nav_mission_planner_reset" */ + 0x70,0x6d,0xd9,0x51,0x1d,0x1b,0x12,0xd1,0x74,0xc9,0x94,0xe9,0xd9,0xd0,0x27,0x2f,0x42,0xca,0x26,0x95,0x21, /* "nav_rth_climb_first_stage_altitude" */ + 0x40,0xe0,0xdb,0xb2,0xa2,0x3a,0x36,0x25,0xa2,0xe9,0x93,0x29,0xd3,0xb3,0xa0,0x4e,0x5e,0xb5,0xe4,0x28, /* "nav_rth_climb_first_stage_mode" */ + 0x1c,0x1b,0x76,0x54,0x47,0x46,0xc4,0xb4,0x5d,0x49,0xdc,0xf9,0x17,0xa5,0x69,0x64,0x70, /* "nav_rth_climb_ignore_emerg" */ + 0x38,0x36,0xed,0x66,0x5e,0xb5,0x24,0xa2,0x25,0xd3,0x3e,0x5d,0xb,0x28,0x87,0xb0,0x80, /* "nav_use_midthr_for_althold" */ + 0x70,0x6d,0xdb,0xc3,0xac,0x78,0x49,0xd7,0xbb,0xa2,0x7b,0xe8, /* "nav_wp_load_on_boot" */ + 0x7,0x6,0xdd,0xbc,0x3a,0xda,0xb2,0x89,0xeb,0x53,0x39,0xa5,0xee,0xea,0x5c,0x42,0xe0, /* "nav_wp_multi_mission_index" */ + 0xe,0x29, /* "neg" */ + 0xc0,0xe2,0xd6,0x92,0xb, /* "neutral" */ + 0x0,0xe7, /* "no" */ + 0x81,0xd5,0x68, /* "num" */ + 0x1e,0x63, /* "off" */ + 0x1,0xee, /* "on" */ + 0x3,0xe6,0x4e,0x8e,0x53,0x37,0x59,0x1e,0x99,0xf2,0x68,0x68, /* "osd_crsf_lq_format" */ + 0x7,0xcc,0x9d,0x2c,0xe8,0x96,0x86,0x89,0x7b,0xa7,0xdb,0xa5,0xc4,0xe8,0xde,0xd8,0x15,0xd3,0xd,0x12,0xf7, /* "osd_estimations_wind_compensation" */ + 0x1,0xf3,0x27,0x4e,0x67,0xc8,0x65,0xe8,0x70,0x99,0xf4,0x2c,0xc,0x9b,0xd6,0x87,0x0, /* "osd_gforce_axis_alarm_max" */ + 0x7c,0xc9,0xd3,0x99,0xf2,0x19,0x7a,0x1c,0x26,0x7d,0xb,0x3,0x26,0xf5,0xa9,0x70, /* "osd_gforce_axis_alarm_min" */ + 0x1f,0x32,0x75,0xf,0x69,0x7b,0x7,0xcd,0x34,0x4b,0xdd,0xd0,0xc9,0xbd,0x98,0xe4,0x52,0xb8, /* "osd_home_position_arm_screen" */ + 0xf,0x99,0x3a,0x8a,0x93,0xb2,0x9,0x3,0x2e,0x85,0x94,0xe9,0x12,0x63,0x16,0x45,0x70,0xcb,0xd2,0x26,0x70,0x60,0x73,0xda,0x25,0xa5, /* "osd_hud_radar_alt_difference_display_time" */ + 0x3,0xe6,0x4e,0xa2,0xa4,0xec,0x82,0x40,0xcb,0xa4,0x4c,0xe8,0x17,0xc,0xbd,0x22,0x67,0x6,0x7,0x3d,0xa2,0x5a,0x50, /* "osd_hud_radar_distance_display_time" */ + 0x3e,0x64,0xea,0x2a,0x4e,0xc8,0x24,0xc,0xbb,0x20,0xb8,0xe5,0xeb,0x43,0x80, /* "osd_hud_radar_range_max" */ + 0x3e,0x64,0xea,0x2a,0x4e,0xc8,0x24,0xc,0xbb,0x20,0xb8,0xe5,0xeb,0x52,0xe0, /* "osd_hud_radar_range_min" */ + 0x3e,0x64,0xeb,0xa,0x6a,0x76,0x69,0x21,0x44,0x19,0x76,0x63,0x93,0xd8,0xce,0xce,0x85,0x80, /* "osd_left_sidebar_scroll_step" */ + 0x1f,0x32,0x75,0xa1,0x47,0x6b,0x32,0x93,0xb0,0x91,0x46,0x99,0xa5,0xee, /* "osd_mah_used_precision" */ + 0x3,0xe6,0x4e,0xc1,0x95,0x9f,0x46,0xf2,0x17,0xa4,0x49,0xd3,0x49, /* "osd_plus_code_digits" */ + 0x81,0xf3,0x27,0x60,0xca,0xcf,0xa3,0x79,0xb,0xd9,0xa1,0xf2,0xa0, /* "osd_plus_code_short" */ + 0x1f,0x32,0x76,0x49,0x3a,0x29,0xd9,0xa4,0x85,0x10,0x65,0xd9,0x8e,0x4f,0x63,0x3b,0x3a,0x16,0x0, /* "osd_right_sidebar_scroll_step" */ + 0x7c,0xc9,0xd9,0xd0,0x34,0x9f,0x60,0x13,0x97,0xa1,0xad,0x1f,0xd9,0xdc,0x30,0xed,0x12,0xd2, /* "osd_stats_page_auto_swap_time" */ + 0x81,0xf3,0x27,0x67,0x74,0xd0,0x68,0xea,0x5c,0x44,0x8c,0x34,0x7c,0xa7,0xd0,0xb1,0x27,0x77,0x58,0x53,0x50, /* "osd_switch_indicators_align_left" */ + 0xf,0x99,0x3b,0x3c,0xce,0x85,0x6f,0x5b,0x33,0xf4,0x89,0x9c,0x18,0x1c,0xf6,0x89,0x69, /* "osd_system_msg_display_time" */ + 0x40,0xfa,0xd2,0x15,0xa0, /* "output" */ + 0x1f,0x62,0xca,0x49,0x21, /* "override" */ + 0x40,0xfb,0x16,0x52,0x49,0xb,0x30, /* "overrides" */ + 0x41,0x24, /* "pid" */ + 0x4,0x13,0x40, /* "pit" */ + 0x41,0x81,0xa1,0x9f,0x26, /* "platform" */ + 0x82,0xf,0x61,0x66, /* "poles" */ + 0x8,0x3e,0x69,0xa2,0x5e,0xe0, /* "position" */ + 0x42,0x45,0xc,0x9a, /* "prearm" */ + 0x8,0x48,0xa3,0x4c,0xd2,0xf7, /* "precision" */ + 0x2,0x12,0x2d,0x92,0x5b, /* "preview" */ + 0x82,0x12,0x79,0x92,0xc2, /* "profile" */ + 0x82,0x15,0x64,0xca, /* "pulse" */ + 0x8,0x5d,0xbc,0x19,0x5d,0x44,0x90,0xa7, /* "pwm2centideg" */ + 0x4,0x6a,0x16,0x26,0x99, /* "quality" */ + 0x4,0x82,0x40,0xc8, /* "radar" */ + 0x12,0x28,0x9e,0xfa, /* "reboot" */ + 0x2,0x45,0x19,0x53,0x62,0xc8, /* "receiver" */ + 0x12,0x28,0xdf,0x62,0xcb,0x20, /* "recovery" */ + 0x91,0x4c,0x59,0x15,0xc3,0x28, /* "reference" */ + 0x24,0x59,0xd0,0x32,0xa0, /* "restart" */ + 0x24,0x5b,0x16,0x53,0x28, /* "reverse" */ + 0x24,0x93,0xa2,0x80, /* "right" */ + 0x93,0x18, /* "rll" */ + 0x9,0x3e,0x81,0xa2,0x5e,0xe0, /* "rotation" */ + 0x49,0xf7, /* "row" */ + 0x4,0xa0,0xd0, /* "rpm" */ + 0x4c,0x26,0x28, /* "safe" */ + 0x26,0x1a,0x4c, /* "sats" */ + 0x13,0x10,0x66, /* "sbas" */ + 0x9,0x8a,0xb3, /* "sbus" */ + 0x4,0xd0,0x93,0x50,0x8f,0xbb, /* "shiftdown" */ + 0x81,0x36,0x3e,0x5, /* "slope" */ + 0x4,0xda,0x16,0x30, /* "small" */ + 0x13,0x6b,0xdf,0x44,0x38,0xb3,0x98, /* "smoothness" */ + 0x26,0xe9, /* "snr" */ + 0x2,0x6f,0xc,0x92,0xe3, /* "soaring" */ + 0x82,0x70,0x4b,0xab,0x0, /* "spinup" */ + 0x4e,0x43, /* "src" */ + 0x4,0xe8,0xf8, /* "stop" */ + 0x2,0x74,0x90, /* "str" */ + 0x27,0x49,0x15,0xc7,0xa2, /* "strength" */ + 0x1,0x3c,0xb8,0x60, /* "sync" */ + 0x9e,0x67,0x42,0xb4, /* "system" */ + 0x14,0xa,0x58, /* "tail" */ + 0xa,0x15,0x85,0x69,0x69,0x2c, /* "telemetry" */ + 0x82,0x89,0x65, /* "tilt" */ + 0x1,0x47,0xb8,0xa0, /* "tone" */ + 0xa3,0xe0,0x91,0xcc, /* "topics" */ + 0x14,0x92, /* "tri" */ + 0x41,0x49,0x25,0xa0, /* "trim" */ + 0xa8,0x98,0xfc, /* "ublox" */ + 0x2,0xae,0xc,0x9a,0x52, /* "unarmed" */ + 0x2,0xae,0x4d,0x26, /* "units" */ + 0xa,0xcc,0x27,0x28, /* "usage" */ + 0x2b,0x32,0xc8, /* "user" */ + 0x16,0x2b,0x1c,0x52, /* "velned" */ + 0x2,0xc5,0x63,0xc6,0x9a,0x64, /* "velocity" */ + 0x16,0x2c,0xa8,0x91,0x85,0x80, /* "vertical" */ + 0xb2,0x48,0x57, /* "video" */ + 0x82,0xe9,0x25,0x10, /* "width" */ + 0xb,0xa5,0xc4,0x1b,0xdb,0x0, /* "windcomp" */ + 0x5d,0x2e,0x25,0x60, /* "windup" */ + 0xb,0xbe,0x4b,0xc,0x9f,0x57,0x12,0x60, /* "workarounds" */ + 0xc6,0x74, /* "xyz" */ + 0x0,0x00 +}; +static const char wordSymbols[] = {'3','2','_',}; +const char * const table_acc_hardware[] = { + "NONE", + "AUTO", + "MPU6000", + "MPU6500", + "MPU9250", + "BMI160", + "ICM20689", + "BMI088", + "ICM42605", + "BMI270", + "FAKE", +}; +const char * const table_airmodeHandlingType[] = { + "STICK_CENTER", + "THROTTLE_THRESHOLD", + "STICK_CENTER_ONCE", +}; +const char * const table_alignment[] = { + "DEFAULT", + "CW0", + "CW90", + "CW180", + "CW270", + "CW0FLIP", + "CW90FLIP", + "CW180FLIP", + "CW270FLIP", +}; +const char * const table_autotune_rate_adjustment[] = { + "FIXED", + "LIMIT", + "AUTO", +}; +const char * const table_aux_operator[] = { + "OR", + "AND", +}; +const char * const table_baro_hardware[] = { + "NONE", + "AUTO", + "BMP085", + "MS5611", + "BMP280", + "MS5607", + "LPS25H", + "SPL06", + "BMP388", + "DPS310", + "B2SMPB", + "MSP", + "FAKE", +}; +const char * const table_bat_capacity_unit[] = { + "MAH", + "MWH", +}; +const char * const table_bat_voltage_source[] = { + "RAW", + "SAG_COMP", +}; +const char * const table_blackbox_device[] = { + "SERIAL", + "SPIFLASH", + "SDCARD", +}; +const char * const table_current_sensor[] = { + "NONE", + "ADC", + "VIRTUAL", + "FAKE", + "ESC", +}; +const char * const table_debug_modes[] = { + "NONE", + "AGL", + "FLOW_RAW", + "FLOW", + "ALWAYS", + "SAG_COMP_VOLTAGE", + "VIBE", + "CRUISE", + "REM_FLIGHT_TIME", + "SMARTAUDIO", + "ACC", + "NAV_YAW", + "PCF8574", + "DYN_GYRO_LPF", + "AUTOLEVEL", + "ALTITUDE", + "AUTOTRIM", + "AUTOTUNE", + "RATE_DYNAMICS", + "LANDING", +}; +const char * const table_direction[] = { + "RIGHT", + "LEFT", + "YAW", +}; +const char * const table_djiOsdTempSource[] = { + "ESC", + "IMU", + "BARO", +}; +const char * const table_djiRssiSource[] = { + "RSSI", + "CRSF_LQ", +}; +const char * const table_failsafe_procedure[] = { + "LAND", + "DROP", + "RTH", + "NONE", +}; +const char * const table_filter_type[] = { + "PT1", + "BIQUAD", +}; +const char * const table_filter_type_full[] = { + "PT1", + "BIQUAD", + "PT2", + "PT3", +}; +const char * const table_gps_dyn_model[] = { + "PEDESTRIAN", + "AIR_1G", + "AIR_4G", +}; +const char * const table_gps_provider[] = { + "NMEA", + "UBLOX", + "UBLOX7", + "MSP", + "FAKE", +}; +const char * const table_gps_sbas_mode[] = { + "AUTO", + "EGNOS", + "WAAS", + "MSAS", + "GAGAN", + "NONE", +}; +const char * const table_gyro_lpf[] = { + "256HZ", + "188HZ", + "98HZ", + "42HZ", + "20HZ", + "10HZ", +}; +const char * const table_imu_inertia_comp_method[] = { + "VELNED", + "TURNRATE", + "ADAPTIVE", +}; +const char * const table_iterm_relax[] = { + "OFF", + "RP", + "RPY", +}; +const char * const table_log_level[] = { + "ERROR", + "WARNING", + "INFO", + "VERBOSE", + "DEBUG", +}; +const char * const table_mag_hardware[] = { + "NONE", + "AUTO", + "HMC5883", + "AK8975", + "MAG3110", + "AK8963", + "IST8310", + "QMC5883", + "MPU9250", + "IST8308", + "LIS3MDL", + "MSP", + "RM3100", + "VCM5883", + "MLX90393", + "FAKE", +}; +const char * const table_motor_pwm_protocol[] = { + "STANDARD", + "ONESHOT125", + "MULTISHOT", + "BRUSHED", + "DSHOT150", + "DSHOT300", + "DSHOT600", +}; +const char * const table_nav_extra_arming_safety[] = { + "ON", + "ALLOW_BYPASS", +}; +const char * const table_nav_fw_wp_turn_smoothing[] = { + "OFF", + "ON", + "ON-CUT", +}; +const char * const table_nav_overrides_motor_stop[] = { + "OFF_ALWAYS", + "OFF", + "AUTO_ONLY", + "ALL_NAV", +}; +const char * const table_nav_rth_allow_landing[] = { + "NEVER", + "ALWAYS", + "FS_ONLY", +}; +const char * const table_nav_rth_alt_mode[] = { + "CURRENT", + "EXTRA", + "FIXED", + "MAX", + "AT_LEAST", + "AT_LEAST_LINEAR_DESCENT", +}; +const char * const table_nav_rth_climb_first[] = { + "OFF", + "ON", + "ON_FW_SPIRAL", +}; +const char * const table_nav_rth_climb_first_stage_modes[] = { + "AT_LEAST", + "EXTRA", +}; +const char * const table_nav_user_control_mode[] = { + "ATTI", + "CRUISE", +}; +const char * const table_nav_wp_mission_restart[] = { + "START", + "RESUME", + "SWITCH", +}; +const char * const table_off_on[] = { + "OFF", + "ON", +}; +const char * const table_opflow_hardware[] = { + "NONE", + "CXOF", + "MSP", + "FAKE", +}; +const char * const table_osdSpeedSource[] = { + "GROUND", + "3D", + "AIR", +}; +const char * const table_osd_ahi_style[] = { + "DEFAULT", + "LINE", +}; +const char * const table_osd_alignment[] = { + "LEFT", + "RIGHT", +}; +const char * const table_osd_crosshairs_style[] = { + "DEFAULT", + "AIRCRAFT", + "TYPE3", + "TYPE4", + "TYPE5", + "TYPE6", + "TYPE7", + "TYPE8", +}; +const char * const table_osd_crsf_lq_format[] = { + "TYPE1", + "TYPE2", + "TYPE3", +}; +const char * const table_osd_plus_code_short[] = { + "0", + "2", + "4", + "6", +}; +const char * const table_osd_sidebar_scroll[] = { + "NONE", + "ALTITUDE", + "SPEED", + "HOME_DISTANCE", +}; +const char * const table_osd_stats_energy_unit[] = { + "MAH", + "WH", +}; +const char * const table_osd_stats_min_voltage_unit[] = { + "BATTERY", + "CELL", +}; +const char * const table_osd_telemetry[] = { + "OFF", + "ON", + "TEST", +}; +const char * const table_osd_unit[] = { + "IMPERIAL", + "METRIC", + "METRIC_MPH", + "UK", + "GA", +}; +const char * const table_osd_video_system[] = { + "AUTO", + "PAL", + "NTSC", + "HDZERO", + "DJIWTF", +}; +const char * const table_output_mode[] = { + "AUTO", + "MOTORS", + "SERVOS", +}; +const char * const table_pidTypeTable[] = { + "NONE", + "PID", + "PIFF", + "AUTO", +}; +const char * const table_pitot_hardware[] = { + "NONE", + "AUTO", + "MS4525", + "ADC", + "VIRTUAL", + "FAKE", + "MSP", +}; +const char * const table_platform_type[] = { + "MULTIROTOR", + "AIRPLANE", + "HELICOPTER", + "TRICOPTER", + "ROVER", + "BOAT", +}; +const char * const table_rangefinder_hardware[] = { + "NONE", + "SRF10", + "VL53L0X", + "MSP", + "BENEWAKE", + "VL53L1X", + "US42", + "TOF10120_I2C", +}; +const char * const table_receiver_type[] = { + "NONE", + "SERIAL", + "MSP", +}; +const char * const table_reset_type[] = { + "NEVER", + "FIRST_ARM", + "EACH_ARM", +}; +const char * const table_rssi_source[] = { + "NONE", + "AUTO", + "ADC", + "CHANNEL", + "PROTOCOL", + "MSP", +}; +const char * const table_rth_trackback_mode[] = { + "OFF", + "ON", + "FS", +}; +const char * const table_safehome_usage_mode[] = { + "OFF", + "RTH", + "RTH_FS", +}; +const char * const table_serial_rx[] = { + "SPEK1024", + "SPEK2048", + "SBUS", + "SUMD", + "IBUS", + "JETIEXBUS", + "CRSF", + "FPORT", + "SBUS_FAST", + "FPORT2", + "SRXL2", + "GHST", + "MAVLINK", +}; +const char * const table_servo_protocol[] = { + "PWM", + "SBUS", + "SBUS_PWM", +}; +const char * const table_tristate[] = { + "AUTO", + "ON", + "OFF", +}; +const char * const table_tz_automatic_dst[] = { + "OFF", + "EU", + "USA", +}; +const char * const table_voltage_sensor[] = { + "NONE", + "ADC", + "ESC", + "FAKE", +}; +static const lookupTableEntry_t settingLookupTables[] = { + { table_acc_hardware, sizeof(table_acc_hardware) / sizeof(char*) }, + { table_airmodeHandlingType, sizeof(table_airmodeHandlingType) / sizeof(char*) }, + { table_alignment, sizeof(table_alignment) / sizeof(char*) }, + { table_autotune_rate_adjustment, sizeof(table_autotune_rate_adjustment) / sizeof(char*) }, + { table_aux_operator, sizeof(table_aux_operator) / sizeof(char*) }, + { table_baro_hardware, sizeof(table_baro_hardware) / sizeof(char*) }, + { table_bat_capacity_unit, sizeof(table_bat_capacity_unit) / sizeof(char*) }, + { table_bat_voltage_source, sizeof(table_bat_voltage_source) / sizeof(char*) }, + { table_blackbox_device, sizeof(table_blackbox_device) / sizeof(char*) }, + { table_current_sensor, sizeof(table_current_sensor) / sizeof(char*) }, + { table_debug_modes, sizeof(table_debug_modes) / sizeof(char*) }, + { table_direction, sizeof(table_direction) / sizeof(char*) }, + { table_djiOsdTempSource, sizeof(table_djiOsdTempSource) / sizeof(char*) }, + { table_djiRssiSource, sizeof(table_djiRssiSource) / sizeof(char*) }, + { table_failsafe_procedure, sizeof(table_failsafe_procedure) / sizeof(char*) }, + { table_filter_type, sizeof(table_filter_type) / sizeof(char*) }, + { table_filter_type_full, sizeof(table_filter_type_full) / sizeof(char*) }, + { table_gps_dyn_model, sizeof(table_gps_dyn_model) / sizeof(char*) }, + { table_gps_provider, sizeof(table_gps_provider) / sizeof(char*) }, + { table_gps_sbas_mode, sizeof(table_gps_sbas_mode) / sizeof(char*) }, + { table_gyro_lpf, sizeof(table_gyro_lpf) / sizeof(char*) }, + { table_imu_inertia_comp_method, sizeof(table_imu_inertia_comp_method) / sizeof(char*) }, + { table_iterm_relax, sizeof(table_iterm_relax) / sizeof(char*) }, + { table_log_level, sizeof(table_log_level) / sizeof(char*) }, + { table_mag_hardware, sizeof(table_mag_hardware) / sizeof(char*) }, + { table_motor_pwm_protocol, sizeof(table_motor_pwm_protocol) / sizeof(char*) }, + { table_nav_extra_arming_safety, sizeof(table_nav_extra_arming_safety) / sizeof(char*) }, + { table_nav_fw_wp_turn_smoothing, sizeof(table_nav_fw_wp_turn_smoothing) / sizeof(char*) }, + { table_nav_overrides_motor_stop, sizeof(table_nav_overrides_motor_stop) / sizeof(char*) }, + { table_nav_rth_allow_landing, sizeof(table_nav_rth_allow_landing) / sizeof(char*) }, + { table_nav_rth_alt_mode, sizeof(table_nav_rth_alt_mode) / sizeof(char*) }, + { table_nav_rth_climb_first, sizeof(table_nav_rth_climb_first) / sizeof(char*) }, + { table_nav_rth_climb_first_stage_modes, sizeof(table_nav_rth_climb_first_stage_modes) / sizeof(char*) }, + { table_nav_user_control_mode, sizeof(table_nav_user_control_mode) / sizeof(char*) }, + { table_nav_wp_mission_restart, sizeof(table_nav_wp_mission_restart) / sizeof(char*) }, + { table_off_on, sizeof(table_off_on) / sizeof(char*) }, + { table_opflow_hardware, sizeof(table_opflow_hardware) / sizeof(char*) }, + { table_osdSpeedSource, sizeof(table_osdSpeedSource) / sizeof(char*) }, + { table_osd_ahi_style, sizeof(table_osd_ahi_style) / sizeof(char*) }, + { table_osd_alignment, sizeof(table_osd_alignment) / sizeof(char*) }, + { table_osd_crosshairs_style, sizeof(table_osd_crosshairs_style) / sizeof(char*) }, + { table_osd_crsf_lq_format, sizeof(table_osd_crsf_lq_format) / sizeof(char*) }, + { table_osd_plus_code_short, sizeof(table_osd_plus_code_short) / sizeof(char*) }, + { table_osd_sidebar_scroll, sizeof(table_osd_sidebar_scroll) / sizeof(char*) }, + { table_osd_stats_energy_unit, sizeof(table_osd_stats_energy_unit) / sizeof(char*) }, + { table_osd_stats_min_voltage_unit, sizeof(table_osd_stats_min_voltage_unit) / sizeof(char*) }, + { table_osd_telemetry, sizeof(table_osd_telemetry) / sizeof(char*) }, + { table_osd_unit, sizeof(table_osd_unit) / sizeof(char*) }, + { table_osd_video_system, sizeof(table_osd_video_system) / sizeof(char*) }, + { table_output_mode, sizeof(table_output_mode) / sizeof(char*) }, + { table_pidTypeTable, sizeof(table_pidTypeTable) / sizeof(char*) }, + { table_pitot_hardware, sizeof(table_pitot_hardware) / sizeof(char*) }, + { table_platform_type, sizeof(table_platform_type) / sizeof(char*) }, + { table_rangefinder_hardware, sizeof(table_rangefinder_hardware) / sizeof(char*) }, + { table_receiver_type, sizeof(table_receiver_type) / sizeof(char*) }, + { table_reset_type, sizeof(table_reset_type) / sizeof(char*) }, + { table_rssi_source, sizeof(table_rssi_source) / sizeof(char*) }, + { table_rth_trackback_mode, sizeof(table_rth_trackback_mode) / sizeof(char*) }, + { table_safehome_usage_mode, sizeof(table_safehome_usage_mode) / sizeof(char*) }, + { table_serial_rx, sizeof(table_serial_rx) / sizeof(char*) }, + { table_servo_protocol, sizeof(table_servo_protocol) / sizeof(char*) }, + { table_tristate, sizeof(table_tristate) / sizeof(char*) }, + { table_tz_automatic_dst, sizeof(table_tz_automatic_dst) / sizeof(char*) }, + { table_voltage_sensor, sizeof(table_voltage_sensor) / sizeof(char*) }, +}; +static const uint32_t settingMinMaxTable[] = { + 0, + 255, + 100, + 1000, + 10, + 1, + 2000, + 5, + 500, + 32767, + -32768, + 10000, + 4, + 65535, + 2, + 20, + 50, + 200, + 30, + 250, + 5000, + 65000, + -1800, + -550, + 15, + 3600, + 3, + 18, + 80, + 180, + 4294967295, + -20, + 60, + 90, + 95, + 1250, + 3000, + 60000, + 9, + 900, + 1500, + 4000, + 8192, + 2147483647, + -800, + -130, + -128, + -1, + 6, + 8, + 25, + 40, + 45, + 120, + 127, + 150, + 175, + 300, + 400, + 450, + 600, + 750, + 800, + 2250, + 9999, + 27000, + 40000, + 500000, + -18000, + -10000, + -1440, + -1000, + -50, + -40, + -36, + -10, + -2, + 11, + 12, + 13, + 16, + 32, + 36, + 48, + 99, + 126, + 128, + 498, + 1440, + 6000, + 9000, + 9990, + 16000, + 18000, + 20000, + 30000, + 32000, + 50000, +}; +typedef uint8_t setting_min_max_idx_t; +#define SETTING_INDEXES_GET_MIN(val) (val->config.minmax.indexes[0]) +#define SETTING_INDEXES_GET_MAX(val) (val->config.minmax.indexes[1]) +static const setting_t settingsTable[] = { + // PG_GYRO_CONFIG + { {167, 2, 0, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 90}, offsetof(gyroConfig_t, looptime) }, + { {30, 57, 14, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GYRO_LPF }, offsetof(gyroConfig_t, gyro_lpf) }, + { {147, 2, 0, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 3}, offsetof(gyroConfig_t, gyro_anti_aliasing_lpf_hz) }, + { {148, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_FILTER_TYPE }, offsetof(gyroConfig_t, gyro_anti_aliasing_lpf_type) }, + { {175, 2, 60, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 86}, offsetof(gyroConfig_t, gyroMovementCalibrationThreshold) }, + { {30, 132, 1, 14, 21, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 8}, offsetof(gyroConfig_t, gyro_main_lpf_hz) }, + { {30, 132, 1, 14, 32, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_FILTER_TYPE }, offsetof(gyroConfig_t, gyro_main_lpf_type) }, + { {30, 72, 79, 14, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(gyroConfig_t, useDynamicLpf) }, + { {30, 79, 14, 10, 21, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {51, 58}, offsetof(gyroConfig_t, gyroDynamicLpfMinHz) }, + { {30, 79, 14, 6, 21, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {51, 3}, offsetof(gyroConfig_t, gyroDynamicLpfMaxHz) }, + { {30, 79, 14, 238, 1, 56}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {5, 4}, offsetof(gyroConfig_t, gyroDynamicLpfCurveExpo) }, + { {160, 2, 30, 121, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(gyroConfig_t, init_gyro_cal_enabled) }, + { {30, 88, 86, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(gyroConfig_t, gyro_zero_cal[X]) }, + { {30, 88, 87, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(gyroConfig_t, gyro_zero_cal[Y]) }, + { {30, 88, 15, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(gyroConfig_t, gyro_zero_cal[Z]) }, + { {161, 2, 166, 1, 230, 1}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 6}, offsetof(gyroConfig_t, gravity_cmss_cal) }, + // PG_ADC_CHANNEL_CONFIG + { {61, 90, 42, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 12}, offsetof(adcChannelConfig_t, adcFunctionChannel[ADC_BATTERY]) }, + { {36, 90, 42, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 12}, offsetof(adcChannelConfig_t, adcFunctionChannel[ADC_RSSI]) }, + { {43, 90, 42, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 12}, offsetof(adcChannelConfig_t, adcFunctionChannel[ADC_CURRENT]) }, + { {91, 90, 42, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 12}, offsetof(adcChannelConfig_t, adcFunctionChannel[ADC_AIRSPEED]) }, + // PG_ACCELEROMETER_CONFIG + { {39, 185, 1, 21, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 1}, offsetof(accelerometerConfig_t, acc_notch_hz) }, + { {39, 185, 1, 100, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {5, 1}, offsetof(accelerometerConfig_t, acc_notch_cutoff) }, + { {39, 57, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_ACC_HARDWARE }, offsetof(accelerometerConfig_t, acc_hardware) }, + { {39, 14, 21, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 17}, offsetof(accelerometerConfig_t, acc_lpf_hz) }, + { {39, 14, 32, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_FILTER_TYPE }, offsetof(accelerometerConfig_t, acc_soft_lpf_type) }, + { {114, 86, 0, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(accelerometerConfig_t, accZero.raw[X]) }, + { {114, 87, 0, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(accelerometerConfig_t, accZero.raw[Y]) }, + { {114, 15, 0, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(accelerometerConfig_t, accZero.raw[Z]) }, + { {113, 86, 0, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {5, 42}, offsetof(accelerometerConfig_t, accGain.raw[X]) }, + { {113, 87, 0, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {5, 42}, offsetof(accelerometerConfig_t, accGain.raw[Y]) }, + { {113, 15, 0, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {5, 42}, offsetof(accelerometerConfig_t, accGain.raw[Z]) }, + // PG_RANGEFINDER_CONFIG + { {194, 1, 57, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_RANGEFINDER_HARDWARE }, offsetof(rangefinderConfig_t, rangefinder_hardware) }, + { {194, 1, 168, 2, 80, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(rangefinderConfig_t, use_median_filtering) }, + // PG_OPFLOW_CONFIG + { {134, 1, 57, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OPFLOW_HARDWARE }, offsetof(opticalFlowConfig_t, opflow_hardware) }, + { {134, 1, 82, 0, 0, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 11}, offsetof(opticalFlowConfig_t, opflow_scale) }, + { {41, 134, 1, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_ALIGNMENT }, offsetof(opticalFlowConfig_t, opflow_align) }, + // PG_COMPASS_CONFIG + { {41, 35, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_ALIGNMENT }, offsetof(compassConfig_t, mag_align) }, + { {35, 57, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_MAG_HARDWARE }, offsetof(compassConfig_t, mag_hardware) }, + { {35, 245, 1, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {68, 93}, offsetof(compassConfig_t, mag_declination) }, + { {131, 1, 86, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(compassConfig_t, magZero.raw[X]) }, + { {131, 1, 87, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(compassConfig_t, magZero.raw[Y]) }, + { {131, 1, 15, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(compassConfig_t, magZero.raw[Z]) }, + { {130, 1, 86, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(compassConfig_t, magGain[X]) }, + { {130, 1, 87, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(compassConfig_t, magGain[Y]) }, + { {130, 1, 15, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(compassConfig_t, magGain[Z]) }, + { {35, 227, 1, 25, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {15, 53}, offsetof(compassConfig_t, magCalibrationTimeLimit) }, + { {41, 35, 18, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {22, 25}, offsetof(compassConfig_t, rollDeciDegrees) }, + { {41, 35, 11, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {22, 25}, offsetof(compassConfig_t, pitchDeciDegrees) }, + { {41, 35, 8, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {22, 25}, offsetof(compassConfig_t, yawDeciDegrees) }, + // PG_BAROMETER_CONFIG + { {54, 57, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BARO_HARDWARE }, offsetof(barometerConfig_t, baro_hardware) }, + { {54, 121, 207, 1, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 3}, offsetof(barometerConfig_t, baro_calibration_tolerance) }, + // PG_PITOTMETER_CONFIG + { {136, 1, 57, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_PITOT_HARDWARE }, offsetof(pitotmeterConfig_t, pitot_hardware) }, + { {136, 1, 14, 172, 2, 21}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 11}, offsetof(pitotmeterConfig_t, pitot_lpf_milli_hz) }, + { {136, 1, 82, 0, 0, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(pitotmeterConfig_t, pitot_scale) }, + // PG_RX_CONFIG + { {236, 2, 32, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_RECEIVER_TYPE }, offsetof(rxConfig_t, receiverType) }, + { {10, 151, 1, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {3, 6}, offsetof(rxConfig_t, mincheck) }, + { {6, 151, 1, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {3, 6}, offsetof(rxConfig_t, maxcheck) }, + { {36, 84, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_RSSI_SOURCE }, offsetof(rxConfig_t, rssi_source) }, + { {36, 42, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 27}, offsetof(rxConfig_t, rssi_channel) }, + { {36, 10, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(rxConfig_t, rssiMin) }, + { {36, 6, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(rxConfig_t, rssiMax) }, + { {249, 2, 133, 3, 173, 1}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {8, 11}, offsetof(rxConfig_t, sbusSyncInterval) }, + { {59, 80, 14, 21, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {24, 19}, offsetof(rxConfig_t, rcFilterFrequency) }, + { {59, 80, 46, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(rxConfig_t, autoSmooth) }, + { {59, 80, 201, 1, 160, 1}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {5, 2}, offsetof(rxConfig_t, autoSmoothFactor) }, + { {140, 1, 192, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_SERIAL_RX }, offsetof(rxConfig_t, serialrx_provider) }, + { {140, 1, 128, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(rxConfig_t, serialrx_inverted) }, + { {202, 1, 111, 156, 2, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 24}, offsetof(rxConfig_t, srxl2_unit_id) }, + { {202, 1, 150, 1, 134, 2}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(rxConfig_t, srxl2_baud_fast) }, + { {198, 1, 10, 212, 1, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {61, 63}, offsetof(rxConfig_t, rx_min_usec) }, + { {198, 1, 6, 212, 1, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {61, 63}, offsetof(rxConfig_t, rx_max_usec) }, + { {140, 1, 168, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_TRISTATE }, offsetof(rxConfig_t, halfDuplex) }, + // PG_BLACKBOX_CONFIG + { {119, 5, 199, 2, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {5, 13}, offsetof(blackboxConfig_t, rate_num) }, + { {119, 5, 249, 1, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {5, 13}, offsetof(blackboxConfig_t, rate_denom) }, + { {119, 250, 1, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BLACKBOX_DEVICE }, offsetof(blackboxConfig_t, device) }, + // PG_MOTOR_CONFIG + { {6, 38, 0, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {3, 6}, offsetof(motorConfig_t, maxthrottle) }, + { {10, 231, 1, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 6}, offsetof(motorConfig_t, mincommand) }, + { {58, 110, 5, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {16, 96}, offsetof(motorConfig_t, motorPwmRate) }, + { {58, 110, 191, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_MOTOR_PWM_PROTOCOL }, offsetof(motorConfig_t, motorPwmProtocol) }, + { {58, 225, 2, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {12, 1}, offsetof(motorConfig_t, motorPoleCount) }, + // PG_FAILSAFE_CONFIG + { {19, 33, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 17}, offsetof(failsafeConfig_t, failsafe_delay) }, + { {19, 237, 2, 33, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 17}, offsetof(failsafeConfig_t, failsafe_recovery_delay) }, + { {19, 200, 2, 33, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 17}, offsetof(failsafeConfig_t, failsafe_off_delay) }, + { {19, 38, 178, 1, 33, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 57}, offsetof(failsafeConfig_t, failsafe_throttle_low_delay) }, + { {19, 190, 1, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_FAILSAFE_PROCEDURE }, offsetof(failsafeConfig_t, failsafe_procedure) }, + { {19, 203, 1, 60, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 8}, offsetof(failsafeConfig_t, failsafe_stick_motion_threshold) }, + { {19, 2, 18, 24, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {44, 62}, offsetof(failsafeConfig_t, failsafe_fw_roll_angle) }, + { {19, 2, 11, 24, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {44, 62}, offsetof(failsafeConfig_t, failsafe_fw_pitch_angle) }, + { {19, 2, 8, 5, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {71, 3}, offsetof(failsafeConfig_t, failsafe_fw_yaw_rate) }, + { {19, 10, 65, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 21}, offsetof(failsafeConfig_t, failsafe_min_distance) }, + { {19, 10, 65, 190, 1, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_FAILSAFE_PROCEDURE }, offsetof(failsafeConfig_t, failsafe_min_distance_procedure) }, + { {19, 183, 1, 33, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {47, 60}, offsetof(failsafeConfig_t, failsafe_mission_delay) }, + // PG_BOARD_ALIGNMENT + { {41, 120, 18, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {22, 25}, offsetof(boardAlignment_t, rollDeciDegrees) }, + { {41, 120, 11, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {22, 25}, offsetof(boardAlignment_t, pitchDeciDegrees) }, + { {41, 120, 8, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {22, 25}, offsetof(boardAlignment_t, yawDeciDegrees) }, + // PG_BATTERY_METERS_CONFIG + { {61, 109, 32, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_VOLTAGE_SENSOR }, offsetof(batteryMetersConfig_t, voltage.type) }, + { {61, 82, 0, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 13}, offsetof(batteryMetersConfig_t, voltage.scale) }, + { {43, 109, 82, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {69, 11}, offsetof(batteryMetersConfig_t, current.scale) }, + { {43, 109, 69, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(batteryMetersConfig_t, current.offset) }, + { {43, 109, 32, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_CURRENT_SENSOR }, offsetof(batteryMetersConfig_t, current.type) }, + { {149, 1, 63, 129, 3, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BAT_VOLTAGE_SOURCE }, offsetof(batteryMetersConfig_t, voltageSource) }, + { {99, 70, 0, 0, 0, 0}, VAR_UINT32 | MASTER_VALUE, .config.minmax.indexes = {0, 30}, offsetof(batteryMetersConfig_t, cruise_power) }, + { {107, 70, 0, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 13}, offsetof(batteryMetersConfig_t, idle_power) }, + { {28, 124, 133, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(batteryMetersConfig_t, rth_energy_margin) }, + { {45, 98, 146, 1, 0, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 14}, offsetof(batteryMetersConfig_t, throttle_compensation_weight) }, + // PG_BATTERY_PROFILES + { {149, 1, 228, 1, 0, 0}, VAR_UINT8 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 78}, offsetof(batteryProfile_t, cells) }, + { {61, 96, 123, 63, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {2, 8}, offsetof(batteryProfile_t, voltage.cellDetect) }, + { {61, 6, 96, 63, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {2, 8}, offsetof(batteryProfile_t, voltage.cellMax) }, + { {61, 10, 96, 63, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {2, 8}, offsetof(batteryProfile_t, voltage.cellMin) }, + { {61, 214, 1, 96, 63, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {2, 8}, offsetof(batteryProfile_t, voltage.cellWarning) }, + { {92, 94, 0, 0, 0, 0}, VAR_UINT32 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 30}, offsetof(batteryProfile_t, capacity.value) }, + { {92, 94, 214, 1, 0, 0}, VAR_UINT32 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 30}, offsetof(batteryProfile_t, capacity.warning) }, + { {92, 94, 236, 1, 0, 0}, VAR_UINT32 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 30}, offsetof(batteryProfile_t, capacity.critical) }, + { {92, 94, 111, 0, 0, 0}, VAR_UINT8 | BATTERY_CONFIG_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BAT_CAPACITY_UNIT }, offsetof(batteryProfile_t, capacity.unit) }, + { {234, 1, 230, 2, 0, 0}, VAR_UINT8 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 26}, offsetof(batteryProfile_t, controlRateProfile) }, + { {38, 82, 0, 0, 0, 0}, VAR_FLOAT | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 5}, offsetof(batteryProfile_t, motor.throttleScale) }, + { {38, 107, 0, 0, 0, 0}, VAR_FLOAT | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 18}, offsetof(batteryProfile_t, motor.throttleIdle) }, + { {19, 38, 0, 0, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {3, 6}, offsetof(batteryProfile_t, failsafe_throttle) }, + { {1, 4, 155, 2, 45, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {3, 6}, offsetof(batteryProfile_t, nav.mc.hover_throttle) }, + { {1, 2, 99, 45, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {3, 6}, offsetof(batteryProfile_t, nav.fw.cruise_throttle) }, + { {1, 2, 10, 45, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {3, 6}, offsetof(batteryProfile_t, nav.fw.min_throttle) }, + { {1, 2, 6, 45, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {3, 6}, offsetof(batteryProfile_t, nav.fw.max_throttle) }, + { {1, 2, 135, 1, 0, 0}, VAR_UINT8 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 2}, offsetof(batteryProfile_t, nav.fw.pitch_to_throttle) }, + { {1, 2, 16, 45, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {3, 6}, offsetof(batteryProfile_t, nav.fw.launch_throttle) }, + { {1, 2, 16, 107, 45, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {3, 6}, offsetof(batteryProfile_t, nav.fw.launch_idle_throttle) }, + { {13, 152, 1, 43, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 41}, offsetof(batteryProfile_t, powerLimits.continuousCurrent) }, + { {13, 64, 43, 0, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 41}, offsetof(batteryProfile_t, powerLimits.burstCurrent) }, + { {13, 64, 43, 25, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 36}, offsetof(batteryProfile_t, powerLimits.burstCurrentTime) }, + { {13, 64, 43, 161, 1, 25}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 36}, offsetof(batteryProfile_t, powerLimits.burstCurrentFalldownTime) }, + { {13, 152, 1, 70, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 66}, offsetof(batteryProfile_t, powerLimits.continuousPower) }, + { {13, 64, 70, 0, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 66}, offsetof(batteryProfile_t, powerLimits.burstPower) }, + { {13, 64, 70, 25, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 36}, offsetof(batteryProfile_t, powerLimits.burstPowerTime) }, + { {13, 64, 70, 161, 1, 25}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 36}, offsetof(batteryProfile_t, powerLimits.burstPowerFalldownTime) }, + // PG_MIXER_CONFIG + { {58, 154, 1, 128, 1, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(mixerConfig_t, motorDirectionInverted) }, + { {224, 2, 32, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_PLATFORM_TYPE }, offsetof(mixerConfig_t, platformType) }, + { {149, 2, 137, 2, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(mixerConfig_t, hasFlaps) }, + { {184, 1, 229, 2, 32, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {47, 9}, offsetof(mixerConfig_t, appliedMixerPreset) }, + { {219, 2, 49, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OUTPUT_MODE }, offsetof(mixerConfig_t, outputMode) }, + // PG_REVERSIBLE_MOTORS_CONFIG + { {89, 29, 178, 1, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {3, 6}, offsetof(reversibleMotorsConfig_t, deadband_low) }, + { {89, 29, 150, 2, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {3, 6}, offsetof(reversibleMotorsConfig_t, deadband_high) }, + { {89, 197, 2, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {3, 6}, offsetof(reversibleMotorsConfig_t, neutral) }, + // PG_SERVO_CONFIG + { {50, 191, 1, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_SERVO_PROTOCOL }, offsetof(servoConfig_t, servo_protocol) }, + { {50, 97, 231, 2, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {3, 6}, offsetof(servoConfig_t, servoCenterPulse) }, + { {50, 110, 5, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {16, 87}, offsetof(servoConfig_t, servoPwmRate) }, + { {50, 14, 21, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {0, 58}, offsetof(servoConfig_t, servo_lowpass_freq) }, + { {136, 2, 206, 1, 69, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {16, 59}, offsetof(servoConfig_t, flaperon_throw_offset) }, + { {140, 3, 143, 3, 50, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(servoConfig_t, tri_unarmed_servo) }, + { {50, 223, 1, 243, 2, 13}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {5, 32}, offsetof(servoConfig_t, servo_autotrim_rotation_limit) }, + // PG_CONTROL_RATE_PROFILES + { {45, 171, 2, 0, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(controlRateConfig_t, throttle.rcMid8) }, + { {45, 56, 0, 0, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(controlRateConfig_t, throttle.rcExpo8) }, + { {145, 1, 5, 0, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(controlRateConfig_t, throttle.dynPID) }, + { {145, 1, 226, 1, 0, 0}, VAR_UINT16 | CONTROL_RATE_VALUE, .config.minmax.indexes = {3, 6}, offsetof(controlRateConfig_t, throttle.pa_breakpoint) }, + { {2, 145, 1, 25, 233, 1}, VAR_UINT16 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 20}, offsetof(controlRateConfig_t, throttle.fixedWingTauMs) }, + { {59, 56, 0, 0, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(controlRateConfig_t, stabilized.rcExpo8) }, + { {59, 8, 56, 0, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(controlRateConfig_t, stabilized.rcYawExpo8) }, + { {18, 5, 0, 0, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {12, 29}, offsetof(controlRateConfig_t, stabilized.rates[FD_ROLL]) }, + { {11, 5, 0, 0, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {12, 29}, offsetof(controlRateConfig_t, stabilized.rates[FD_PITCH]) }, + { {8, 5, 0, 0, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {5, 29}, offsetof(controlRateConfig_t, stabilized.rates[FD_YAW]) }, + { {48, 59, 56, 0, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(controlRateConfig_t, manual.rcExpo8) }, + { {48, 59, 8, 56, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(controlRateConfig_t, manual.rcYawExpo8) }, + { {48, 18, 5, 0, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(controlRateConfig_t, manual.rates[FD_ROLL]) }, + { {48, 11, 5, 0, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(controlRateConfig_t, manual.rates[FD_PITCH]) }, + { {48, 8, 5, 0, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(controlRateConfig_t, manual.rates[FD_YAW]) }, + { {139, 2, 173, 2, 248, 1}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 16}, offsetof(controlRateConfig_t, misc.fpvCamAngleDegrees) }, + { {5, 66, 97, 139, 1, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {50, 56}, offsetof(controlRateConfig_t, rateDynamics.sensitivityCenter) }, + { {5, 66, 104, 139, 1, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {50, 56}, offsetof(controlRateConfig_t, rateDynamics.sensitivityEnd) }, + { {5, 66, 97, 153, 1, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {4, 34}, offsetof(controlRateConfig_t, rateDynamics.correctionCenter) }, + { {5, 66, 104, 153, 1, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {4, 34}, offsetof(controlRateConfig_t, rateDynamics.correctionEnd) }, + { {5, 66, 97, 146, 1, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 34}, offsetof(controlRateConfig_t, rateDynamics.weightCenter) }, + { {5, 66, 104, 146, 1, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 34}, offsetof(controlRateConfig_t, rateDynamics.weightEnd) }, + // PG_SERIAL_CONFIG + { {235, 2, 229, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {83, 85}, offsetof(serialConfig_t, reboot_character) }, + // PG_IMU_CONFIG + { {34, 101, 175, 1, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 13}, offsetof(imuConfig_t, dcm_kp_acc) }, + { {34, 101, 174, 1, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 13}, offsetof(imuConfig_t, dcm_ki_acc) }, + { {34, 101, 175, 1, 35, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 13}, offsetof(imuConfig_t, dcm_kp_mag) }, + { {34, 101, 174, 1, 35, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 13}, offsetof(imuConfig_t, dcm_ki_mag) }, + { {252, 2, 24, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 29}, offsetof(imuConfig_t, small_angle) }, + { {34, 39, 171, 1, 5, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 18}, offsetof(imuConfig_t, acc_ignore_rate) }, + { {34, 39, 171, 1, 251, 2}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(imuConfig_t, acc_ignore_slope) }, + { {34, 20, 8, 152, 3, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(imuConfig_t, gps_yaw_windcomp) }, + { {34, 159, 2, 98, 170, 2}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_IMU_INERTIA_COMP_METHOD }, offsetof(imuConfig_t, inertia_comp_method) }, + // PG_ARMING_CONFIG + { {135, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(armingConfig_t, fixed_wing_auto_arm) }, + { {102, 162, 2, 31, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(armingConfig_t, disarm_kill_switch) }, + { {31, 102, 33, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 3}, offsetof(armingConfig_t, switchDisarmDelayMs) }, + { {227, 2, 85, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 11}, offsetof(armingConfig_t, prearmTimeoutMs) }, + // PG_GENERAL_SETTINGS + { {219, 1, 246, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 84}, offsetof(generalSettings_t, appliedDefaults) }, + // PG_GPS_CONFIG + { {20, 192, 1, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GPS_PROVIDER }, offsetof(gpsConfig_t, provider) }, + { {20, 248, 2, 49, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GPS_SBAS_MODE }, offsetof(gpsConfig_t, sbasMode) }, + { {20, 79, 184, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GPS_DYN_MODEL }, offsetof(gpsConfig_t, dynModel) }, + { {20, 46, 232, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(gpsConfig_t, autoConfig) }, + { {20, 46, 150, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(gpsConfig_t, autoBaud) }, + { {20, 142, 3, 72, 144, 2}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(gpsConfig_t, ubloxUseGalileo) }, + { {20, 10, 247, 2, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {7, 4}, offsetof(gpsConfig_t, gpsMinSats) }, + // PG_RC_CONTROLS_CONFIG + { {29, 0, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 81}, offsetof(rcControlsConfig_t, deadband) }, + { {8, 29, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(rcControlsConfig_t, yaw_deadband) }, + { {23, 127, 29, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {14, 19}, offsetof(rcControlsConfig_t, pos_hold_deadband) }, + { {77, 29, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {14, 19}, offsetof(rcControlsConfig_t, control_deadband) }, + { {74, 127, 29, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {4, 19}, offsetof(rcControlsConfig_t, alt_hold_deadband) }, + { {89, 29, 38, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 17}, offsetof(rcControlsConfig_t, mid_throttle_deadband) }, + { {148, 1, 32, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_AIRMODEHANDLINGTYPE }, offsetof(rcControlsConfig_t, airmodeHandlingType) }, + { {148, 1, 38, 60, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {3, 6}, offsetof(rcControlsConfig_t, airmodeThrottleThreshold) }, + // PG_PID_PROFILE + { {4, 7, 11, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_PITCH].P) }, + { {4, 22, 11, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_PITCH].I) }, + { {4, 17, 11, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_PITCH].D) }, + { {4, 95, 11, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_PITCH].FF) }, + { {4, 7, 18, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_ROLL].P) }, + { {4, 22, 18, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_ROLL].I) }, + { {4, 17, 18, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_ROLL].D) }, + { {4, 95, 18, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_ROLL].FF) }, + { {4, 7, 8, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_YAW].P) }, + { {4, 22, 8, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_YAW].I) }, + { {4, 17, 8, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_YAW].D) }, + { {4, 95, 8, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_YAW].FF) }, + { {4, 7, 44, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_LEVEL].P) }, + { {4, 22, 44, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_LEVEL].I) }, + { {4, 17, 44, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_LEVEL].D) }, + { {2, 7, 11, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_PITCH].P) }, + { {2, 22, 11, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_PITCH].I) }, + { {2, 17, 11, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_PITCH].D) }, + { {2, 106, 11, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_PITCH].FF) }, + { {2, 7, 18, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_ROLL].P) }, + { {2, 22, 18, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_ROLL].I) }, + { {2, 17, 18, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_ROLL].D) }, + { {2, 106, 18, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_ROLL].FF) }, + { {2, 7, 8, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_YAW].P) }, + { {2, 22, 8, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_YAW].I) }, + { {2, 17, 8, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_YAW].D) }, + { {2, 106, 8, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_YAW].FF) }, + { {2, 7, 44, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_LEVEL].P) }, + { {2, 22, 44, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_LEVEL].I) }, + { {2, 17, 44, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_LEVEL].D) }, + { {6, 24, 172, 1, 242, 2}, VAR_INT16 | PROFILE_VALUE, .config.minmax.indexes = {2, 39}, offsetof(pidProfile_t, max_angle_inclination[FD_ROLL]) }, + { {6, 24, 172, 1, 223, 2}, VAR_INT16 | PROFILE_VALUE, .config.minmax.indexes = {2, 39}, offsetof(pidProfile_t, max_angle_inclination[FD_PITCH]) }, + { {103, 14, 21, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 8}, offsetof(pidProfile_t, dterm_lpf_hz) }, + { {103, 14, 32, 0, 0, 0}, VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_FILTER_TYPE_FULL }, offsetof(pidProfile_t, dterm_lpf_type) }, + { {103, 179, 1, 21, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 8}, offsetof(pidProfile_t, dterm_lpf2_hz) }, + { {103, 179, 1, 32, 0, 0}, VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_FILTER_TYPE_FULL }, offsetof(pidProfile_t, dterm_lpf2_type) }, + { {8, 14, 21, 0, 0, 0}, VAR_UINT8 | PROFILE_VALUE, .config.minmax.indexes = {0, 17}, offsetof(pidProfile_t, yaw_lpf_hz) }, + { {2, 108, 206, 1, 13, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 8}, offsetof(pidProfile_t, fixedWingItermThrowLimit) }, + { {2, 238, 2, 91, 0, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {57, 89}, offsetof(pidProfile_t, fixedWingReferenceAirspeed) }, + { {142, 2, 0, 0, 0, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {0, 14}, offsetof(pidProfile_t, fixedWingCoordinatedYawGain) }, + { {141, 2, 0, 0, 0, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {0, 14}, offsetof(pidProfile_t, fixedWingCoordinatedPitchGain) }, + { {140, 2, 0, 0, 0, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {0, 5}, offsetof(pidProfile_t, fixedWingItermLimitOnStickPosition) }, + { {143, 2, 0, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 33}, offsetof(pidProfile_t, fixedWingYawItermBankFreeze) }, + { {189, 1, 13, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {2, 3}, offsetof(pidProfile_t, pidSumLimit) }, + { {189, 1, 13, 8, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {2, 3}, offsetof(pidProfile_t, pidSumLimitYaw) }, + { {108, 153, 3, 0, 0, 0}, VAR_UINT8 | PROFILE_VALUE, .config.minmax.indexes = {0, 33}, offsetof(pidProfile_t, itermWindupPointPercent) }, + { {5, 112, 13, 18, 11, 0}, VAR_UINT32 | PROFILE_VALUE, .config.minmax.indexes = {0, 67}, offsetof(pidProfile_t, axisAccelerationLimitRollPitch) }, + { {5, 112, 13, 8, 0, 0}, VAR_UINT32 | PROFILE_VALUE, .config.minmax.indexes = {0, 67}, offsetof(pidProfile_t, axisAccelerationLimitYaw) }, + { {126, 127, 5, 13, 0, 0}, VAR_UINT8 | PROFILE_VALUE, .config.minmax.indexes = {4, 19}, offsetof(pidProfile_t, heading_hold_rate_limit) }, + { {1, 4, 23, 15, 7, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_POS_Z].P) }, + { {1, 4, 62, 15, 7, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_VEL_Z].P) }, + { {1, 4, 62, 15, 22, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_VEL_Z].I) }, + { {1, 4, 62, 15, 17, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_VEL_Z].D) }, + { {1, 4, 23, 27, 7, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_POS_XY].P) }, + { {1, 4, 62, 27, 7, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_VEL_XY].P) }, + { {1, 4, 62, 27, 22, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_VEL_XY].I) }, + { {1, 4, 62, 27, 17, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_VEL_XY].D) }, + { {1, 4, 62, 27, 106, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_VEL_XY].FF) }, + { {1, 4, 126, 7, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_HEADING].P) }, + { {188, 2, 0, 0, 0, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(pidProfile_t, navVelXyDTermLpfHz) }, + { {185, 2, 0, 0, 0, 0}, VAR_UINT8 | PROFILE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(pidProfile_t, navVelXyDtermAttenuation) }, + { {187, 2, 0, 0, 0, 0}, VAR_UINT8 | PROFILE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(pidProfile_t, navVelXyDtermAttenuationStart) }, + { {186, 2, 0, 0, 0, 0}, VAR_UINT8 | PROFILE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(pidProfile_t, navVelXyDtermAttenuationEnd) }, + { {1, 2, 23, 15, 7, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_POS_Z].P) }, + { {1, 2, 23, 15, 22, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_POS_Z].I) }, + { {1, 2, 23, 15, 17, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_POS_Z].D) }, + { {1, 2, 23, 27, 7, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_POS_XY].P) }, + { {1, 2, 23, 27, 22, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_POS_XY].I) }, + { {1, 2, 23, 27, 17, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_POS_XY].D) }, + { {1, 2, 126, 7, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_HEADING].P) }, + { {1, 2, 23, 125, 7, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_POS_HEADING].P) }, + { {1, 2, 23, 125, 22, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_POS_HEADING].I) }, + { {1, 2, 23, 125, 17, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_POS_HEADING].D) }, + { {178, 2, 0, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {2, 3}, offsetof(pidProfile_t, navFwPosHdgPidsumLimit) }, + { {4, 108, 195, 1, 0, 0}, VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_ITERM_RELAX }, offsetof(pidProfile_t, iterm_relax) }, + { {4, 108, 195, 1, 100, 0}, VAR_UINT8 | PROFILE_VALUE, .config.minmax.indexes = {5, 2}, offsetof(pidProfile_t, iterm_relax_cutoff) }, + { {17, 75, 10, 0, 0, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {0, 5}, offsetof(pidProfile_t, dBoostMin) }, + { {17, 75, 6, 0, 0, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {5, 26}, offsetof(pidProfile_t, dBoostMax) }, + { {240, 1, 0, 0, 0, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {3, 92}, offsetof(pidProfile_t, dBoostMaxAtAlleceleration) }, + { {239, 1, 0, 0, 0, 0}, VAR_UINT8 | PROFILE_VALUE, .config.minmax.indexes = {4, 19}, offsetof(pidProfile_t, dBoostGyroDeltaLpfHz) }, + { {115, 165, 1, 0, 0, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {5, 15}, offsetof(pidProfile_t, antigravityGain) }, + { {115, 215, 1, 0, 0, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {5, 15}, offsetof(pidProfile_t, antigravityAccelerator) }, + { {115, 100, 14, 21, 0, 0}, VAR_UINT8 | PROFILE_VALUE, .config.minmax.indexes = {5, 18}, offsetof(pidProfile_t, antigravityCutoff) }, + { {222, 2, 32, 0, 0, 0}, VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_PIDTYPETABLE }, offsetof(pidProfile_t, pidControllerType) }, + { {4, 95, 14, 21, 0, 0}, VAR_UINT8 | PROFILE_VALUE, .config.minmax.indexes = {0, 17}, offsetof(pidProfile_t, controlDerivativeLpfHz) }, + { {2, 44, 11, 141, 3, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {75, 4}, offsetof(pidProfile_t, fixedWingLevelTrim) }, + { {142, 1, 137, 1, 132, 3}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {0, 5}, offsetof(pidProfile_t, smithPredictorStrength) }, + { {142, 1, 137, 1, 33, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {0, 49}, offsetof(pidProfile_t, smithPredictorDelay) }, + { {142, 1, 137, 1, 14, 21}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {5, 8}, offsetof(pidProfile_t, smithPredictorFilterHz) }, + { {2, 44, 11, 165, 1, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {0, 15}, offsetof(pidProfile_t, fixedWingLevelTrimGain) }, + // PG_PID_AUTOTUNE_CONFIG + { {2, 116, 10, 203, 1, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(pidAutotuneConfig_t, fw_min_stick) }, + { {2, 116, 5, 216, 1, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_AUTOTUNE_RATE_ADJUSTMENT }, offsetof(pidAutotuneConfig_t, fw_rate_adjustment) }, + { {2, 116, 6, 5, 247, 1}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {16, 2}, offsetof(pidAutotuneConfig_t, fw_max_rate_deflection) }, + // PG_POSITION_ESTIMATION_CONFIG + { {9, 46, 35, 244, 1, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(positionEstimationConfig_t, automatic_mag_declination) }, + { {9, 166, 1, 121, 207, 1}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 1}, offsetof(positionEstimationConfig_t, gravity_calibration_tolerance) }, + { {9, 72, 20, 147, 3, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(positionEstimationConfig_t, use_gps_velned) }, + { {9, 72, 20, 198, 2, 54}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(positionEstimationConfig_t, use_gps_no_baro) }, + { {157, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(positionEstimationConfig_t, allow_dead_reckoning) }, + { {9, 197, 1, 53, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_RESET_TYPE }, offsetof(positionEstimationConfig_t, reset_altitude_type) }, + { {9, 197, 1, 170, 1, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_RESET_TYPE }, offsetof(positionEstimationConfig_t, reset_home_type) }, + { {9, 6, 143, 1, 53, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 3}, offsetof(positionEstimationConfig_t, max_surface_altitude) }, + { {9, 26, 15, 143, 1, 7}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(positionEstimationConfig_t, w_z_surface_p) }, + { {9, 26, 15, 143, 1, 52}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(positionEstimationConfig_t, w_z_surface_v) }, + { {9, 26, 27, 163, 1, 7}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(positionEstimationConfig_t, w_xy_flow_p) }, + { {9, 26, 27, 163, 1, 52}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(positionEstimationConfig_t, w_xy_flow_v) }, + { {9, 26, 15, 54, 7, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(positionEstimationConfig_t, w_z_baro_p) }, + { {9, 26, 15, 20, 7, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(positionEstimationConfig_t, w_z_gps_p) }, + { {9, 26, 15, 20, 52, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(positionEstimationConfig_t, w_z_gps_v) }, + { {9, 26, 27, 20, 7, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(positionEstimationConfig_t, w_xy_gps_p) }, + { {9, 26, 27, 20, 52, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(positionEstimationConfig_t, w_xy_gps_v) }, + { {9, 26, 15, 196, 1, 52}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(positionEstimationConfig_t, w_z_res_v) }, + { {9, 26, 27, 196, 1, 52}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(positionEstimationConfig_t, w_xy_res_v) }, + { {9, 26, 155, 3, 39, 7}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 5}, offsetof(positionEstimationConfig_t, w_xyz_acc_p) }, + { {9, 26, 39, 224, 1, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 5}, offsetof(positionEstimationConfig_t, w_acc_bias) }, + { {9, 6, 133, 2, 159, 1}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 64}, offsetof(positionEstimationConfig_t, max_eph_epv) }, + { {9, 54, 159, 1, 0, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 64}, offsetof(positionEstimationConfig_t, baro_epv) }, + // PG_NAV_CONFIG + { {1, 102, 201, 2, 129, 1}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(navConfig_t, general.flags.disarm_on_landing) }, + { {1, 68, 123, 139, 1, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {5, 24}, offsetof(navConfig_t, general.land_detect_sensitivity) }, + { {193, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(navConfig_t, general.flags.use_thr_mid_for_althold) }, + { {176, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_NAV_EXTRA_ARMING_SAFETY }, offsetof(navConfig_t, general.flags.extra_arming_safety) }, + { {1, 146, 3, 77, 49, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_NAV_USER_CONTROL_MODE }, offsetof(navConfig_t, general.flags.user_control_mode) }, + { {1, 226, 2, 85, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(navConfig_t, general.pos_failure_timeout) }, + { {194, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(navConfig_t, general.waypoint_load_on_boot) }, + { {1, 73, 193, 1, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {4, 11}, offsetof(navConfig_t, general.waypoint_radius) }, + { {1, 73, 132, 2, 53, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 6}, offsetof(navConfig_t, general.waypoint_enforce_altitude) }, + { {1, 73, 6, 246, 2, 65}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 40}, offsetof(navConfig_t, general.waypoint_safe_distance) }, + { {1, 73, 183, 1, 239, 2}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_NAV_WP_MISSION_RESTART }, offsetof(navConfig_t, general.flags.waypoint_mission_restart) }, + { {195, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {5, 38}, offsetof(navConfig_t, general.waypoint_multi_mission_index) }, + { {180, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(navConfig_t, fw.wp_tracking_accuracy) }, + { {181, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {18, 28}, offsetof(navConfig_t, fw.wp_tracking_max_angle) }, + { {182, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_NAV_FW_WP_TURN_SMOOTHING }, offsetof(navConfig_t, fw.wp_turn_smoothing) }, + { {1, 46, 37, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {4, 6}, offsetof(navConfig_t, general.auto_speed) }, + { {1, 6, 46, 37, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {4, 6}, offsetof(navConfig_t, general.max_auto_speed) }, + { {1, 46, 76, 5, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {4, 6}, offsetof(navConfig_t, general.max_auto_climb_rate) }, + { {1, 48, 37, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {4, 6}, offsetof(navConfig_t, general.max_manual_speed) }, + { {1, 48, 76, 5, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {4, 6}, offsetof(navConfig_t, general.max_manual_climb_rate) }, + { {1, 68, 182, 1, 213, 1}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {16, 8}, offsetof(navConfig_t, general.land_minalt_vspd) }, + { {1, 68, 181, 1, 213, 1}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {2, 6}, offsetof(navConfig_t, general.land_maxalt_vspd) }, + { {1, 68, 141, 1, 182, 1}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {16, 3}, offsetof(navConfig_t, general.land_slowdown_minalt) }, + { {1, 68, 141, 1, 181, 1}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {8, 41}, offsetof(navConfig_t, general.land_slowdown_maxalt) }, + { {1, 130, 2, 129, 1, 37}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {2, 6}, offsetof(navConfig_t, general.emerg_descent_rate) }, + { {1, 10, 28, 65, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 20}, offsetof(navConfig_t, general.min_rth_distance) }, + { {1, 221, 2, 58, 130, 3}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_NAV_OVERRIDES_MOTOR_STOP }, offsetof(navConfig_t, general.flags.nav_overrides_motor_stop) }, + { {179, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(navConfig_t, general.flags.soaring_motor_stop) }, + { {1, 2, 255, 2, 11, 29}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 24}, offsetof(navConfig_t, fw.soaring_pitch_deadband) }, + { {1, 28, 76, 162, 1, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_NAV_RTH_CLIMB_FIRST }, offsetof(navConfig_t, general.flags.rth_climb_first) }, + { {191, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_NAV_RTH_CLIMB_FIRST_STAGE_MODES }, offsetof(navConfig_t, general.flags.rth_climb_first_stage_mode) }, + { {190, 2, 0, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 21}, offsetof(navConfig_t, general.rth_climb_first_stage_altitude) }, + { {192, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(navConfig_t, general.flags.rth_climb_ignore_emerg) }, + { {1, 28, 135, 3, 162, 1}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(navConfig_t, general.flags.rth_tail_first) }, + { {1, 28, 218, 1, 129, 1}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_NAV_RTH_ALLOW_LANDING }, offsetof(navConfig_t, general.flags.rth_allow_landing) }, + { {1, 28, 74, 49, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_NAV_RTH_ALT_MODE }, offsetof(navConfig_t, general.flags.rth_alt_control_mode) }, + { {1, 28, 74, 77, 220, 2}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(navConfig_t, general.flags.rth_alt_control_override) }, + { {1, 28, 147, 1, 60, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 21}, offsetof(navConfig_t, general.rth_abort_threshold) }, + { {183, 2, 0, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 3}, offsetof(navConfig_t, general.max_terrain_follow_altitude) }, + { {1, 6, 53, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 21}, offsetof(navConfig_t, general.max_altitude) }, + { {1, 28, 53, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 21}, offsetof(navConfig_t, general.rth_altitude) }, + { {1, 28, 170, 1, 53, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 21}, offsetof(navConfig_t, general.rth_home_altitude) }, + { {1, 28, 208, 1, 49, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_RTH_TRACKBACK_MODE }, offsetof(navConfig_t, general.flags.rth_trackback_mode) }, + { {1, 28, 208, 1, 65, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {16, 6}, offsetof(navConfig_t, general.rth_trackback_distance) }, + { {199, 1, 6, 65, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 21}, offsetof(navConfig_t, general.safehome_max_distance) }, + { {199, 1, 145, 3, 49, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_SAFEHOME_USAGE_MODE }, offsetof(navConfig_t, general.flags.safehome_usage_mode) }, + { {189, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(navConfig_t, general.flags.mission_planner_reset) }, + { {1, 4, 117, 24, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {24, 52}, offsetof(navConfig_t, mc.max_bank_angle) }, + { {1, 46, 102, 33, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {2, 11}, offsetof(navConfig_t, general.auto_disarm_delay) }, + { {1, 4, 55, 37, 60, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 3}, offsetof(navConfig_t, mc.braking_speed_threshold) }, + { {1, 4, 55, 252, 1, 37}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 3}, offsetof(navConfig_t, mc.braking_disengage_speed) }, + { {1, 4, 55, 85, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {2, 20}, offsetof(navConfig_t, mc.braking_timeout) }, + { {1, 4, 55, 75, 160, 1}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 17}, offsetof(navConfig_t, mc.braking_boost_factor) }, + { {1, 4, 55, 75, 85, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 20}, offsetof(navConfig_t, mc.braking_boost_timeout) }, + { {1, 4, 55, 75, 37, 60}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {2, 3}, offsetof(navConfig_t, mc.braking_boost_speed_threshold) }, + { {184, 2, 0, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 3}, offsetof(navConfig_t, mc.braking_boost_disengage_speed) }, + { {1, 4, 55, 117, 24, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {24, 32}, offsetof(navConfig_t, mc.braking_bank_angle) }, + { {1, 4, 23, 242, 1, 25}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 1}, offsetof(navConfig_t, mc.posDecelerationTime) }, + { {1, 4, 23, 56, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 1}, offsetof(navConfig_t, mc.posResponseExpo) }, + { {1, 4, 73, 141, 1, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(navConfig_t, mc.slowDownForTurning) }, + { {1, 2, 117, 24, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {7, 28}, offsetof(navConfig_t, fw.max_bank_angle) }, + { {1, 2, 76, 24, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {7, 28}, offsetof(navConfig_t, fw.max_climb_angle) }, + { {1, 2, 157, 1, 24, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {7, 28}, offsetof(navConfig_t, fw.max_dive_angle) }, + { {1, 2, 135, 1, 201, 1}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 38}, offsetof(navConfig_t, fw.pitch_to_throttle_smooth) }, + { {2, 10, 38, 128, 2, 11}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 59}, offsetof(navConfig_t, fw.minThrottleDownPitchAngle) }, + { {1, 2, 135, 1, 60, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 39}, offsetof(navConfig_t, fw.pitch_to_throttle_thresh) }, + { {1, 2, 177, 1, 193, 1}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 95}, offsetof(navConfig_t, fw.loiter_radius) }, + { {2, 177, 1, 154, 1, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_DIRECTION }, offsetof(navConfig_t, fw.loiter_direction) }, + { {1, 2, 99, 37, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 13}, offsetof(navConfig_t, fw.cruise_speed) }, + { {1, 2, 77, 253, 2, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 38}, offsetof(navConfig_t, fw.control_smoothness) }, + { {1, 2, 68, 157, 1, 24}, VAR_INT8 | MASTER_VALUE, .config.minmax.indexes = {31, 15}, offsetof(navConfig_t, fw.land_dive_angle) }, + { {1, 2, 16, 148, 3, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {2, 11}, offsetof(navConfig_t, fw.launch_velocity_thresh) }, + { {1, 2, 16, 112, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {3, 94}, offsetof(navConfig_t, fw.launch_accel_thresh) }, + { {1, 2, 16, 6, 24, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {7, 29}, offsetof(navConfig_t, fw.launch_max_angle) }, + { {1, 2, 16, 123, 25, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {4, 3}, offsetof(navConfig_t, fw.launch_time_thresh) }, + { {1, 2, 16, 107, 58, 33}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 37}, offsetof(navConfig_t, fw.launch_idle_motor_timer) }, + { {1, 2, 16, 58, 33, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 20}, offsetof(navConfig_t, fw.launch_motor_timer) }, + { {1, 2, 16, 128, 3, 25}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 3}, offsetof(navConfig_t, fw.launch_motor_spinup_time) }, + { {1, 2, 16, 104, 25, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 20}, offsetof(navConfig_t, fw.launch_end_time) }, + { {1, 2, 16, 10, 25, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 37}, offsetof(navConfig_t, fw.launch_min_time) }, + { {1, 2, 16, 85, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 37}, offsetof(navConfig_t, fw.launch_timeout) }, + { {1, 2, 16, 6, 53, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 37}, offsetof(navConfig_t, fw.launch_max_altitude) }, + { {1, 2, 16, 76, 24, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {7, 52}, offsetof(navConfig_t, fw.launch_climb_angle) }, + { {1, 2, 16, 48, 38, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(navConfig_t, fw.launch_manual_throttle) }, + { {1, 2, 16, 147, 1, 29}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {14, 19}, offsetof(navConfig_t, fw.launch_abort_deadband) }, + { {1, 2, 99, 8, 5, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 32}, offsetof(navConfig_t, fw.cruise_yaw_rate) }, + { {177, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(navConfig_t, fw.allow_manual_thr_increase) }, + { {1, 72, 2, 8, 77, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(navConfig_t, fw.useFwNavYawControl) }, + { {1, 2, 8, 29, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 33}, offsetof(navConfig_t, fw.yawControlDeadband) }, + // PG_OSD_CONFIG + { {3, 136, 3, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSD_TELEMETRY }, offsetof(osdConfig_t, telemetry) }, + { {3, 150, 3, 134, 3, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSD_VIDEO_SYSTEM }, offsetof(osdConfig_t, video_system) }, + { {3, 244, 2, 250, 2, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 5}, offsetof(osdConfig_t, row_shiftdown) }, + { {3, 144, 3, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSD_UNIT }, offsetof(osdConfig_t, units) }, + { {3, 71, 124, 111, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSD_STATS_ENERGY_UNIT }, offsetof(osdConfig_t, stats_energy_unit) }, + { {3, 71, 10, 63, 111, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSD_STATS_MIN_VOLTAGE_UNIT }, offsetof(osdConfig_t, stats_min_voltage_unit) }, + { {216, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(osdConfig_t, stats_page_auto_swap_time) }, + { {3, 36, 12, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(osdConfig_t, rssi_alarm) }, + { {3, 25, 12, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 60}, offsetof(osdConfig_t, time_alarm) }, + { {3, 74, 12, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 11}, offsetof(osdConfig_t, alt_alarm) }, + { {3, 156, 1, 12, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 97}, offsetof(osdConfig_t, dist_alarm) }, + { {3, 196, 2, 74, 12, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 11}, offsetof(osdConfig_t, neg_alt_alarm) }, + { {3, 43, 12, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 1}, offsetof(osdConfig_t, current_alarm) }, + { {3, 145, 2, 12, 0, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 15}, offsetof(osdConfig_t, gforce_alarm) }, + { {205, 2, 0, 0, 0, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {31, 15}, offsetof(osdConfig_t, gforce_axis_alarm_min) }, + { {204, 2, 0, 0, 0, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {31, 15}, offsetof(osdConfig_t, gforce_axis_alarm_max) }, + { {3, 34, 51, 12, 10, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {23, 35}, offsetof(osdConfig_t, imu_temp_alarm_min) }, + { {3, 34, 51, 12, 6, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {23, 35}, offsetof(osdConfig_t, imu_temp_alarm_max) }, + { {3, 105, 51, 12, 6, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {23, 40}, offsetof(osdConfig_t, esc_temp_alarm_max) }, + { {3, 105, 51, 12, 10, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {23, 40}, offsetof(osdConfig_t, esc_temp_alarm_min) }, + { {3, 54, 51, 12, 10, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {23, 35}, offsetof(osdConfig_t, baro_temp_alarm_min) }, + { {3, 54, 51, 12, 6, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {23, 35}, offsetof(osdConfig_t, baro_temp_alarm_max) }, + { {3, 254, 2, 12, 0, 0}, VAR_INT8 | MASTER_VALUE, .config.minmax.indexes = {31, 4}, offsetof(osdConfig_t, snr_alarm) }, + { {3, 166, 2, 233, 2, 12}, VAR_INT8 | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(osdConfig_t, link_quality_alarm) }, + { {3, 36, 122, 12, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {45, 0}, offsetof(osdConfig_t, rssi_dbm_alarm) }, + { {3, 36, 122, 6, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {72, 0}, offsetof(osdConfig_t, rssi_dbm_max) }, + { {3, 36, 122, 10, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {45, 0}, offsetof(osdConfig_t, rssi_dbm_min) }, + { {3, 51, 163, 2, 41, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSD_ALIGNMENT }, offsetof(osdConfig_t, temp_label_align) }, + { {3, 91, 12, 10, 0, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 65}, offsetof(osdConfig_t, airspeed_alarm_min) }, + { {3, 91, 12, 6, 0, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 65}, offsetof(osdConfig_t, airspeed_alarm_max) }, + { {3, 40, 240, 2, 18, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(osdConfig_t, ahi_reverse_roll) }, + { {3, 40, 6, 11, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {4, 33}, offsetof(osdConfig_t, ahi_max_pitch) }, + { {3, 237, 1, 204, 1, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSD_CROSSHAIRS_STYLE }, offsetof(osdConfig_t, crosshairs_style) }, + { {202, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSD_CRSF_LQ_FORMAT }, offsetof(osdConfig_t, crsf_lq_format) }, + { {3, 153, 2, 69, 0, 0}, VAR_INT8 | MASTER_VALUE, .config.minmax.indexes = {76, 14}, offsetof(osdConfig_t, horizon_offset) }, + { {3, 93, 211, 1, 0, 0}, VAR_INT8 | MASTER_VALUE, .config.minmax.indexes = {73, 28}, offsetof(osdConfig_t, camera_uptilt) }, + { {3, 40, 93, 211, 1, 98}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(osdConfig_t, ahi_camera_uptilt_comp) }, + { {3, 93, 164, 1, 167, 1}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {32, 55}, offsetof(osdConfig_t, camera_fov_h) }, + { {3, 93, 164, 1, 52, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {18, 53}, offsetof(osdConfig_t, camera_fov_v) }, + { {3, 67, 133, 1, 167, 1}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 12}, offsetof(osdConfig_t, hud_margin_h) }, + { {3, 67, 133, 1, 52, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {5, 26}, offsetof(osdConfig_t, hud_margin_v) }, + { {3, 67, 152, 2, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(osdConfig_t, hud_homing) }, + { {3, 67, 151, 2, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(osdConfig_t, hud_homepoint) }, + { {3, 67, 234, 2, 155, 1}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 12}, offsetof(osdConfig_t, hud_radar_disp) }, + { {210, 2, 0, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {5, 18}, offsetof(osdConfig_t, hud_radar_range_min) }, + { {209, 2, 0, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {2, 91}, offsetof(osdConfig_t, hud_radar_range_max) }, + { {207, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(osdConfig_t, hud_radar_alt_difference_display_time) }, + { {208, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {5, 4}, offsetof(osdConfig_t, hud_radar_distance_display_time) }, + { {3, 67, 73, 155, 1, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 26}, offsetof(osdConfig_t, hud_wp_disp) }, + { {3, 165, 2, 83, 138, 1}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSD_SIDEBAR_SCROLL }, offsetof(osdConfig_t, left_sidebar_scroll) }, + { {3, 241, 2, 83, 138, 1}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSD_SIDEBAR_SCROLL }, offsetof(osdConfig_t, right_sidebar_scroll) }, + { {3, 83, 138, 1, 220, 1}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(osdConfig_t, sidebar_scroll_arrows) }, + { {3, 132, 1, 63, 243, 1}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {5, 14}, offsetof(osdConfig_t, main_voltage_decimals) }, + { {3, 235, 1, 251, 1, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {49, 77}, offsetof(osdConfig_t, coordinate_digits) }, + { {203, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(osdConfig_t, estimations_wind_compensation) }, + { {3, 19, 31, 164, 2, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(osdConfig_t, osd_failsafe_switch_layout) }, + { {213, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {4, 79}, offsetof(osdConfig_t, plus_code_digits) }, + { {214, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSD_PLUS_CODE_SHORT }, offsetof(osdConfig_t, plus_code_short) }, + { {3, 40, 204, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSD_AHI_STYLE }, offsetof(osdConfig_t, ahi_style) }, + { {3, 138, 2, 146, 2, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(osdConfig_t, force_grid) }, + { {3, 40, 225, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(osdConfig_t, ahi_bordered) }, + { {3, 40, 151, 3, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 1}, offsetof(osdConfig_t, ahi_width) }, + { {3, 40, 169, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 1}, offsetof(osdConfig_t, ahi_height) }, + { {3, 40, 149, 3, 69, 0}, VAR_INT8 | MASTER_VALUE, .config.minmax.indexes = {46, 54}, offsetof(osdConfig_t, ahi_vertical_offset) }, + { {3, 83, 154, 2, 69, 0}, VAR_INT8 | MASTER_VALUE, .config.minmax.indexes = {46, 54}, offsetof(osdConfig_t, sidebar_horizontal_offset) }, + { {211, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 1}, offsetof(osdConfig_t, left_sidebar_scroll_step) }, + { {215, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 1}, offsetof(osdConfig_t, right_sidebar_scroll_step) }, + { {3, 83, 169, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 7}, offsetof(osdConfig_t, sidebar_height) }, + { {3, 40, 11, 173, 1, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 18}, offsetof(osdConfig_t, ahi_pitch_interval) }, + { {206, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(osdConfig_t, osd_home_position_arm_screen) }, + { {3, 187, 1, 50, 158, 2}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(osdConfig_t, pan_servo_index) }, + { {3, 187, 1, 50, 232, 2}, VAR_INT8 | MASTER_VALUE, .config.minmax.indexes = {74, 82}, offsetof(osdConfig_t, pan_servo_pwm2centideg) }, + { {3, 105, 245, 2, 228, 2}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {26, 48}, offsetof(osdConfig_t, esc_rpm_precision) }, + { {212, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {12, 48}, offsetof(osdConfig_t, mAh_used_precision) }, + { {3, 31, 47, 88, 81, 0}, VAR_STRING | MASTER_VALUE, .config.minmax.indexes = {0, 7}, offsetof(osdConfig_t, osd_switch_indicator0_name) }, + { {3, 31, 47, 186, 1, 81}, VAR_STRING | MASTER_VALUE, .config.minmax.indexes = {0, 7}, offsetof(osdConfig_t, osd_switch_indicator1_name) }, + { {3, 31, 47, 209, 1, 81}, VAR_STRING | MASTER_VALUE, .config.minmax.indexes = {0, 7}, offsetof(osdConfig_t, osd_switch_indicator2_name) }, + { {3, 31, 47, 205, 1, 81}, VAR_STRING | MASTER_VALUE, .config.minmax.indexes = {0, 7}, offsetof(osdConfig_t, osd_switch_indicator3_name) }, + { {3, 31, 47, 88, 42, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {7, 27}, offsetof(osdConfig_t, osd_switch_indicator0_channel) }, + { {3, 31, 47, 186, 1, 42}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {7, 27}, offsetof(osdConfig_t, osd_switch_indicator1_channel) }, + { {3, 31, 47, 209, 1, 42}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {7, 27}, offsetof(osdConfig_t, osd_switch_indicator2_channel) }, + { {3, 31, 47, 205, 1, 42}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {7, 27}, offsetof(osdConfig_t, osd_switch_indicator3_channel) }, + { {217, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(osdConfig_t, osd_switch_indicators_align_left) }, + { {218, 2, 0, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {8, 20}, offsetof(osdConfig_t, system_msg_display_time) }, + // PG_OSD_COMMON_CONFIG + { {3, 37, 84, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSDSPEEDSOURCE }, offsetof(osdCommonConfig_t, speedSource) }, + // PG_SYSTEM_CONFIG + { {241, 1, 49, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_DEBUG_MODES }, offsetof(systemConfig_t, debug_mode) }, + { {38, 137, 3, 98, 131, 3}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(systemConfig_t, throttle_tilt_compensation_strength) }, + { {81, 0, 0, 0, 0, 0}, VAR_STRING | MASTER_VALUE, .config.minmax.indexes = {0, 80}, offsetof(systemConfig_t, name) }, + // PG_MODE_ACTIVATION_OPERATOR_CONFIG + { {174, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_AUX_OPERATOR }, offsetof(modeActivationOperatorConfig_t, modeActivationOperator) }, + // PG_STATS_CONFIG + { {71, 0, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(statsConfig_t, stats_enabled) }, + { {71, 144, 1, 25, 0, 0}, VAR_UINT32 | MASTER_VALUE, .config.minmax.indexes = {0, 43}, offsetof(statsConfig_t, stats_total_time) }, + { {71, 144, 1, 156, 1, 0}, VAR_UINT32 | MASTER_VALUE, .config.minmax.indexes = {0, 43}, offsetof(statsConfig_t, stats_total_dist) }, + { {71, 144, 1, 124, 0, 0}, VAR_UINT32 | MASTER_VALUE, .config.minmax.indexes = {0, 43}, offsetof(statsConfig_t, stats_total_energy) }, + // PG_TIME_CONFIG + { {210, 1, 69, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {70, 88}, offsetof(timeConfig_t, tz_offset) }, + { {210, 1, 222, 1, 129, 2}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_TZ_AUTOMATIC_DST }, offsetof(timeConfig_t, tz_automatic_dst) }, + // PG_DISPLAY_CONFIG + { {253, 1, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(displayConfig_t, force_sw_blink) }, + // PG_LOG_CONFIG + { {176, 1, 44, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_LOG_LEVEL }, offsetof(logConfig_t, level) }, + { {176, 1, 139, 3, 0, 0}, VAR_UINT32 | MASTER_VALUE, .config.minmax.indexes = {0, 30}, offsetof(logConfig_t, topics) }, + // PG_SMARTPORT_MASTER_CONFIG + { {200, 1, 180, 1, 168, 1}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(smartportMasterConfig_t, halfDuplex) }, + { {200, 1, 180, 1, 128, 1}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(smartportMasterConfig_t, inverted) }, + // PG_DJI_OSD_CONFIG + { {78, 154, 3, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 1}, offsetof(djiOsdConfig_t, proto_workarounds) }, + { {255, 1, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(djiOsdConfig_t, use_name_for_messages) }, + { {78, 105, 51, 84, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_DJIOSDTEMPSOURCE }, offsetof(djiOsdConfig_t, esc_temperature_source) }, + { {78, 169, 2, 37, 84, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSDSPEEDSOURCE }, offsetof(djiOsdConfig_t, messageSpeedSource) }, + { {78, 36, 84, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_DJIRSSISOURCE }, offsetof(djiOsdConfig_t, rssi_source) }, + { {78, 72, 217, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(djiOsdConfig_t, useAdjustments) }, + { {254, 1, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {5, 55}, offsetof(djiOsdConfig_t, craftNameAlternatingDuration) }, + // PG_BEEPER_CONFIG + { {158, 1, 118, 131, 2, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(beeperConfig_t, dshot_beeper_enabled) }, + { {158, 1, 118, 138, 3, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {5, 7}, offsetof(beeperConfig_t, dshot_beeper_tone) }, + { {118, 110, 49, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(beeperConfig_t, pwmMode) }, + // PG_POWER_LIMITS_CONFIG + { {13, 188, 1, 7, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 11}, offsetof(powerLimitsConfig_t, piP) }, + { {13, 188, 1, 22, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 11}, offsetof(powerLimitsConfig_t, piI) }, + { {13, 221, 1, 80, 100, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(powerLimitsConfig_t, attnFilterCutoff) }, +}; diff --git a/src/main/fc/settings_generated.h b/src/main/fc/settings_generated.h new file mode 100644 index 0000000000..2ad7c90104 --- /dev/null +++ b/src/main/fc/settings_generated.h @@ -0,0 +1,2209 @@ +// This file has been automatically generated by utils/settings.rb +// Don't make any modifications to it. They will be lost. + +#pragma once +#define SETTING_MAX_NAME_LENGTH 42 +#define SETTING_MAX_WORD_LENGTH 42 +#define SETTING_ENCODED_NAME_MAX_BYTES 6 +#define SETTINGS_WORDS_BITS_PER_CHAR 5 +#define SETTINGS_TABLE_COUNT 518 +typedef uint16_t setting_offset_t; +#define SETTINGS_PGN_COUNT 41 +typedef int16_t setting_min_t; +typedef uint32_t setting_max_t; +#define SETTING_MIN_MAX_INDEX_BYTES 2 +enum { + TABLE_ACC_HARDWARE, + TABLE_AIRMODEHANDLINGTYPE, + TABLE_ALIGNMENT, + TABLE_AUTOTUNE_RATE_ADJUSTMENT, + TABLE_AUX_OPERATOR, + TABLE_BARO_HARDWARE, + TABLE_BAT_CAPACITY_UNIT, + TABLE_BAT_VOLTAGE_SOURCE, + TABLE_BLACKBOX_DEVICE, + TABLE_CURRENT_SENSOR, + TABLE_DEBUG_MODES, + TABLE_DIRECTION, + TABLE_DJIOSDTEMPSOURCE, + TABLE_DJIRSSISOURCE, + TABLE_FAILSAFE_PROCEDURE, + TABLE_FILTER_TYPE, + TABLE_FILTER_TYPE_FULL, + TABLE_GPS_DYN_MODEL, + TABLE_GPS_PROVIDER, + TABLE_GPS_SBAS_MODE, + TABLE_GYRO_LPF, + TABLE_IMU_INERTIA_COMP_METHOD, + TABLE_ITERM_RELAX, + TABLE_LOG_LEVEL, + TABLE_MAG_HARDWARE, + TABLE_MOTOR_PWM_PROTOCOL, + TABLE_NAV_EXTRA_ARMING_SAFETY, + TABLE_NAV_FW_WP_TURN_SMOOTHING, + TABLE_NAV_OVERRIDES_MOTOR_STOP, + TABLE_NAV_RTH_ALLOW_LANDING, + TABLE_NAV_RTH_ALT_MODE, + TABLE_NAV_RTH_CLIMB_FIRST, + TABLE_NAV_RTH_CLIMB_FIRST_STAGE_MODES, + TABLE_NAV_USER_CONTROL_MODE, + TABLE_NAV_WP_MISSION_RESTART, + TABLE_OFF_ON, + TABLE_OPFLOW_HARDWARE, + TABLE_OSDSPEEDSOURCE, + TABLE_OSD_AHI_STYLE, + TABLE_OSD_ALIGNMENT, + TABLE_OSD_CROSSHAIRS_STYLE, + TABLE_OSD_CRSF_LQ_FORMAT, + TABLE_OSD_PLUS_CODE_SHORT, + TABLE_OSD_SIDEBAR_SCROLL, + TABLE_OSD_STATS_ENERGY_UNIT, + TABLE_OSD_STATS_MIN_VOLTAGE_UNIT, + TABLE_OSD_TELEMETRY, + TABLE_OSD_UNIT, + TABLE_OSD_VIDEO_SYSTEM, + TABLE_OUTPUT_MODE, + TABLE_PIDTYPETABLE, + TABLE_PITOT_HARDWARE, + TABLE_PLATFORM_TYPE, + TABLE_RANGEFINDER_HARDWARE, + TABLE_RECEIVER_TYPE, + TABLE_RESET_TYPE, + TABLE_RSSI_SOURCE, + TABLE_RTH_TRACKBACK_MODE, + TABLE_SAFEHOME_USAGE_MODE, + TABLE_SERIAL_RX, + TABLE_SERVO_PROTOCOL, + TABLE_TRISTATE, + TABLE_TZ_AUTOMATIC_DST, + TABLE_VOLTAGE_SENSOR, + LOOKUP_TABLE_COUNT, +}; +extern const char * const table_acc_hardware[]; +extern const char * const table_airmodeHandlingType[]; +extern const char * const table_alignment[]; +extern const char * const table_autotune_rate_adjustment[]; +extern const char * const table_aux_operator[]; +extern const char * const table_baro_hardware[]; +extern const char * const table_bat_capacity_unit[]; +extern const char * const table_bat_voltage_source[]; +extern const char * const table_blackbox_device[]; +extern const char * const table_current_sensor[]; +extern const char * const table_debug_modes[]; +extern const char * const table_direction[]; +extern const char * const table_djiOsdTempSource[]; +extern const char * const table_djiRssiSource[]; +extern const char * const table_failsafe_procedure[]; +extern const char * const table_filter_type[]; +extern const char * const table_filter_type_full[]; +extern const char * const table_gps_dyn_model[]; +extern const char * const table_gps_provider[]; +extern const char * const table_gps_sbas_mode[]; +extern const char * const table_gyro_lpf[]; +extern const char * const table_imu_inertia_comp_method[]; +extern const char * const table_iterm_relax[]; +extern const char * const table_log_level[]; +extern const char * const table_mag_hardware[]; +extern const char * const table_motor_pwm_protocol[]; +extern const char * const table_nav_extra_arming_safety[]; +extern const char * const table_nav_fw_wp_turn_smoothing[]; +extern const char * const table_nav_overrides_motor_stop[]; +extern const char * const table_nav_rth_allow_landing[]; +extern const char * const table_nav_rth_alt_mode[]; +extern const char * const table_nav_rth_climb_first[]; +extern const char * const table_nav_rth_climb_first_stage_modes[]; +extern const char * const table_nav_user_control_mode[]; +extern const char * const table_nav_wp_mission_restart[]; +extern const char * const table_off_on[]; +extern const char * const table_opflow_hardware[]; +extern const char * const table_osdSpeedSource[]; +extern const char * const table_osd_ahi_style[]; +extern const char * const table_osd_alignment[]; +extern const char * const table_osd_crosshairs_style[]; +extern const char * const table_osd_crsf_lq_format[]; +extern const char * const table_osd_plus_code_short[]; +extern const char * const table_osd_sidebar_scroll[]; +extern const char * const table_osd_stats_energy_unit[]; +extern const char * const table_osd_stats_min_voltage_unit[]; +extern const char * const table_osd_telemetry[]; +extern const char * const table_osd_unit[]; +extern const char * const table_osd_video_system[]; +extern const char * const table_output_mode[]; +extern const char * const table_pidTypeTable[]; +extern const char * const table_pitot_hardware[]; +extern const char * const table_platform_type[]; +extern const char * const table_rangefinder_hardware[]; +extern const char * const table_receiver_type[]; +extern const char * const table_reset_type[]; +extern const char * const table_rssi_source[]; +extern const char * const table_rth_trackback_mode[]; +extern const char * const table_safehome_usage_mode[]; +extern const char * const table_serial_rx[]; +extern const char * const table_servo_protocol[]; +extern const char * const table_tristate[]; +extern const char * const table_tz_automatic_dst[]; +extern const char * const table_voltage_sensor[]; +#define SETTING_CONSTANT_RPYL_PID_MIN 0 +#define SETTING_CONSTANT_RPYL_PID_MAX 255 +#define SETTING_CONSTANT_MANUAL_RATE_MIN 0 +#define SETTING_CONSTANT_MANUAL_RATE_MAX 100 +#define SETTING_CONSTANT_ROLL_PITCH_RATE_MIN 4 +#define SETTING_CONSTANT_ROLL_PITCH_RATE_MAX 180 +#define SETTING_CONSTANT_MAX_CONTROL_RATE_PROFILE_COUNT 3 +#define SETTING_CONSTANT_MAX_BATTERY_PROFILE_COUNT 3 +#define SETTING_LOOPTIME_DEFAULT 1000 +#define SETTING_LOOPTIME 0 +#define SETTING_LOOPTIME_MIN 0 +#define SETTING_LOOPTIME_MAX 9000 +#define SETTING_GYRO_HARDWARE_LPF_DEFAULT 0 +#define SETTING_GYRO_HARDWARE_LPF 1 +#define SETTING_GYRO_HARDWARE_LPF_MIN 0 +#define SETTING_GYRO_HARDWARE_LPF_MAX 0 +#define SETTING_GYRO_ANTI_ALIASING_LPF_HZ_DEFAULT 250 +#define SETTING_GYRO_ANTI_ALIASING_LPF_HZ 2 +#define SETTING_GYRO_ANTI_ALIASING_LPF_HZ_MIN 0 +#define SETTING_GYRO_ANTI_ALIASING_LPF_HZ_MAX 1000 +#define SETTING_GYRO_ANTI_ALIASING_LPF_TYPE_DEFAULT 0 +#define SETTING_GYRO_ANTI_ALIASING_LPF_TYPE 3 +#define SETTING_GYRO_ANTI_ALIASING_LPF_TYPE_MIN 0 +#define SETTING_GYRO_ANTI_ALIASING_LPF_TYPE_MAX 0 +#define SETTING_MORON_THRESHOLD_DEFAULT 32 +#define SETTING_MORON_THRESHOLD 4 +#define SETTING_MORON_THRESHOLD_MIN 0 +#define SETTING_MORON_THRESHOLD_MAX 128 +#define SETTING_GYRO_MAIN_LPF_HZ_DEFAULT 60 +#define SETTING_GYRO_MAIN_LPF_HZ 5 +#define SETTING_GYRO_MAIN_LPF_HZ_MIN 0 +#define SETTING_GYRO_MAIN_LPF_HZ_MAX 500 +#define SETTING_GYRO_MAIN_LPF_TYPE_DEFAULT 1 +#define SETTING_GYRO_MAIN_LPF_TYPE 6 +#define SETTING_GYRO_MAIN_LPF_TYPE_MIN 0 +#define SETTING_GYRO_MAIN_LPF_TYPE_MAX 0 +#define SETTING_GYRO_USE_DYN_LPF_DEFAULT 0 +#define SETTING_GYRO_USE_DYN_LPF 7 +#define SETTING_GYRO_USE_DYN_LPF_MIN 0 +#define SETTING_GYRO_USE_DYN_LPF_MAX 0 +#define SETTING_GYRO_DYN_LPF_MIN_HZ_DEFAULT 200 +#define SETTING_GYRO_DYN_LPF_MIN_HZ 8 +#define SETTING_GYRO_DYN_LPF_MIN_HZ_MIN 40 +#define SETTING_GYRO_DYN_LPF_MIN_HZ_MAX 400 +#define SETTING_GYRO_DYN_LPF_MAX_HZ_DEFAULT 500 +#define SETTING_GYRO_DYN_LPF_MAX_HZ 9 +#define SETTING_GYRO_DYN_LPF_MAX_HZ_MIN 40 +#define SETTING_GYRO_DYN_LPF_MAX_HZ_MAX 1000 +#define SETTING_GYRO_DYN_LPF_CURVE_EXPO_DEFAULT 5 +#define SETTING_GYRO_DYN_LPF_CURVE_EXPO 10 +#define SETTING_GYRO_DYN_LPF_CURVE_EXPO_MIN 1 +#define SETTING_GYRO_DYN_LPF_CURVE_EXPO_MAX 10 +#define SETTING_INIT_GYRO_CAL_DEFAULT 1 +#define SETTING_INIT_GYRO_CAL 11 +#define SETTING_INIT_GYRO_CAL_MIN 0 +#define SETTING_INIT_GYRO_CAL_MAX 0 +#define SETTING_GYRO_ZERO_X_DEFAULT 0 +#define SETTING_GYRO_ZERO_X 12 +#define SETTING_GYRO_ZERO_X_MIN -32768 +#define SETTING_GYRO_ZERO_X_MAX 32767 +#define SETTING_GYRO_ZERO_Y_DEFAULT 0 +#define SETTING_GYRO_ZERO_Y 13 +#define SETTING_GYRO_ZERO_Y_MIN -32768 +#define SETTING_GYRO_ZERO_Y_MAX 32767 +#define SETTING_GYRO_ZERO_Z_DEFAULT 0 +#define SETTING_GYRO_ZERO_Z 14 +#define SETTING_GYRO_ZERO_Z_MIN -32768 +#define SETTING_GYRO_ZERO_Z_MAX 32767 +#define SETTING_INS_GRAVITY_CMSS_DEFAULT 0.0f +#define SETTING_INS_GRAVITY_CMSS 15 +#define SETTING_INS_GRAVITY_CMSS_MIN 0 +#define SETTING_INS_GRAVITY_CMSS_MAX 2000 +#define SETTING_VBAT_ADC_CHANNEL 16 +#define SETTING_VBAT_ADC_CHANNEL_MIN 0 +#define SETTING_VBAT_ADC_CHANNEL_MAX 4 +#define SETTING_RSSI_ADC_CHANNEL 17 +#define SETTING_RSSI_ADC_CHANNEL_MIN 0 +#define SETTING_RSSI_ADC_CHANNEL_MAX 4 +#define SETTING_CURRENT_ADC_CHANNEL 18 +#define SETTING_CURRENT_ADC_CHANNEL_MIN 0 +#define SETTING_CURRENT_ADC_CHANNEL_MAX 4 +#define SETTING_AIRSPEED_ADC_CHANNEL 19 +#define SETTING_AIRSPEED_ADC_CHANNEL_MIN 0 +#define SETTING_AIRSPEED_ADC_CHANNEL_MAX 4 +#define SETTING_ACC_NOTCH_HZ_DEFAULT 0 +#define SETTING_ACC_NOTCH_HZ 20 +#define SETTING_ACC_NOTCH_HZ_MIN 0 +#define SETTING_ACC_NOTCH_HZ_MAX 255 +#define SETTING_ACC_NOTCH_CUTOFF_DEFAULT 1 +#define SETTING_ACC_NOTCH_CUTOFF 21 +#define SETTING_ACC_NOTCH_CUTOFF_MIN 1 +#define SETTING_ACC_NOTCH_CUTOFF_MAX 255 +#define SETTING_ACC_HARDWARE_DEFAULT 1 +#define SETTING_ACC_HARDWARE 22 +#define SETTING_ACC_HARDWARE_MIN 0 +#define SETTING_ACC_HARDWARE_MAX 0 +#define SETTING_ACC_LPF_HZ_DEFAULT 15 +#define SETTING_ACC_LPF_HZ 23 +#define SETTING_ACC_LPF_HZ_MIN 0 +#define SETTING_ACC_LPF_HZ_MAX 200 +#define SETTING_ACC_LPF_TYPE_DEFAULT 1 +#define SETTING_ACC_LPF_TYPE 24 +#define SETTING_ACC_LPF_TYPE_MIN 0 +#define SETTING_ACC_LPF_TYPE_MAX 0 +#define SETTING_ACCZERO_X_DEFAULT 0 +#define SETTING_ACCZERO_X 25 +#define SETTING_ACCZERO_X_MIN -32768 +#define SETTING_ACCZERO_X_MAX 32767 +#define SETTING_ACCZERO_Y_DEFAULT 0 +#define SETTING_ACCZERO_Y 26 +#define SETTING_ACCZERO_Y_MIN -32768 +#define SETTING_ACCZERO_Y_MAX 32767 +#define SETTING_ACCZERO_Z_DEFAULT 0 +#define SETTING_ACCZERO_Z 27 +#define SETTING_ACCZERO_Z_MIN -32768 +#define SETTING_ACCZERO_Z_MAX 32767 +#define SETTING_ACCGAIN_X_DEFAULT 4096 +#define SETTING_ACCGAIN_X 28 +#define SETTING_ACCGAIN_X_MIN 1 +#define SETTING_ACCGAIN_X_MAX 8192 +#define SETTING_ACCGAIN_Y_DEFAULT 4096 +#define SETTING_ACCGAIN_Y 29 +#define SETTING_ACCGAIN_Y_MIN 1 +#define SETTING_ACCGAIN_Y_MAX 8192 +#define SETTING_ACCGAIN_Z_DEFAULT 4096 +#define SETTING_ACCGAIN_Z 30 +#define SETTING_ACCGAIN_Z_MIN 1 +#define SETTING_ACCGAIN_Z_MAX 8192 +#define SETTING_RANGEFINDER_HARDWARE_DEFAULT 0 +#define SETTING_RANGEFINDER_HARDWARE 31 +#define SETTING_RANGEFINDER_HARDWARE_MIN 0 +#define SETTING_RANGEFINDER_HARDWARE_MAX 0 +#define SETTING_RANGEFINDER_MEDIAN_FILTER_DEFAULT 0 +#define SETTING_RANGEFINDER_MEDIAN_FILTER 32 +#define SETTING_RANGEFINDER_MEDIAN_FILTER_MIN 0 +#define SETTING_RANGEFINDER_MEDIAN_FILTER_MAX 0 +#define SETTING_OPFLOW_HARDWARE_DEFAULT 0 +#define SETTING_OPFLOW_HARDWARE 33 +#define SETTING_OPFLOW_HARDWARE_MIN 0 +#define SETTING_OPFLOW_HARDWARE_MAX 0 +#define SETTING_OPFLOW_SCALE_DEFAULT 10.5f +#define SETTING_OPFLOW_SCALE 34 +#define SETTING_OPFLOW_SCALE_MIN 0 +#define SETTING_OPFLOW_SCALE_MAX 10000 +#define SETTING_ALIGN_OPFLOW_DEFAULT 5 +#define SETTING_ALIGN_OPFLOW 35 +#define SETTING_ALIGN_OPFLOW_MIN 0 +#define SETTING_ALIGN_OPFLOW_MAX 0 +#define SETTING_ALIGN_MAG_DEFAULT 0 +#define SETTING_ALIGN_MAG 36 +#define SETTING_ALIGN_MAG_MIN 0 +#define SETTING_ALIGN_MAG_MAX 0 +#define SETTING_MAG_HARDWARE_DEFAULT 1 +#define SETTING_MAG_HARDWARE 37 +#define SETTING_MAG_HARDWARE_MIN 0 +#define SETTING_MAG_HARDWARE_MAX 0 +#define SETTING_MAG_DECLINATION_DEFAULT 0 +#define SETTING_MAG_DECLINATION 38 +#define SETTING_MAG_DECLINATION_MIN -18000 +#define SETTING_MAG_DECLINATION_MAX 18000 +#define SETTING_MAGZERO_X 39 +#define SETTING_MAGZERO_X_MIN -32768 +#define SETTING_MAGZERO_X_MAX 32767 +#define SETTING_MAGZERO_Y 40 +#define SETTING_MAGZERO_Y_MIN -32768 +#define SETTING_MAGZERO_Y_MAX 32767 +#define SETTING_MAGZERO_Z 41 +#define SETTING_MAGZERO_Z_MIN -32768 +#define SETTING_MAGZERO_Z_MAX 32767 +#define SETTING_MAGGAIN_X_DEFAULT 1024 +#define SETTING_MAGGAIN_X 42 +#define SETTING_MAGGAIN_X_MIN -32768 +#define SETTING_MAGGAIN_X_MAX 32767 +#define SETTING_MAGGAIN_Y_DEFAULT 1024 +#define SETTING_MAGGAIN_Y 43 +#define SETTING_MAGGAIN_Y_MIN -32768 +#define SETTING_MAGGAIN_Y_MAX 32767 +#define SETTING_MAGGAIN_Z_DEFAULT 1024 +#define SETTING_MAGGAIN_Z 44 +#define SETTING_MAGGAIN_Z_MIN -32768 +#define SETTING_MAGGAIN_Z_MAX 32767 +#define SETTING_MAG_CALIBRATION_TIME_DEFAULT 30 +#define SETTING_MAG_CALIBRATION_TIME 45 +#define SETTING_MAG_CALIBRATION_TIME_MIN 20 +#define SETTING_MAG_CALIBRATION_TIME_MAX 120 +#define SETTING_ALIGN_MAG_ROLL_DEFAULT 0 +#define SETTING_ALIGN_MAG_ROLL 46 +#define SETTING_ALIGN_MAG_ROLL_MIN -1800 +#define SETTING_ALIGN_MAG_ROLL_MAX 3600 +#define SETTING_ALIGN_MAG_PITCH_DEFAULT 0 +#define SETTING_ALIGN_MAG_PITCH 47 +#define SETTING_ALIGN_MAG_PITCH_MIN -1800 +#define SETTING_ALIGN_MAG_PITCH_MAX 3600 +#define SETTING_ALIGN_MAG_YAW_DEFAULT 0 +#define SETTING_ALIGN_MAG_YAW 48 +#define SETTING_ALIGN_MAG_YAW_MIN -1800 +#define SETTING_ALIGN_MAG_YAW_MAX 3600 +#define SETTING_BARO_HARDWARE_DEFAULT 1 +#define SETTING_BARO_HARDWARE 49 +#define SETTING_BARO_HARDWARE_MIN 0 +#define SETTING_BARO_HARDWARE_MAX 0 +#define SETTING_BARO_CAL_TOLERANCE_DEFAULT 150 +#define SETTING_BARO_CAL_TOLERANCE 50 +#define SETTING_BARO_CAL_TOLERANCE_MIN 0 +#define SETTING_BARO_CAL_TOLERANCE_MAX 1000 +#define SETTING_PITOT_HARDWARE_DEFAULT 0 +#define SETTING_PITOT_HARDWARE 51 +#define SETTING_PITOT_HARDWARE_MIN 0 +#define SETTING_PITOT_HARDWARE_MAX 0 +#define SETTING_PITOT_LPF_MILLI_HZ_DEFAULT 350 +#define SETTING_PITOT_LPF_MILLI_HZ 52 +#define SETTING_PITOT_LPF_MILLI_HZ_MIN 0 +#define SETTING_PITOT_LPF_MILLI_HZ_MAX 10000 +#define SETTING_PITOT_SCALE_DEFAULT 1.0f +#define SETTING_PITOT_SCALE 53 +#define SETTING_PITOT_SCALE_MIN 0 +#define SETTING_PITOT_SCALE_MAX 100 +#define SETTING_RECEIVER_TYPE 54 +#define SETTING_RECEIVER_TYPE_MIN 0 +#define SETTING_RECEIVER_TYPE_MAX 0 +#define SETTING_MIN_CHECK_DEFAULT 1100 +#define SETTING_MIN_CHECK 55 +#define SETTING_MIN_CHECK_MIN 1000 +#define SETTING_MIN_CHECK_MAX 2000 +#define SETTING_MAX_CHECK_DEFAULT 1900 +#define SETTING_MAX_CHECK 56 +#define SETTING_MAX_CHECK_MIN 1000 +#define SETTING_MAX_CHECK_MAX 2000 +#define SETTING_RSSI_SOURCE_DEFAULT 1 +#define SETTING_RSSI_SOURCE 57 +#define SETTING_RSSI_SOURCE_MIN 0 +#define SETTING_RSSI_SOURCE_MAX 0 +#define SETTING_RSSI_CHANNEL_DEFAULT 0 +#define SETTING_RSSI_CHANNEL 58 +#define SETTING_RSSI_CHANNEL_MIN 0 +#define SETTING_RSSI_CHANNEL_MAX 18 +#define SETTING_RSSI_MIN_DEFAULT 0 +#define SETTING_RSSI_MIN 59 +#define SETTING_RSSI_MIN_MIN 0 +#define SETTING_RSSI_MIN_MAX 100 +#define SETTING_RSSI_MAX_DEFAULT 100 +#define SETTING_RSSI_MAX 60 +#define SETTING_RSSI_MAX_MIN 0 +#define SETTING_RSSI_MAX_MAX 100 +#define SETTING_SBUS_SYNC_INTERVAL_DEFAULT 3000 +#define SETTING_SBUS_SYNC_INTERVAL 61 +#define SETTING_SBUS_SYNC_INTERVAL_MIN 500 +#define SETTING_SBUS_SYNC_INTERVAL_MAX 10000 +#define SETTING_RC_FILTER_LPF_HZ_DEFAULT 50 +#define SETTING_RC_FILTER_LPF_HZ 62 +#define SETTING_RC_FILTER_LPF_HZ_MIN 15 +#define SETTING_RC_FILTER_LPF_HZ_MAX 250 +#define SETTING_RC_FILTER_AUTO_DEFAULT 0 +#define SETTING_RC_FILTER_AUTO 63 +#define SETTING_RC_FILTER_AUTO_MIN 0 +#define SETTING_RC_FILTER_AUTO_MAX 0 +#define SETTING_RC_FILTER_SMOOTHING_FACTOR_DEFAULT 30 +#define SETTING_RC_FILTER_SMOOTHING_FACTOR 64 +#define SETTING_RC_FILTER_SMOOTHING_FACTOR_MIN 1 +#define SETTING_RC_FILTER_SMOOTHING_FACTOR_MAX 100 +#define SETTING_SERIALRX_PROVIDER 65 +#define SETTING_SERIALRX_PROVIDER_MIN 0 +#define SETTING_SERIALRX_PROVIDER_MAX 0 +#define SETTING_SERIALRX_INVERTED_DEFAULT 0 +#define SETTING_SERIALRX_INVERTED 66 +#define SETTING_SERIALRX_INVERTED_MIN 0 +#define SETTING_SERIALRX_INVERTED_MAX 0 +#define SETTING_SRXL2_UNIT_ID_DEFAULT 1 +#define SETTING_SRXL2_UNIT_ID 67 +#define SETTING_SRXL2_UNIT_ID_MIN 0 +#define SETTING_SRXL2_UNIT_ID_MAX 15 +#define SETTING_SRXL2_BAUD_FAST_DEFAULT 1 +#define SETTING_SRXL2_BAUD_FAST 68 +#define SETTING_SRXL2_BAUD_FAST_MIN 0 +#define SETTING_SRXL2_BAUD_FAST_MAX 0 +#define SETTING_RX_MIN_USEC_DEFAULT 885 +#define SETTING_RX_MIN_USEC 69 +#define SETTING_RX_MIN_USEC_MIN 750 +#define SETTING_RX_MIN_USEC_MAX 2250 +#define SETTING_RX_MAX_USEC_DEFAULT 2115 +#define SETTING_RX_MAX_USEC 70 +#define SETTING_RX_MAX_USEC_MIN 750 +#define SETTING_RX_MAX_USEC_MAX 2250 +#define SETTING_SERIALRX_HALFDUPLEX_DEFAULT 0 +#define SETTING_SERIALRX_HALFDUPLEX 71 +#define SETTING_SERIALRX_HALFDUPLEX_MIN 0 +#define SETTING_SERIALRX_HALFDUPLEX_MAX 0 +#define SETTING_BLACKBOX_RATE_NUM_DEFAULT 1 +#define SETTING_BLACKBOX_RATE_NUM 72 +#define SETTING_BLACKBOX_RATE_NUM_MIN 1 +#define SETTING_BLACKBOX_RATE_NUM_MAX 65535 +#define SETTING_BLACKBOX_RATE_DENOM_DEFAULT 1 +#define SETTING_BLACKBOX_RATE_DENOM 73 +#define SETTING_BLACKBOX_RATE_DENOM_MIN 1 +#define SETTING_BLACKBOX_RATE_DENOM_MAX 65535 +#define SETTING_BLACKBOX_DEVICE 74 +#define SETTING_BLACKBOX_DEVICE_MIN 0 +#define SETTING_BLACKBOX_DEVICE_MAX 0 +#define SETTING_MAX_THROTTLE_DEFAULT 1850 +#define SETTING_MAX_THROTTLE 75 +#define SETTING_MAX_THROTTLE_MIN 1000 +#define SETTING_MAX_THROTTLE_MAX 2000 +#define SETTING_MIN_COMMAND_DEFAULT 1000 +#define SETTING_MIN_COMMAND 76 +#define SETTING_MIN_COMMAND_MIN 0 +#define SETTING_MIN_COMMAND_MAX 2000 +#define SETTING_MOTOR_PWM_RATE_DEFAULT 16000 +#define SETTING_MOTOR_PWM_RATE 77 +#define SETTING_MOTOR_PWM_RATE_MIN 50 +#define SETTING_MOTOR_PWM_RATE_MAX 32000 +#define SETTING_MOTOR_PWM_PROTOCOL_DEFAULT 1 +#define SETTING_MOTOR_PWM_PROTOCOL 78 +#define SETTING_MOTOR_PWM_PROTOCOL_MIN 0 +#define SETTING_MOTOR_PWM_PROTOCOL_MAX 0 +#define SETTING_MOTOR_POLES_DEFAULT 14 +#define SETTING_MOTOR_POLES 79 +#define SETTING_MOTOR_POLES_MIN 4 +#define SETTING_MOTOR_POLES_MAX 255 +#define SETTING_FAILSAFE_DELAY_DEFAULT 5 +#define SETTING_FAILSAFE_DELAY 80 +#define SETTING_FAILSAFE_DELAY_MIN 0 +#define SETTING_FAILSAFE_DELAY_MAX 200 +#define SETTING_FAILSAFE_RECOVERY_DELAY_DEFAULT 5 +#define SETTING_FAILSAFE_RECOVERY_DELAY 81 +#define SETTING_FAILSAFE_RECOVERY_DELAY_MIN 0 +#define SETTING_FAILSAFE_RECOVERY_DELAY_MAX 200 +#define SETTING_FAILSAFE_OFF_DELAY_DEFAULT 200 +#define SETTING_FAILSAFE_OFF_DELAY 82 +#define SETTING_FAILSAFE_OFF_DELAY_MIN 0 +#define SETTING_FAILSAFE_OFF_DELAY_MAX 200 +#define SETTING_FAILSAFE_THROTTLE_LOW_DELAY_DEFAULT 0 +#define SETTING_FAILSAFE_THROTTLE_LOW_DELAY 83 +#define SETTING_FAILSAFE_THROTTLE_LOW_DELAY_MIN 0 +#define SETTING_FAILSAFE_THROTTLE_LOW_DELAY_MAX 300 +#define SETTING_FAILSAFE_PROCEDURE_DEFAULT 0 +#define SETTING_FAILSAFE_PROCEDURE 84 +#define SETTING_FAILSAFE_PROCEDURE_MIN 0 +#define SETTING_FAILSAFE_PROCEDURE_MAX 0 +#define SETTING_FAILSAFE_STICK_THRESHOLD_DEFAULT 50 +#define SETTING_FAILSAFE_STICK_THRESHOLD 85 +#define SETTING_FAILSAFE_STICK_THRESHOLD_MIN 0 +#define SETTING_FAILSAFE_STICK_THRESHOLD_MAX 500 +#define SETTING_FAILSAFE_FW_ROLL_ANGLE_DEFAULT -200 +#define SETTING_FAILSAFE_FW_ROLL_ANGLE 86 +#define SETTING_FAILSAFE_FW_ROLL_ANGLE_MIN -800 +#define SETTING_FAILSAFE_FW_ROLL_ANGLE_MAX 800 +#define SETTING_FAILSAFE_FW_PITCH_ANGLE_DEFAULT 100 +#define SETTING_FAILSAFE_FW_PITCH_ANGLE 87 +#define SETTING_FAILSAFE_FW_PITCH_ANGLE_MIN -800 +#define SETTING_FAILSAFE_FW_PITCH_ANGLE_MAX 800 +#define SETTING_FAILSAFE_FW_YAW_RATE_DEFAULT -45 +#define SETTING_FAILSAFE_FW_YAW_RATE 88 +#define SETTING_FAILSAFE_FW_YAW_RATE_MIN -1000 +#define SETTING_FAILSAFE_FW_YAW_RATE_MAX 1000 +#define SETTING_FAILSAFE_MIN_DISTANCE_DEFAULT 0 +#define SETTING_FAILSAFE_MIN_DISTANCE 89 +#define SETTING_FAILSAFE_MIN_DISTANCE_MIN 0 +#define SETTING_FAILSAFE_MIN_DISTANCE_MAX 65000 +#define SETTING_FAILSAFE_MIN_DISTANCE_PROCEDURE_DEFAULT 1 +#define SETTING_FAILSAFE_MIN_DISTANCE_PROCEDURE 90 +#define SETTING_FAILSAFE_MIN_DISTANCE_PROCEDURE_MIN 0 +#define SETTING_FAILSAFE_MIN_DISTANCE_PROCEDURE_MAX 0 +#define SETTING_FAILSAFE_MISSION_DELAY_DEFAULT 0 +#define SETTING_FAILSAFE_MISSION_DELAY 91 +#define SETTING_FAILSAFE_MISSION_DELAY_MIN -1 +#define SETTING_FAILSAFE_MISSION_DELAY_MAX 600 +#define SETTING_ALIGN_BOARD_ROLL 92 +#define SETTING_ALIGN_BOARD_ROLL_MIN -1800 +#define SETTING_ALIGN_BOARD_ROLL_MAX 3600 +#define SETTING_ALIGN_BOARD_PITCH 93 +#define SETTING_ALIGN_BOARD_PITCH_MIN -1800 +#define SETTING_ALIGN_BOARD_PITCH_MAX 3600 +#define SETTING_ALIGN_BOARD_YAW 94 +#define SETTING_ALIGN_BOARD_YAW_MIN -1800 +#define SETTING_ALIGN_BOARD_YAW_MAX 3600 +#define SETTING_VBAT_METER_TYPE_DEFAULT 1 +#define SETTING_VBAT_METER_TYPE 95 +#define SETTING_VBAT_METER_TYPE_MIN 0 +#define SETTING_VBAT_METER_TYPE_MAX 0 +#define SETTING_VBAT_SCALE 96 +#define SETTING_VBAT_SCALE_MIN 0 +#define SETTING_VBAT_SCALE_MAX 65535 +#define SETTING_CURRENT_METER_SCALE 97 +#define SETTING_CURRENT_METER_SCALE_MIN -10000 +#define SETTING_CURRENT_METER_SCALE_MAX 10000 +#define SETTING_CURRENT_METER_OFFSET 98 +#define SETTING_CURRENT_METER_OFFSET_MIN -32768 +#define SETTING_CURRENT_METER_OFFSET_MAX 32767 +#define SETTING_CURRENT_METER_TYPE_DEFAULT 1 +#define SETTING_CURRENT_METER_TYPE 99 +#define SETTING_CURRENT_METER_TYPE_MIN 0 +#define SETTING_CURRENT_METER_TYPE_MAX 0 +#define SETTING_BAT_VOLTAGE_SRC_DEFAULT 0 +#define SETTING_BAT_VOLTAGE_SRC 100 +#define SETTING_BAT_VOLTAGE_SRC_MIN 0 +#define SETTING_BAT_VOLTAGE_SRC_MAX 0 +#define SETTING_CRUISE_POWER_DEFAULT 0 +#define SETTING_CRUISE_POWER 101 +#define SETTING_CRUISE_POWER_MIN 0 +#define SETTING_CRUISE_POWER_MAX 4294967295 +#define SETTING_IDLE_POWER_DEFAULT 0 +#define SETTING_IDLE_POWER 102 +#define SETTING_IDLE_POWER_MIN 0 +#define SETTING_IDLE_POWER_MAX 65535 +#define SETTING_RTH_ENERGY_MARGIN_DEFAULT 5 +#define SETTING_RTH_ENERGY_MARGIN 103 +#define SETTING_RTH_ENERGY_MARGIN_MIN 0 +#define SETTING_RTH_ENERGY_MARGIN_MAX 100 +#define SETTING_THR_COMP_WEIGHT_DEFAULT 1 +#define SETTING_THR_COMP_WEIGHT 104 +#define SETTING_THR_COMP_WEIGHT_MIN 0 +#define SETTING_THR_COMP_WEIGHT_MAX 2 +#define SETTING_BAT_CELLS_DEFAULT 0 +#define SETTING_BAT_CELLS 105 +#define SETTING_BAT_CELLS_MIN 0 +#define SETTING_BAT_CELLS_MAX 12 +#define SETTING_VBAT_CELL_DETECT_VOLTAGE_DEFAULT 425 +#define SETTING_VBAT_CELL_DETECT_VOLTAGE 106 +#define SETTING_VBAT_CELL_DETECT_VOLTAGE_MIN 100 +#define SETTING_VBAT_CELL_DETECT_VOLTAGE_MAX 500 +#define SETTING_VBAT_MAX_CELL_VOLTAGE_DEFAULT 420 +#define SETTING_VBAT_MAX_CELL_VOLTAGE 107 +#define SETTING_VBAT_MAX_CELL_VOLTAGE_MIN 100 +#define SETTING_VBAT_MAX_CELL_VOLTAGE_MAX 500 +#define SETTING_VBAT_MIN_CELL_VOLTAGE_DEFAULT 330 +#define SETTING_VBAT_MIN_CELL_VOLTAGE 108 +#define SETTING_VBAT_MIN_CELL_VOLTAGE_MIN 100 +#define SETTING_VBAT_MIN_CELL_VOLTAGE_MAX 500 +#define SETTING_VBAT_WARNING_CELL_VOLTAGE_DEFAULT 350 +#define SETTING_VBAT_WARNING_CELL_VOLTAGE 109 +#define SETTING_VBAT_WARNING_CELL_VOLTAGE_MIN 100 +#define SETTING_VBAT_WARNING_CELL_VOLTAGE_MAX 500 +#define SETTING_BATTERY_CAPACITY_DEFAULT 0 +#define SETTING_BATTERY_CAPACITY 110 +#define SETTING_BATTERY_CAPACITY_MIN 0 +#define SETTING_BATTERY_CAPACITY_MAX 4294967295 +#define SETTING_BATTERY_CAPACITY_WARNING_DEFAULT 0 +#define SETTING_BATTERY_CAPACITY_WARNING 111 +#define SETTING_BATTERY_CAPACITY_WARNING_MIN 0 +#define SETTING_BATTERY_CAPACITY_WARNING_MAX 4294967295 +#define SETTING_BATTERY_CAPACITY_CRITICAL_DEFAULT 0 +#define SETTING_BATTERY_CAPACITY_CRITICAL 112 +#define SETTING_BATTERY_CAPACITY_CRITICAL_MIN 0 +#define SETTING_BATTERY_CAPACITY_CRITICAL_MAX 4294967295 +#define SETTING_BATTERY_CAPACITY_UNIT_DEFAULT 0 +#define SETTING_BATTERY_CAPACITY_UNIT 113 +#define SETTING_BATTERY_CAPACITY_UNIT_MIN 0 +#define SETTING_BATTERY_CAPACITY_UNIT_MAX 0 +#define SETTING_CONTROLRATE_PROFILE_DEFAULT 0 +#define SETTING_CONTROLRATE_PROFILE 114 +#define SETTING_CONTROLRATE_PROFILE_MIN 0 +#define SETTING_CONTROLRATE_PROFILE_MAX 3 +#define SETTING_THROTTLE_SCALE_DEFAULT 1.0f +#define SETTING_THROTTLE_SCALE 115 +#define SETTING_THROTTLE_SCALE_MIN 0 +#define SETTING_THROTTLE_SCALE_MAX 1 +#define SETTING_THROTTLE_IDLE_DEFAULT 15 +#define SETTING_THROTTLE_IDLE 116 +#define SETTING_THROTTLE_IDLE_MIN 0 +#define SETTING_THROTTLE_IDLE_MAX 30 +#define SETTING_FAILSAFE_THROTTLE_DEFAULT 1000 +#define SETTING_FAILSAFE_THROTTLE 117 +#define SETTING_FAILSAFE_THROTTLE_MIN 1000 +#define SETTING_FAILSAFE_THROTTLE_MAX 2000 +#define SETTING_NAV_MC_HOVER_THR_DEFAULT 1500 +#define SETTING_NAV_MC_HOVER_THR 118 +#define SETTING_NAV_MC_HOVER_THR_MIN 1000 +#define SETTING_NAV_MC_HOVER_THR_MAX 2000 +#define SETTING_NAV_FW_CRUISE_THR_DEFAULT 1400 +#define SETTING_NAV_FW_CRUISE_THR 119 +#define SETTING_NAV_FW_CRUISE_THR_MIN 1000 +#define SETTING_NAV_FW_CRUISE_THR_MAX 2000 +#define SETTING_NAV_FW_MIN_THR_DEFAULT 1200 +#define SETTING_NAV_FW_MIN_THR 120 +#define SETTING_NAV_FW_MIN_THR_MIN 1000 +#define SETTING_NAV_FW_MIN_THR_MAX 2000 +#define SETTING_NAV_FW_MAX_THR_DEFAULT 1700 +#define SETTING_NAV_FW_MAX_THR 121 +#define SETTING_NAV_FW_MAX_THR_MIN 1000 +#define SETTING_NAV_FW_MAX_THR_MAX 2000 +#define SETTING_NAV_FW_PITCH2THR_DEFAULT 10 +#define SETTING_NAV_FW_PITCH2THR 122 +#define SETTING_NAV_FW_PITCH2THR_MIN 0 +#define SETTING_NAV_FW_PITCH2THR_MAX 100 +#define SETTING_NAV_FW_LAUNCH_THR_DEFAULT 1700 +#define SETTING_NAV_FW_LAUNCH_THR 123 +#define SETTING_NAV_FW_LAUNCH_THR_MIN 1000 +#define SETTING_NAV_FW_LAUNCH_THR_MAX 2000 +#define SETTING_NAV_FW_LAUNCH_IDLE_THR_DEFAULT 1000 +#define SETTING_NAV_FW_LAUNCH_IDLE_THR 124 +#define SETTING_NAV_FW_LAUNCH_IDLE_THR_MIN 1000 +#define SETTING_NAV_FW_LAUNCH_IDLE_THR_MAX 2000 +#define SETTING_LIMIT_CONT_CURRENT_DEFAULT 0 +#define SETTING_LIMIT_CONT_CURRENT 125 +#define SETTING_LIMIT_CONT_CURRENT_MIN 0 +#define SETTING_LIMIT_CONT_CURRENT_MAX 4000 +#define SETTING_LIMIT_BURST_CURRENT_DEFAULT 0 +#define SETTING_LIMIT_BURST_CURRENT 126 +#define SETTING_LIMIT_BURST_CURRENT_MIN 0 +#define SETTING_LIMIT_BURST_CURRENT_MAX 4000 +#define SETTING_LIMIT_BURST_CURRENT_TIME_DEFAULT 0 +#define SETTING_LIMIT_BURST_CURRENT_TIME 127 +#define SETTING_LIMIT_BURST_CURRENT_TIME_MIN 0 +#define SETTING_LIMIT_BURST_CURRENT_TIME_MAX 3000 +#define SETTING_LIMIT_BURST_CURRENT_FALLDOWN_TIME_DEFAULT 0 +#define SETTING_LIMIT_BURST_CURRENT_FALLDOWN_TIME 128 +#define SETTING_LIMIT_BURST_CURRENT_FALLDOWN_TIME_MIN 0 +#define SETTING_LIMIT_BURST_CURRENT_FALLDOWN_TIME_MAX 3000 +#define SETTING_LIMIT_CONT_POWER_DEFAULT 0 +#define SETTING_LIMIT_CONT_POWER 129 +#define SETTING_LIMIT_CONT_POWER_MIN 0 +#define SETTING_LIMIT_CONT_POWER_MAX 40000 +#define SETTING_LIMIT_BURST_POWER_DEFAULT 0 +#define SETTING_LIMIT_BURST_POWER 130 +#define SETTING_LIMIT_BURST_POWER_MIN 0 +#define SETTING_LIMIT_BURST_POWER_MAX 40000 +#define SETTING_LIMIT_BURST_POWER_TIME_DEFAULT 0 +#define SETTING_LIMIT_BURST_POWER_TIME 131 +#define SETTING_LIMIT_BURST_POWER_TIME_MIN 0 +#define SETTING_LIMIT_BURST_POWER_TIME_MAX 3000 +#define SETTING_LIMIT_BURST_POWER_FALLDOWN_TIME_DEFAULT 0 +#define SETTING_LIMIT_BURST_POWER_FALLDOWN_TIME 132 +#define SETTING_LIMIT_BURST_POWER_FALLDOWN_TIME_MIN 0 +#define SETTING_LIMIT_BURST_POWER_FALLDOWN_TIME_MAX 3000 +#define SETTING_MOTOR_DIRECTION_INVERTED_DEFAULT 0 +#define SETTING_MOTOR_DIRECTION_INVERTED 133 +#define SETTING_MOTOR_DIRECTION_INVERTED_MIN 0 +#define SETTING_MOTOR_DIRECTION_INVERTED_MAX 0 +#define SETTING_PLATFORM_TYPE_DEFAULT 0 +#define SETTING_PLATFORM_TYPE 134 +#define SETTING_PLATFORM_TYPE_MIN 0 +#define SETTING_PLATFORM_TYPE_MAX 0 +#define SETTING_HAS_FLAPS_DEFAULT 0 +#define SETTING_HAS_FLAPS 135 +#define SETTING_HAS_FLAPS_MIN 0 +#define SETTING_HAS_FLAPS_MAX 0 +#define SETTING_MODEL_PREVIEW_TYPE_DEFAULT -1 +#define SETTING_MODEL_PREVIEW_TYPE 136 +#define SETTING_MODEL_PREVIEW_TYPE_MIN -1 +#define SETTING_MODEL_PREVIEW_TYPE_MAX 32767 +#define SETTING_OUTPUT_MODE_DEFAULT 0 +#define SETTING_OUTPUT_MODE 137 +#define SETTING_OUTPUT_MODE_MIN 0 +#define SETTING_OUTPUT_MODE_MAX 0 +#define SETTING_3D_DEADBAND_LOW_DEFAULT 1406 +#define SETTING_3D_DEADBAND_LOW 138 +#define SETTING_3D_DEADBAND_LOW_MIN 1000 +#define SETTING_3D_DEADBAND_LOW_MAX 2000 +#define SETTING_3D_DEADBAND_HIGH_DEFAULT 1514 +#define SETTING_3D_DEADBAND_HIGH 139 +#define SETTING_3D_DEADBAND_HIGH_MIN 1000 +#define SETTING_3D_DEADBAND_HIGH_MAX 2000 +#define SETTING_3D_NEUTRAL_DEFAULT 1460 +#define SETTING_3D_NEUTRAL 140 +#define SETTING_3D_NEUTRAL_MIN 1000 +#define SETTING_3D_NEUTRAL_MAX 2000 +#define SETTING_SERVO_PROTOCOL_DEFAULT 0 +#define SETTING_SERVO_PROTOCOL 141 +#define SETTING_SERVO_PROTOCOL_MIN 0 +#define SETTING_SERVO_PROTOCOL_MAX 0 +#define SETTING_SERVO_CENTER_PULSE_DEFAULT 1500 +#define SETTING_SERVO_CENTER_PULSE 142 +#define SETTING_SERVO_CENTER_PULSE_MIN 1000 +#define SETTING_SERVO_CENTER_PULSE_MAX 2000 +#define SETTING_SERVO_PWM_RATE_DEFAULT 50 +#define SETTING_SERVO_PWM_RATE 143 +#define SETTING_SERVO_PWM_RATE_MIN 50 +#define SETTING_SERVO_PWM_RATE_MAX 498 +#define SETTING_SERVO_LPF_HZ_DEFAULT 20 +#define SETTING_SERVO_LPF_HZ 144 +#define SETTING_SERVO_LPF_HZ_MIN 0 +#define SETTING_SERVO_LPF_HZ_MAX 400 +#define SETTING_FLAPERON_THROW_OFFSET_DEFAULT 200 +#define SETTING_FLAPERON_THROW_OFFSET 145 +#define SETTING_FLAPERON_THROW_OFFSET_MIN 50 +#define SETTING_FLAPERON_THROW_OFFSET_MAX 450 +#define SETTING_TRI_UNARMED_SERVO_DEFAULT 1 +#define SETTING_TRI_UNARMED_SERVO 146 +#define SETTING_TRI_UNARMED_SERVO_MIN 0 +#define SETTING_TRI_UNARMED_SERVO_MAX 0 +#define SETTING_SERVO_AUTOTRIM_ROTATION_LIMIT_DEFAULT 15 +#define SETTING_SERVO_AUTOTRIM_ROTATION_LIMIT 147 +#define SETTING_SERVO_AUTOTRIM_ROTATION_LIMIT_MIN 1 +#define SETTING_SERVO_AUTOTRIM_ROTATION_LIMIT_MAX 60 +#define SETTING_THR_MID_DEFAULT 50 +#define SETTING_THR_MID 148 +#define SETTING_THR_MID_MIN 0 +#define SETTING_THR_MID_MAX 100 +#define SETTING_THR_EXPO_DEFAULT 0 +#define SETTING_THR_EXPO 149 +#define SETTING_THR_EXPO_MIN 0 +#define SETTING_THR_EXPO_MAX 100 +#define SETTING_TPA_RATE_DEFAULT 0 +#define SETTING_TPA_RATE 150 +#define SETTING_TPA_RATE_MIN 0 +#define SETTING_TPA_RATE_MAX 100 +#define SETTING_TPA_BREAKPOINT_DEFAULT 1500 +#define SETTING_TPA_BREAKPOINT 151 +#define SETTING_TPA_BREAKPOINT_MIN 1000 +#define SETTING_TPA_BREAKPOINT_MAX 2000 +#define SETTING_FW_TPA_TIME_CONSTANT_DEFAULT 1500 +#define SETTING_FW_TPA_TIME_CONSTANT 152 +#define SETTING_FW_TPA_TIME_CONSTANT_MIN 0 +#define SETTING_FW_TPA_TIME_CONSTANT_MAX 5000 +#define SETTING_RC_EXPO_DEFAULT 70 +#define SETTING_RC_EXPO 153 +#define SETTING_RC_EXPO_MIN 0 +#define SETTING_RC_EXPO_MAX 100 +#define SETTING_RC_YAW_EXPO_DEFAULT 20 +#define SETTING_RC_YAW_EXPO 154 +#define SETTING_RC_YAW_EXPO_MIN 0 +#define SETTING_RC_YAW_EXPO_MAX 100 +#define SETTING_ROLL_RATE_DEFAULT 20 +#define SETTING_ROLL_RATE 155 +#define SETTING_ROLL_RATE_MIN 4 +#define SETTING_ROLL_RATE_MAX 180 +#define SETTING_PITCH_RATE_DEFAULT 20 +#define SETTING_PITCH_RATE 156 +#define SETTING_PITCH_RATE_MIN 4 +#define SETTING_PITCH_RATE_MAX 180 +#define SETTING_YAW_RATE_DEFAULT 20 +#define SETTING_YAW_RATE 157 +#define SETTING_YAW_RATE_MIN 1 +#define SETTING_YAW_RATE_MAX 180 +#define SETTING_MANUAL_RC_EXPO_DEFAULT 35 +#define SETTING_MANUAL_RC_EXPO 158 +#define SETTING_MANUAL_RC_EXPO_MIN 0 +#define SETTING_MANUAL_RC_EXPO_MAX 100 +#define SETTING_MANUAL_RC_YAW_EXPO_DEFAULT 20 +#define SETTING_MANUAL_RC_YAW_EXPO 159 +#define SETTING_MANUAL_RC_YAW_EXPO_MIN 0 +#define SETTING_MANUAL_RC_YAW_EXPO_MAX 100 +#define SETTING_MANUAL_ROLL_RATE_DEFAULT 100 +#define SETTING_MANUAL_ROLL_RATE 160 +#define SETTING_MANUAL_ROLL_RATE_MIN 0 +#define SETTING_MANUAL_ROLL_RATE_MAX 100 +#define SETTING_MANUAL_PITCH_RATE_DEFAULT 100 +#define SETTING_MANUAL_PITCH_RATE 161 +#define SETTING_MANUAL_PITCH_RATE_MIN 0 +#define SETTING_MANUAL_PITCH_RATE_MAX 100 +#define SETTING_MANUAL_YAW_RATE_DEFAULT 100 +#define SETTING_MANUAL_YAW_RATE 162 +#define SETTING_MANUAL_YAW_RATE_MIN 0 +#define SETTING_MANUAL_YAW_RATE_MAX 100 +#define SETTING_FPV_MIX_DEGREES_DEFAULT 0 +#define SETTING_FPV_MIX_DEGREES 163 +#define SETTING_FPV_MIX_DEGREES_MIN 0 +#define SETTING_FPV_MIX_DEGREES_MAX 50 +#define SETTING_RATE_DYNAMICS_CENTER_SENSITIVITY_DEFAULT 100 +#define SETTING_RATE_DYNAMICS_CENTER_SENSITIVITY 164 +#define SETTING_RATE_DYNAMICS_CENTER_SENSITIVITY_MIN 25 +#define SETTING_RATE_DYNAMICS_CENTER_SENSITIVITY_MAX 175 +#define SETTING_RATE_DYNAMICS_END_SENSITIVITY_DEFAULT 100 +#define SETTING_RATE_DYNAMICS_END_SENSITIVITY 165 +#define SETTING_RATE_DYNAMICS_END_SENSITIVITY_MIN 25 +#define SETTING_RATE_DYNAMICS_END_SENSITIVITY_MAX 175 +#define SETTING_RATE_DYNAMICS_CENTER_CORRECTION_DEFAULT 10 +#define SETTING_RATE_DYNAMICS_CENTER_CORRECTION 166 +#define SETTING_RATE_DYNAMICS_CENTER_CORRECTION_MIN 10 +#define SETTING_RATE_DYNAMICS_CENTER_CORRECTION_MAX 95 +#define SETTING_RATE_DYNAMICS_END_CORRECTION_DEFAULT 10 +#define SETTING_RATE_DYNAMICS_END_CORRECTION 167 +#define SETTING_RATE_DYNAMICS_END_CORRECTION_MIN 10 +#define SETTING_RATE_DYNAMICS_END_CORRECTION_MAX 95 +#define SETTING_RATE_DYNAMICS_CENTER_WEIGHT_DEFAULT 0 +#define SETTING_RATE_DYNAMICS_CENTER_WEIGHT 168 +#define SETTING_RATE_DYNAMICS_CENTER_WEIGHT_MIN 0 +#define SETTING_RATE_DYNAMICS_CENTER_WEIGHT_MAX 95 +#define SETTING_RATE_DYNAMICS_END_WEIGHT_DEFAULT 0 +#define SETTING_RATE_DYNAMICS_END_WEIGHT 169 +#define SETTING_RATE_DYNAMICS_END_WEIGHT_MIN 0 +#define SETTING_RATE_DYNAMICS_END_WEIGHT_MAX 95 +#define SETTING_REBOOT_CHARACTER_DEFAULT 82 +#define SETTING_REBOOT_CHARACTER 170 +#define SETTING_REBOOT_CHARACTER_MIN 48 +#define SETTING_REBOOT_CHARACTER_MAX 126 +#define SETTING_IMU_DCM_KP_DEFAULT 2000 +#define SETTING_IMU_DCM_KP 171 +#define SETTING_IMU_DCM_KP_MIN 0 +#define SETTING_IMU_DCM_KP_MAX 65535 +#define SETTING_IMU_DCM_KI_DEFAULT 50 +#define SETTING_IMU_DCM_KI 172 +#define SETTING_IMU_DCM_KI_MIN 0 +#define SETTING_IMU_DCM_KI_MAX 65535 +#define SETTING_IMU_DCM_KP_MAG_DEFAULT 2000 +#define SETTING_IMU_DCM_KP_MAG 173 +#define SETTING_IMU_DCM_KP_MAG_MIN 0 +#define SETTING_IMU_DCM_KP_MAG_MAX 65535 +#define SETTING_IMU_DCM_KI_MAG_DEFAULT 50 +#define SETTING_IMU_DCM_KI_MAG 174 +#define SETTING_IMU_DCM_KI_MAG_MIN 0 +#define SETTING_IMU_DCM_KI_MAG_MAX 65535 +#define SETTING_SMALL_ANGLE_DEFAULT 25 +#define SETTING_SMALL_ANGLE 175 +#define SETTING_SMALL_ANGLE_MIN 0 +#define SETTING_SMALL_ANGLE_MAX 180 +#define SETTING_IMU_ACC_IGNORE_RATE_DEFAULT 15 +#define SETTING_IMU_ACC_IGNORE_RATE 176 +#define SETTING_IMU_ACC_IGNORE_RATE_MIN 0 +#define SETTING_IMU_ACC_IGNORE_RATE_MAX 30 +#define SETTING_IMU_ACC_IGNORE_SLOPE_DEFAULT 5 +#define SETTING_IMU_ACC_IGNORE_SLOPE 177 +#define SETTING_IMU_ACC_IGNORE_SLOPE_MIN 0 +#define SETTING_IMU_ACC_IGNORE_SLOPE_MAX 10 +#define SETTING_IMU_GPS_YAW_WINDCOMP_DEFAULT 1 +#define SETTING_IMU_GPS_YAW_WINDCOMP 178 +#define SETTING_IMU_GPS_YAW_WINDCOMP_MIN 0 +#define SETTING_IMU_GPS_YAW_WINDCOMP_MAX 0 +#define SETTING_IMU_INERTIA_COMP_METHOD_DEFAULT 0 +#define SETTING_IMU_INERTIA_COMP_METHOD 179 +#define SETTING_IMU_INERTIA_COMP_METHOD_MIN 0 +#define SETTING_IMU_INERTIA_COMP_METHOD_MAX 0 +#define SETTING_FIXED_WING_AUTO_ARM_DEFAULT 0 +#define SETTING_FIXED_WING_AUTO_ARM 180 +#define SETTING_FIXED_WING_AUTO_ARM_MIN 0 +#define SETTING_FIXED_WING_AUTO_ARM_MAX 0 +#define SETTING_DISARM_KILL_SWITCH_DEFAULT 1 +#define SETTING_DISARM_KILL_SWITCH 181 +#define SETTING_DISARM_KILL_SWITCH_MIN 0 +#define SETTING_DISARM_KILL_SWITCH_MAX 0 +#define SETTING_SWITCH_DISARM_DELAY_DEFAULT 250 +#define SETTING_SWITCH_DISARM_DELAY 182 +#define SETTING_SWITCH_DISARM_DELAY_MIN 0 +#define SETTING_SWITCH_DISARM_DELAY_MAX 1000 +#define SETTING_PREARM_TIMEOUT_DEFAULT 10000 +#define SETTING_PREARM_TIMEOUT 183 +#define SETTING_PREARM_TIMEOUT_MIN 0 +#define SETTING_PREARM_TIMEOUT_MAX 10000 +#define SETTING_APPLIED_DEFAULTS_DEFAULT 0 +#define SETTING_APPLIED_DEFAULTS 184 +#define SETTING_APPLIED_DEFAULTS_MIN 0 +#define SETTING_APPLIED_DEFAULTS_MAX 99 +#define SETTING_GPS_PROVIDER_DEFAULT 1 +#define SETTING_GPS_PROVIDER 185 +#define SETTING_GPS_PROVIDER_MIN 0 +#define SETTING_GPS_PROVIDER_MAX 0 +#define SETTING_GPS_SBAS_MODE_DEFAULT 5 +#define SETTING_GPS_SBAS_MODE 186 +#define SETTING_GPS_SBAS_MODE_MIN 0 +#define SETTING_GPS_SBAS_MODE_MAX 0 +#define SETTING_GPS_DYN_MODEL_DEFAULT 1 +#define SETTING_GPS_DYN_MODEL 187 +#define SETTING_GPS_DYN_MODEL_MIN 0 +#define SETTING_GPS_DYN_MODEL_MAX 0 +#define SETTING_GPS_AUTO_CONFIG_DEFAULT 1 +#define SETTING_GPS_AUTO_CONFIG 188 +#define SETTING_GPS_AUTO_CONFIG_MIN 0 +#define SETTING_GPS_AUTO_CONFIG_MAX 0 +#define SETTING_GPS_AUTO_BAUD_DEFAULT 1 +#define SETTING_GPS_AUTO_BAUD 189 +#define SETTING_GPS_AUTO_BAUD_MIN 0 +#define SETTING_GPS_AUTO_BAUD_MAX 0 +#define SETTING_GPS_UBLOX_USE_GALILEO_DEFAULT 0 +#define SETTING_GPS_UBLOX_USE_GALILEO 190 +#define SETTING_GPS_UBLOX_USE_GALILEO_MIN 0 +#define SETTING_GPS_UBLOX_USE_GALILEO_MAX 0 +#define SETTING_GPS_MIN_SATS_DEFAULT 6 +#define SETTING_GPS_MIN_SATS 191 +#define SETTING_GPS_MIN_SATS_MIN 5 +#define SETTING_GPS_MIN_SATS_MAX 10 +#define SETTING_DEADBAND_DEFAULT 5 +#define SETTING_DEADBAND 192 +#define SETTING_DEADBAND_MIN 0 +#define SETTING_DEADBAND_MAX 32 +#define SETTING_YAW_DEADBAND_DEFAULT 5 +#define SETTING_YAW_DEADBAND 193 +#define SETTING_YAW_DEADBAND_MIN 0 +#define SETTING_YAW_DEADBAND_MAX 100 +#define SETTING_POS_HOLD_DEADBAND_DEFAULT 10 +#define SETTING_POS_HOLD_DEADBAND 194 +#define SETTING_POS_HOLD_DEADBAND_MIN 2 +#define SETTING_POS_HOLD_DEADBAND_MAX 250 +#define SETTING_CONTROL_DEADBAND_DEFAULT 10 +#define SETTING_CONTROL_DEADBAND 195 +#define SETTING_CONTROL_DEADBAND_MIN 2 +#define SETTING_CONTROL_DEADBAND_MAX 250 +#define SETTING_ALT_HOLD_DEADBAND_DEFAULT 50 +#define SETTING_ALT_HOLD_DEADBAND 196 +#define SETTING_ALT_HOLD_DEADBAND_MIN 10 +#define SETTING_ALT_HOLD_DEADBAND_MAX 250 +#define SETTING_3D_DEADBAND_THROTTLE_DEFAULT 50 +#define SETTING_3D_DEADBAND_THROTTLE 197 +#define SETTING_3D_DEADBAND_THROTTLE_MIN 0 +#define SETTING_3D_DEADBAND_THROTTLE_MAX 200 +#define SETTING_AIRMODE_TYPE_DEFAULT 0 +#define SETTING_AIRMODE_TYPE 198 +#define SETTING_AIRMODE_TYPE_MIN 0 +#define SETTING_AIRMODE_TYPE_MAX 0 +#define SETTING_AIRMODE_THROTTLE_THRESHOLD_DEFAULT 1150 +#define SETTING_AIRMODE_THROTTLE_THRESHOLD 199 +#define SETTING_AIRMODE_THROTTLE_THRESHOLD_MIN 1000 +#define SETTING_AIRMODE_THROTTLE_THRESHOLD_MAX 2000 +#define SETTING_MC_P_PITCH_DEFAULT 40 +#define SETTING_MC_P_PITCH 200 +#define SETTING_MC_P_PITCH_MIN 0 +#define SETTING_MC_P_PITCH_MAX 255 +#define SETTING_MC_I_PITCH_DEFAULT 30 +#define SETTING_MC_I_PITCH 201 +#define SETTING_MC_I_PITCH_MIN 0 +#define SETTING_MC_I_PITCH_MAX 255 +#define SETTING_MC_D_PITCH_DEFAULT 23 +#define SETTING_MC_D_PITCH 202 +#define SETTING_MC_D_PITCH_MIN 0 +#define SETTING_MC_D_PITCH_MAX 255 +#define SETTING_MC_CD_PITCH_DEFAULT 60 +#define SETTING_MC_CD_PITCH 203 +#define SETTING_MC_CD_PITCH_MIN 0 +#define SETTING_MC_CD_PITCH_MAX 255 +#define SETTING_MC_P_ROLL_DEFAULT 40 +#define SETTING_MC_P_ROLL 204 +#define SETTING_MC_P_ROLL_MIN 0 +#define SETTING_MC_P_ROLL_MAX 255 +#define SETTING_MC_I_ROLL_DEFAULT 30 +#define SETTING_MC_I_ROLL 205 +#define SETTING_MC_I_ROLL_MIN 0 +#define SETTING_MC_I_ROLL_MAX 255 +#define SETTING_MC_D_ROLL_DEFAULT 23 +#define SETTING_MC_D_ROLL 206 +#define SETTING_MC_D_ROLL_MIN 0 +#define SETTING_MC_D_ROLL_MAX 255 +#define SETTING_MC_CD_ROLL_DEFAULT 60 +#define SETTING_MC_CD_ROLL 207 +#define SETTING_MC_CD_ROLL_MIN 0 +#define SETTING_MC_CD_ROLL_MAX 255 +#define SETTING_MC_P_YAW_DEFAULT 85 +#define SETTING_MC_P_YAW 208 +#define SETTING_MC_P_YAW_MIN 0 +#define SETTING_MC_P_YAW_MAX 255 +#define SETTING_MC_I_YAW_DEFAULT 45 +#define SETTING_MC_I_YAW 209 +#define SETTING_MC_I_YAW_MIN 0 +#define SETTING_MC_I_YAW_MAX 255 +#define SETTING_MC_D_YAW_DEFAULT 0 +#define SETTING_MC_D_YAW 210 +#define SETTING_MC_D_YAW_MIN 0 +#define SETTING_MC_D_YAW_MAX 255 +#define SETTING_MC_CD_YAW_DEFAULT 60 +#define SETTING_MC_CD_YAW 211 +#define SETTING_MC_CD_YAW_MIN 0 +#define SETTING_MC_CD_YAW_MAX 255 +#define SETTING_MC_P_LEVEL_DEFAULT 20 +#define SETTING_MC_P_LEVEL 212 +#define SETTING_MC_P_LEVEL_MIN 0 +#define SETTING_MC_P_LEVEL_MAX 255 +#define SETTING_MC_I_LEVEL_DEFAULT 15 +#define SETTING_MC_I_LEVEL 213 +#define SETTING_MC_I_LEVEL_MIN 0 +#define SETTING_MC_I_LEVEL_MAX 255 +#define SETTING_MC_D_LEVEL_DEFAULT 75 +#define SETTING_MC_D_LEVEL 214 +#define SETTING_MC_D_LEVEL_MIN 0 +#define SETTING_MC_D_LEVEL_MAX 255 +#define SETTING_FW_P_PITCH_DEFAULT 5 +#define SETTING_FW_P_PITCH 215 +#define SETTING_FW_P_PITCH_MIN 0 +#define SETTING_FW_P_PITCH_MAX 255 +#define SETTING_FW_I_PITCH_DEFAULT 7 +#define SETTING_FW_I_PITCH 216 +#define SETTING_FW_I_PITCH_MIN 0 +#define SETTING_FW_I_PITCH_MAX 255 +#define SETTING_FW_D_PITCH_DEFAULT 0 +#define SETTING_FW_D_PITCH 217 +#define SETTING_FW_D_PITCH_MIN 0 +#define SETTING_FW_D_PITCH_MAX 255 +#define SETTING_FW_FF_PITCH_DEFAULT 50 +#define SETTING_FW_FF_PITCH 218 +#define SETTING_FW_FF_PITCH_MIN 0 +#define SETTING_FW_FF_PITCH_MAX 255 +#define SETTING_FW_P_ROLL_DEFAULT 5 +#define SETTING_FW_P_ROLL 219 +#define SETTING_FW_P_ROLL_MIN 0 +#define SETTING_FW_P_ROLL_MAX 255 +#define SETTING_FW_I_ROLL_DEFAULT 7 +#define SETTING_FW_I_ROLL 220 +#define SETTING_FW_I_ROLL_MIN 0 +#define SETTING_FW_I_ROLL_MAX 255 +#define SETTING_FW_D_ROLL_DEFAULT 0 +#define SETTING_FW_D_ROLL 221 +#define SETTING_FW_D_ROLL_MIN 0 +#define SETTING_FW_D_ROLL_MAX 255 +#define SETTING_FW_FF_ROLL_DEFAULT 50 +#define SETTING_FW_FF_ROLL 222 +#define SETTING_FW_FF_ROLL_MIN 0 +#define SETTING_FW_FF_ROLL_MAX 255 +#define SETTING_FW_P_YAW_DEFAULT 6 +#define SETTING_FW_P_YAW 223 +#define SETTING_FW_P_YAW_MIN 0 +#define SETTING_FW_P_YAW_MAX 255 +#define SETTING_FW_I_YAW_DEFAULT 10 +#define SETTING_FW_I_YAW 224 +#define SETTING_FW_I_YAW_MIN 0 +#define SETTING_FW_I_YAW_MAX 255 +#define SETTING_FW_D_YAW_DEFAULT 0 +#define SETTING_FW_D_YAW 225 +#define SETTING_FW_D_YAW_MIN 0 +#define SETTING_FW_D_YAW_MAX 255 +#define SETTING_FW_FF_YAW_DEFAULT 60 +#define SETTING_FW_FF_YAW 226 +#define SETTING_FW_FF_YAW_MIN 0 +#define SETTING_FW_FF_YAW_MAX 255 +#define SETTING_FW_P_LEVEL_DEFAULT 20 +#define SETTING_FW_P_LEVEL 227 +#define SETTING_FW_P_LEVEL_MIN 0 +#define SETTING_FW_P_LEVEL_MAX 255 +#define SETTING_FW_I_LEVEL_DEFAULT 5 +#define SETTING_FW_I_LEVEL 228 +#define SETTING_FW_I_LEVEL_MIN 0 +#define SETTING_FW_I_LEVEL_MAX 255 +#define SETTING_FW_D_LEVEL_DEFAULT 75 +#define SETTING_FW_D_LEVEL 229 +#define SETTING_FW_D_LEVEL_MIN 0 +#define SETTING_FW_D_LEVEL_MAX 255 +#define SETTING_MAX_ANGLE_INCLINATION_RLL_DEFAULT 300 +#define SETTING_MAX_ANGLE_INCLINATION_RLL 230 +#define SETTING_MAX_ANGLE_INCLINATION_RLL_MIN 100 +#define SETTING_MAX_ANGLE_INCLINATION_RLL_MAX 900 +#define SETTING_MAX_ANGLE_INCLINATION_PIT_DEFAULT 300 +#define SETTING_MAX_ANGLE_INCLINATION_PIT 231 +#define SETTING_MAX_ANGLE_INCLINATION_PIT_MIN 100 +#define SETTING_MAX_ANGLE_INCLINATION_PIT_MAX 900 +#define SETTING_DTERM_LPF_HZ_DEFAULT 110 +#define SETTING_DTERM_LPF_HZ 232 +#define SETTING_DTERM_LPF_HZ_MIN 0 +#define SETTING_DTERM_LPF_HZ_MAX 500 +#define SETTING_DTERM_LPF_TYPE_DEFAULT 2 +#define SETTING_DTERM_LPF_TYPE 233 +#define SETTING_DTERM_LPF_TYPE_MIN 0 +#define SETTING_DTERM_LPF_TYPE_MAX 0 +#define SETTING_DTERM_LPF2_HZ_DEFAULT 0 +#define SETTING_DTERM_LPF2_HZ 234 +#define SETTING_DTERM_LPF2_HZ_MIN 0 +#define SETTING_DTERM_LPF2_HZ_MAX 500 +#define SETTING_DTERM_LPF2_TYPE_DEFAULT 0 +#define SETTING_DTERM_LPF2_TYPE 235 +#define SETTING_DTERM_LPF2_TYPE_MIN 0 +#define SETTING_DTERM_LPF2_TYPE_MAX 0 +#define SETTING_YAW_LPF_HZ_DEFAULT 0 +#define SETTING_YAW_LPF_HZ 236 +#define SETTING_YAW_LPF_HZ_MIN 0 +#define SETTING_YAW_LPF_HZ_MAX 200 +#define SETTING_FW_ITERM_THROW_LIMIT_DEFAULT 165 +#define SETTING_FW_ITERM_THROW_LIMIT 237 +#define SETTING_FW_ITERM_THROW_LIMIT_MIN 0 +#define SETTING_FW_ITERM_THROW_LIMIT_MAX 500 +#define SETTING_FW_REFERENCE_AIRSPEED_DEFAULT 1500 +#define SETTING_FW_REFERENCE_AIRSPEED 238 +#define SETTING_FW_REFERENCE_AIRSPEED_MIN 300 +#define SETTING_FW_REFERENCE_AIRSPEED_MAX 6000 +#define SETTING_FW_TURN_ASSIST_YAW_GAIN_DEFAULT 1 +#define SETTING_FW_TURN_ASSIST_YAW_GAIN 239 +#define SETTING_FW_TURN_ASSIST_YAW_GAIN_MIN 0 +#define SETTING_FW_TURN_ASSIST_YAW_GAIN_MAX 2 +#define SETTING_FW_TURN_ASSIST_PITCH_GAIN_DEFAULT 1 +#define SETTING_FW_TURN_ASSIST_PITCH_GAIN 240 +#define SETTING_FW_TURN_ASSIST_PITCH_GAIN_MIN 0 +#define SETTING_FW_TURN_ASSIST_PITCH_GAIN_MAX 2 +#define SETTING_FW_ITERM_LIMIT_STICK_POSITION_DEFAULT 0.5f +#define SETTING_FW_ITERM_LIMIT_STICK_POSITION 241 +#define SETTING_FW_ITERM_LIMIT_STICK_POSITION_MIN 0 +#define SETTING_FW_ITERM_LIMIT_STICK_POSITION_MAX 1 +#define SETTING_FW_YAW_ITERM_FREEZE_BANK_ANGLE_DEFAULT 0 +#define SETTING_FW_YAW_ITERM_FREEZE_BANK_ANGLE 242 +#define SETTING_FW_YAW_ITERM_FREEZE_BANK_ANGLE_MIN 0 +#define SETTING_FW_YAW_ITERM_FREEZE_BANK_ANGLE_MAX 90 +#define SETTING_PIDSUM_LIMIT_DEFAULT 500 +#define SETTING_PIDSUM_LIMIT 243 +#define SETTING_PIDSUM_LIMIT_MIN 100 +#define SETTING_PIDSUM_LIMIT_MAX 1000 +#define SETTING_PIDSUM_LIMIT_YAW_DEFAULT 350 +#define SETTING_PIDSUM_LIMIT_YAW 244 +#define SETTING_PIDSUM_LIMIT_YAW_MIN 100 +#define SETTING_PIDSUM_LIMIT_YAW_MAX 1000 +#define SETTING_ITERM_WINDUP_DEFAULT 50 +#define SETTING_ITERM_WINDUP 245 +#define SETTING_ITERM_WINDUP_MIN 0 +#define SETTING_ITERM_WINDUP_MAX 90 +#define SETTING_RATE_ACCEL_LIMIT_ROLL_PITCH_DEFAULT 0 +#define SETTING_RATE_ACCEL_LIMIT_ROLL_PITCH 246 +#define SETTING_RATE_ACCEL_LIMIT_ROLL_PITCH_MIN 0 +#define SETTING_RATE_ACCEL_LIMIT_ROLL_PITCH_MAX 500000 +#define SETTING_RATE_ACCEL_LIMIT_YAW_DEFAULT 10000 +#define SETTING_RATE_ACCEL_LIMIT_YAW 247 +#define SETTING_RATE_ACCEL_LIMIT_YAW_MIN 0 +#define SETTING_RATE_ACCEL_LIMIT_YAW_MAX 500000 +#define SETTING_HEADING_HOLD_RATE_LIMIT_DEFAULT 90 +#define SETTING_HEADING_HOLD_RATE_LIMIT 248 +#define SETTING_HEADING_HOLD_RATE_LIMIT_MIN 10 +#define SETTING_HEADING_HOLD_RATE_LIMIT_MAX 250 +#define SETTING_NAV_MC_POS_Z_P_DEFAULT 50 +#define SETTING_NAV_MC_POS_Z_P 249 +#define SETTING_NAV_MC_POS_Z_P_MIN 0 +#define SETTING_NAV_MC_POS_Z_P_MAX 255 +#define SETTING_NAV_MC_VEL_Z_P_DEFAULT 100 +#define SETTING_NAV_MC_VEL_Z_P 250 +#define SETTING_NAV_MC_VEL_Z_P_MIN 0 +#define SETTING_NAV_MC_VEL_Z_P_MAX 255 +#define SETTING_NAV_MC_VEL_Z_I_DEFAULT 50 +#define SETTING_NAV_MC_VEL_Z_I 251 +#define SETTING_NAV_MC_VEL_Z_I_MIN 0 +#define SETTING_NAV_MC_VEL_Z_I_MAX 255 +#define SETTING_NAV_MC_VEL_Z_D_DEFAULT 10 +#define SETTING_NAV_MC_VEL_Z_D 252 +#define SETTING_NAV_MC_VEL_Z_D_MIN 0 +#define SETTING_NAV_MC_VEL_Z_D_MAX 255 +#define SETTING_NAV_MC_POS_XY_P_DEFAULT 65 +#define SETTING_NAV_MC_POS_XY_P 253 +#define SETTING_NAV_MC_POS_XY_P_MIN 0 +#define SETTING_NAV_MC_POS_XY_P_MAX 255 +#define SETTING_NAV_MC_VEL_XY_P_DEFAULT 40 +#define SETTING_NAV_MC_VEL_XY_P 254 +#define SETTING_NAV_MC_VEL_XY_P_MIN 0 +#define SETTING_NAV_MC_VEL_XY_P_MAX 255 +#define SETTING_NAV_MC_VEL_XY_I_DEFAULT 15 +#define SETTING_NAV_MC_VEL_XY_I 255 +#define SETTING_NAV_MC_VEL_XY_I_MIN 0 +#define SETTING_NAV_MC_VEL_XY_I_MAX 255 +#define SETTING_NAV_MC_VEL_XY_D_DEFAULT 100 +#define SETTING_NAV_MC_VEL_XY_D 256 +#define SETTING_NAV_MC_VEL_XY_D_MIN 0 +#define SETTING_NAV_MC_VEL_XY_D_MAX 255 +#define SETTING_NAV_MC_VEL_XY_FF_DEFAULT 40 +#define SETTING_NAV_MC_VEL_XY_FF 257 +#define SETTING_NAV_MC_VEL_XY_FF_MIN 0 +#define SETTING_NAV_MC_VEL_XY_FF_MAX 255 +#define SETTING_NAV_MC_HEADING_P_DEFAULT 60 +#define SETTING_NAV_MC_HEADING_P 258 +#define SETTING_NAV_MC_HEADING_P_MIN 0 +#define SETTING_NAV_MC_HEADING_P_MAX 255 +#define SETTING_NAV_MC_VEL_XY_DTERM_LPF_HZ_DEFAULT 2 +#define SETTING_NAV_MC_VEL_XY_DTERM_LPF_HZ 259 +#define SETTING_NAV_MC_VEL_XY_DTERM_LPF_HZ_MIN 0 +#define SETTING_NAV_MC_VEL_XY_DTERM_LPF_HZ_MAX 100 +#define SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_DEFAULT 90 +#define SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION 260 +#define SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_MIN 0 +#define SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_MAX 100 +#define SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_START_DEFAULT 10 +#define SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_START 261 +#define SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_START_MIN 0 +#define SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_START_MAX 100 +#define SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_END_DEFAULT 60 +#define SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_END 262 +#define SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_END_MIN 0 +#define SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_END_MAX 100 +#define SETTING_NAV_FW_POS_Z_P_DEFAULT 40 +#define SETTING_NAV_FW_POS_Z_P 263 +#define SETTING_NAV_FW_POS_Z_P_MIN 0 +#define SETTING_NAV_FW_POS_Z_P_MAX 255 +#define SETTING_NAV_FW_POS_Z_I_DEFAULT 5 +#define SETTING_NAV_FW_POS_Z_I 264 +#define SETTING_NAV_FW_POS_Z_I_MIN 0 +#define SETTING_NAV_FW_POS_Z_I_MAX 255 +#define SETTING_NAV_FW_POS_Z_D_DEFAULT 10 +#define SETTING_NAV_FW_POS_Z_D 265 +#define SETTING_NAV_FW_POS_Z_D_MIN 0 +#define SETTING_NAV_FW_POS_Z_D_MAX 255 +#define SETTING_NAV_FW_POS_XY_P_DEFAULT 75 +#define SETTING_NAV_FW_POS_XY_P 266 +#define SETTING_NAV_FW_POS_XY_P_MIN 0 +#define SETTING_NAV_FW_POS_XY_P_MAX 255 +#define SETTING_NAV_FW_POS_XY_I_DEFAULT 5 +#define SETTING_NAV_FW_POS_XY_I 267 +#define SETTING_NAV_FW_POS_XY_I_MIN 0 +#define SETTING_NAV_FW_POS_XY_I_MAX 255 +#define SETTING_NAV_FW_POS_XY_D_DEFAULT 8 +#define SETTING_NAV_FW_POS_XY_D 268 +#define SETTING_NAV_FW_POS_XY_D_MIN 0 +#define SETTING_NAV_FW_POS_XY_D_MAX 255 +#define SETTING_NAV_FW_HEADING_P_DEFAULT 60 +#define SETTING_NAV_FW_HEADING_P 269 +#define SETTING_NAV_FW_HEADING_P_MIN 0 +#define SETTING_NAV_FW_HEADING_P_MAX 255 +#define SETTING_NAV_FW_POS_HDG_P_DEFAULT 30 +#define SETTING_NAV_FW_POS_HDG_P 270 +#define SETTING_NAV_FW_POS_HDG_P_MIN 0 +#define SETTING_NAV_FW_POS_HDG_P_MAX 255 +#define SETTING_NAV_FW_POS_HDG_I_DEFAULT 2 +#define SETTING_NAV_FW_POS_HDG_I 271 +#define SETTING_NAV_FW_POS_HDG_I_MIN 0 +#define SETTING_NAV_FW_POS_HDG_I_MAX 255 +#define SETTING_NAV_FW_POS_HDG_D_DEFAULT 0 +#define SETTING_NAV_FW_POS_HDG_D 272 +#define SETTING_NAV_FW_POS_HDG_D_MIN 0 +#define SETTING_NAV_FW_POS_HDG_D_MAX 255 +#define SETTING_NAV_FW_POS_HDG_PIDSUM_LIMIT_DEFAULT 350 +#define SETTING_NAV_FW_POS_HDG_PIDSUM_LIMIT 273 +#define SETTING_NAV_FW_POS_HDG_PIDSUM_LIMIT_MIN 100 +#define SETTING_NAV_FW_POS_HDG_PIDSUM_LIMIT_MAX 1000 +#define SETTING_MC_ITERM_RELAX_DEFAULT 1 +#define SETTING_MC_ITERM_RELAX 274 +#define SETTING_MC_ITERM_RELAX_MIN 0 +#define SETTING_MC_ITERM_RELAX_MAX 0 +#define SETTING_MC_ITERM_RELAX_CUTOFF_DEFAULT 15 +#define SETTING_MC_ITERM_RELAX_CUTOFF 275 +#define SETTING_MC_ITERM_RELAX_CUTOFF_MIN 1 +#define SETTING_MC_ITERM_RELAX_CUTOFF_MAX 100 +#define SETTING_D_BOOST_MIN_DEFAULT 0.5f +#define SETTING_D_BOOST_MIN 276 +#define SETTING_D_BOOST_MIN_MIN 0 +#define SETTING_D_BOOST_MIN_MAX 1 +#define SETTING_D_BOOST_MAX_DEFAULT 1.25f +#define SETTING_D_BOOST_MAX 277 +#define SETTING_D_BOOST_MAX_MIN 1 +#define SETTING_D_BOOST_MAX_MAX 3 +#define SETTING_D_BOOST_MAX_AT_ACCELERATION_DEFAULT 7500 +#define SETTING_D_BOOST_MAX_AT_ACCELERATION 278 +#define SETTING_D_BOOST_MAX_AT_ACCELERATION_MIN 1000 +#define SETTING_D_BOOST_MAX_AT_ACCELERATION_MAX 16000 +#define SETTING_D_BOOST_GYRO_DELTA_LPF_HZ_DEFAULT 80 +#define SETTING_D_BOOST_GYRO_DELTA_LPF_HZ 279 +#define SETTING_D_BOOST_GYRO_DELTA_LPF_HZ_MIN 10 +#define SETTING_D_BOOST_GYRO_DELTA_LPF_HZ_MAX 250 +#define SETTING_ANTIGRAVITY_GAIN_DEFAULT 1 +#define SETTING_ANTIGRAVITY_GAIN 280 +#define SETTING_ANTIGRAVITY_GAIN_MIN 1 +#define SETTING_ANTIGRAVITY_GAIN_MAX 20 +#define SETTING_ANTIGRAVITY_ACCELERATOR_DEFAULT 1 +#define SETTING_ANTIGRAVITY_ACCELERATOR 281 +#define SETTING_ANTIGRAVITY_ACCELERATOR_MIN 1 +#define SETTING_ANTIGRAVITY_ACCELERATOR_MAX 20 +#define SETTING_ANTIGRAVITY_CUTOFF_LPF_HZ_DEFAULT 15 +#define SETTING_ANTIGRAVITY_CUTOFF_LPF_HZ 282 +#define SETTING_ANTIGRAVITY_CUTOFF_LPF_HZ_MIN 1 +#define SETTING_ANTIGRAVITY_CUTOFF_LPF_HZ_MAX 30 +#define SETTING_PID_TYPE_DEFAULT 3 +#define SETTING_PID_TYPE 283 +#define SETTING_PID_TYPE_MIN 0 +#define SETTING_PID_TYPE_MAX 0 +#define SETTING_MC_CD_LPF_HZ_DEFAULT 30 +#define SETTING_MC_CD_LPF_HZ 284 +#define SETTING_MC_CD_LPF_HZ_MIN 0 +#define SETTING_MC_CD_LPF_HZ_MAX 200 +#define SETTING_FW_LEVEL_PITCH_TRIM_DEFAULT 0 +#define SETTING_FW_LEVEL_PITCH_TRIM 285 +#define SETTING_FW_LEVEL_PITCH_TRIM_MIN -10 +#define SETTING_FW_LEVEL_PITCH_TRIM_MAX 10 +#define SETTING_SMITH_PREDICTOR_STRENGTH_DEFAULT 0.5f +#define SETTING_SMITH_PREDICTOR_STRENGTH 286 +#define SETTING_SMITH_PREDICTOR_STRENGTH_MIN 0 +#define SETTING_SMITH_PREDICTOR_STRENGTH_MAX 1 +#define SETTING_SMITH_PREDICTOR_DELAY_DEFAULT 0 +#define SETTING_SMITH_PREDICTOR_DELAY 287 +#define SETTING_SMITH_PREDICTOR_DELAY_MIN 0 +#define SETTING_SMITH_PREDICTOR_DELAY_MAX 8 +#define SETTING_SMITH_PREDICTOR_LPF_HZ_DEFAULT 50 +#define SETTING_SMITH_PREDICTOR_LPF_HZ 288 +#define SETTING_SMITH_PREDICTOR_LPF_HZ_MIN 1 +#define SETTING_SMITH_PREDICTOR_LPF_HZ_MAX 500 +#define SETTING_FW_LEVEL_PITCH_GAIN_DEFAULT 5 +#define SETTING_FW_LEVEL_PITCH_GAIN 289 +#define SETTING_FW_LEVEL_PITCH_GAIN_MIN 0 +#define SETTING_FW_LEVEL_PITCH_GAIN_MAX 20 +#define SETTING_FW_AUTOTUNE_MIN_STICK_DEFAULT 50 +#define SETTING_FW_AUTOTUNE_MIN_STICK 290 +#define SETTING_FW_AUTOTUNE_MIN_STICK_MIN 0 +#define SETTING_FW_AUTOTUNE_MIN_STICK_MAX 100 +#define SETTING_FW_AUTOTUNE_RATE_ADJUSTMENT_DEFAULT 2 +#define SETTING_FW_AUTOTUNE_RATE_ADJUSTMENT 291 +#define SETTING_FW_AUTOTUNE_RATE_ADJUSTMENT_MIN 0 +#define SETTING_FW_AUTOTUNE_RATE_ADJUSTMENT_MAX 0 +#define SETTING_FW_AUTOTUNE_MAX_RATE_DEFLECTION_DEFAULT 80 +#define SETTING_FW_AUTOTUNE_MAX_RATE_DEFLECTION 292 +#define SETTING_FW_AUTOTUNE_MAX_RATE_DEFLECTION_MIN 50 +#define SETTING_FW_AUTOTUNE_MAX_RATE_DEFLECTION_MAX 100 +#define SETTING_INAV_AUTO_MAG_DECL_DEFAULT 1 +#define SETTING_INAV_AUTO_MAG_DECL 293 +#define SETTING_INAV_AUTO_MAG_DECL_MIN 0 +#define SETTING_INAV_AUTO_MAG_DECL_MAX 0 +#define SETTING_INAV_GRAVITY_CAL_TOLERANCE_DEFAULT 5 +#define SETTING_INAV_GRAVITY_CAL_TOLERANCE 294 +#define SETTING_INAV_GRAVITY_CAL_TOLERANCE_MIN 0 +#define SETTING_INAV_GRAVITY_CAL_TOLERANCE_MAX 255 +#define SETTING_INAV_USE_GPS_VELNED_DEFAULT 1 +#define SETTING_INAV_USE_GPS_VELNED 295 +#define SETTING_INAV_USE_GPS_VELNED_MIN 0 +#define SETTING_INAV_USE_GPS_VELNED_MAX 0 +#define SETTING_INAV_USE_GPS_NO_BARO_DEFAULT 0 +#define SETTING_INAV_USE_GPS_NO_BARO 296 +#define SETTING_INAV_USE_GPS_NO_BARO_MIN 0 +#define SETTING_INAV_USE_GPS_NO_BARO_MAX 0 +#define SETTING_INAV_ALLOW_DEAD_RECKONING_DEFAULT 0 +#define SETTING_INAV_ALLOW_DEAD_RECKONING 297 +#define SETTING_INAV_ALLOW_DEAD_RECKONING_MIN 0 +#define SETTING_INAV_ALLOW_DEAD_RECKONING_MAX 0 +#define SETTING_INAV_RESET_ALTITUDE_DEFAULT 1 +#define SETTING_INAV_RESET_ALTITUDE 298 +#define SETTING_INAV_RESET_ALTITUDE_MIN 0 +#define SETTING_INAV_RESET_ALTITUDE_MAX 0 +#define SETTING_INAV_RESET_HOME_DEFAULT 1 +#define SETTING_INAV_RESET_HOME 299 +#define SETTING_INAV_RESET_HOME_MIN 0 +#define SETTING_INAV_RESET_HOME_MAX 0 +#define SETTING_INAV_MAX_SURFACE_ALTITUDE_DEFAULT 200 +#define SETTING_INAV_MAX_SURFACE_ALTITUDE 300 +#define SETTING_INAV_MAX_SURFACE_ALTITUDE_MIN 0 +#define SETTING_INAV_MAX_SURFACE_ALTITUDE_MAX 1000 +#define SETTING_INAV_W_Z_SURFACE_P_DEFAULT 3.5f +#define SETTING_INAV_W_Z_SURFACE_P 301 +#define SETTING_INAV_W_Z_SURFACE_P_MIN 0 +#define SETTING_INAV_W_Z_SURFACE_P_MAX 100 +#define SETTING_INAV_W_Z_SURFACE_V_DEFAULT 6.1f +#define SETTING_INAV_W_Z_SURFACE_V 302 +#define SETTING_INAV_W_Z_SURFACE_V_MIN 0 +#define SETTING_INAV_W_Z_SURFACE_V_MAX 100 +#define SETTING_INAV_W_XY_FLOW_P_DEFAULT 1.0f +#define SETTING_INAV_W_XY_FLOW_P 303 +#define SETTING_INAV_W_XY_FLOW_P_MIN 0 +#define SETTING_INAV_W_XY_FLOW_P_MAX 100 +#define SETTING_INAV_W_XY_FLOW_V_DEFAULT 2.0f +#define SETTING_INAV_W_XY_FLOW_V 304 +#define SETTING_INAV_W_XY_FLOW_V_MIN 0 +#define SETTING_INAV_W_XY_FLOW_V_MAX 100 +#define SETTING_INAV_W_Z_BARO_P_DEFAULT 0.35f +#define SETTING_INAV_W_Z_BARO_P 305 +#define SETTING_INAV_W_Z_BARO_P_MIN 0 +#define SETTING_INAV_W_Z_BARO_P_MAX 10 +#define SETTING_INAV_W_Z_GPS_P_DEFAULT 0.2f +#define SETTING_INAV_W_Z_GPS_P 306 +#define SETTING_INAV_W_Z_GPS_P_MIN 0 +#define SETTING_INAV_W_Z_GPS_P_MAX 10 +#define SETTING_INAV_W_Z_GPS_V_DEFAULT 0.1f +#define SETTING_INAV_W_Z_GPS_V 307 +#define SETTING_INAV_W_Z_GPS_V_MIN 0 +#define SETTING_INAV_W_Z_GPS_V_MAX 10 +#define SETTING_INAV_W_XY_GPS_P_DEFAULT 1.0f +#define SETTING_INAV_W_XY_GPS_P 308 +#define SETTING_INAV_W_XY_GPS_P_MIN 0 +#define SETTING_INAV_W_XY_GPS_P_MAX 10 +#define SETTING_INAV_W_XY_GPS_V_DEFAULT 2.0f +#define SETTING_INAV_W_XY_GPS_V 309 +#define SETTING_INAV_W_XY_GPS_V_MIN 0 +#define SETTING_INAV_W_XY_GPS_V_MAX 10 +#define SETTING_INAV_W_Z_RES_V_DEFAULT 0.5f +#define SETTING_INAV_W_Z_RES_V 310 +#define SETTING_INAV_W_Z_RES_V_MIN 0 +#define SETTING_INAV_W_Z_RES_V_MAX 10 +#define SETTING_INAV_W_XY_RES_V_DEFAULT 0.5f +#define SETTING_INAV_W_XY_RES_V 311 +#define SETTING_INAV_W_XY_RES_V_MIN 0 +#define SETTING_INAV_W_XY_RES_V_MAX 10 +#define SETTING_INAV_W_XYZ_ACC_P_DEFAULT 1.0f +#define SETTING_INAV_W_XYZ_ACC_P 312 +#define SETTING_INAV_W_XYZ_ACC_P_MIN 0 +#define SETTING_INAV_W_XYZ_ACC_P_MAX 1 +#define SETTING_INAV_W_ACC_BIAS_DEFAULT 0.01f +#define SETTING_INAV_W_ACC_BIAS 313 +#define SETTING_INAV_W_ACC_BIAS_MIN 0 +#define SETTING_INAV_W_ACC_BIAS_MAX 1 +#define SETTING_INAV_MAX_EPH_EPV_DEFAULT 1000 +#define SETTING_INAV_MAX_EPH_EPV 314 +#define SETTING_INAV_MAX_EPH_EPV_MIN 0 +#define SETTING_INAV_MAX_EPH_EPV_MAX 9999 +#define SETTING_INAV_BARO_EPV_DEFAULT 100 +#define SETTING_INAV_BARO_EPV 315 +#define SETTING_INAV_BARO_EPV_MIN 0 +#define SETTING_INAV_BARO_EPV_MAX 9999 +#define SETTING_NAV_DISARM_ON_LANDING_DEFAULT 0 +#define SETTING_NAV_DISARM_ON_LANDING 316 +#define SETTING_NAV_DISARM_ON_LANDING_MIN 0 +#define SETTING_NAV_DISARM_ON_LANDING_MAX 0 +#define SETTING_NAV_LAND_DETECT_SENSITIVITY_DEFAULT 5 +#define SETTING_NAV_LAND_DETECT_SENSITIVITY 317 +#define SETTING_NAV_LAND_DETECT_SENSITIVITY_MIN 1 +#define SETTING_NAV_LAND_DETECT_SENSITIVITY_MAX 15 +#define SETTING_NAV_USE_MIDTHR_FOR_ALTHOLD_DEFAULT 0 +#define SETTING_NAV_USE_MIDTHR_FOR_ALTHOLD 318 +#define SETTING_NAV_USE_MIDTHR_FOR_ALTHOLD_MIN 0 +#define SETTING_NAV_USE_MIDTHR_FOR_ALTHOLD_MAX 0 +#define SETTING_NAV_EXTRA_ARMING_SAFETY_DEFAULT 0 +#define SETTING_NAV_EXTRA_ARMING_SAFETY 319 +#define SETTING_NAV_EXTRA_ARMING_SAFETY_MIN 0 +#define SETTING_NAV_EXTRA_ARMING_SAFETY_MAX 0 +#define SETTING_NAV_USER_CONTROL_MODE_DEFAULT 0 +#define SETTING_NAV_USER_CONTROL_MODE 320 +#define SETTING_NAV_USER_CONTROL_MODE_MIN 0 +#define SETTING_NAV_USER_CONTROL_MODE_MAX 0 +#define SETTING_NAV_POSITION_TIMEOUT_DEFAULT 5 +#define SETTING_NAV_POSITION_TIMEOUT 321 +#define SETTING_NAV_POSITION_TIMEOUT_MIN 0 +#define SETTING_NAV_POSITION_TIMEOUT_MAX 10 +#define SETTING_NAV_WP_LOAD_ON_BOOT_DEFAULT 0 +#define SETTING_NAV_WP_LOAD_ON_BOOT 322 +#define SETTING_NAV_WP_LOAD_ON_BOOT_MIN 0 +#define SETTING_NAV_WP_LOAD_ON_BOOT_MAX 0 +#define SETTING_NAV_WP_RADIUS_DEFAULT 100 +#define SETTING_NAV_WP_RADIUS 323 +#define SETTING_NAV_WP_RADIUS_MIN 10 +#define SETTING_NAV_WP_RADIUS_MAX 10000 +#define SETTING_NAV_WP_ENFORCE_ALTITUDE_DEFAULT 0 +#define SETTING_NAV_WP_ENFORCE_ALTITUDE 324 +#define SETTING_NAV_WP_ENFORCE_ALTITUDE_MIN 0 +#define SETTING_NAV_WP_ENFORCE_ALTITUDE_MAX 2000 +#define SETTING_NAV_WP_MAX_SAFE_DISTANCE_DEFAULT 100 +#define SETTING_NAV_WP_MAX_SAFE_DISTANCE 325 +#define SETTING_NAV_WP_MAX_SAFE_DISTANCE_MIN 0 +#define SETTING_NAV_WP_MAX_SAFE_DISTANCE_MAX 1500 +#define SETTING_NAV_WP_MISSION_RESTART_DEFAULT 1 +#define SETTING_NAV_WP_MISSION_RESTART 326 +#define SETTING_NAV_WP_MISSION_RESTART_MIN 0 +#define SETTING_NAV_WP_MISSION_RESTART_MAX 0 +#define SETTING_NAV_WP_MULTI_MISSION_INDEX_DEFAULT 1 +#define SETTING_NAV_WP_MULTI_MISSION_INDEX 327 +#define SETTING_NAV_WP_MULTI_MISSION_INDEX_MIN 1 +#define SETTING_NAV_WP_MULTI_MISSION_INDEX_MAX 9 +#define SETTING_NAV_FW_WP_TRACKING_ACCURACY_DEFAULT 0 +#define SETTING_NAV_FW_WP_TRACKING_ACCURACY 328 +#define SETTING_NAV_FW_WP_TRACKING_ACCURACY_MIN 0 +#define SETTING_NAV_FW_WP_TRACKING_ACCURACY_MAX 10 +#define SETTING_NAV_FW_WP_TRACKING_MAX_ANGLE_DEFAULT 60 +#define SETTING_NAV_FW_WP_TRACKING_MAX_ANGLE 329 +#define SETTING_NAV_FW_WP_TRACKING_MAX_ANGLE_MIN 30 +#define SETTING_NAV_FW_WP_TRACKING_MAX_ANGLE_MAX 80 +#define SETTING_NAV_FW_WP_TURN_SMOOTHING_DEFAULT 0 +#define SETTING_NAV_FW_WP_TURN_SMOOTHING 330 +#define SETTING_NAV_FW_WP_TURN_SMOOTHING_MIN 0 +#define SETTING_NAV_FW_WP_TURN_SMOOTHING_MAX 0 +#define SETTING_NAV_AUTO_SPEED_DEFAULT 300 +#define SETTING_NAV_AUTO_SPEED 331 +#define SETTING_NAV_AUTO_SPEED_MIN 10 +#define SETTING_NAV_AUTO_SPEED_MAX 2000 +#define SETTING_NAV_MAX_AUTO_SPEED_DEFAULT 1000 +#define SETTING_NAV_MAX_AUTO_SPEED 332 +#define SETTING_NAV_MAX_AUTO_SPEED_MIN 10 +#define SETTING_NAV_MAX_AUTO_SPEED_MAX 2000 +#define SETTING_NAV_AUTO_CLIMB_RATE_DEFAULT 500 +#define SETTING_NAV_AUTO_CLIMB_RATE 333 +#define SETTING_NAV_AUTO_CLIMB_RATE_MIN 10 +#define SETTING_NAV_AUTO_CLIMB_RATE_MAX 2000 +#define SETTING_NAV_MANUAL_SPEED_DEFAULT 500 +#define SETTING_NAV_MANUAL_SPEED 334 +#define SETTING_NAV_MANUAL_SPEED_MIN 10 +#define SETTING_NAV_MANUAL_SPEED_MAX 2000 +#define SETTING_NAV_MANUAL_CLIMB_RATE_DEFAULT 200 +#define SETTING_NAV_MANUAL_CLIMB_RATE 335 +#define SETTING_NAV_MANUAL_CLIMB_RATE_MIN 10 +#define SETTING_NAV_MANUAL_CLIMB_RATE_MAX 2000 +#define SETTING_NAV_LAND_MINALT_VSPD_DEFAULT 50 +#define SETTING_NAV_LAND_MINALT_VSPD 336 +#define SETTING_NAV_LAND_MINALT_VSPD_MIN 50 +#define SETTING_NAV_LAND_MINALT_VSPD_MAX 500 +#define SETTING_NAV_LAND_MAXALT_VSPD_DEFAULT 200 +#define SETTING_NAV_LAND_MAXALT_VSPD 337 +#define SETTING_NAV_LAND_MAXALT_VSPD_MIN 100 +#define SETTING_NAV_LAND_MAXALT_VSPD_MAX 2000 +#define SETTING_NAV_LAND_SLOWDOWN_MINALT_DEFAULT 500 +#define SETTING_NAV_LAND_SLOWDOWN_MINALT 338 +#define SETTING_NAV_LAND_SLOWDOWN_MINALT_MIN 50 +#define SETTING_NAV_LAND_SLOWDOWN_MINALT_MAX 1000 +#define SETTING_NAV_LAND_SLOWDOWN_MAXALT_DEFAULT 2000 +#define SETTING_NAV_LAND_SLOWDOWN_MAXALT 339 +#define SETTING_NAV_LAND_SLOWDOWN_MAXALT_MIN 500 +#define SETTING_NAV_LAND_SLOWDOWN_MAXALT_MAX 4000 +#define SETTING_NAV_EMERG_LANDING_SPEED_DEFAULT 500 +#define SETTING_NAV_EMERG_LANDING_SPEED 340 +#define SETTING_NAV_EMERG_LANDING_SPEED_MIN 100 +#define SETTING_NAV_EMERG_LANDING_SPEED_MAX 2000 +#define SETTING_NAV_MIN_RTH_DISTANCE_DEFAULT 500 +#define SETTING_NAV_MIN_RTH_DISTANCE 341 +#define SETTING_NAV_MIN_RTH_DISTANCE_MIN 0 +#define SETTING_NAV_MIN_RTH_DISTANCE_MAX 5000 +#define SETTING_NAV_OVERRIDES_MOTOR_STOP_DEFAULT 3 +#define SETTING_NAV_OVERRIDES_MOTOR_STOP 342 +#define SETTING_NAV_OVERRIDES_MOTOR_STOP_MIN 0 +#define SETTING_NAV_OVERRIDES_MOTOR_STOP_MAX 0 +#define SETTING_NAV_FW_SOARING_MOTOR_STOP_DEFAULT 0 +#define SETTING_NAV_FW_SOARING_MOTOR_STOP 343 +#define SETTING_NAV_FW_SOARING_MOTOR_STOP_MIN 0 +#define SETTING_NAV_FW_SOARING_MOTOR_STOP_MAX 0 +#define SETTING_NAV_FW_SOARING_PITCH_DEADBAND_DEFAULT 5 +#define SETTING_NAV_FW_SOARING_PITCH_DEADBAND 344 +#define SETTING_NAV_FW_SOARING_PITCH_DEADBAND_MIN 0 +#define SETTING_NAV_FW_SOARING_PITCH_DEADBAND_MAX 15 +#define SETTING_NAV_RTH_CLIMB_FIRST_DEFAULT 1 +#define SETTING_NAV_RTH_CLIMB_FIRST 345 +#define SETTING_NAV_RTH_CLIMB_FIRST_MIN 0 +#define SETTING_NAV_RTH_CLIMB_FIRST_MAX 0 +#define SETTING_NAV_RTH_CLIMB_FIRST_STAGE_MODE_DEFAULT 0 +#define SETTING_NAV_RTH_CLIMB_FIRST_STAGE_MODE 346 +#define SETTING_NAV_RTH_CLIMB_FIRST_STAGE_MODE_MIN 0 +#define SETTING_NAV_RTH_CLIMB_FIRST_STAGE_MODE_MAX 0 +#define SETTING_NAV_RTH_CLIMB_FIRST_STAGE_ALTITUDE_DEFAULT 0 +#define SETTING_NAV_RTH_CLIMB_FIRST_STAGE_ALTITUDE 347 +#define SETTING_NAV_RTH_CLIMB_FIRST_STAGE_ALTITUDE_MIN 0 +#define SETTING_NAV_RTH_CLIMB_FIRST_STAGE_ALTITUDE_MAX 65000 +#define SETTING_NAV_RTH_CLIMB_IGNORE_EMERG_DEFAULT 0 +#define SETTING_NAV_RTH_CLIMB_IGNORE_EMERG 348 +#define SETTING_NAV_RTH_CLIMB_IGNORE_EMERG_MIN 0 +#define SETTING_NAV_RTH_CLIMB_IGNORE_EMERG_MAX 0 +#define SETTING_NAV_RTH_TAIL_FIRST_DEFAULT 0 +#define SETTING_NAV_RTH_TAIL_FIRST 349 +#define SETTING_NAV_RTH_TAIL_FIRST_MIN 0 +#define SETTING_NAV_RTH_TAIL_FIRST_MAX 0 +#define SETTING_NAV_RTH_ALLOW_LANDING_DEFAULT 1 +#define SETTING_NAV_RTH_ALLOW_LANDING 350 +#define SETTING_NAV_RTH_ALLOW_LANDING_MIN 0 +#define SETTING_NAV_RTH_ALLOW_LANDING_MAX 0 +#define SETTING_NAV_RTH_ALT_MODE_DEFAULT 4 +#define SETTING_NAV_RTH_ALT_MODE 351 +#define SETTING_NAV_RTH_ALT_MODE_MIN 0 +#define SETTING_NAV_RTH_ALT_MODE_MAX 0 +#define SETTING_NAV_RTH_ALT_CONTROL_OVERRIDE_DEFAULT 0 +#define SETTING_NAV_RTH_ALT_CONTROL_OVERRIDE 352 +#define SETTING_NAV_RTH_ALT_CONTROL_OVERRIDE_MIN 0 +#define SETTING_NAV_RTH_ALT_CONTROL_OVERRIDE_MAX 0 +#define SETTING_NAV_RTH_ABORT_THRESHOLD_DEFAULT 50000 +#define SETTING_NAV_RTH_ABORT_THRESHOLD 353 +#define SETTING_NAV_RTH_ABORT_THRESHOLD_MIN 0 +#define SETTING_NAV_RTH_ABORT_THRESHOLD_MAX 65000 +#define SETTING_NAV_MAX_TERRAIN_FOLLOW_ALT_DEFAULT 100 +#define SETTING_NAV_MAX_TERRAIN_FOLLOW_ALT 354 +#define SETTING_NAV_MAX_TERRAIN_FOLLOW_ALT_MIN 0 +#define SETTING_NAV_MAX_TERRAIN_FOLLOW_ALT_MAX 1000 +#define SETTING_NAV_MAX_ALTITUDE_DEFAULT 0 +#define SETTING_NAV_MAX_ALTITUDE 355 +#define SETTING_NAV_MAX_ALTITUDE_MIN 0 +#define SETTING_NAV_MAX_ALTITUDE_MAX 65000 +#define SETTING_NAV_RTH_ALTITUDE_DEFAULT 1000 +#define SETTING_NAV_RTH_ALTITUDE 356 +#define SETTING_NAV_RTH_ALTITUDE_MIN 0 +#define SETTING_NAV_RTH_ALTITUDE_MAX 65000 +#define SETTING_NAV_RTH_HOME_ALTITUDE_DEFAULT 0 +#define SETTING_NAV_RTH_HOME_ALTITUDE 357 +#define SETTING_NAV_RTH_HOME_ALTITUDE_MIN 0 +#define SETTING_NAV_RTH_HOME_ALTITUDE_MAX 65000 +#define SETTING_NAV_RTH_TRACKBACK_MODE_DEFAULT 0 +#define SETTING_NAV_RTH_TRACKBACK_MODE 358 +#define SETTING_NAV_RTH_TRACKBACK_MODE_MIN 0 +#define SETTING_NAV_RTH_TRACKBACK_MODE_MAX 0 +#define SETTING_NAV_RTH_TRACKBACK_DISTANCE_DEFAULT 500 +#define SETTING_NAV_RTH_TRACKBACK_DISTANCE 359 +#define SETTING_NAV_RTH_TRACKBACK_DISTANCE_MIN 50 +#define SETTING_NAV_RTH_TRACKBACK_DISTANCE_MAX 2000 +#define SETTING_SAFEHOME_MAX_DISTANCE_DEFAULT 20000 +#define SETTING_SAFEHOME_MAX_DISTANCE 360 +#define SETTING_SAFEHOME_MAX_DISTANCE_MIN 0 +#define SETTING_SAFEHOME_MAX_DISTANCE_MAX 65000 +#define SETTING_SAFEHOME_USAGE_MODE_DEFAULT 1 +#define SETTING_SAFEHOME_USAGE_MODE 361 +#define SETTING_SAFEHOME_USAGE_MODE_MIN 0 +#define SETTING_SAFEHOME_USAGE_MODE_MAX 0 +#define SETTING_NAV_MISSION_PLANNER_RESET_DEFAULT 1 +#define SETTING_NAV_MISSION_PLANNER_RESET 362 +#define SETTING_NAV_MISSION_PLANNER_RESET_MIN 0 +#define SETTING_NAV_MISSION_PLANNER_RESET_MAX 0 +#define SETTING_NAV_MC_BANK_ANGLE_DEFAULT 30 +#define SETTING_NAV_MC_BANK_ANGLE 363 +#define SETTING_NAV_MC_BANK_ANGLE_MIN 15 +#define SETTING_NAV_MC_BANK_ANGLE_MAX 45 +#define SETTING_NAV_AUTO_DISARM_DELAY_DEFAULT 2000 +#define SETTING_NAV_AUTO_DISARM_DELAY 364 +#define SETTING_NAV_AUTO_DISARM_DELAY_MIN 100 +#define SETTING_NAV_AUTO_DISARM_DELAY_MAX 10000 +#define SETTING_NAV_MC_BRAKING_SPEED_THRESHOLD_DEFAULT 100 +#define SETTING_NAV_MC_BRAKING_SPEED_THRESHOLD 365 +#define SETTING_NAV_MC_BRAKING_SPEED_THRESHOLD_MIN 0 +#define SETTING_NAV_MC_BRAKING_SPEED_THRESHOLD_MAX 1000 +#define SETTING_NAV_MC_BRAKING_DISENGAGE_SPEED_DEFAULT 75 +#define SETTING_NAV_MC_BRAKING_DISENGAGE_SPEED 366 +#define SETTING_NAV_MC_BRAKING_DISENGAGE_SPEED_MIN 0 +#define SETTING_NAV_MC_BRAKING_DISENGAGE_SPEED_MAX 1000 +#define SETTING_NAV_MC_BRAKING_TIMEOUT_DEFAULT 2000 +#define SETTING_NAV_MC_BRAKING_TIMEOUT 367 +#define SETTING_NAV_MC_BRAKING_TIMEOUT_MIN 100 +#define SETTING_NAV_MC_BRAKING_TIMEOUT_MAX 5000 +#define SETTING_NAV_MC_BRAKING_BOOST_FACTOR_DEFAULT 100 +#define SETTING_NAV_MC_BRAKING_BOOST_FACTOR 368 +#define SETTING_NAV_MC_BRAKING_BOOST_FACTOR_MIN 0 +#define SETTING_NAV_MC_BRAKING_BOOST_FACTOR_MAX 200 +#define SETTING_NAV_MC_BRAKING_BOOST_TIMEOUT_DEFAULT 750 +#define SETTING_NAV_MC_BRAKING_BOOST_TIMEOUT 369 +#define SETTING_NAV_MC_BRAKING_BOOST_TIMEOUT_MIN 0 +#define SETTING_NAV_MC_BRAKING_BOOST_TIMEOUT_MAX 5000 +#define SETTING_NAV_MC_BRAKING_BOOST_SPEED_THRESHOLD_DEFAULT 150 +#define SETTING_NAV_MC_BRAKING_BOOST_SPEED_THRESHOLD 370 +#define SETTING_NAV_MC_BRAKING_BOOST_SPEED_THRESHOLD_MIN 100 +#define SETTING_NAV_MC_BRAKING_BOOST_SPEED_THRESHOLD_MAX 1000 +#define SETTING_NAV_MC_BRAKING_BOOST_DISENGAGE_SPEED_DEFAULT 100 +#define SETTING_NAV_MC_BRAKING_BOOST_DISENGAGE_SPEED 371 +#define SETTING_NAV_MC_BRAKING_BOOST_DISENGAGE_SPEED_MIN 0 +#define SETTING_NAV_MC_BRAKING_BOOST_DISENGAGE_SPEED_MAX 1000 +#define SETTING_NAV_MC_BRAKING_BANK_ANGLE_DEFAULT 40 +#define SETTING_NAV_MC_BRAKING_BANK_ANGLE 372 +#define SETTING_NAV_MC_BRAKING_BANK_ANGLE_MIN 15 +#define SETTING_NAV_MC_BRAKING_BANK_ANGLE_MAX 60 +#define SETTING_NAV_MC_POS_DECELERATION_TIME_DEFAULT 120 +#define SETTING_NAV_MC_POS_DECELERATION_TIME 373 +#define SETTING_NAV_MC_POS_DECELERATION_TIME_MIN 0 +#define SETTING_NAV_MC_POS_DECELERATION_TIME_MAX 255 +#define SETTING_NAV_MC_POS_EXPO_DEFAULT 10 +#define SETTING_NAV_MC_POS_EXPO 374 +#define SETTING_NAV_MC_POS_EXPO_MIN 0 +#define SETTING_NAV_MC_POS_EXPO_MAX 255 +#define SETTING_NAV_MC_WP_SLOWDOWN_DEFAULT 1 +#define SETTING_NAV_MC_WP_SLOWDOWN 375 +#define SETTING_NAV_MC_WP_SLOWDOWN_MIN 0 +#define SETTING_NAV_MC_WP_SLOWDOWN_MAX 0 +#define SETTING_NAV_FW_BANK_ANGLE_DEFAULT 35 +#define SETTING_NAV_FW_BANK_ANGLE 376 +#define SETTING_NAV_FW_BANK_ANGLE_MIN 5 +#define SETTING_NAV_FW_BANK_ANGLE_MAX 80 +#define SETTING_NAV_FW_CLIMB_ANGLE_DEFAULT 20 +#define SETTING_NAV_FW_CLIMB_ANGLE 377 +#define SETTING_NAV_FW_CLIMB_ANGLE_MIN 5 +#define SETTING_NAV_FW_CLIMB_ANGLE_MAX 80 +#define SETTING_NAV_FW_DIVE_ANGLE_DEFAULT 15 +#define SETTING_NAV_FW_DIVE_ANGLE 378 +#define SETTING_NAV_FW_DIVE_ANGLE_MIN 5 +#define SETTING_NAV_FW_DIVE_ANGLE_MAX 80 +#define SETTING_NAV_FW_PITCH2THR_SMOOTHING_DEFAULT 6 +#define SETTING_NAV_FW_PITCH2THR_SMOOTHING 379 +#define SETTING_NAV_FW_PITCH2THR_SMOOTHING_MIN 0 +#define SETTING_NAV_FW_PITCH2THR_SMOOTHING_MAX 9 +#define SETTING_FW_MIN_THROTTLE_DOWN_PITCH_DEFAULT 0 +#define SETTING_FW_MIN_THROTTLE_DOWN_PITCH 380 +#define SETTING_FW_MIN_THROTTLE_DOWN_PITCH_MIN 0 +#define SETTING_FW_MIN_THROTTLE_DOWN_PITCH_MAX 450 +#define SETTING_NAV_FW_PITCH2THR_THRESHOLD_DEFAULT 50 +#define SETTING_NAV_FW_PITCH2THR_THRESHOLD 381 +#define SETTING_NAV_FW_PITCH2THR_THRESHOLD_MIN 0 +#define SETTING_NAV_FW_PITCH2THR_THRESHOLD_MAX 900 +#define SETTING_NAV_FW_LOITER_RADIUS_DEFAULT 7500 +#define SETTING_NAV_FW_LOITER_RADIUS 382 +#define SETTING_NAV_FW_LOITER_RADIUS_MIN 0 +#define SETTING_NAV_FW_LOITER_RADIUS_MAX 30000 +#define SETTING_FW_LOITER_DIRECTION_DEFAULT 0 +#define SETTING_FW_LOITER_DIRECTION 383 +#define SETTING_FW_LOITER_DIRECTION_MIN 0 +#define SETTING_FW_LOITER_DIRECTION_MAX 0 +#define SETTING_NAV_FW_CRUISE_SPEED_DEFAULT 0 +#define SETTING_NAV_FW_CRUISE_SPEED 384 +#define SETTING_NAV_FW_CRUISE_SPEED_MIN 0 +#define SETTING_NAV_FW_CRUISE_SPEED_MAX 65535 +#define SETTING_NAV_FW_CONTROL_SMOOTHNESS_DEFAULT 0 +#define SETTING_NAV_FW_CONTROL_SMOOTHNESS 385 +#define SETTING_NAV_FW_CONTROL_SMOOTHNESS_MIN 0 +#define SETTING_NAV_FW_CONTROL_SMOOTHNESS_MAX 9 +#define SETTING_NAV_FW_LAND_DIVE_ANGLE_DEFAULT 2 +#define SETTING_NAV_FW_LAND_DIVE_ANGLE 386 +#define SETTING_NAV_FW_LAND_DIVE_ANGLE_MIN -20 +#define SETTING_NAV_FW_LAND_DIVE_ANGLE_MAX 20 +#define SETTING_NAV_FW_LAUNCH_VELOCITY_DEFAULT 300 +#define SETTING_NAV_FW_LAUNCH_VELOCITY 387 +#define SETTING_NAV_FW_LAUNCH_VELOCITY_MIN 100 +#define SETTING_NAV_FW_LAUNCH_VELOCITY_MAX 10000 +#define SETTING_NAV_FW_LAUNCH_ACCEL_DEFAULT 1863 +#define SETTING_NAV_FW_LAUNCH_ACCEL 388 +#define SETTING_NAV_FW_LAUNCH_ACCEL_MIN 1000 +#define SETTING_NAV_FW_LAUNCH_ACCEL_MAX 20000 +#define SETTING_NAV_FW_LAUNCH_MAX_ANGLE_DEFAULT 45 +#define SETTING_NAV_FW_LAUNCH_MAX_ANGLE 389 +#define SETTING_NAV_FW_LAUNCH_MAX_ANGLE_MIN 5 +#define SETTING_NAV_FW_LAUNCH_MAX_ANGLE_MAX 180 +#define SETTING_NAV_FW_LAUNCH_DETECT_TIME_DEFAULT 40 +#define SETTING_NAV_FW_LAUNCH_DETECT_TIME 390 +#define SETTING_NAV_FW_LAUNCH_DETECT_TIME_MIN 10 +#define SETTING_NAV_FW_LAUNCH_DETECT_TIME_MAX 1000 +#define SETTING_NAV_FW_LAUNCH_IDLE_MOTOR_DELAY_DEFAULT 0 +#define SETTING_NAV_FW_LAUNCH_IDLE_MOTOR_DELAY 391 +#define SETTING_NAV_FW_LAUNCH_IDLE_MOTOR_DELAY_MIN 0 +#define SETTING_NAV_FW_LAUNCH_IDLE_MOTOR_DELAY_MAX 60000 +#define SETTING_NAV_FW_LAUNCH_MOTOR_DELAY_DEFAULT 500 +#define SETTING_NAV_FW_LAUNCH_MOTOR_DELAY 392 +#define SETTING_NAV_FW_LAUNCH_MOTOR_DELAY_MIN 0 +#define SETTING_NAV_FW_LAUNCH_MOTOR_DELAY_MAX 5000 +#define SETTING_NAV_FW_LAUNCH_SPINUP_TIME_DEFAULT 100 +#define SETTING_NAV_FW_LAUNCH_SPINUP_TIME 393 +#define SETTING_NAV_FW_LAUNCH_SPINUP_TIME_MIN 0 +#define SETTING_NAV_FW_LAUNCH_SPINUP_TIME_MAX 1000 +#define SETTING_NAV_FW_LAUNCH_END_TIME_DEFAULT 3000 +#define SETTING_NAV_FW_LAUNCH_END_TIME 394 +#define SETTING_NAV_FW_LAUNCH_END_TIME_MIN 0 +#define SETTING_NAV_FW_LAUNCH_END_TIME_MAX 5000 +#define SETTING_NAV_FW_LAUNCH_MIN_TIME_DEFAULT 0 +#define SETTING_NAV_FW_LAUNCH_MIN_TIME 395 +#define SETTING_NAV_FW_LAUNCH_MIN_TIME_MIN 0 +#define SETTING_NAV_FW_LAUNCH_MIN_TIME_MAX 60000 +#define SETTING_NAV_FW_LAUNCH_TIMEOUT_DEFAULT 5000 +#define SETTING_NAV_FW_LAUNCH_TIMEOUT 396 +#define SETTING_NAV_FW_LAUNCH_TIMEOUT_MIN 0 +#define SETTING_NAV_FW_LAUNCH_TIMEOUT_MAX 60000 +#define SETTING_NAV_FW_LAUNCH_MAX_ALTITUDE_DEFAULT 0 +#define SETTING_NAV_FW_LAUNCH_MAX_ALTITUDE 397 +#define SETTING_NAV_FW_LAUNCH_MAX_ALTITUDE_MIN 0 +#define SETTING_NAV_FW_LAUNCH_MAX_ALTITUDE_MAX 60000 +#define SETTING_NAV_FW_LAUNCH_CLIMB_ANGLE_DEFAULT 18 +#define SETTING_NAV_FW_LAUNCH_CLIMB_ANGLE 398 +#define SETTING_NAV_FW_LAUNCH_CLIMB_ANGLE_MIN 5 +#define SETTING_NAV_FW_LAUNCH_CLIMB_ANGLE_MAX 45 +#define SETTING_NAV_FW_LAUNCH_MANUAL_THROTTLE_DEFAULT 0 +#define SETTING_NAV_FW_LAUNCH_MANUAL_THROTTLE 399 +#define SETTING_NAV_FW_LAUNCH_MANUAL_THROTTLE_MIN 0 +#define SETTING_NAV_FW_LAUNCH_MANUAL_THROTTLE_MAX 0 +#define SETTING_NAV_FW_LAUNCH_ABORT_DEADBAND_DEFAULT 100 +#define SETTING_NAV_FW_LAUNCH_ABORT_DEADBAND 400 +#define SETTING_NAV_FW_LAUNCH_ABORT_DEADBAND_MIN 2 +#define SETTING_NAV_FW_LAUNCH_ABORT_DEADBAND_MAX 250 +#define SETTING_NAV_FW_CRUISE_YAW_RATE_DEFAULT 20 +#define SETTING_NAV_FW_CRUISE_YAW_RATE 401 +#define SETTING_NAV_FW_CRUISE_YAW_RATE_MIN 0 +#define SETTING_NAV_FW_CRUISE_YAW_RATE_MAX 60 +#define SETTING_NAV_FW_ALLOW_MANUAL_THR_INCREASE_DEFAULT 0 +#define SETTING_NAV_FW_ALLOW_MANUAL_THR_INCREASE 402 +#define SETTING_NAV_FW_ALLOW_MANUAL_THR_INCREASE_MIN 0 +#define SETTING_NAV_FW_ALLOW_MANUAL_THR_INCREASE_MAX 0 +#define SETTING_NAV_USE_FW_YAW_CONTROL_DEFAULT 0 +#define SETTING_NAV_USE_FW_YAW_CONTROL 403 +#define SETTING_NAV_USE_FW_YAW_CONTROL_MIN 0 +#define SETTING_NAV_USE_FW_YAW_CONTROL_MAX 0 +#define SETTING_NAV_FW_YAW_DEADBAND_DEFAULT 0 +#define SETTING_NAV_FW_YAW_DEADBAND 404 +#define SETTING_NAV_FW_YAW_DEADBAND_MIN 0 +#define SETTING_NAV_FW_YAW_DEADBAND_MAX 90 +#define SETTING_OSD_TELEMETRY_DEFAULT 0 +#define SETTING_OSD_TELEMETRY 405 +#define SETTING_OSD_TELEMETRY_MIN 0 +#define SETTING_OSD_TELEMETRY_MAX 0 +#define SETTING_OSD_VIDEO_SYSTEM_DEFAULT 0 +#define SETTING_OSD_VIDEO_SYSTEM 406 +#define SETTING_OSD_VIDEO_SYSTEM_MIN 0 +#define SETTING_OSD_VIDEO_SYSTEM_MAX 0 +#define SETTING_OSD_ROW_SHIFTDOWN_DEFAULT 0 +#define SETTING_OSD_ROW_SHIFTDOWN 407 +#define SETTING_OSD_ROW_SHIFTDOWN_MIN 0 +#define SETTING_OSD_ROW_SHIFTDOWN_MAX 1 +#define SETTING_OSD_UNITS_DEFAULT 1 +#define SETTING_OSD_UNITS 408 +#define SETTING_OSD_UNITS_MIN 0 +#define SETTING_OSD_UNITS_MAX 0 +#define SETTING_OSD_STATS_ENERGY_UNIT_DEFAULT 0 +#define SETTING_OSD_STATS_ENERGY_UNIT 409 +#define SETTING_OSD_STATS_ENERGY_UNIT_MIN 0 +#define SETTING_OSD_STATS_ENERGY_UNIT_MAX 0 +#define SETTING_OSD_STATS_MIN_VOLTAGE_UNIT_DEFAULT 0 +#define SETTING_OSD_STATS_MIN_VOLTAGE_UNIT 410 +#define SETTING_OSD_STATS_MIN_VOLTAGE_UNIT_MIN 0 +#define SETTING_OSD_STATS_MIN_VOLTAGE_UNIT_MAX 0 +#define SETTING_OSD_STATS_PAGE_AUTO_SWAP_TIME_DEFAULT 3 +#define SETTING_OSD_STATS_PAGE_AUTO_SWAP_TIME 411 +#define SETTING_OSD_STATS_PAGE_AUTO_SWAP_TIME_MIN 0 +#define SETTING_OSD_STATS_PAGE_AUTO_SWAP_TIME_MAX 10 +#define SETTING_OSD_RSSI_ALARM_DEFAULT 20 +#define SETTING_OSD_RSSI_ALARM 412 +#define SETTING_OSD_RSSI_ALARM_MIN 0 +#define SETTING_OSD_RSSI_ALARM_MAX 100 +#define SETTING_OSD_TIME_ALARM_DEFAULT 10 +#define SETTING_OSD_TIME_ALARM 413 +#define SETTING_OSD_TIME_ALARM_MIN 0 +#define SETTING_OSD_TIME_ALARM_MAX 600 +#define SETTING_OSD_ALT_ALARM_DEFAULT 100 +#define SETTING_OSD_ALT_ALARM 414 +#define SETTING_OSD_ALT_ALARM_MIN 0 +#define SETTING_OSD_ALT_ALARM_MAX 10000 +#define SETTING_OSD_DIST_ALARM_DEFAULT 1000 +#define SETTING_OSD_DIST_ALARM 415 +#define SETTING_OSD_DIST_ALARM_MIN 0 +#define SETTING_OSD_DIST_ALARM_MAX 50000 +#define SETTING_OSD_NEG_ALT_ALARM_DEFAULT 5 +#define SETTING_OSD_NEG_ALT_ALARM 416 +#define SETTING_OSD_NEG_ALT_ALARM_MIN 0 +#define SETTING_OSD_NEG_ALT_ALARM_MAX 10000 +#define SETTING_OSD_CURRENT_ALARM_DEFAULT 0 +#define SETTING_OSD_CURRENT_ALARM 417 +#define SETTING_OSD_CURRENT_ALARM_MIN 0 +#define SETTING_OSD_CURRENT_ALARM_MAX 255 +#define SETTING_OSD_GFORCE_ALARM_DEFAULT 5 +#define SETTING_OSD_GFORCE_ALARM 418 +#define SETTING_OSD_GFORCE_ALARM_MIN 0 +#define SETTING_OSD_GFORCE_ALARM_MAX 20 +#define SETTING_OSD_GFORCE_AXIS_ALARM_MIN_DEFAULT -5 +#define SETTING_OSD_GFORCE_AXIS_ALARM_MIN 419 +#define SETTING_OSD_GFORCE_AXIS_ALARM_MIN_MIN -20 +#define SETTING_OSD_GFORCE_AXIS_ALARM_MIN_MAX 20 +#define SETTING_OSD_GFORCE_AXIS_ALARM_MAX_DEFAULT 5 +#define SETTING_OSD_GFORCE_AXIS_ALARM_MAX 420 +#define SETTING_OSD_GFORCE_AXIS_ALARM_MAX_MIN -20 +#define SETTING_OSD_GFORCE_AXIS_ALARM_MAX_MAX 20 +#define SETTING_OSD_IMU_TEMP_ALARM_MIN_DEFAULT -200 +#define SETTING_OSD_IMU_TEMP_ALARM_MIN 421 +#define SETTING_OSD_IMU_TEMP_ALARM_MIN_MIN -550 +#define SETTING_OSD_IMU_TEMP_ALARM_MIN_MAX 1250 +#define SETTING_OSD_IMU_TEMP_ALARM_MAX_DEFAULT 600 +#define SETTING_OSD_IMU_TEMP_ALARM_MAX 422 +#define SETTING_OSD_IMU_TEMP_ALARM_MAX_MIN -550 +#define SETTING_OSD_IMU_TEMP_ALARM_MAX_MAX 1250 +#define SETTING_OSD_ESC_TEMP_ALARM_MAX_DEFAULT 900 +#define SETTING_OSD_ESC_TEMP_ALARM_MAX 423 +#define SETTING_OSD_ESC_TEMP_ALARM_MAX_MIN -550 +#define SETTING_OSD_ESC_TEMP_ALARM_MAX_MAX 1500 +#define SETTING_OSD_ESC_TEMP_ALARM_MIN_DEFAULT -200 +#define SETTING_OSD_ESC_TEMP_ALARM_MIN 424 +#define SETTING_OSD_ESC_TEMP_ALARM_MIN_MIN -550 +#define SETTING_OSD_ESC_TEMP_ALARM_MIN_MAX 1500 +#define SETTING_OSD_BARO_TEMP_ALARM_MIN_DEFAULT -200 +#define SETTING_OSD_BARO_TEMP_ALARM_MIN 425 +#define SETTING_OSD_BARO_TEMP_ALARM_MIN_MIN -550 +#define SETTING_OSD_BARO_TEMP_ALARM_MIN_MAX 1250 +#define SETTING_OSD_BARO_TEMP_ALARM_MAX_DEFAULT 600 +#define SETTING_OSD_BARO_TEMP_ALARM_MAX 426 +#define SETTING_OSD_BARO_TEMP_ALARM_MAX_MIN -550 +#define SETTING_OSD_BARO_TEMP_ALARM_MAX_MAX 1250 +#define SETTING_OSD_SNR_ALARM_DEFAULT 4 +#define SETTING_OSD_SNR_ALARM 427 +#define SETTING_OSD_SNR_ALARM_MIN -20 +#define SETTING_OSD_SNR_ALARM_MAX 10 +#define SETTING_OSD_LINK_QUALITY_ALARM_DEFAULT 70 +#define SETTING_OSD_LINK_QUALITY_ALARM 428 +#define SETTING_OSD_LINK_QUALITY_ALARM_MIN 0 +#define SETTING_OSD_LINK_QUALITY_ALARM_MAX 100 +#define SETTING_OSD_RSSI_DBM_ALARM_DEFAULT 0 +#define SETTING_OSD_RSSI_DBM_ALARM 429 +#define SETTING_OSD_RSSI_DBM_ALARM_MIN -130 +#define SETTING_OSD_RSSI_DBM_ALARM_MAX 0 +#define SETTING_OSD_RSSI_DBM_MAX_DEFAULT -30 +#define SETTING_OSD_RSSI_DBM_MAX 430 +#define SETTING_OSD_RSSI_DBM_MAX_MIN -50 +#define SETTING_OSD_RSSI_DBM_MAX_MAX 0 +#define SETTING_OSD_RSSI_DBM_MIN_DEFAULT -120 +#define SETTING_OSD_RSSI_DBM_MIN 431 +#define SETTING_OSD_RSSI_DBM_MIN_MIN -130 +#define SETTING_OSD_RSSI_DBM_MIN_MAX 0 +#define SETTING_OSD_TEMP_LABEL_ALIGN_DEFAULT 0 +#define SETTING_OSD_TEMP_LABEL_ALIGN 432 +#define SETTING_OSD_TEMP_LABEL_ALIGN_MIN 0 +#define SETTING_OSD_TEMP_LABEL_ALIGN_MAX 0 +#define SETTING_OSD_AIRSPEED_ALARM_MIN_DEFAULT 0 +#define SETTING_OSD_AIRSPEED_ALARM_MIN 433 +#define SETTING_OSD_AIRSPEED_ALARM_MIN_MIN 0 +#define SETTING_OSD_AIRSPEED_ALARM_MIN_MAX 27000 +#define SETTING_OSD_AIRSPEED_ALARM_MAX_DEFAULT 0 +#define SETTING_OSD_AIRSPEED_ALARM_MAX 434 +#define SETTING_OSD_AIRSPEED_ALARM_MAX_MIN 0 +#define SETTING_OSD_AIRSPEED_ALARM_MAX_MAX 27000 +#define SETTING_OSD_AHI_REVERSE_ROLL_DEFAULT 0 +#define SETTING_OSD_AHI_REVERSE_ROLL 435 +#define SETTING_OSD_AHI_REVERSE_ROLL_MIN 0 +#define SETTING_OSD_AHI_REVERSE_ROLL_MAX 0 +#define SETTING_OSD_AHI_MAX_PITCH_DEFAULT 20 +#define SETTING_OSD_AHI_MAX_PITCH 436 +#define SETTING_OSD_AHI_MAX_PITCH_MIN 10 +#define SETTING_OSD_AHI_MAX_PITCH_MAX 90 +#define SETTING_OSD_CROSSHAIRS_STYLE_DEFAULT 0 +#define SETTING_OSD_CROSSHAIRS_STYLE 437 +#define SETTING_OSD_CROSSHAIRS_STYLE_MIN 0 +#define SETTING_OSD_CROSSHAIRS_STYLE_MAX 0 +#define SETTING_OSD_CRSF_LQ_FORMAT_DEFAULT 0 +#define SETTING_OSD_CRSF_LQ_FORMAT 438 +#define SETTING_OSD_CRSF_LQ_FORMAT_MIN 0 +#define SETTING_OSD_CRSF_LQ_FORMAT_MAX 0 +#define SETTING_OSD_HORIZON_OFFSET_DEFAULT 0 +#define SETTING_OSD_HORIZON_OFFSET 439 +#define SETTING_OSD_HORIZON_OFFSET_MIN -2 +#define SETTING_OSD_HORIZON_OFFSET_MAX 2 +#define SETTING_OSD_CAMERA_UPTILT_DEFAULT 0 +#define SETTING_OSD_CAMERA_UPTILT 440 +#define SETTING_OSD_CAMERA_UPTILT_MIN -40 +#define SETTING_OSD_CAMERA_UPTILT_MAX 80 +#define SETTING_OSD_AHI_CAMERA_UPTILT_COMP_DEFAULT 0 +#define SETTING_OSD_AHI_CAMERA_UPTILT_COMP 441 +#define SETTING_OSD_AHI_CAMERA_UPTILT_COMP_MIN 0 +#define SETTING_OSD_AHI_CAMERA_UPTILT_COMP_MAX 0 +#define SETTING_OSD_CAMERA_FOV_H_DEFAULT 135 +#define SETTING_OSD_CAMERA_FOV_H 442 +#define SETTING_OSD_CAMERA_FOV_H_MIN 60 +#define SETTING_OSD_CAMERA_FOV_H_MAX 150 +#define SETTING_OSD_CAMERA_FOV_V_DEFAULT 85 +#define SETTING_OSD_CAMERA_FOV_V 443 +#define SETTING_OSD_CAMERA_FOV_V_MIN 30 +#define SETTING_OSD_CAMERA_FOV_V_MAX 120 +#define SETTING_OSD_HUD_MARGIN_H_DEFAULT 3 +#define SETTING_OSD_HUD_MARGIN_H 444 +#define SETTING_OSD_HUD_MARGIN_H_MIN 0 +#define SETTING_OSD_HUD_MARGIN_H_MAX 4 +#define SETTING_OSD_HUD_MARGIN_V_DEFAULT 3 +#define SETTING_OSD_HUD_MARGIN_V 445 +#define SETTING_OSD_HUD_MARGIN_V_MIN 1 +#define SETTING_OSD_HUD_MARGIN_V_MAX 3 +#define SETTING_OSD_HUD_HOMING_DEFAULT 0 +#define SETTING_OSD_HUD_HOMING 446 +#define SETTING_OSD_HUD_HOMING_MIN 0 +#define SETTING_OSD_HUD_HOMING_MAX 0 +#define SETTING_OSD_HUD_HOMEPOINT_DEFAULT 0 +#define SETTING_OSD_HUD_HOMEPOINT 447 +#define SETTING_OSD_HUD_HOMEPOINT_MIN 0 +#define SETTING_OSD_HUD_HOMEPOINT_MAX 0 +#define SETTING_OSD_HUD_RADAR_DISP_DEFAULT 0 +#define SETTING_OSD_HUD_RADAR_DISP 448 +#define SETTING_OSD_HUD_RADAR_DISP_MIN 0 +#define SETTING_OSD_HUD_RADAR_DISP_MAX 4 +#define SETTING_OSD_HUD_RADAR_RANGE_MIN_DEFAULT 3 +#define SETTING_OSD_HUD_RADAR_RANGE_MIN 449 +#define SETTING_OSD_HUD_RADAR_RANGE_MIN_MIN 1 +#define SETTING_OSD_HUD_RADAR_RANGE_MIN_MAX 30 +#define SETTING_OSD_HUD_RADAR_RANGE_MAX_DEFAULT 4000 +#define SETTING_OSD_HUD_RADAR_RANGE_MAX 450 +#define SETTING_OSD_HUD_RADAR_RANGE_MAX_MIN 100 +#define SETTING_OSD_HUD_RADAR_RANGE_MAX_MAX 9990 +#define SETTING_OSD_HUD_RADAR_ALT_DIFFERENCE_DISPLAY_TIME_DEFAULT 3 +#define SETTING_OSD_HUD_RADAR_ALT_DIFFERENCE_DISPLAY_TIME 451 +#define SETTING_OSD_HUD_RADAR_ALT_DIFFERENCE_DISPLAY_TIME_MIN 0 +#define SETTING_OSD_HUD_RADAR_ALT_DIFFERENCE_DISPLAY_TIME_MAX 10 +#define SETTING_OSD_HUD_RADAR_DISTANCE_DISPLAY_TIME_DEFAULT 3 +#define SETTING_OSD_HUD_RADAR_DISTANCE_DISPLAY_TIME 452 +#define SETTING_OSD_HUD_RADAR_DISTANCE_DISPLAY_TIME_MIN 1 +#define SETTING_OSD_HUD_RADAR_DISTANCE_DISPLAY_TIME_MAX 10 +#define SETTING_OSD_HUD_WP_DISP_DEFAULT 0 +#define SETTING_OSD_HUD_WP_DISP 453 +#define SETTING_OSD_HUD_WP_DISP_MIN 0 +#define SETTING_OSD_HUD_WP_DISP_MAX 3 +#define SETTING_OSD_LEFT_SIDEBAR_SCROLL_DEFAULT 0 +#define SETTING_OSD_LEFT_SIDEBAR_SCROLL 454 +#define SETTING_OSD_LEFT_SIDEBAR_SCROLL_MIN 0 +#define SETTING_OSD_LEFT_SIDEBAR_SCROLL_MAX 0 +#define SETTING_OSD_RIGHT_SIDEBAR_SCROLL_DEFAULT 0 +#define SETTING_OSD_RIGHT_SIDEBAR_SCROLL 455 +#define SETTING_OSD_RIGHT_SIDEBAR_SCROLL_MIN 0 +#define SETTING_OSD_RIGHT_SIDEBAR_SCROLL_MAX 0 +#define SETTING_OSD_SIDEBAR_SCROLL_ARROWS_DEFAULT 0 +#define SETTING_OSD_SIDEBAR_SCROLL_ARROWS 456 +#define SETTING_OSD_SIDEBAR_SCROLL_ARROWS_MIN 0 +#define SETTING_OSD_SIDEBAR_SCROLL_ARROWS_MAX 0 +#define SETTING_OSD_MAIN_VOLTAGE_DECIMALS_DEFAULT 1 +#define SETTING_OSD_MAIN_VOLTAGE_DECIMALS 457 +#define SETTING_OSD_MAIN_VOLTAGE_DECIMALS_MIN 1 +#define SETTING_OSD_MAIN_VOLTAGE_DECIMALS_MAX 2 +#define SETTING_OSD_COORDINATE_DIGITS_DEFAULT 9 +#define SETTING_OSD_COORDINATE_DIGITS 458 +#define SETTING_OSD_COORDINATE_DIGITS_MIN 8 +#define SETTING_OSD_COORDINATE_DIGITS_MAX 11 +#define SETTING_OSD_ESTIMATIONS_WIND_COMPENSATION_DEFAULT 1 +#define SETTING_OSD_ESTIMATIONS_WIND_COMPENSATION 459 +#define SETTING_OSD_ESTIMATIONS_WIND_COMPENSATION_MIN 0 +#define SETTING_OSD_ESTIMATIONS_WIND_COMPENSATION_MAX 0 +#define SETTING_OSD_FAILSAFE_SWITCH_LAYOUT_DEFAULT 0 +#define SETTING_OSD_FAILSAFE_SWITCH_LAYOUT 460 +#define SETTING_OSD_FAILSAFE_SWITCH_LAYOUT_MIN 0 +#define SETTING_OSD_FAILSAFE_SWITCH_LAYOUT_MAX 0 +#define SETTING_OSD_PLUS_CODE_DIGITS_DEFAULT 11 +#define SETTING_OSD_PLUS_CODE_DIGITS 461 +#define SETTING_OSD_PLUS_CODE_DIGITS_MIN 10 +#define SETTING_OSD_PLUS_CODE_DIGITS_MAX 13 +#define SETTING_OSD_PLUS_CODE_SHORT_DEFAULT 0 +#define SETTING_OSD_PLUS_CODE_SHORT 462 +#define SETTING_OSD_PLUS_CODE_SHORT_MIN 0 +#define SETTING_OSD_PLUS_CODE_SHORT_MAX 0 +#define SETTING_OSD_AHI_STYLE_DEFAULT 0 +#define SETTING_OSD_AHI_STYLE 463 +#define SETTING_OSD_AHI_STYLE_MIN 0 +#define SETTING_OSD_AHI_STYLE_MAX 0 +#define SETTING_OSD_FORCE_GRID_DEFAULT 0 +#define SETTING_OSD_FORCE_GRID 464 +#define SETTING_OSD_FORCE_GRID_MIN 0 +#define SETTING_OSD_FORCE_GRID_MAX 0 +#define SETTING_OSD_AHI_BORDERED_DEFAULT 0 +#define SETTING_OSD_AHI_BORDERED 465 +#define SETTING_OSD_AHI_BORDERED_MIN 0 +#define SETTING_OSD_AHI_BORDERED_MAX 0 +#define SETTING_OSD_AHI_WIDTH_DEFAULT 132 +#define SETTING_OSD_AHI_WIDTH 466 +#define SETTING_OSD_AHI_WIDTH_MIN 0 +#define SETTING_OSD_AHI_WIDTH_MAX 255 +#define SETTING_OSD_AHI_HEIGHT_DEFAULT 162 +#define SETTING_OSD_AHI_HEIGHT 467 +#define SETTING_OSD_AHI_HEIGHT_MIN 0 +#define SETTING_OSD_AHI_HEIGHT_MAX 255 +#define SETTING_OSD_AHI_VERTICAL_OFFSET_DEFAULT -18 +#define SETTING_OSD_AHI_VERTICAL_OFFSET 468 +#define SETTING_OSD_AHI_VERTICAL_OFFSET_MIN -128 +#define SETTING_OSD_AHI_VERTICAL_OFFSET_MAX 127 +#define SETTING_OSD_SIDEBAR_HORIZONTAL_OFFSET_DEFAULT 0 +#define SETTING_OSD_SIDEBAR_HORIZONTAL_OFFSET 469 +#define SETTING_OSD_SIDEBAR_HORIZONTAL_OFFSET_MIN -128 +#define SETTING_OSD_SIDEBAR_HORIZONTAL_OFFSET_MAX 127 +#define SETTING_OSD_LEFT_SIDEBAR_SCROLL_STEP_DEFAULT 0 +#define SETTING_OSD_LEFT_SIDEBAR_SCROLL_STEP 470 +#define SETTING_OSD_LEFT_SIDEBAR_SCROLL_STEP_MIN 0 +#define SETTING_OSD_LEFT_SIDEBAR_SCROLL_STEP_MAX 255 +#define SETTING_OSD_RIGHT_SIDEBAR_SCROLL_STEP_DEFAULT 0 +#define SETTING_OSD_RIGHT_SIDEBAR_SCROLL_STEP 471 +#define SETTING_OSD_RIGHT_SIDEBAR_SCROLL_STEP_MIN 0 +#define SETTING_OSD_RIGHT_SIDEBAR_SCROLL_STEP_MAX 255 +#define SETTING_OSD_SIDEBAR_HEIGHT_DEFAULT 3 +#define SETTING_OSD_SIDEBAR_HEIGHT 472 +#define SETTING_OSD_SIDEBAR_HEIGHT_MIN 0 +#define SETTING_OSD_SIDEBAR_HEIGHT_MAX 5 +#define SETTING_OSD_AHI_PITCH_INTERVAL_DEFAULT 0 +#define SETTING_OSD_AHI_PITCH_INTERVAL 473 +#define SETTING_OSD_AHI_PITCH_INTERVAL_MIN 0 +#define SETTING_OSD_AHI_PITCH_INTERVAL_MAX 30 +#define SETTING_OSD_HOME_POSITION_ARM_SCREEN_DEFAULT 1 +#define SETTING_OSD_HOME_POSITION_ARM_SCREEN 474 +#define SETTING_OSD_HOME_POSITION_ARM_SCREEN_MIN 0 +#define SETTING_OSD_HOME_POSITION_ARM_SCREEN_MAX 0 +#define SETTING_OSD_PAN_SERVO_INDEX_DEFAULT 0 +#define SETTING_OSD_PAN_SERVO_INDEX 475 +#define SETTING_OSD_PAN_SERVO_INDEX_MIN 0 +#define SETTING_OSD_PAN_SERVO_INDEX_MAX 10 +#define SETTING_OSD_PAN_SERVO_PWM2CENTIDEG_DEFAULT 0 +#define SETTING_OSD_PAN_SERVO_PWM2CENTIDEG 476 +#define SETTING_OSD_PAN_SERVO_PWM2CENTIDEG_MIN -36 +#define SETTING_OSD_PAN_SERVO_PWM2CENTIDEG_MAX 36 +#define SETTING_OSD_ESC_RPM_PRECISION_DEFAULT 3 +#define SETTING_OSD_ESC_RPM_PRECISION 477 +#define SETTING_OSD_ESC_RPM_PRECISION_MIN 3 +#define SETTING_OSD_ESC_RPM_PRECISION_MAX 6 +#define SETTING_OSD_MAH_USED_PRECISION_DEFAULT 4 +#define SETTING_OSD_MAH_USED_PRECISION 478 +#define SETTING_OSD_MAH_USED_PRECISION_MIN 4 +#define SETTING_OSD_MAH_USED_PRECISION_MAX 6 +#define SETTING_OSD_SWITCH_INDICATOR_ZERO_NAME_DEFAULT { 70, 76, 65, 80, 0 } +#define SETTING_OSD_SWITCH_INDICATOR_ZERO_NAME 479 +#define SETTING_OSD_SWITCH_INDICATOR_ZERO_NAME_MIN 0 +#define SETTING_OSD_SWITCH_INDICATOR_ZERO_NAME_MAX 5 +#define SETTING_OSD_SWITCH_INDICATOR_ONE_NAME_DEFAULT { 71, 69, 65, 82, 0 } +#define SETTING_OSD_SWITCH_INDICATOR_ONE_NAME 480 +#define SETTING_OSD_SWITCH_INDICATOR_ONE_NAME_MIN 0 +#define SETTING_OSD_SWITCH_INDICATOR_ONE_NAME_MAX 5 +#define SETTING_OSD_SWITCH_INDICATOR_TWO_NAME_DEFAULT { 67, 65, 77, 0 } +#define SETTING_OSD_SWITCH_INDICATOR_TWO_NAME 481 +#define SETTING_OSD_SWITCH_INDICATOR_TWO_NAME_MIN 0 +#define SETTING_OSD_SWITCH_INDICATOR_TWO_NAME_MAX 5 +#define SETTING_OSD_SWITCH_INDICATOR_THREE_NAME_DEFAULT { 76, 73, 71, 84, 0 } +#define SETTING_OSD_SWITCH_INDICATOR_THREE_NAME 482 +#define SETTING_OSD_SWITCH_INDICATOR_THREE_NAME_MIN 0 +#define SETTING_OSD_SWITCH_INDICATOR_THREE_NAME_MAX 5 +#define SETTING_OSD_SWITCH_INDICATOR_ZERO_CHANNEL_DEFAULT 5 +#define SETTING_OSD_SWITCH_INDICATOR_ZERO_CHANNEL 483 +#define SETTING_OSD_SWITCH_INDICATOR_ZERO_CHANNEL_MIN 5 +#define SETTING_OSD_SWITCH_INDICATOR_ZERO_CHANNEL_MAX 18 +#define SETTING_OSD_SWITCH_INDICATOR_ONE_CHANNEL_DEFAULT 5 +#define SETTING_OSD_SWITCH_INDICATOR_ONE_CHANNEL 484 +#define SETTING_OSD_SWITCH_INDICATOR_ONE_CHANNEL_MIN 5 +#define SETTING_OSD_SWITCH_INDICATOR_ONE_CHANNEL_MAX 18 +#define SETTING_OSD_SWITCH_INDICATOR_TWO_CHANNEL_DEFAULT 5 +#define SETTING_OSD_SWITCH_INDICATOR_TWO_CHANNEL 485 +#define SETTING_OSD_SWITCH_INDICATOR_TWO_CHANNEL_MIN 5 +#define SETTING_OSD_SWITCH_INDICATOR_TWO_CHANNEL_MAX 18 +#define SETTING_OSD_SWITCH_INDICATOR_THREE_CHANNEL_DEFAULT 5 +#define SETTING_OSD_SWITCH_INDICATOR_THREE_CHANNEL 486 +#define SETTING_OSD_SWITCH_INDICATOR_THREE_CHANNEL_MIN 5 +#define SETTING_OSD_SWITCH_INDICATOR_THREE_CHANNEL_MAX 18 +#define SETTING_OSD_SWITCH_INDICATORS_ALIGN_LEFT_DEFAULT 1 +#define SETTING_OSD_SWITCH_INDICATORS_ALIGN_LEFT 487 +#define SETTING_OSD_SWITCH_INDICATORS_ALIGN_LEFT_MIN 0 +#define SETTING_OSD_SWITCH_INDICATORS_ALIGN_LEFT_MAX 0 +#define SETTING_OSD_SYSTEM_MSG_DISPLAY_TIME_DEFAULT 1000 +#define SETTING_OSD_SYSTEM_MSG_DISPLAY_TIME 488 +#define SETTING_OSD_SYSTEM_MSG_DISPLAY_TIME_MIN 500 +#define SETTING_OSD_SYSTEM_MSG_DISPLAY_TIME_MAX 5000 +#define SETTING_OSD_SPEED_SOURCE_DEFAULT 0 +#define SETTING_OSD_SPEED_SOURCE 489 +#define SETTING_OSD_SPEED_SOURCE_MIN 0 +#define SETTING_OSD_SPEED_SOURCE_MAX 0 +#define SETTING_DEBUG_MODE_DEFAULT 0 +#define SETTING_DEBUG_MODE 490 +#define SETTING_DEBUG_MODE_MIN 0 +#define SETTING_DEBUG_MODE_MAX 0 +#define SETTING_THROTTLE_TILT_COMP_STR_DEFAULT 0 +#define SETTING_THROTTLE_TILT_COMP_STR 491 +#define SETTING_THROTTLE_TILT_COMP_STR_MIN 0 +#define SETTING_THROTTLE_TILT_COMP_STR_MAX 100 +#define SETTING_NAME_DEFAULT { 0 } +#define SETTING_NAME 492 +#define SETTING_NAME_MIN 0 +#define SETTING_NAME_MAX 16 +#define SETTING_MODE_RANGE_LOGIC_OPERATOR_DEFAULT 0 +#define SETTING_MODE_RANGE_LOGIC_OPERATOR 493 +#define SETTING_MODE_RANGE_LOGIC_OPERATOR_MIN 0 +#define SETTING_MODE_RANGE_LOGIC_OPERATOR_MAX 0 +#define SETTING_STATS_DEFAULT 0 +#define SETTING_STATS 494 +#define SETTING_STATS_MIN 0 +#define SETTING_STATS_MAX 0 +#define SETTING_STATS_TOTAL_TIME_DEFAULT 0 +#define SETTING_STATS_TOTAL_TIME 495 +#define SETTING_STATS_TOTAL_TIME_MIN 0 +#define SETTING_STATS_TOTAL_TIME_MAX 2147483647 +#define SETTING_STATS_TOTAL_DIST_DEFAULT 0 +#define SETTING_STATS_TOTAL_DIST 496 +#define SETTING_STATS_TOTAL_DIST_MIN 0 +#define SETTING_STATS_TOTAL_DIST_MAX 2147483647 +#define SETTING_STATS_TOTAL_ENERGY_DEFAULT 0 +#define SETTING_STATS_TOTAL_ENERGY 497 +#define SETTING_STATS_TOTAL_ENERGY_MIN 0 +#define SETTING_STATS_TOTAL_ENERGY_MAX 2147483647 +#define SETTING_TZ_OFFSET_DEFAULT 0 +#define SETTING_TZ_OFFSET 498 +#define SETTING_TZ_OFFSET_MIN -1440 +#define SETTING_TZ_OFFSET_MAX 1440 +#define SETTING_TZ_AUTOMATIC_DST_DEFAULT 0 +#define SETTING_TZ_AUTOMATIC_DST 499 +#define SETTING_TZ_AUTOMATIC_DST_MIN 0 +#define SETTING_TZ_AUTOMATIC_DST_MAX 0 +#define SETTING_DISPLAY_FORCE_SW_BLINK_DEFAULT 0 +#define SETTING_DISPLAY_FORCE_SW_BLINK 500 +#define SETTING_DISPLAY_FORCE_SW_BLINK_MIN 0 +#define SETTING_DISPLAY_FORCE_SW_BLINK_MAX 0 +#define SETTING_LOG_LEVEL_DEFAULT 0 +#define SETTING_LOG_LEVEL 501 +#define SETTING_LOG_LEVEL_MIN 0 +#define SETTING_LOG_LEVEL_MAX 0 +#define SETTING_LOG_TOPICS_DEFAULT 0 +#define SETTING_LOG_TOPICS 502 +#define SETTING_LOG_TOPICS_MIN 0 +#define SETTING_LOG_TOPICS_MAX 4294967295 +#define SETTING_SMARTPORT_MASTER_HALFDUPLEX_DEFAULT 1 +#define SETTING_SMARTPORT_MASTER_HALFDUPLEX 503 +#define SETTING_SMARTPORT_MASTER_HALFDUPLEX_MIN 0 +#define SETTING_SMARTPORT_MASTER_HALFDUPLEX_MAX 0 +#define SETTING_SMARTPORT_MASTER_INVERTED_DEFAULT 0 +#define SETTING_SMARTPORT_MASTER_INVERTED 504 +#define SETTING_SMARTPORT_MASTER_INVERTED_MIN 0 +#define SETTING_SMARTPORT_MASTER_INVERTED_MAX 0 +#define SETTING_DJI_WORKAROUNDS_DEFAULT 1 +#define SETTING_DJI_WORKAROUNDS 505 +#define SETTING_DJI_WORKAROUNDS_MIN 0 +#define SETTING_DJI_WORKAROUNDS_MAX 255 +#define SETTING_DJI_USE_NAME_FOR_MESSAGES_DEFAULT 1 +#define SETTING_DJI_USE_NAME_FOR_MESSAGES 506 +#define SETTING_DJI_USE_NAME_FOR_MESSAGES_MIN 0 +#define SETTING_DJI_USE_NAME_FOR_MESSAGES_MAX 0 +#define SETTING_DJI_ESC_TEMP_SOURCE_DEFAULT 0 +#define SETTING_DJI_ESC_TEMP_SOURCE 507 +#define SETTING_DJI_ESC_TEMP_SOURCE_MIN 0 +#define SETTING_DJI_ESC_TEMP_SOURCE_MAX 0 +#define SETTING_DJI_MESSAGE_SPEED_SOURCE_DEFAULT 1 +#define SETTING_DJI_MESSAGE_SPEED_SOURCE 508 +#define SETTING_DJI_MESSAGE_SPEED_SOURCE_MIN 0 +#define SETTING_DJI_MESSAGE_SPEED_SOURCE_MAX 0 +#define SETTING_DJI_RSSI_SOURCE_DEFAULT 0 +#define SETTING_DJI_RSSI_SOURCE 509 +#define SETTING_DJI_RSSI_SOURCE_MIN 0 +#define SETTING_DJI_RSSI_SOURCE_MAX 0 +#define SETTING_DJI_USE_ADJUSTMENTS_DEFAULT 0 +#define SETTING_DJI_USE_ADJUSTMENTS 510 +#define SETTING_DJI_USE_ADJUSTMENTS_MIN 0 +#define SETTING_DJI_USE_ADJUSTMENTS_MAX 0 +#define SETTING_DJI_CN_ALTERNATING_DURATION_DEFAULT 30 +#define SETTING_DJI_CN_ALTERNATING_DURATION 511 +#define SETTING_DJI_CN_ALTERNATING_DURATION_MIN 1 +#define SETTING_DJI_CN_ALTERNATING_DURATION_MAX 150 +#define SETTING_DSHOT_BEEPER_ENABLED_DEFAULT 1 +#define SETTING_DSHOT_BEEPER_ENABLED 512 +#define SETTING_DSHOT_BEEPER_ENABLED_MIN 0 +#define SETTING_DSHOT_BEEPER_ENABLED_MAX 0 +#define SETTING_DSHOT_BEEPER_TONE_DEFAULT 1 +#define SETTING_DSHOT_BEEPER_TONE 513 +#define SETTING_DSHOT_BEEPER_TONE_MIN 1 +#define SETTING_DSHOT_BEEPER_TONE_MAX 5 +#define SETTING_BEEPER_PWM_MODE_DEFAULT 0 +#define SETTING_BEEPER_PWM_MODE 514 +#define SETTING_BEEPER_PWM_MODE_MIN 0 +#define SETTING_BEEPER_PWM_MODE_MAX 0 +#define SETTING_LIMIT_PI_P_DEFAULT 100 +#define SETTING_LIMIT_PI_P 515 +#define SETTING_LIMIT_PI_P_MIN 0 +#define SETTING_LIMIT_PI_P_MAX 10000 +#define SETTING_LIMIT_PI_I_DEFAULT 100 +#define SETTING_LIMIT_PI_I 516 +#define SETTING_LIMIT_PI_I_MIN 0 +#define SETTING_LIMIT_PI_I_MAX 10000 +#define SETTING_LIMIT_ATTN_FILTER_CUTOFF_DEFAULT 1.2f +#define SETTING_LIMIT_ATTN_FILTER_CUTOFF 517 +#define SETTING_LIMIT_ATTN_FILTER_CUTOFF_MIN 0 +#define SETTING_LIMIT_ATTN_FILTER_CUTOFF_MAX 100 diff --git a/src/main/flight/imu.c b/src/main/flight/imu.c index bdd69ba6d2..89467545f8 100644 --- a/src/main/flight/imu.c +++ b/src/main/flight/imu.c @@ -111,6 +111,8 @@ STATIC_FASTRAM pt1Filter_t GPS3DspeedFilter; FASTRAM bool gpsHeadingInitialized; +FASTRAM bool imuUpdated = false; + PG_REGISTER_WITH_RESET_TEMPLATE(imuConfig_t, imuConfig, PG_IMU_CONFIG, 2); PG_RESET_TEMPLATE(imuConfig_t, imuConfig, @@ -362,7 +364,7 @@ static void imuMahonyAHRSupdate(float dt, const fpVector3_t * gyroBF, const fpVe vectorNormalize(&vMag, &vMag); #ifdef USE_SIMULATOR - if (ARMING_FLAG(SIMULATOR_MODE)) { + if (ARMING_FLAG(SIMULATOR_MODE_HITL) || ARMING_FLAG(SIMULATOR_MODE_SITL)) { imuSetMagneticDeclination(0); } #endif @@ -511,7 +513,7 @@ static void imuMahonyAHRSupdate(float dt, const fpVector3_t * gyroBF, const fpVe STATIC_UNIT_TESTED void imuUpdateEulerAngles(void) { #ifdef USE_SIMULATOR - if (ARMING_FLAG(SIMULATOR_MODE) && !SIMULATOR_HAS_OPTION(HITL_USE_IMU)) { + if ((ARMING_FLAG(SIMULATOR_MODE_HITL) && !SIMULATOR_HAS_OPTION(HITL_USE_IMU)) || (ARMING_FLAG(SIMULATOR_MODE_SITL) && imuUpdated)) { imuComputeQuaternionFromRPY(attitude.values.roll, attitude.values.pitch, attitude.values.yaw); imuComputeRotationMatrix(); } @@ -633,7 +635,7 @@ static void imuCalculateTurnRateacceleration(fpVector3_t *vEstcentrifugalAccelBF { //fixed wing only static float lastspeed = -1.0f; - float currentspeed; + float currentspeed = 0; if (isGPSTrustworthy()){ //first speed choice is gps currentspeed = GPS3DspeedFiltered; @@ -824,3 +826,15 @@ float calculateCosTiltAngle(void) { return 1.0f - 2.0f * sq(orientation.q1) - 2.0f * sq(orientation.q2); } + +#if defined(SITL_BUILD) || defined (USE_SIMULATOR) + +void imuSetAttitudeRPY(int16_t roll, int16_t pitch, int16_t yaw) +{ + attitude.values.roll = roll; + attitude.values.pitch = pitch; + attitude.values.yaw = yaw; + imuUpdated = true; +} +#endif + diff --git a/src/main/flight/imu.h b/src/main/flight/imu.h index f438cc079f..a3b87e6736 100644 --- a/src/main/flight/imu.h +++ b/src/main/flight/imu.h @@ -86,3 +86,7 @@ void imuTransformVectorBodyToEarth(fpVector3_t * v); void imuTransformVectorEarthToBody(fpVector3_t * v); void imuInit(void); + +#if defined(SITL_BUILD) +void imuSetAttitudeRPY(int16_t roll, int16_t pitch, int16_t yaw); +#endif diff --git a/src/main/flight/kalman.c b/src/main/flight/kalman.c index 6bc869aef8..5ec003859c 100755 --- a/src/main/flight/kalman.c +++ b/src/main/flight/kalman.c @@ -23,7 +23,11 @@ FILE_COMPILE_FOR_SPEED #include +#if !defined(SITL_BUILD) #include "arm_math.h" +#else +#include +#endif #include "kalman.h" #include "build/debug.h" @@ -93,8 +97,13 @@ static void updateAxisVariance(kalman_t *kalmanState, float rate) kalmanState->axisMean = kalmanState->axisSumMean * kalmanState->inverseN; kalmanState->axisVar = kalmanState->axisSumVar * kalmanState->inverseN; +#if !defined(SITL_BUILD) float squirt; arm_sqrt_f32(kalmanState->axisVar, &squirt); +#else + float squirt = sqrtf(kalmanState->axisVar); +#endif + kalmanState->r = squirt * VARIANCE_SCALE; } diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index c06fc5bb46..4e3c5e18df 100644 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -340,6 +340,7 @@ static void applyTurtleModeToMotors(void) { void FAST_CODE writeMotors(void) { +#if !defined(SITL_BUILD) for (int i = 0; i < motorCount; i++) { uint16_t motorValue; @@ -422,6 +423,7 @@ void FAST_CODE writeMotors(void) pwmWriteMotor(i, motorValue); } +#endif } void writeAllMotors(int16_t mc) @@ -442,7 +444,10 @@ void stopMotors(void) void stopPwmAllMotors(void) { +#if !defined(SITL_BUILD) pwmShutdownPulsesForAllMotors(motorCount); +#endif + } static int getReversibleMotorsThrottleDeadband(void) diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c index 5f2194faba..5212d191e4 100755 --- a/src/main/flight/servos.c +++ b/src/main/flight/servos.c @@ -223,7 +223,8 @@ static void filterServos(void) void writeServos(void) { filterServos(); - + +#if !defined(SITL_BUILD) int servoIndex = 0; bool zeroServoValue = false; @@ -241,6 +242,7 @@ void writeServos(void) pwmWriteServo(servoIndex++, servo[i]); } } +#endif } void servoMixer(float dT) @@ -573,7 +575,7 @@ void processContinuousServoAutotrim(const float dT) void processServoAutotrim(const float dT) { #ifdef USE_SIMULATOR - if (ARMING_FLAG(SIMULATOR_MODE)) { + if (ARMING_FLAG(SIMULATOR_MODE_HITL)) { return; } #endif diff --git a/src/main/io/gps.c b/src/main/io/gps.c index 042286c238..85418c7c2d 100755 --- a/src/main/io/gps.c +++ b/src/main/io/gps.c @@ -103,6 +103,13 @@ static gpsProviderDescriptor_t gpsProviders[GPS_PROVIDER_COUNT] = { #else { false, 0, NULL, NULL }, #endif + +#ifdef USE_GPS_FAKE + {true, 0, &gpsFakeRestart, &gpsFakeHandle}, +#else + { false, 0, NULL, NULL }, +#endif + }; PG_REGISTER_WITH_RESET_TEMPLATE(gpsConfig_t, gpsConfig, PG_GPS_CONFIG, 2); @@ -251,76 +258,6 @@ void gpsInit(void) gpsSetState(GPS_INITIALIZING); } -#ifdef USE_FAKE_GPS -static bool gpsFakeGPSUpdate(void) -{ -#define FAKE_GPS_INITIAL_LAT 509102311 -#define FAKE_GPS_INITIAL_LON -15349744 -#define FAKE_GPS_GROUND_ARMED_SPEED 350 // In cm/s -#define FAKE_GPS_GROUND_UNARMED_SPEED 0 -#define FAKE_GPS_GROUND_COURSE_DECIDEGREES 300 //30deg - - // Each degree in latitude corresponds to 111km. - // Each degree in longitude at the equator is 111km, - // going down to zero as latitude gets close to 90º. - // We approximate it linearly. - - static int32_t lat = FAKE_GPS_INITIAL_LAT; - static int32_t lon = FAKE_GPS_INITIAL_LON; - - timeMs_t now = millis(); - uint32_t delta = now - gpsState.lastMessageMs; - if (delta > 100) { - int32_t speed = ARMING_FLAG(ARMED) ? FAKE_GPS_GROUND_ARMED_SPEED : FAKE_GPS_GROUND_UNARMED_SPEED; - speed = speed * sin_approx((now % 1000) / 1000.f * M_PIf) * +speed; - int32_t cmDelta = speed * (delta / 1000.0f); - int32_t latCmDelta = cmDelta * cos_approx(DECIDEGREES_TO_RADIANS(FAKE_GPS_GROUND_COURSE_DECIDEGREES)); - int32_t lonCmDelta = cmDelta * sin_approx(DECIDEGREES_TO_RADIANS(FAKE_GPS_GROUND_COURSE_DECIDEGREES)); - int32_t latDelta = ceilf((float)latCmDelta / (111 * 1000 * 100 / 1e7)); - int32_t lonDelta = ceilf((float)lonCmDelta / (111 * 1000 * 100 / 1e7)); - if (speed > 0 && latDelta == 0 && lonDelta == 0) { - return false; - } - lat += latDelta; - lon += lonDelta; - gpsSol.fixType = GPS_FIX_3D; - gpsSol.numSat = 6; - gpsSol.llh.lat = lat; - gpsSol.llh.lon = lon; - gpsSol.llh.alt = 0; - gpsSol.groundSpeed = speed; - gpsSol.groundCourse = FAKE_GPS_GROUND_COURSE_DECIDEGREES; - gpsSol.velNED[X] = speed * cos_approx(DECIDEGREES_TO_RADIANS(FAKE_GPS_GROUND_COURSE_DECIDEGREES)); - gpsSol.velNED[Y] = speed * sin_approx(DECIDEGREES_TO_RADIANS(FAKE_GPS_GROUND_COURSE_DECIDEGREES)); - gpsSol.velNED[Z] = 0; - gpsSol.flags.validVelNE = true; - gpsSol.flags.validVelD = true; - gpsSol.flags.validEPE = true; - gpsSol.flags.validTime = true; - gpsSol.eph = 100; - gpsSol.epv = 100; - gpsSol.time.year = 1983; - gpsSol.time.month = 1; - gpsSol.time.day = 1; - gpsSol.time.hours = 3; - gpsSol.time.minutes = 15; - gpsSol.time.seconds = 42; - - ENABLE_STATE(GPS_FIX); - sensorsSet(SENSOR_GPS); - gpsUpdateTime(); - onNewGPSData(); - - gpsSetProtocolTimeout(gpsState.baseTimeoutMs); - - gpsSetState(GPS_RUNNING); - gpsSol.flags.gpsHeartbeat = !gpsSol.flags.gpsHeartbeat; - return true; - } - return false; -} -#endif - uint16_t gpsConstrainEPE(uint32_t epe) { return (epe > 9999) ? 9999 : epe; // max 99.99m error @@ -348,16 +285,13 @@ bool gpsUpdate(void) } #ifdef USE_SIMULATOR - if (ARMING_FLAG(SIMULATOR_MODE)) { + if (ARMING_FLAG(SIMULATOR_MODE_HITL)) { gpsUpdateTime(); gpsSetState(GPS_RUNNING); sensorsSet(SENSOR_GPS); return gpsSol.flags.hasNewData; } #endif -#ifdef USE_FAKE_GPS - return gpsFakeGPSUpdate(); -#else // Assume that we don't have new data this run gpsSol.flags.hasNewData = false; @@ -403,7 +337,6 @@ bool gpsUpdate(void) } return gpsSol.flags.hasNewData; -#endif } void gpsEnablePassthrough(serialPort_t *gpsPassthroughPort) diff --git a/src/main/io/gps.h b/src/main/io/gps.h index e887dae254..92241c9560 100755 --- a/src/main/io/gps.h +++ b/src/main/io/gps.h @@ -18,6 +18,7 @@ #pragma once #include +#include #include "config/parameter_group.h" @@ -36,6 +37,7 @@ typedef enum { GPS_UBLOX, GPS_UBLOX7PLUS, GPS_MSP, + GPS_FAKE, GPS_PROVIDER_COUNT } gpsProvider_e; @@ -162,3 +164,18 @@ bool isGPSHeadingValid(void); struct serialPort_s; void gpsEnablePassthrough(struct serialPort_s *gpsPassthroughPort); void mspGPSReceiveNewData(const uint8_t * bufferPtr); + +#if defined(USE_GPS_FAKE) +void gpsFakeSet( + gpsFixType_e fixType, + uint8_t numSat, + int32_t lat, + int32_t lon, + int32_t alt, + int16_t groundSpeed, + int16_t groundCourse, + int16_t velNED_X, + int16_t velNED_Y, + int16_t velNED_Z, + time_t time); +#endif diff --git a/src/main/io/gps_fake.c b/src/main/io/gps_fake.c new file mode 100644 index 0000000000..e056ed5a3f --- /dev/null +++ b/src/main/io/gps_fake.c @@ -0,0 +1,98 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#include +#include +#include +#include +#include +#include + +#include "platform.h" +#include "build/build_config.h" + +#if defined(USE_GPS_FAKE) + +#include "common/axis.h" + +#include "io/gps.h" +#include "io/gps_private.h" + +void gpsFakeRestart(void) +{ + // NOP +} + +void gpsFakeHandle(void) +{ + gpsProcessNewSolutionData(); +} + +void gpsFakeSet( + gpsFixType_e fixType, + uint8_t numSat, + int32_t lat, + int32_t lon, + int32_t alt, + int16_t groundSpeed, + int16_t groundCourse, + int16_t velNED_X, + int16_t velNED_Y, + int16_t velNED_Z, + time_t time) +{ + gpsSol.fixType = fixType; + gpsSol.hdop = gpsSol.fixType == GPS_NO_FIX ? 9999 : 100; + gpsSol.numSat = numSat; + + gpsSol.llh.lat = lat; + gpsSol.llh.lon = lon; + gpsSol.llh.alt = alt; + gpsSol.groundSpeed = groundSpeed; + gpsSol.groundCourse = groundCourse; + gpsSol.velNED[X] = velNED_X; + gpsSol.velNED[Y] = velNED_Y; + gpsSol.velNED[Z] = velNED_Z; + gpsSol.eph = 100; + gpsSol.epv = 100; + gpsSol.flags.validVelNE = true; + gpsSol.flags.validVelD = true; + gpsSol.flags.validEPE = true; + gpsSol.flags.hasNewData = true; + + if (time) { + struct tm* gTime = gmtime(&time); + + gpsSol.time.year = (uint16_t)(gTime->tm_year + 1900); + gpsSol.time.month = (uint16_t)(gTime->tm_mon + 1); + gpsSol.time.day = (uint8_t)gTime->tm_mday; + gpsSol.time.hours = (uint8_t)gTime->tm_hour; + gpsSol.time.minutes = (uint8_t)gTime->tm_min; + gpsSol.time.seconds = (uint8_t)gTime->tm_sec; + gpsSol.time.millis = 0; + gpsSol.flags.validTime = gpsSol.fixType >= 3; + } +} + +#endif \ No newline at end of file diff --git a/src/main/io/gps_private.h b/src/main/io/gps_private.h index fd35d8540f..6e9abc72ff 100755 --- a/src/main/io/gps_private.h +++ b/src/main/io/gps_private.h @@ -78,4 +78,10 @@ extern void gpsHandleNMEA(void); extern void gpsRestartMSP(void); extern void gpsHandleMSP(void); +#if defined(USE_GPS_FAKE) +extern void gpsFakeRestart(void); +extern void gpsFakeHandle(void); +#endif + + #endif diff --git a/src/main/io/osd.c b/src/main/io/osd.c index eed14a2764..ca7d172d19 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -654,7 +654,7 @@ static uint16_t osdGetCrsfLQ(void) { int16_t statsLQ = rxLinkStatistics.uplinkLQ; int16_t scaledLQ = scaleRange(constrain(statsLQ, 0, 100), 0, 100, 170, 300); - int16_t displayedLQ; + int16_t displayedLQ = 0; switch (osdConfig()->crsf_lq_format) { case OSD_CRSF_LQ_TYPE1: displayedLQ = statsLQ; @@ -741,7 +741,7 @@ static void osdFormatCoordinate(char *buff, char sym, int32_t val) // longitude maximum integer width is 4 (-180). int integerDigits = tfp_sprintf(buff + 1, (integerPart == 0 && val < 0) ? "-%d" : "%d", (int)integerPart); // We can show up to 7 digits in decimalPart. - int32_t decimalPart = abs(val % GPS_DEGREES_DIVIDER); + int32_t decimalPart = abs(val % (int)GPS_DEGREES_DIVIDER); STATIC_ASSERT(GPS_DEGREES_DIVIDER == 1e7, adjust_max_decimal_digits); int decimalDigits; if (!isBfCompatibleVideoSystem(osdConfig())) { @@ -896,7 +896,9 @@ static const char * osdArmingDisabledReasonMessage(void) FALLTHROUGH; case ARMED: FALLTHROUGH; - case SIMULATOR_MODE: + case SIMULATOR_MODE_HITL: + FALLTHROUGH; + case SIMULATOR_MODE_SITL: FALLTHROUGH; case WAS_EVER_ARMED: break; diff --git a/src/main/io/osd_dji_hd.c b/src/main/io/osd_dji_hd.c index 074a23cd47..294a5fd5c2 100644 --- a/src/main/io/osd_dji_hd.c +++ b/src/main/io/osd_dji_hd.c @@ -537,7 +537,9 @@ static char * osdArmingDisabledReasonMessage(void) FALLTHROUGH; case ARMED: FALLTHROUGH; - case SIMULATOR_MODE: + case SIMULATOR_MODE_HITL: + FALLTHROUGH; + case SIMULATOR_MODE_SITL: FALLTHROUGH; case WAS_EVER_ARMED: break; diff --git a/src/main/io/serial.c b/src/main/io/serial.c index 3ca560cf30..35b71e12b3 100644 --- a/src/main/io/serial.c +++ b/src/main/io/serial.c @@ -40,6 +40,10 @@ #include "drivers/serial_uart.h" #endif +#if defined(SITL_BUILD) +#include "drivers/serial_tcp.h" +#endif + #include "drivers/light_led.h" #if defined(USE_VCP) @@ -328,6 +332,13 @@ bool doesConfigurationUsePort(serialPortIdentifier_e identifier) return candidate != NULL && candidate->functionMask; } +#if defined(SITL_BUILD) +serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, void *rxCallbackData, uint32_t baudRate, portMode_t mode, portOptions_t options) +{ + return tcpOpen(USARTx, callback, rxCallbackData, baudRate, mode, options); +} +#endif + serialPort_t *openSerialPort( serialPortIdentifier_e identifier, serialPortFunction_e function, diff --git a/src/main/io/vtx.c b/src/main/io/vtx.c index c7891ce6bd..495554e93a 100644 --- a/src/main/io/vtx.c +++ b/src/main/io/vtx.c @@ -22,6 +22,7 @@ #include #include "platform.h" +#if defined(USE_VTX_CONTROL) #include "common/maths.h" #include "common/time.h" @@ -194,3 +195,5 @@ void vtxUpdate(timeUs_t currentTimeUs) currentSchedule = (currentSchedule + 1) % VTX_PARAM_COUNT; } } + +#endif diff --git a/src/main/main.c b/src/main/main.c index 7a46b485d7..c002fbab25 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -53,8 +53,14 @@ static void processLoopback(void) #endif } +#if defined(SITL_BUILD) +int main(int argc, char *argv[]) +{ + parseArguments(argc, argv); +#else int main(void) { +#endif init(); loopbackInit(); diff --git a/src/main/navigation/navigation_pos_estimator.c b/src/main/navigation/navigation_pos_estimator.c index d9aaef2842..57443ebffd 100755 --- a/src/main/navigation/navigation_pos_estimator.c +++ b/src/main/navigation/navigation_pos_estimator.c @@ -446,7 +446,7 @@ static void updateIMUTopic(timeUs_t currentTimeUs) /* If calibration is incomplete - report zero acceleration */ if (gravityCalibrationComplete()) { #ifdef USE_SIMULATOR - if (ARMING_FLAG(SIMULATOR_MODE)) { + if (ARMING_FLAG(SIMULATOR_MODE_HITL) || ARMING_FLAG(SIMULATOR_MODE_SITL)) { posEstimator.imu.calibratedGravityCMSS = GRAVITY_CMSS; } #endif diff --git a/src/main/programming/logic_condition.c b/src/main/programming/logic_condition.c index ff50a317d7..95e76eb774 100644 --- a/src/main/programming/logic_condition.c +++ b/src/main/programming/logic_condition.c @@ -93,7 +93,9 @@ static int logicConditionCompute( uint8_t lcIndex ) { int temporaryValue; +#if defined(USE_VTX_CONTROL) vtxDeviceCapability_t vtxDeviceCapability; +#endif switch (operation) { @@ -284,7 +286,8 @@ static int logicConditionCompute( break; case LOGIC_CONDITION_SET_VTX_POWER_LEVEL: -#if defined(USE_VTX_SMARTAUDIO) || defined(USE_VTX_TRAMP) +#if defined(USE_VTX_CONTROL) +#if(defined(USE_VTX_SMARTAUDIO) || defined(USE_VTX_TRAMP)) if ( logicConditionValuesByType[LOGIC_CONDITION_SET_VTX_POWER_LEVEL] != operandA && vtxCommonGetDeviceCapability(vtxCommonDevice(), &vtxDeviceCapability) @@ -324,7 +327,7 @@ static int logicConditionCompute( return false; } break; - +#endif case LOGIC_CONDITION_INVERT_ROLL: LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_ROLL); return true; diff --git a/src/main/rx/fport.c b/src/main/rx/fport.c index 79b07766b3..b859390c0f 100644 --- a/src/main/rx/fport.c +++ b/src/main/rx/fport.c @@ -36,8 +36,8 @@ FILE_COMPILE_FOR_SPEED #ifdef USE_TELEMETRY #include "telemetry/telemetry.h" -#include "telemetry/smartport.h" #endif +#include "telemetry/smartport.h" #include "rx/frsky_crc.h" #include "rx/rx.h" diff --git a/src/main/sensors/acceleration.c b/src/main/sensors/acceleration.c index 45be068a39..ed125f36c3 100644 --- a/src/main/sensors/acceleration.c +++ b/src/main/sensors/acceleration.c @@ -504,7 +504,7 @@ float accGetMeasuredMaxG(void) void accUpdate(void) { #ifdef USE_SIMULATOR - if (ARMING_FLAG(SIMULATOR_MODE)) { + if (ARMING_FLAG(SIMULATOR_MODE_HITL)) { //output: acc.accADCf //unused: acc.dev.ADCRaw[], acc.accClipCount, acc.accVibeSq[] return; @@ -513,15 +513,20 @@ void accUpdate(void) if (!acc.dev.readFn(&acc.dev)) { return; } - for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { accADC[axis] = acc.dev.ADCRaw[axis]; DEBUG_SET(DEBUG_ACC, axis, accADC[axis]); } - performAcclerationCalibration(); + if (!ARMING_FLAG(SIMULATOR_MODE_SITL)) { + performAcclerationCalibration(); - applyAccelerationZero(&accelerometerConfig()->accZero, &accelerometerConfig()->accGain); + applyAccelerationZero(&accelerometerConfig()->accZero, &accelerometerConfig()->accGain); + applyAccelerationZero(&accelerometerConfig()->accZero, &accelerometerConfig()->accGain); + applyAccelerationZero(&accelerometerConfig()->accZero, &accelerometerConfig()->accGain); + applyAccelerationZero(&accelerometerConfig()->accZero, &accelerometerConfig()->accGain); + applyAccelerationZero(&accelerometerConfig()->accZero, &accelerometerConfig()->accGain); + } applySensorAlignment(accADC, accADC, acc.dev.accAlign); applyBoardAlignment(accADC); @@ -599,8 +604,9 @@ bool accIsClipped(void) void accSetCalibrationValues(void) { - if ((accelerometerConfig()->accZero.raw[X] == 0) && (accelerometerConfig()->accZero.raw[Y] == 0) && (accelerometerConfig()->accZero.raw[Z] == 0) && - (accelerometerConfig()->accGain.raw[X] == 4096) && (accelerometerConfig()->accGain.raw[Y] == 4096) &&(accelerometerConfig()->accGain.raw[Z] == 4096)) { + if (!ARMING_FLAG(SIMULATOR_MODE_SITL) && + ((accelerometerConfig()->accZero.raw[X] == 0) && (accelerometerConfig()->accZero.raw[Y] == 0) && (accelerometerConfig()->accZero.raw[Z] == 0) && + (accelerometerConfig()->accGain.raw[X] == 4096) && (accelerometerConfig()->accGain.raw[Y] == 4096) &&(accelerometerConfig()->accGain.raw[Z] == 4096))) { DISABLE_STATE(ACCELEROMETER_CALIBRATED); } else { diff --git a/src/main/sensors/barometer.c b/src/main/sensors/barometer.c index ac229de7d4..b28d266d7b 100644 --- a/src/main/sensors/barometer.c +++ b/src/main/sensors/barometer.c @@ -275,7 +275,7 @@ uint32_t baroUpdate(void) baro.dev.start_ut(&baro.dev); } #ifdef USE_SIMULATOR - if (!ARMING_FLAG(SIMULATOR_MODE)) { + if (!ARMING_FLAG(SIMULATOR_MODE_HITL)) { //output: baro.baroPressure, baro.baroTemperature baro.dev.calculate(&baro.dev, &baro.baroPressure, &baro.baroTemperature); } @@ -293,7 +293,7 @@ static float pressureToAltitude(const float pressure) return (1.0f - powf(pressure / 101325.0f, 0.190295f)) * 4433000.0f; } -static float altitudeToPressure(const float altCm) +float altitudeToPressure(const float altCm) { return powf(1.0f - (altCm / 4433000.0f), 5.254999) * 101325.0f; } diff --git a/src/main/sensors/barometer.h b/src/main/sensors/barometer.h index c2722e7d3c..2bbb1a976b 100644 --- a/src/main/sensors/barometer.h +++ b/src/main/sensors/barometer.h @@ -66,4 +66,8 @@ int32_t baroGetLatestAltitude(void); int16_t baroGetTemperature(void); bool baroIsHealthy(void); +#if defined(SITL_BUILD) +float altitudeToPressure(const float altCm); +#endif + #endif diff --git a/src/main/sensors/battery.c b/src/main/sensors/battery.c index 9652e15c4f..649062dddd 100644 --- a/src/main/sensors/battery.c +++ b/src/main/sensors/battery.c @@ -59,6 +59,9 @@ #include "io/beeper.h" +#if defined(USE_FAKE_BATT_SENSOR) +#include "sensors/battery_sensor_fake.h" +#endif #define ADCVREF 3300 // in mV (3300 = 3.3V) @@ -283,21 +286,17 @@ static void updateBatteryVoltage(timeUs_t timeDelta, bool justConnected) } break; #endif - case VOLTAGE_SENSOR_NONE: + +#if defined(USE_FAKE_BATT_SENSOR) + case VOLTAGE_SENSOR_FAKE: + vbat = fakeBattSensorGetVBat(); + break; +#endif + case VOLTAGE_SENSOR_NONE: default: vbat = 0; break; } -#ifdef USE_SIMULATOR - if (ARMING_FLAG(SIMULATOR_MODE)) { - if (SIMULATOR_HAS_OPTION(HITL_SIMULATE_BATTERY)) { - vbat = ((uint16_t)simulatorData.vbat) * 10; - batteryFullVoltage = 1260; - batteryWarningVoltage = 1020; - batteryCriticalVoltage = 960; - } - } -#endif if (justConnected) { pt1FilterReset(&vbatFilterState, vbat); } else { @@ -574,6 +573,12 @@ void currentMeterUpdate(timeUs_t timeDelta) } break; #endif + +#if defined(USE_FAKE_BATT_SENSOR) + case CURRENT_SENSOR_FAKE: + amperage = fakeBattSensorGetAmerperage(); + break; +#endif case CURRENT_SENSOR_NONE: default: amperage = 0; diff --git a/src/main/sensors/battery_config_structs.h b/src/main/sensors/battery_config_structs.h index 9ce524fa77..81eafef44a 100644 --- a/src/main/sensors/battery_config_structs.h +++ b/src/main/sensors/battery_config_structs.h @@ -29,14 +29,16 @@ typedef enum { CURRENT_SENSOR_NONE = 0, CURRENT_SENSOR_ADC, CURRENT_SENSOR_VIRTUAL, + CURRENT_SENSOR_FAKE, CURRENT_SENSOR_ESC, - CURRENT_SENSOR_MAX = CURRENT_SENSOR_VIRTUAL + CURRENT_SENSOR_MAX = CURRENT_SENSOR_FAKE } currentSensor_e; typedef enum { VOLTAGE_SENSOR_NONE = 0, VOLTAGE_SENSOR_ADC, - VOLTAGE_SENSOR_ESC + VOLTAGE_SENSOR_ESC, + VOLTAGE_SENSOR_FAKE } voltageSensor_e; typedef enum { diff --git a/src/main/sensors/battery_sensor_fake.c b/src/main/sensors/battery_sensor_fake.c new file mode 100644 index 0000000000..9c2ad69d6c --- /dev/null +++ b/src/main/sensors/battery_sensor_fake.c @@ -0,0 +1,58 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + + +#include +#include +#include "platform.h" + +#if defined(USE_FAKE_BATT_SENSOR) + +#include "common/utils.h" +#include "sensors/battery_sensor_fake.h" + +static uint16_t fakeVbat; +static uint16_t fakeAmerperage; + +void fakeBattSensorSetVbat(uint16_t vbat) +{ + fakeVbat = vbat; +} + +void fakeBattSensorSetAmperage(uint16_t amperage) +{ + fakeAmerperage = amperage; +} + +uint16_t fakeBattSensorGetVBat(void) +{ + return fakeVbat; +} + +uint16_t fakeBattSensorGetAmerperage(void) +{ + return fakeAmerperage; +} + +#endif \ No newline at end of file diff --git a/src/main/sensors/battery_sensor_fake.h b/src/main/sensors/battery_sensor_fake.h new file mode 100644 index 0000000000..1e5f2691fe --- /dev/null +++ b/src/main/sensors/battery_sensor_fake.h @@ -0,0 +1,30 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#pragma once + +void fakeBattSensorSetVbat(uint16_t vbat); +void fakeBattSensorSetAmperage(uint16_t amperage); +uint16_t fakeBattSensorGetVBat(void); +uint16_t fakeBattSensorGetAmerperage(void); diff --git a/src/main/sensors/compass.c b/src/main/sensors/compass.c index 9bee826c12..4e610ee00a 100644 --- a/src/main/sensors/compass.c +++ b/src/main/sensors/compass.c @@ -357,7 +357,7 @@ bool compassIsCalibrationComplete(void) void compassUpdate(timeUs_t currentTimeUs) { #ifdef USE_SIMULATOR - if (ARMING_FLAG(SIMULATOR_MODE)) { + if (ARMING_FLAG(SIMULATOR_MODE_HITL)) { magUpdatedAtLeastOnce = true; return; } diff --git a/src/main/sensors/diagnostics.c b/src/main/sensors/diagnostics.c index 0702f78991..408772eb82 100644 --- a/src/main/sensors/diagnostics.c +++ b/src/main/sensors/diagnostics.c @@ -63,7 +63,7 @@ hardwareSensorStatus_e getHwAccelerometerStatus(void) hardwareSensorStatus_e getHwCompassStatus(void) { #ifdef USE_SIMULATOR - if (ARMING_FLAG(SIMULATOR_MODE) && sensors(SENSOR_MAG)) { + if ((ARMING_FLAG(SIMULATOR_MODE_HITL) || ARMING_FLAG(SIMULATOR_MODE_SITL)) && sensors(SENSOR_MAG)) { return HW_SENSOR_OK; } #endif diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index d40676477b..115c971f3d 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -22,7 +22,7 @@ #include "platform.h" -FILE_COMPILE_FOR_SPEED +//FILE_COMPILE_FOR_SPEED #include "build/build_config.h" #include "build/debug.h" @@ -486,7 +486,7 @@ void FAST_CODE NOINLINE gyroFilter() ); secondaryDynamicGyroNotchFiltersUpdate( - &secondaryDynamicGyroNotchState, + &secondaryDynamicGyroNotchState, gyroAnalyseState.filterUpdateAxis, gyroAnalyseState.centerFrequency[gyroAnalyseState.filterUpdateAxis] ); @@ -500,7 +500,7 @@ void FAST_CODE NOINLINE gyroFilter() void FAST_CODE NOINLINE gyroUpdate() { #ifdef USE_SIMULATOR - if (ARMING_FLAG(SIMULATOR_MODE)) { + if (ARMING_FLAG(SIMULATOR_MODE_HITL)) { //output: gyro.gyroADCf[axis] //unused: dev->gyroADCRaw[], dev->gyroZero[]; return; diff --git a/src/main/sensors/pitotmeter.c b/src/main/sensors/pitotmeter.c index eb2cad13f0..29418e3ec0 100644 --- a/src/main/sensors/pitotmeter.c +++ b/src/main/sensors/pitotmeter.c @@ -34,6 +34,7 @@ #include "drivers/pitotmeter/pitotmeter_adc.h" #include "drivers/pitotmeter/pitotmeter_msp.h" #include "drivers/pitotmeter/pitotmeter_virtual.h" +#include "drivers/pitotmeter/pitotmeter_fake.h" #include "drivers/time.h" #include "fc/config.h" @@ -207,9 +208,15 @@ STATIC_PROTOTHREAD(pitotThread) pitot.dev.calculate(&pitot.dev, &pitotPressureTmp, NULL); #ifdef USE_SIMULATOR - if (SIMULATOR_HAS_OPTION(HITL_AIRSPEED)) { - pitotPressureTmp = sq(simulatorData.airSpeed) * SSL_AIR_DENSITY / 20000.0f + SSL_AIR_PRESSURE; - } + float airSpeed; + if (SIMULATOR_HAS_OPTION(HITL_AIRSPEED)) { + airSpeed = simulatorData.airSpeed; + } else if (pitotmeterConfig()->pitot_hardware == PITOT_FAKE) { + airSpeed = fakePitotGetAirspeed(); + } else { + airSpeed = 0; + } + pitotPressureTmp = sq(airSpeed) * SSL_AIR_DENSITY / 20000.0f + SSL_AIR_PRESSURE; #endif ptYield(); @@ -235,9 +242,13 @@ STATIC_PROTOTHREAD(pitotThread) pitot.airSpeed = 0.0f; } #ifdef USE_SIMULATOR - if (SIMULATOR_HAS_OPTION(HITL_AIRSPEED)) { - pitot.airSpeed = simulatorData.airSpeed; - } + if (SIMULATOR_HAS_OPTION(HITL_AIRSPEED)) { + pitot.airSpeed = simulatorData.airSpeed; + } else if (pitotmeterConfig()->pitot_hardware == PITOT_FAKE) { + pitot.airSpeed = fakePitotGetAirspeed(); + } else { + pitot.airSpeed = 0; + } #endif } diff --git a/src/main/target/SITL/CMakeLists.txt b/src/main/target/SITL/CMakeLists.txt new file mode 100644 index 0000000000..088bec688a --- /dev/null +++ b/src/main/target/SITL/CMakeLists.txt @@ -0,0 +1 @@ +target_sitl(SITL) diff --git a/src/main/target/SITL/config.c b/src/main/target/SITL/config.c new file mode 100644 index 0000000000..e97f78931e --- /dev/null +++ b/src/main/target/SITL/config.c @@ -0,0 +1,28 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + +#include +#include + +#include "config/config_master.h" +#include "io/serial.h" + +void targetConfiguration(void) +{ + serialConfigMutable()->portConfigs[1].functionMask = FUNCTION_MSP; + serialConfigMutable()->portConfigs[1].msp_baudrateIndex = BAUD_57600; +} diff --git a/src/main/target/SITL/sim/realFlight.c b/src/main/target/SITL/sim/realFlight.c new file mode 100644 index 0000000000..4289d87d25 --- /dev/null +++ b/src/main/target/SITL/sim/realFlight.c @@ -0,0 +1,421 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#include +#include +#include +#include +#include +#include +#include + +#include "platform.h" + +#include "target.h" +#include "target/SITL/sim/realFlight.h" +#include "target/SITL/sim/simple_soap_client.h" +#include "target/SITL/sim/xplane.h" +#include "target/SITL/sim/simHelper.h" +#include "fc/runtime_config.h" +#include "drivers/time.h" +#include "drivers/accgyro/accgyro_fake.h" +#include "drivers/barometer/barometer_fake.h" +#include "sensors/battery_sensor_fake.h" +#include "sensors/acceleration.h" +#include "sensors/barometer.h" +#include "drivers/pitotmeter/pitotmeter_fake.h" +#include "common/utils.h" +#include "common/maths.h" +#include "flight/mixer.h" +#include "flight/servos.h" +#include "flight/imu.h" +#include "io/gps.h" + +#define RF_PORT 18083 +// RealFlight scenerys doesn't represent real landscapes, so fake some nice coords: Area 51 ;) +#define FAKE_LAT 37.277127f +#define FAKE_LON -115.799669f + +static uint8_t pwmMapping[RF_MAX_PWM_OUTS]; +static uint8_t mappingCount; + +static pthread_cond_t sockcond1 = PTHREAD_COND_INITIALIZER; +static pthread_cond_t sockcond2 = PTHREAD_COND_INITIALIZER; +static pthread_mutex_t sockmtx = PTHREAD_MUTEX_INITIALIZER; + +static soap_client_t *client = NULL; +static soap_client_t *clientNext = NULL; + +static pthread_t soapThread; +static pthread_t creationThread; + +static bool isInitalised = false; +static bool useImu = false; + +typedef struct +{ + double m_channelValues[RF_MAX_PWM_OUTS]; + double m_currentPhysicsSpeedMultiplier; + double m_currentPhysicsTime_SEC; + double m_airspeed_MPS; + double m_altitudeASL_MTR; + double m_altitudeAGL_MTR; + double m_groundspeed_MPS; + double m_pitchRate_DEGpSEC; + double m_rollRate_DEGpSEC; + double m_yawRate_DEGpSEC; + double m_azimuth_DEG; + double m_inclination_DEG; + double m_roll_DEG; + double m_orientationQuaternion_X; + double m_orientationQuaternion_Y; + double m_orientationQuaternion_Z; + double m_orientationQuaternion_W; + double m_aircraftPositionX_MTR; + double m_aircraftPositionY_MTR; + double m_velocityWorldU_MPS; + double m_velocityWorldV_MPS; + double m_velocityWorldW_MPS; + double m_velocityBodyU_MPS; + double m_velocityBodyV_MPS; + double m_velocityBodyW_MPS; + double m_accelerationWorldAX_MPS2; + double m_accelerationWorldAY_MPS2; + double m_accelerationWorldAZ_MPS2; + double m_accelerationBodyAX_MPS2; + double m_accelerationBodyAY_MPS2; + double m_accelerationBodyAZ_MPS2; + double m_windX_MPS; + double m_windY_MPS; + double m_windZ_MPSPS; + double m_propRPM; + double m_heliMainRotorRPM; + double m_batteryVoltage_VOLTS; + double m_batteryCurrentDraw_AMPS; + double m_batteryRemainingCapacity_MAH; + double m_fuelRemaining_OZ; + bool m_isLocked; + bool m_hasLostComponents; + bool m_anEngineIsRunning; + bool m_isTouchingGround; + bool m_flightAxisControllerIsActive; + char* m_currentAircraftStatus; + bool m_resetButtonHasBeenPressed; +} rfValues_t; + +rfValues_t rfValues; + +static void deleteClient(soap_client_t *client) +{ + soapClientClose(client); + free(client); + client = NULL; +} + +static void startRequest(char* action, const char* fmt, ...) +{ + pthread_mutex_lock(&sockmtx); + while (clientNext == NULL) { + pthread_cond_wait(&sockcond1, &sockmtx); + } + + client = clientNext; + clientNext = NULL; + + pthread_cond_broadcast(&sockcond2); + pthread_mutex_unlock(&sockmtx); + + va_list va; + va_start(va, fmt); + soapClientSendRequestVa(client, action, fmt, va); + va_end(va); +} + +static char* endRequest(void) +{ + char* ret = soapClientReceive(client); + deleteClient(client); + return ret; +} + +// Simple, but fast ;) +static double getDoubleFromResponse(const char* response, const char* elementName) +{ + if (!response) { + return 0; + } + + char* pos = strstr(response, elementName); + if (!pos) { + return 0; + } + return atof(pos + strlen(elementName) + 1); +} + + +/* +Currently unused +static bool getBoolFromResponse(const char* response, const char* elementName) +{ + if (!response) { + return false; + } + + char* pos = strstr(response, elementName); + if (!pos) { + return false; + } + return (strncmp(pos + strlen(elementName) + 1, "true", 4) == 0); +} +*/ + +static char* getStringFromResponse(const char* response, const char* elementName) +{ + if (!response) { + return 0; + } + + char* pos = strstr(response, elementName); + if (!pos) { + return NULL; + } + + pos += strlen(elementName) + 1; + char* end = strstr(pos, "%u%.4f%.4f%.4f%.4f%.4f%.4f%.4f%.4f%.4f%.4f%.4f%.4f", + 0xFFF, servoValues[0], servoValues[1], servoValues[2], servoValues[3], servoValues[4], servoValues[5], servoValues[6], servoValues[7], servoValues[8], servoValues[9], servoValues[10], servoValues[11]); + char* response = endRequest(); + + //rfValues.m_currentPhysicsTime_SEC = getDoubleFromResponse(response, "m-currentPhysicsTime-SEC"); + //rfValues.m_currentPhysicsSpeedMultiplier = getDoubleFromResponse(response, "m-currentPhysicsSpeedMultiplier"); + rfValues.m_airspeed_MPS = getDoubleFromResponse(response, "m-airspeed-MPS"); + rfValues.m_altitudeASL_MTR = getDoubleFromResponse(response, "12"); + endRequest(); + startRequest("InjectUAVControllerInterface", "12"); + endRequest(); + + exchangeData(); + ENABLE_ARMING_FLAG(SIMULATOR_MODE_SITL); + isInitalised = true; + } + exchangeData(); + + unlockMainPID(); + } + + return NULL; +} + + +static void* creationWorker(void* arg) +{ + char* ip = (char*)arg; + + while (true) { + pthread_mutex_lock(&sockmtx); + while (clientNext != NULL) { + pthread_cond_wait(&sockcond2, &sockmtx); + } + pthread_mutex_unlock(&sockmtx); + + soap_client_t *cli = malloc(sizeof(soap_client_t)); + if (!soapClientConnect(cli, ip, RF_PORT)) { + continue; + } + + clientNext = cli; + pthread_mutex_lock(&sockmtx); + pthread_cond_broadcast(&sockcond1); + pthread_mutex_unlock(&sockmtx); + } + + return NULL; +} + +bool simRealFlightInit(char* ip, uint8_t* mapping, uint8_t mapCount, bool imu) +{ + memcpy(pwmMapping, mapping, mapCount); + mappingCount = mapCount; + useImu = imu; + + if (pthread_create(&soapThread, NULL, soapWorker, NULL) < 0) { + return false; + } + + if (pthread_create(&creationThread, NULL, creationWorker, (void*)ip) < 0) { + return false; + } + + // Wait until the connection is established, the interface has been initialised + // and the first valid packet has been received to avoid problems with the startup calibration. + while (!isInitalised) { + // ... + } + + return true; +} diff --git a/src/main/target/SITL/sim/realFlight.h b/src/main/target/SITL/sim/realFlight.h new file mode 100644 index 0000000000..f93ab49f48 --- /dev/null +++ b/src/main/target/SITL/sim/realFlight.h @@ -0,0 +1,29 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#include + +#define RF_MAX_PWM_OUTS 12 + +bool simRealFlightInit(char* ip, uint8_t* mapping, uint8_t mapCount, bool imu); \ No newline at end of file diff --git a/src/main/target/SITL/sim/simHelper.c b/src/main/target/SITL/sim/simHelper.c new file mode 100644 index 0000000000..4f7fb57244 --- /dev/null +++ b/src/main/target/SITL/sim/simHelper.c @@ -0,0 +1,47 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#include +#include +#include + +#include "target/SITL/sim/simHelper.h" + +inline double clampd(double value, double min, double max) +{ + if (value < min) { + value = min; + } + + if (value > max) { + value = max; + } + + return value; +} + +inline int16_t clampToInt16(double value) +{ + return (int16_t)round(clampd(value, INT16_MIN, INT16_MAX)); +} diff --git a/src/main/target/SITL/sim/simHelper.h b/src/main/target/SITL/sim/simHelper.h new file mode 100644 index 0000000000..2a9b25e410 --- /dev/null +++ b/src/main/target/SITL/sim/simHelper.h @@ -0,0 +1,33 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#include + +#define EARTH_RADIUS ((double)6378.137) +#define DEG2RAD(deg) (deg * (double)M_PIf / (double)180.0) +#define PWM_TO_FLOAT_0_1(x) (((int)x - 1000) / 1000.0f) +#define PWM_TO_FLOAT_MINUS_1_1(x) (((int)x - 1500) / 500.0f) + +double clampd(double value, double min, double max); +int16_t clampToInt16(double value); diff --git a/src/main/target/SITL/sim/simple_soap_client.c b/src/main/target/SITL/sim/simple_soap_client.c new file mode 100644 index 0000000000..b3763b2ab0 --- /dev/null +++ b/src/main/target/SITL/sim/simple_soap_client.c @@ -0,0 +1,162 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#define _GNU_SOURCE + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "simple_soap_client.h" + +#define REC_BUF_SIZE 6000 +char recBuffer[REC_BUF_SIZE]; + +bool soapClientConnect(soap_client_t *client, const char *address, int port) +{ + client->sockedFd = socket(AF_INET, SOCK_STREAM, IPPROTO_TCP); + if (client->sockedFd < 0) { + return false; + } + + int one = 1; + if (setsockopt(client->sockedFd, SOL_SOCKET, SO_REUSEADDR, &one,sizeof(one)) < 0) { + return false; + } + + client->socketAddr.sin_family = AF_INET; + client->socketAddr.sin_port = htons(port); + client->socketAddr.sin_addr.s_addr = inet_addr(address); + + if (connect(client->sockedFd, (struct sockaddr*)&client->socketAddr, sizeof(client->socketAddr)) < 0) { + return false; + } + + client->isConnected = true; + client->isInitalised = true; + + return true; +} + +void soapClientClose(soap_client_t *client) +{ + close(client->sockedFd); + memset(client, 0, sizeof(soap_client_t)); +} + +void soapClientSendRequestVa(soap_client_t *client, const char* action, const char *fmt, va_list va) +{ + if (!client->isConnected) { + return; + } + + char* requestBody; + vasprintf(&requestBody, fmt, va); + + char* request; + asprintf(&request, "POST / HTTP/1.1\r\nsoapaction: %s\r\ncontent-length: %u\r\ncontent-type: text/xml;charset='UTF-8'\r\nConnection: Keep-Alive\r\n\r\n%s", + action, (unsigned)strlen(requestBody), requestBody); + + send(client->sockedFd, request, strlen(request), 0); +} + +void soapClientSendRequest(soap_client_t *client, const char* action, const char *fmt, ...) +{ + va_list va; + + va_start(va, fmt); + soapClientSendRequestVa(client, action, fmt, va); + va_end(va); +} + +static bool soapClientPoll(soap_client_t *client, uint32_t timeout_ms) +{ + fd_set fds; + struct timeval tv; + + FD_ZERO(&fds); + FD_SET(client->sockedFd, &fds); + + tv.tv_sec = timeout_ms / 1000; + tv.tv_usec = (timeout_ms % 1000) * 1000UL; + + if (select(client->sockedFd + 1, &fds, NULL, NULL, &tv) != 1) { + return false; + } + return true; +} + + +char* soapClientReceive(soap_client_t *client) +{ + if (!client->isInitalised){ + return false; + } + + if (!soapClientPoll(client, 1000)) { + return false; + } + + ssize_t size = recv(client->sockedFd, recBuffer, REC_BUF_SIZE, 0); + + if (size <= 0) { + return NULL; + } + + char* pos = strstr(recBuffer, "Content-Length: "); + if (!pos) { + return NULL; + } + + uint32_t contentLength = strtoul(pos + 16, NULL, 10); + char *body = strstr(pos, "\r\n\r\n"); + if (!body) { + return NULL; + } + + body += 4; + + ssize_t expectedLength = contentLength + body - recBuffer; + if ((unsigned)expectedLength >= sizeof(recBuffer)) { + return NULL; + } + + while (size < expectedLength){ + ssize_t size2 = recv(client->sockedFd, &recBuffer[size], sizeof(recBuffer - size + 1), 0); + if (size2 <= 0) { + return NULL; + } + size += size2; + } + + recBuffer[size] = '\0'; + return strdup(body); +} + diff --git a/src/main/target/SITL/sim/simple_soap_client.h b/src/main/target/SITL/sim/simple_soap_client.h new file mode 100644 index 0000000000..5b97a595a3 --- /dev/null +++ b/src/main/target/SITL/sim/simple_soap_client.h @@ -0,0 +1,46 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#include + +#define SOAP_REC_BUF_SIZE 256 * 1024 + +typedef struct { + int sockedFd; + struct sockaddr_in socketAddr; + bool isInitalised; + bool isConnected; +} soap_client_t; + +typedef struct { + soap_client_t client; + char* content; +} send_info_t; + + +bool soapClientConnect(soap_client_t *client, const char *address, int port); +void soapClientClose(soap_client_t *client); +void soapClientSendRequestVa(soap_client_t *client, const char* action, const char *fmt, va_list va); +void soapClientSendRequest(soap_client_t *client, const char* action, const char *fmt, ...); +char* soapClientReceive(soap_client_t *client); \ No newline at end of file diff --git a/src/main/target/SITL/sim/xplane.c b/src/main/target/SITL/sim/xplane.c new file mode 100644 index 0000000000..70ecb3361f --- /dev/null +++ b/src/main/target/SITL/sim/xplane.c @@ -0,0 +1,403 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "platform.h" + +#include "target.h" +#include "target/SITL/sim/xplane.h" +#include "target/SITL/sim/simHelper.h" +#include "fc/runtime_config.h" +#include "drivers/time.h" +#include "drivers/accgyro/accgyro_fake.h" +#include "drivers/barometer/barometer_fake.h" +#include "sensors/battery_sensor_fake.h" +#include "sensors/acceleration.h" +#include "drivers/pitotmeter/pitotmeter_fake.h" +#include "common/utils.h" +#include "common/maths.h" +#include "flight/mixer.h" +#include "flight/servos.h" +#include "flight/imu.h" +#include "io/gps.h" + +#define XP_PORT 49000 + + +static uint8_t pwmMapping[XP_MAX_PWM_OUTS]; +static uint8_t mappingCount; + +static struct sockaddr_in serverAddr; +static int sockFd; +static pthread_t listenThread; +static bool initalized = false; +static bool useImu = false; + +static float lattitude = 0; +static float longitude = 0; +static float elevation = 0; +static float local_vx = 0; +static float local_vy = 0; +static float local_vz = 0; +static float groundspeed = 0; +static float airspeed = 0; +static float roll = 0; +static float pitch = 0; +static float yaw = 0; +static float hpath = 0; +static float accel_x = 0; +static float accel_y = 0; +static float accel_z = 0; +static float gyro_x = 0; +static float gyro_y = 0; +static float gyro_z = 0; +static float barometer = 0; + + +typedef enum +{ + DREF_LATITUDE, + DREF_LONGITUDE, + DREF_ELEVATION, + DREF_LOCAL_VX, + DREF_LOCAL_VY, + DREF_LOCAL_VZ, + DREF_GROUNDSPEED, + DREF_TRUE_AIRSPEED, + DREF_POS_PHI, + DREF_POS_THETA, + DREF_POS_PSI, + DREF_POS_HPATH, + DREF_FORCE_G_AXI1, + DREF_FORCE_G_SIDE, + DREF_FORCE_G_NRML, + DREF_POS_P, + DREF_POS_Q, + DREF_POS_R, + DREF_POS_BARO_CURRENT_INHG, + DREF_COUNT +} dref_t; + +uint32_t xint2uint32 (uint8_t * buf) +{ + return buf[3] << 24 | buf [2] << 16 | buf [1] << 8 | buf [0]; +} + +float xflt2float (uint8_t * buf) +{ + union { + float f; + uint32_t i; + } v; + + v.i = xint2uint32 (buf); + return v.f; +} + +static void registerDref(dref_t id, char* dref, uint32_t freq) +{ + char buf[413]; + memset(buf, 0, sizeof(buf)); + + strcpy(buf, "RREF"); + memcpy(buf + 5, &freq, 4); + memcpy(buf + 9, &id, 4); + memcpy(buf + 13, dref, strlen(dref) + 1); + + sendto(sockFd, (void*)buf, sizeof(buf), 0, (struct sockaddr*)&serverAddr, sizeof(serverAddr)); +} + +static void sendDref(char* dref, float value) +{ + char buf[509]; + strcpy(buf, "DREF"); + memcpy(buf + 5, &value, 4); + memset(buf + 9, ' ', sizeof(buf) - 9); + strcpy(buf + 9, dref); + + sendto(sockFd, (void*)buf, sizeof(buf), 0, (struct sockaddr*)&serverAddr, sizeof(serverAddr)); +} + +static void* listenWorker(void* arg) +{ + UNUSED(arg); + + uint8_t buf[1024]; + struct sockaddr remoteAddr; + socklen_t slen = sizeof(remoteAddr); + int recvLen; + + while (true) + { + + float motorValue = 0; + float yokeValues[3] = { 0 }; + int y = 0; + for (int i = 0; i < mappingCount; i++) { + if (y > 2) { + break; + } + if (pwmMapping[i] & 0x80) { // Motor) + motorValue = PWM_TO_FLOAT_0_1(motor[pwmMapping[i] & 0x7f]); + } else { + yokeValues[y] = PWM_TO_FLOAT_MINUS_1_1(servo[pwmMapping[i]]); + y++; + } + } + + sendDref("sim/operation/override/override_joystick", 1); + sendDref("sim/cockpit2/engine/actuators/throttle_ratio_all", motorValue); + sendDref("sim/joystick/yoke_roll_ratio", yokeValues[0]); + sendDref("sim/joystick/yoke_pitch_ratio", yokeValues[1]); + sendDref("sim/joystick/yoke_heading_ratio", yokeValues[2]); + + recvLen = recvfrom(sockFd, buf, sizeof(buf), 0, (struct sockaddr*)&remoteAddr, &slen); + if (recvLen < 0 && errno != EWOULDBLOCK) { + break; + } + + if (strncmp((char*)buf, "RREF", 4) != 0) { + break; + } + + for (int i = 5; i < recvLen; i += 8) { + dref_t dref = (dref_t)xint2uint32(&buf[i]); + float value = xflt2float(&(buf[i + 4])); + + switch (dref) + { + case DREF_LATITUDE: + lattitude = value; + break; + + case DREF_LONGITUDE: + longitude = value; + break; + + case DREF_ELEVATION: + elevation = value; + break; + + case DREF_LOCAL_VX: + local_vx = value; + break; + + case DREF_LOCAL_VY: + local_vy = value; + break; + + case DREF_LOCAL_VZ: + local_vz = value; + break; + + case DREF_GROUNDSPEED: + groundspeed = value; + break; + + case DREF_TRUE_AIRSPEED: + airspeed = value; + break; + + case DREF_POS_PHI: + roll = value; + break; + + case DREF_POS_THETA: + pitch = value; + break; + + case DREF_POS_PSI: + yaw = value; + break; + + case DREF_POS_HPATH: + hpath = value; + break; + + case DREF_FORCE_G_AXI1: + accel_x = value; + break; + + case DREF_FORCE_G_SIDE: + accel_y = value; + break; + + case DREF_FORCE_G_NRML: + accel_z = value; + break; + + case DREF_POS_P: + gyro_x = value; + break; + + case DREF_POS_Q: + gyro_y = value; + break; + + case DREF_POS_R: + gyro_z = value; + break; + + case DREF_POS_BARO_CURRENT_INHG: + barometer = value; + break; + + default: + break; + } + + } + + if (hpath < 0) { + hpath += 3600; + } + + if (yaw < 0){ + yaw += 3600; + } + + gpsFakeSet( + GPS_FIX_3D, + 16, + (int32_t)round(lattitude * 10000000), + (int32_t)round(longitude * 10000000), + (int32_t)round(elevation * 100), + (int16_t)round(groundspeed * 100), + (int16_t)round(hpath * 10), + 0, //(int16_t)round(-local_vz * 100), + 0, //(int16_t)round(local_vx * 100), + 0, //(int16_t)round(-local_vy * 100), + 0 + ); + + if (!useImu) { + imuSetAttitudeRPY( + (int16_t)round(roll * 10), + (int16_t)round(-pitch * 10), + (int16_t)round(yaw * 10) + ); + imuUpdateAttitude(micros()); + } + + fakeAccSet( + clampToInt16(-accel_x * GRAVITY_MSS * 1000), + clampToInt16(accel_y * GRAVITY_MSS * 1000), + clampToInt16(accel_z * GRAVITY_MSS * 1000) + ); + + fakeGyroSet( + clampToInt16(gyro_x * 16.0f), + clampToInt16(-gyro_y * 16.0f), + clampToInt16(-gyro_z * 16.0f) + ); + + fakeBaroSet((int32_t)round(barometer * 3386.39f), DEGREES_TO_CENTIDEGREES(21)); + fakePitotSetAirspeed(airspeed * 100.0f); + + fakeBattSensorSetVbat(16.8 * 100); + + if (!initalized) { + ENABLE_ARMING_FLAG(SIMULATOR_MODE_SITL); + initalized = true; + } + + unlockMainPID(); + } + + return NULL; +} + +bool simXPlaneInit(char* ip, int port, uint8_t* mapping, uint8_t mapCount, bool imu) +{ + memcpy(pwmMapping, mapping, mapCount); + mappingCount = mapCount; + useImu = imu; + + sockFd = socket(AF_INET, SOCK_DGRAM, IPPROTO_UDP); + + if (sockFd < 0) { + return false; + } + + struct sockaddr_in addr; + addr.sin_family = AF_INET; + addr.sin_addr.s_addr = htonl(INADDR_ANY); + addr.sin_port = htons(0); + + struct timeval tv; + tv.tv_sec = 1; + tv.tv_usec = 0; + if (setsockopt(sockFd, SOL_SOCKET, SO_RCVTIMEO, (struct timeval *) &tv,sizeof(struct timeval))) { + return false; + } + + if (bind(sockFd, (struct sockaddr *) &addr, sizeof(addr)) < 0) { + return false; + } + + serverAddr.sin_family = AF_INET; + serverAddr.sin_addr.s_addr = inet_addr(ip); + serverAddr.sin_port = htons(port); + + registerDref(DREF_LATITUDE, "sim/flightmodel/position/latitude", 100); + registerDref(DREF_LONGITUDE, "sim/flightmodel/position/longitude", 100); + registerDref(DREF_ELEVATION, "sim/flightmodel/position/elevation", 100); + registerDref(DREF_LOCAL_VX, "sim/flightmodel/position/local_vx", 100); + registerDref(DREF_LOCAL_VY, "sim/flightmodel/position/local_vy", 100); + registerDref(DREF_LOCAL_VZ, "sim/flightmodel/position/local_vz", 100); + registerDref(DREF_GROUNDSPEED, "sim/flightmodel/position/groundspeed", 100); + registerDref(DREF_TRUE_AIRSPEED, "sim/flightmodel/position/true_airspeed", 100); + registerDref(DREF_POS_PHI, "sim/flightmodel/position/phi", 100); + registerDref(DREF_POS_THETA, "sim/flightmodel/position/theta", 100); + registerDref(DREF_POS_PSI, "sim/flightmodel/position/psi", 100); + registerDref(DREF_POS_HPATH, "sim/flightmodel/position/hpath", 100); + registerDref(DREF_FORCE_G_AXI1, "sim/flightmodel/forces/g_axil", 100); + registerDref(DREF_FORCE_G_SIDE, "sim/flightmodel/forces/g_side", 100); + registerDref(DREF_FORCE_G_NRML, "sim/flightmodel/forces/g_nrml", 100); + registerDref(DREF_POS_P, "sim/flightmodel/position/P", 100); + registerDref(DREF_POS_Q, "sim/flightmodel/position/Q", 100); + registerDref(DREF_POS_R, "sim/flightmodel/position/R", 100); + registerDref(DREF_POS_BARO_CURRENT_INHG, "sim/weather/barometer_current_inhg", 100); + + if (pthread_create(&listenThread, NULL, listenWorker, NULL) < 0) { + return false; + } + + while(!initalized) { + // + } + + return true; + +} \ No newline at end of file diff --git a/src/main/target/SITL/sim/xplane.h b/src/main/target/SITL/sim/xplane.h new file mode 100644 index 0000000000..04d8c53a7a --- /dev/null +++ b/src/main/target/SITL/sim/xplane.h @@ -0,0 +1,29 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#include + +#define XP_MAX_PWM_OUTS 4 + +bool simXPlaneInit(char* ip, int port, uint8_t* mapping, uint8_t mapCount, bool imu); \ No newline at end of file diff --git a/src/main/target/SITL/target.c b/src/main/target/SITL/target.c new file mode 100644 index 0000000000..5c7a3f7b23 --- /dev/null +++ b/src/main/target/SITL/target.c @@ -0,0 +1,345 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include "target.h" + +#include "fc/runtime_config.h" +#include "common/utils.h" +#include "scheduler/scheduler.h" +#include "drivers/system.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" +#include "drivers/serial.h" + +#include "target/SITL/sim/realFlight.h" +#include "target/SITL/sim/xplane.h" + +// More dummys +const int timerHardwareCount = 0; +timerHardware_t timerHardware[1]; +uint32_t SystemCoreClock = 500 * 1e6; // fake 500 MHz; +char _estack = 0 ; +char _Min_Stack_Size = 0; + +static pthread_mutex_t mainLoopLock; +static SitlSim_e sitlSim = SITL_SIM_NONE; +static struct timespec start_time; +static uint8_t pwmMapping[MAX_MOTORS + MAX_SERVOS]; +static uint8_t mappingCount = 0; +static bool useImu = false; +static char *simIp = NULL; +static int simPort = 0; + +void systemInit(void) { + + printf("INAV %d.%d.%d SITL\n", FC_VERSION_MAJOR, FC_VERSION_MINOR, FC_VERSION_PATCH_LEVEL); + clock_gettime(CLOCK_MONOTONIC, &start_time); + printf("[SYSTEM] Init...\n"); + + if (pthread_mutex_init(&mainLoopLock, NULL) != 0) { + printf("[SYSTEM] Unable to create mainLoop lock.\n"); + exit(1); + } + + if (sitlSim != SITL_SIM_NONE) { + printf("[SIM] Waiting for connection...\n"); + } + + switch (sitlSim) { + case SITL_SIM_REALFLIGHT: + if (mappingCount > RF_MAX_PWM_OUTS) { + printf("[SIM] Mapping error. RealFligt supports a maximum of %i PWM outputs.", RF_MAX_PWM_OUTS); + sitlSim = SITL_SIM_NONE; + break; + } + if (simRealFlightInit(simIp, pwmMapping, mappingCount, useImu)) { + printf("[SIM] Connection with RealFlight (%s) successfully established. \n", simIp); + } else { + printf("[SIM] Connection with RealFlight (%s) NOT established. \n", simIp); + } + break; + case SITL_SIM_XPLANE: + if (mappingCount > XP_MAX_PWM_OUTS) { + printf("[SIM] Mapping error. RealFligt supports a maximum of %i PWM outputs.", XP_MAX_PWM_OUTS); + sitlSim = SITL_SIM_NONE; + break; + } + if (simXPlaneInit(simIp, simPort, pwmMapping, mappingCount, useImu)) { + printf("[SIM] Connection with XPlane successfully established. \n"); + } else { + printf("[SIM] Connection with XPLane NOT established. \n"); + } + break; + default: + printf("[SIM] No interface specified. Configurator only.\n"); + break; + } + + rescheduleTask(TASK_SERIAL, 1); +} + +bool parseMapping(char* mapStr) +{ + char *split = strtok(mapStr, ","); + char numBuf[2]; + while(split) + { + if (strlen(split) != 6) { + return false; + } + + if (split[0] == 'M' || split[0] == 'S') { + memcpy(numBuf, &split[1], 2); + int pwmOut = atoi(numBuf); + memcpy(numBuf, &split[4], 2); + int rOut = atoi(numBuf); + if (pwmOut < 0 || rOut < 1) { + return false; + } + if (split[0] == 'M') { + pwmMapping[rOut - 1] = pwmOut - 1; + pwmMapping[rOut - 1] |= 0x80; + mappingCount++; + } else if (split[0] == 'S') { + pwmMapping[rOut - 1] = pwmOut; + mappingCount++; + } + } else { + return false; + } + split = strtok(NULL, ","); + } + + return true; +} + +void printCmdLineOptions(void) +{ + printf("Avaiable options:\n"); + printf("--sim=[rf|xp] Simulator interface: rf = RealFligt, xp = XPlane. Example: --sim=rf\n"); + printf("--simip=[ip] IP-Address oft the simulator host. If not specified localhost (127.0.0.1) is used."); + printf("--simport=[port] Port oft the simulator host."); + printf("--useimu Use IMU sensor data from the simulator instead of using attitude data from the simulator directly (experimental, not recommended)."); + printf("--chanmap=[mapstring] Channel mapping, Maps INAVs motor and servo PWM outputs to the virtual receiver output in the simulator.\n"); + printf(" The mapstring has the following format: M(otor)|S(servo)-,)... All numbers must have two digits\n"); + printf(" For example map motor 1 to virtal receiver output 1, servo 1 to output 2 and servo 2 to output 3:\n"); + printf(" --chanmap=M01-01,S01-02,S02-03\n"); +} + +void parseArguments(int argc, char *argv[]) +{ + int c; + while(1) { + static struct option longOpt[] = { + {"sim", optional_argument, 0, 's'}, + {"useimu", optional_argument, 0, 'u'}, + {"chanmap", optional_argument, 0, 'c'}, + {"simip", optional_argument, 0, 'i'}, + {"simport", optional_argument, 0, 'p'}, + {"help", optional_argument, 0, 'h'}, + {NULL, 0, NULL, 0} + }; + + c = getopt_long_only(argc, argv, "s:c:h", longOpt, NULL); + if (c == -1) + break; + + switch (c) { + case 's': + if (strcmp(optarg, "rf") == 0) { + sitlSim = SITL_SIM_REALFLIGHT; + } else if (strcmp(optarg, "xp") == 0){ + sitlSim = SITL_SIM_XPLANE; + } else { + printf("[SIM] Unsupported simulator %s.\n", optarg); + } + break; + + case 'c': + if (!parseMapping(optarg) && sitlSim != SITL_SIM_NONE) { + printf("[SIM] Invalid channel mapping string.\n"); + printCmdLineOptions(); + exit(0); + } + break; + case 'p': + simPort = atoi(optarg); + break; + case 'u': + useImu = true; + break; + case 'i': + simIp = optarg; + break; + + case 'h': + printCmdLineOptions(); + exit(0); + break; + } + } + + if (simIp == NULL) { + simIp = malloc(10); + strcpy(simIp, "127.0.0.1"); + } +} + + +bool lockMainPID(void) { + return pthread_mutex_trylock(&mainLoopLock) == 0; +} + +void unlockMainPID(void) +{ + pthread_mutex_unlock(&mainLoopLock); +} + +// Replacements for system functions +void microsleep(uint32_t usec) { + struct timespec ts; + ts.tv_sec = 0; + ts.tv_nsec = usec*1000UL; + while (nanosleep(&ts, &ts) == -1 && errno == EINTR) ; +} + +void delayMicroseconds_real(uint32_t us) { + microsleep(us); +} + +timeUs_t micros(void) { + struct timespec now; + clock_gettime(CLOCK_MONOTONIC, &now); + + return (now.tv_sec - start_time.tv_sec) * 1000000 + (now.tv_nsec - start_time.tv_nsec) / 1000; +} + +uint64_t microsISR(void) +{ + return micros(); +} + +uint32_t millis(void) { + return (uint32_t)(micros() / 1000); +} + +void delayMicroseconds(timeUs_t us) +{ + timeUs_t now = micros(); + while (micros() - now < us); +} + +void delay(timeMs_t ms) +{ + while (ms--) + delayMicroseconds(1000); +} + +void systemReset(void) +{ + printf("[SYSTEM] Reset\n"); + exit(0); +} + +void systemResetToBootloader(void) +{ + printf("[SYSTEM] Reset to bootloader\n"); + exit(0); +} + +void failureMode(failureMode_e mode) { + printf("[SYSTEM] Failure mode %d\n", mode); + while (1); +} + +// Even more dummys and stubs +uint32_t getEscUpdateFrequency(void) +{ + return 400; +} + +pwmInitError_e getPwmInitError(void) +{ + return PWM_INIT_ERROR_NONE; +} + +const char *getPwmInitErrorMessage(void) +{ + return "No error"; +} + +void IOConfigGPIO(IO_t io, ioConfig_t cfg) +{ + UNUSED(io); + UNUSED(cfg); +} + +void systemClockSetup(uint8_t cpuUnderclock) +{ + UNUSED(cpuUnderclock); +} + +void timerInit(void) { + // NOP +} + +bool isMPUSoftReset(void) +{ + return false; +} + +// Not in linux libs, but in arm-none-eabi ?!? +// https://github.com/lattera/freebsd/blob/master/lib/libc/string/strnstr.c +char * strnstr(const char *s, const char *find, size_t slen) +{ + char c, sc; + size_t len; + + if ((c = *find++) != '\0') { + len = strlen(find); + do { + do { + if (slen-- < 1 || (sc = *s++) == '\0') + return (NULL); + } while (sc != c); + if (len > slen) + return (NULL); + } while (strncmp(s, find, len) != 0); + s--; + } + return ((char *)s); +} diff --git a/src/main/target/SITL/target.h b/src/main/target/SITL/target.h new file mode 100644 index 0000000000..4b4f209c5e --- /dev/null +++ b/src/main/target/SITL/target.h @@ -0,0 +1,188 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#pragma once + +#include +#include +#include + +#include + +#define TARGET_BOARD_IDENTIFIER "SITL" +#define USBD_PRODUCT_STRING "SITL" + +#define REQUIRE_PRINTF_LONG_SUPPORT + +// file name to save config +#define EEPROM_FILENAME "eeprom.bin" +#define CONFIG_IN_FILE +#define EEPROM_SIZE 32768 + +#undef SCHEDULER_DELAY_LIMIT +#define SCHEDULER_DELAY_LIMIT 1 + +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 +#define USE_UART4 +#define USE_UART5 +#define USE_UART6 +#define USE_UART7 +#define USE_UART8 + +#define SERIAL_PORT_COUNT 8 + +#define DEFAULT_RX_FEATURE FEATURE_RX_MSP +#define DEFAULT_FEATURES (FEATURE_GPS | FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT) + +#define USE_IMU_FAKE +#define USE_ADC +#define USE_MAG +#define USE_BARO + +#undef USE_DASHBOARD +#undef USE_TELEMETRY_LTM + +#undef USE_GYRO_KALMAN // Strange behaviour under x86/x64 ?!? +#undef USE_VCP +#undef USE_PPM +#undef USE_PWM +#undef USE_LED_STRIP +#undef USE_TELEMETRY +#undef USE_MSP_OVER_TELEMETRY +#undef USE_TELEMETRY_FRSKY_HUB +#undef USE_TELEMETRY_HOTT +#undef USE_TELEMETRY_SMARTPORT +#undef USE_TELEMETRY_MAVLINK +#undef USE_RESOURCE_MGMT +#undef USE_TELEMETRY_CRSF +#undef USE_TELEMETRY_IBUS +#undef USE_TELEMETRY_JETIEXBUS +#undef USE_TELEMETRY_SRXL +#undef USE_TELEMETRY_GHST +#undef USE_VTX_COMMON +#undef USE_VTX_CONTROL +#undef USE_VTX_SMARTAUDIO +#undef USE_VTX_TRAMP +#undef USE_CAMERA_CONTROL +#undef USE_BRUSHED_ESC_AUTODETECT +#undef USE_SERIAL_4WAY_BLHELI_BOOTLOADER +#undef USE_SERIAL_4WAY_SK_BOOTLOADER + +#undef USE_I2C +#undef USE_SPI + +// Some dummys +#define TARGET_FLASH_SIZE 2048 + +#define LED_STRIP_TIMER 1 +#define SOFTSERIAL_1_TIMER 2 +#define SOFTSERIAL_2_TIMER 3 + +#define DEFIO_NO_PORTS + +extern uint32_t SystemCoreClock; + +#define U_ID_0 0 +#define U_ID_1 1 +#define U_ID_2 2 + +typedef struct +{ + void* dummy; +} TIM_TypeDef; + +typedef struct +{ + void* dummy; +} TIM_OCInitTypeDef; + +typedef struct { + void* dummy; +} DMA_TypeDef; + +typedef struct { + void* dummy; +} DMA_Channel_TypeDef; + +typedef struct +{ + void* dummy; +} SPI_TypeDef; + +typedef struct +{ + void* dummy; +} I2C_TypeDef; + +typedef enum {RESET = 0, SET = !RESET} FlagStatus, ITStatus; +typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState; +typedef enum {TEST_IRQ = 0 } IRQn_Type; +typedef enum { + EXTI_Trigger_Rising = 0x08, + EXTI_Trigger_Falling = 0x0C, + EXTI_Trigger_Rising_Falling = 0x10 +} EXTITrigger_TypeDef; + +typedef struct +{ + uint32_t IDR; + uint32_t ODR; + uint32_t BSRR; + uint32_t BRR; +} GPIO_TypeDef; + +#define GPIOA_BASE ((intptr_t)0x0001) + +typedef struct +{ + uint32_t dummy; +} USART_TypeDef; + +#define USART1 ((USART_TypeDef *)0x0001) +#define USART2 ((USART_TypeDef *)0x0002) +#define USART3 ((USART_TypeDef *)0x0003) +#define USART4 ((USART_TypeDef *)0x0004) +#define USART5 ((USART_TypeDef *)0x0005) +#define USART6 ((USART_TypeDef *)0x0006) +#define USART7 ((USART_TypeDef *)0x0007) +#define USART8 ((USART_TypeDef *)0x0008) + +#define UART4 ((USART_TypeDef *)0x0004) +#define UART5 ((USART_TypeDef *)0x0005) +#define UART7 ((USART_TypeDef *)0x0007) +#define UART8 ((USART_TypeDef *)0x0008) + +typedef enum +{ + SITL_SIM_NONE, + SITL_SIM_REALFLIGHT, + SITL_SIM_XPLANE, +} SitlSim_e; + +bool lockMainPID(void); +void unlockMainPID(void); +void parseArguments(int argc, char *argv[]); +char *strnstr(const char *s, const char *find, size_t slen); diff --git a/src/main/target/common.h b/src/main/target/common.h index 2365be9671..2bcfe0acc5 100644 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -183,6 +183,12 @@ #define USE_SIMULATOR #define USE_PITOT_VIRTUAL +#define USE_FAKE_BATT_SENSOR +#define USE_PITOT_FAKE +#define USE_IMU_FAKE +#define USE_FAKE_BARO +#define USE_FAKE_MAG +#define USE_GPS_FAKE //Designed to free space of F722 and F411 MCUs #if (MCU_FLASH_SIZE > 512) diff --git a/src/main/target/common_post.h b/src/main/target/common_post.h index 30b6331a60..6f32e76184 100644 --- a/src/main/target/common_post.h +++ b/src/main/target/common_post.h @@ -58,7 +58,7 @@ extern uint8_t __config_end; #define USE_ARM_MATH // try to use FPU functions -#if defined(SIMULATOR_BUILD) || defined(UNIT_TEST) +#if defined(SITL_BUILD) || defined(UNIT_TEST) // This feature uses 'arm_math.h', which does not exist for x86. #undef USE_DYNAMIC_FILTERS #undef USE_ARM_MATH @@ -85,7 +85,9 @@ extern uint8_t __config_end; #endif -#if defined(CONFIG_IN_RAM) || defined(CONFIG_IN_EXTERNAL_FLASH) +#endif + +#if defined(CONFIG_IN_RAM) || defined(CONFIG_IN_FILE) || defined(CONFIG_IN_EXTERNAL_FLASH) #ifndef EEPROM_SIZE #define EEPROM_SIZE 8192 #endif diff --git a/src/main/target/link/sitl.ld b/src/main/target/link/sitl.ld new file mode 100644 index 0000000000..4053d05347 --- /dev/null +++ b/src/main/target/link/sitl.ld @@ -0,0 +1,21 @@ +SECTIONS { + /* BLOCK: on Windows (PE) output section must be page-aligned. Use 4-byte alignment otherwise */ + /* SUBALIGN: force 4-byte alignment of input sections for pg_registry. + Gcc defaults to 32 bytes; padding is then inserted between object files, breaking the init structure. */ + .pg_registry BLOCK( DEFINED(__section_alignment__) ? __section_alignment__ : 4 ) : SUBALIGN(4) + { + PROVIDE_HIDDEN (__pg_registry_start = . ); + PROVIDE_HIDDEN (___pg_registry_start = . ); + KEEP (*(.pg_registry)) + KEEP (*(SORT(.pg_registry.*))) + PROVIDE_HIDDEN (__pg_registry_end = . ); + PROVIDE_HIDDEN (___pg_registry_end = . ); + + PROVIDE_HIDDEN (__pg_resetdata_start = . ); + PROVIDE_HIDDEN (___pg_resetdata_start = . ); + KEEP (*(.pg_resetdata)) + PROVIDE_HIDDEN (__pg_resetdata_end = . ); + PROVIDE_HIDDEN (___pg_resetdata_end = . ); + } +} +INSERT AFTER .text; diff --git a/src/utils/compiler.rb b/src/utils/compiler.rb index dc44611426..29b8f10418 100644 --- a/src/utils/compiler.rb +++ b/src/utils/compiler.rb @@ -30,7 +30,7 @@ require 'rbconfig' require 'shellwords' class Compiler - def initialize + def initialize(use_host_gcc) # Look for the compiler in PATH manually, since there # are some issues with the built-in search by spawn() # on Windows if PATH contains spaces. @@ -38,7 +38,11 @@ class Compiler dirs = ((ENV["CPP_PATH"] || "") + File::PATH_SEPARATOR + (ENV["PATH"] || "")).split(File::PATH_SEPARATOR) bin = ENV["SETTINGS_CXX"] if bin.empty? - bin = "arm-none-eabi-g++" + if use_host_gcc + bin = "g++" + else + bin = "arm-none-eabi-g++" + end end dirs.each do |dir| p = File.join(dir, bin) diff --git a/src/utils/settings.rb b/src/utils/settings.rb index e0b7a75898..8fdf8e9288 100755 --- a/src/utils/settings.rb +++ b/src/utils/settings.rb @@ -274,12 +274,12 @@ end OFF_ON_TABLE = Hash["name" => "off_on", "values" => ["OFF", "ON"]] class Generator - def initialize(src_root, settings_file, output_dir) + def initialize(src_root, settings_file, output_dir, use_host_gcc) @src_root = src_root @settings_file = settings_file @output_dir = output_dir || File.dirname(settings_file) - @compiler = Compiler.new + @compiler = Compiler.new(use_host_gcc) @count = 0 @max_name_length = 0 @@ -1130,7 +1130,7 @@ class Generator end def usage - puts "Usage: ruby #{__FILE__} [--json ]" + puts "Usage: ruby #{__FILE__} [--use_host_gcc] [--json ]" end if __FILE__ == $0 @@ -1148,11 +1148,13 @@ if __FILE__ == $0 opts = GetoptLong.new( [ "--output-dir", "-o", GetoptLong::REQUIRED_ARGUMENT ], [ "--help", "-h", GetoptLong::NO_ARGUMENT ], + [ "--use_host_gcc", "-g", GetoptLong::REQUIRED_ARGUMENT], [ "--json", "-j", GetoptLong::REQUIRED_ARGUMENT ], ) jsonFile = nil output_dir = nil + use_host_gcc = nil opts.each do |opt, arg| case opt @@ -1161,12 +1163,14 @@ if __FILE__ == $0 when "--help" usage() exit(0) + when "--use_host_gcc" + use_host_gcc = true when "--json" jsonFile = arg end end - gen = Generator.new(src_root, settings_file, output_dir) + gen = Generator.new(src_root, settings_file, output_dir, use_host_gcc) if jsonFile gen.write_json(jsonFile) From a39b0a309a906f19ac5991a1885bf17b53b7c3fe Mon Sep 17 00:00:00 2001 From: Scavanger Date: Tue, 24 Jan 2023 10:14:14 -0300 Subject: [PATCH 008/130] Formatting --- cmake/sitl.cmake | 2 +- docs/SITL/SITL.md | 8 ++++---- src/main/config/config_streamer_file.c | 2 +- src/main/io/gps_fake.c | 2 +- src/main/sensors/battery_sensor_fake.c | 2 +- src/main/target/SITL/sim/realFlight.h | 2 +- src/main/target/SITL/sim/simple_soap_client.h | 2 +- src/main/target/SITL/sim/xplane.h | 2 +- 8 files changed, 11 insertions(+), 11 deletions(-) diff --git a/cmake/sitl.cmake b/cmake/sitl.cmake index ba7448623c..e66c7a9e5d 100644 --- a/cmake/sitl.cmake +++ b/cmake/sitl.cmake @@ -140,4 +140,4 @@ function (target_sitl name) EXCLUDE_FROM_ALL 1 EXCLUDE_FROM_DEFAULT_BUILD 1) endif() -endfunction() \ No newline at end of file +endfunction() diff --git a/docs/SITL/SITL.md b/docs/SITL/SITL.md index ebc4696614..660da06f26 100644 --- a/docs/SITL/SITL.md +++ b/docs/SITL/SITL.md @@ -1,6 +1,6 @@ # SITL -![INAV-SIM-OSD](/assetes/INAV-SIM-OSD.png) +![INAV-SIM-OSD](assetes/INAV-SIM-OSD.png) ## ATTENTION! SITL is currently still under development, its use is still a bit cumbersome. @@ -46,7 +46,7 @@ The following sensors are emulated: - barometer - Battery (current and voltage), depending on simulator -![SITL-Fake-Sensors](/assets/SITL-Fake-Sensors.png) +![SITL-Fake-Sensors](assets/SITL-Fake-Sensors.png) Magnetometer (compass) is not yet supported, therefore no support for copters. @@ -59,7 +59,7 @@ To connect the Configurator to SITL: Select TCP and connect to ```127.0.0.1:5760 The assignment and status of user UART/TCP connections is displayed on the console. -![STL-Output](/assets/SITL-UART-TCP-Connecion.png) +![STL-Output](assets/SITL-UART-TCP-Connecion.png) All other interfaces (I2C, SPI, etc.) are not emulated. @@ -73,7 +73,7 @@ Please use the linked version, which has a smaller buffer, otherwise the control ### Example SBUS: For this you need a FT232 module. With FT-Prog (https://ftdichip.com/utilities/) the signals can be inverted: Devices->Scan and Parse, then Hardware Specific -> Invert RS232 Signals -> Invert RXD. -![SITL-SBUS-FT232](/assets/SITL-SBUS-FT232.png) +![SITL-SBUS-FT232](assets/SITL-SBUS-FT232.png) For SBUS, the command line arguments of the python script are: ```python tcp_serial_redirect.py --parity E --stopbits 2 -c 127.0.0.1:[INAV-UART-PORT] COMXX 100000``` diff --git a/src/main/config/config_streamer_file.c b/src/main/config/config_streamer_file.c index 8fec837ce4..c3fdbba95c 100644 --- a/src/main/config/config_streamer_file.c +++ b/src/main/config/config_streamer_file.c @@ -102,4 +102,4 @@ int config_streamer_impl_write_word(config_streamer_t *c, config_streamer_buffer return 0; } -#endif \ No newline at end of file +#endif diff --git a/src/main/io/gps_fake.c b/src/main/io/gps_fake.c index e056ed5a3f..6d57489343 100644 --- a/src/main/io/gps_fake.c +++ b/src/main/io/gps_fake.c @@ -95,4 +95,4 @@ void gpsFakeSet( } } -#endif \ No newline at end of file +#endif diff --git a/src/main/sensors/battery_sensor_fake.c b/src/main/sensors/battery_sensor_fake.c index 9c2ad69d6c..745d5273d0 100644 --- a/src/main/sensors/battery_sensor_fake.c +++ b/src/main/sensors/battery_sensor_fake.c @@ -55,4 +55,4 @@ uint16_t fakeBattSensorGetAmerperage(void) return fakeAmerperage; } -#endif \ No newline at end of file +#endif diff --git a/src/main/target/SITL/sim/realFlight.h b/src/main/target/SITL/sim/realFlight.h index f93ab49f48..af34c2c524 100644 --- a/src/main/target/SITL/sim/realFlight.h +++ b/src/main/target/SITL/sim/realFlight.h @@ -26,4 +26,4 @@ #define RF_MAX_PWM_OUTS 12 -bool simRealFlightInit(char* ip, uint8_t* mapping, uint8_t mapCount, bool imu); \ No newline at end of file +bool simRealFlightInit(char* ip, uint8_t* mapping, uint8_t mapCount, bool imu); diff --git a/src/main/target/SITL/sim/simple_soap_client.h b/src/main/target/SITL/sim/simple_soap_client.h index 5b97a595a3..35f2299e1d 100644 --- a/src/main/target/SITL/sim/simple_soap_client.h +++ b/src/main/target/SITL/sim/simple_soap_client.h @@ -43,4 +43,4 @@ bool soapClientConnect(soap_client_t *client, const char *address, int port); void soapClientClose(soap_client_t *client); void soapClientSendRequestVa(soap_client_t *client, const char* action, const char *fmt, va_list va); void soapClientSendRequest(soap_client_t *client, const char* action, const char *fmt, ...); -char* soapClientReceive(soap_client_t *client); \ No newline at end of file +char* soapClientReceive(soap_client_t *client); diff --git a/src/main/target/SITL/sim/xplane.h b/src/main/target/SITL/sim/xplane.h index 04d8c53a7a..1777a30af2 100644 --- a/src/main/target/SITL/sim/xplane.h +++ b/src/main/target/SITL/sim/xplane.h @@ -26,4 +26,4 @@ #define XP_MAX_PWM_OUTS 4 -bool simXPlaneInit(char* ip, int port, uint8_t* mapping, uint8_t mapCount, bool imu); \ No newline at end of file +bool simXPlaneInit(char* ip, int port, uint8_t* mapping, uint8_t mapCount, bool imu); From 09a2e4bd51b153f2d666610355b77c54d9a78fdf Mon Sep 17 00:00:00 2001 From: Scavanger Date: Tue, 24 Jan 2023 10:17:13 -0300 Subject: [PATCH 009/130] Typo --- docs/SITL/SITL.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/SITL/SITL.md b/docs/SITL/SITL.md index 660da06f26..f2fb492ac6 100644 --- a/docs/SITL/SITL.md +++ b/docs/SITL/SITL.md @@ -1,6 +1,6 @@ # SITL -![INAV-SIM-OSD](assetes/INAV-SIM-OSD.png) +![INAV-SIM-OSD](assets/INAV-SIM-OSD.png) ## ATTENTION! SITL is currently still under development, its use is still a bit cumbersome. From 3f750f28bb39ae6c4a3091509c6ff6f85cc543ab Mon Sep 17 00:00:00 2001 From: Scavanger Date: Tue, 24 Jan 2023 10:40:16 -0300 Subject: [PATCH 010/130] Move FAKE sensor defs --- src/main/fc/fc_msp.c | 4 ++++ src/main/sensors/pitotmeter.c | 4 ++++ src/main/target/SITL/target.h | 6 +++++- src/main/target/common.h | 5 ----- 4 files changed, 13 insertions(+), 6 deletions(-) diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 84a3aede8c..2c547b28b7 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -3562,11 +3562,15 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu sbufAdvance(src, sizeof(uint16_t) * XYZ_AXIS_COUNT); } +#if defined(USE_FAKE_BATT_SENSOR) if (SIMULATOR_HAS_OPTION(HITL_EXT_BATTERY_VOLTAGE)) { fakeBattSensorSetVbat(sbufReadU8(src) * 10); } else { +#endif fakeBattSensorSetVbat((uint16_t)(SIMULATOR_FULL_BATTERY * 10.0f)); +#if defined(USE_FAKE_BATT_SENSOR) } +#endif if (SIMULATOR_HAS_OPTION(HITL_AIRSPEED)) { simulatorData.airSpeed = sbufReadU16(src); diff --git a/src/main/sensors/pitotmeter.c b/src/main/sensors/pitotmeter.c index 29418e3ec0..eb470cbc40 100644 --- a/src/main/sensors/pitotmeter.c +++ b/src/main/sensors/pitotmeter.c @@ -211,8 +211,10 @@ STATIC_PROTOTHREAD(pitotThread) float airSpeed; if (SIMULATOR_HAS_OPTION(HITL_AIRSPEED)) { airSpeed = simulatorData.airSpeed; +#if defined(USE_PITOT_FAKE) } else if (pitotmeterConfig()->pitot_hardware == PITOT_FAKE) { airSpeed = fakePitotGetAirspeed(); +#endif } else { airSpeed = 0; } @@ -244,8 +246,10 @@ STATIC_PROTOTHREAD(pitotThread) #ifdef USE_SIMULATOR if (SIMULATOR_HAS_OPTION(HITL_AIRSPEED)) { pitot.airSpeed = simulatorData.airSpeed; +#if defined(USE_PITOT_FAKE) } else if (pitotmeterConfig()->pitot_hardware == PITOT_FAKE) { pitot.airSpeed = fakePitotGetAirspeed(); +#endif } else { pitot.airSpeed = 0; } diff --git a/src/main/target/SITL/target.h b/src/main/target/SITL/target.h index 4b4f209c5e..e3d5e5003a 100644 --- a/src/main/target/SITL/target.h +++ b/src/main/target/SITL/target.h @@ -57,10 +57,14 @@ #define DEFAULT_RX_FEATURE FEATURE_RX_MSP #define DEFAULT_FEATURES (FEATURE_GPS | FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT) -#define USE_IMU_FAKE #define USE_ADC #define USE_MAG #define USE_BARO +#define USE_PITOT_FAKE +#define USE_IMU_FAKE +#define USE_FAKE_BARO +#define USE_FAKE_MAG +#define USE_GPS_FAKE #undef USE_DASHBOARD #undef USE_TELEMETRY_LTM diff --git a/src/main/target/common.h b/src/main/target/common.h index 2bcfe0acc5..8b7c8b2897 100644 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -184,11 +184,6 @@ #define USE_SIMULATOR #define USE_PITOT_VIRTUAL #define USE_FAKE_BATT_SENSOR -#define USE_PITOT_FAKE -#define USE_IMU_FAKE -#define USE_FAKE_BARO -#define USE_FAKE_MAG -#define USE_GPS_FAKE //Designed to free space of F722 and F411 MCUs #if (MCU_FLASH_SIZE > 512) From aeada84a733228e63131f8f3a3e5f93ba36e2eb1 Mon Sep 17 00:00:00 2001 From: Scavanger Date: Tue, 24 Jan 2023 11:36:09 -0300 Subject: [PATCH 011/130] Fix build bug --- cmake/settings.cmake | 2 +- src/utils/settings.rb | 6 +++--- 2 files changed, 4 insertions(+), 4 deletions(-) mode change 100755 => 100644 src/utils/settings.rb diff --git a/cmake/settings.cmake b/cmake/settings.cmake index fc35c2e016..ba83773704 100644 --- a/cmake/settings.cmake +++ b/cmake/settings.cmake @@ -37,7 +37,7 @@ function(enable_settings exe name) OUTPUT ${output} COMMAND ${CMAKE_COMMAND} -E env CFLAGS="${cflags}" TARGET=${name} PATH="$ENV{PATH}" SETTINGS_CXX=${args_SETTINGS_CXX} - ${RUBY_EXECUTABLE} ${SETTINGS_GENERATOR} ${MAIN_DIR} ${SETTINGS_FILE} ${USE_HOST_GCC} -o "${dir}" + ${RUBY_EXECUTABLE} ${SETTINGS_GENERATOR} ${MAIN_DIR} ${SETTINGS_FILE} -o "${dir}" ${USE_HOST_GCC} DEPENDS ${SETTINGS_GENERATOR} ${SETTINGS_FILE} ) set(${args_OUTPUTS} ${output} PARENT_SCOPE) diff --git a/src/utils/settings.rb b/src/utils/settings.rb old mode 100755 new mode 100644 index 8fdf8e9288..f10248cce2 --- a/src/utils/settings.rb +++ b/src/utils/settings.rb @@ -1148,8 +1148,8 @@ if __FILE__ == $0 opts = GetoptLong.new( [ "--output-dir", "-o", GetoptLong::REQUIRED_ARGUMENT ], [ "--help", "-h", GetoptLong::NO_ARGUMENT ], - [ "--use_host_gcc", "-g", GetoptLong::REQUIRED_ARGUMENT], [ "--json", "-j", GetoptLong::REQUIRED_ARGUMENT ], + [ "--use_host_gcc", "-g", GetoptLong::NO_ARGUMENT ] ) jsonFile = nil @@ -1163,10 +1163,10 @@ if __FILE__ == $0 when "--help" usage() exit(0) - when "--use_host_gcc" - use_host_gcc = true when "--json" jsonFile = arg + when "--use_host_gcc" + use_host_gcc = true end end From 900cf60ce36a50f3368b6fd60f6f14fb69a67b39 Mon Sep 17 00:00:00 2001 From: Scavanger Date: Tue, 24 Jan 2023 15:11:23 -0300 Subject: [PATCH 012/130] Delete setting_generate.c/h --- src/main/fc/settings_generated.c | 1697 ----------------------- src/main/fc/settings_generated.h | 2209 ------------------------------ 2 files changed, 3906 deletions(-) delete mode 100644 src/main/fc/settings_generated.c delete mode 100644 src/main/fc/settings_generated.h diff --git a/src/main/fc/settings_generated.c b/src/main/fc/settings_generated.c deleted file mode 100644 index da2700a955..0000000000 --- a/src/main/fc/settings_generated.c +++ /dev/null @@ -1,1697 +0,0 @@ -// This file has been automatically generated by utils/settings.rb -// Don't make any modifications to it. They will be lost. - -#include "platform.h" -#include "config/parameter_group_ids.h" -#include "fc/settings.h" -#include "sensors/gyro.h" -#include "fc/config.h" -#include "sensors/acceleration.h" -#include "sensors/rangefinder.h" -#include "sensors/opflow.h" -#include "sensors/compass.h" -#include "sensors/barometer.h" -#include "sensors/pitotmeter.h" -#include "rx/rx.h" -#include "rx/spektrum.h" -#include "blackbox/blackbox.h" -#include "flight/mixer.h" -#include "flight/failsafe.h" -#include "sensors/boardalignment.h" -#include "sensors/battery_config_structs.h" -#include "sensors/battery_config_structs.h" -#include "flight/servos.h" -#include "fc/controlrate_profile_config_struct.h" -#include "io/serial.h" -#include "flight/imu.h" -#include "config/general_settings.h" -#include "fc/rc_controls.h" -#include "flight/pid.h" -#include "navigation/navigation.h" -#include "io/osd.h" -#include "drivers/osd.h" -#include "io/osd_common.h" -#include "fc/config.h" -#include "fc/rc_modes.h" -#include "fc/stats.h" -#include "common/time.h" -#include "drivers/display.h" -#include "common/log.h" -#include "io/smartport_master.h" -#include "io/osd_dji_hd.h" -#include "fc/config.h" -#include "flight/power_limits.h" -#pragma GCC diagnostic ignored "-Wunused-const-variable" -const pgn_t settingsPgn[] = { - PG_GYRO_CONFIG, - PG_ADC_CHANNEL_CONFIG, - PG_ACCELEROMETER_CONFIG, - PG_RANGEFINDER_CONFIG, - PG_OPFLOW_CONFIG, - PG_COMPASS_CONFIG, - PG_BAROMETER_CONFIG, - PG_PITOTMETER_CONFIG, - PG_RX_CONFIG, - PG_BLACKBOX_CONFIG, - PG_MOTOR_CONFIG, - PG_FAILSAFE_CONFIG, - PG_BOARD_ALIGNMENT, - PG_BATTERY_METERS_CONFIG, - PG_BATTERY_PROFILES, - PG_MIXER_CONFIG, - PG_REVERSIBLE_MOTORS_CONFIG, - PG_SERVO_CONFIG, - PG_CONTROL_RATE_PROFILES, - PG_SERIAL_CONFIG, - PG_IMU_CONFIG, - PG_ARMING_CONFIG, - PG_GENERAL_SETTINGS, - PG_GPS_CONFIG, - PG_RC_CONTROLS_CONFIG, - PG_PID_PROFILE, - PG_PID_AUTOTUNE_CONFIG, - PG_POSITION_ESTIMATION_CONFIG, - PG_NAV_CONFIG, - PG_OSD_CONFIG, - PG_OSD_COMMON_CONFIG, - PG_SYSTEM_CONFIG, - PG_MODE_ACTIVATION_OPERATOR_CONFIG, - PG_STATS_CONFIG, - PG_TIME_CONFIG, - PG_DISPLAY_CONFIG, - PG_LOG_CONFIG, - PG_SMARTPORT_MASTER_CONFIG, - PG_DJI_OSD_CONFIG, - PG_BEEPER_CONFIG, - PG_POWER_LIMITS_CONFIG, -}; -const uint8_t settingsPgnCounts[] = { - 16, - 4, - 11, - 2, - 3, - 13, - 2, - 3, - 18, - 3, - 5, - 12, - 3, - 10, - 28, - 5, - 3, - 7, - 22, - 1, - 9, - 4, - 1, - 7, - 8, - 90, - 3, - 23, - 89, - 84, - 1, - 3, - 1, - 4, - 2, - 1, - 2, - 2, - 7, - 3, - 3, -}; -static const uint8_t settingNamesWords[] = { - 0x70,0x6c, /* "nav" */ - 0x3,0x5c, /* "fw" */ - 0xf,0x99, /* "osd" */ - 0x0,0xd1, /* "mc" */ - 0x82,0x41,0xa1, /* "rate" */ - 0x40,0xd0,0xe0, /* "max" */ - 0x10, /* "p" */ - 0x6,0x43,0x70, /* "yaw" */ - 0x25,0xc1,0xb0, /* "inav" */ - 0x1a,0x97, /* "min" */ - 0x2,0x9,0xa0,0xd0, /* "pitch" */ - 0x0,0xb0,0x32,0x68, /* "alarm" */ - 0x18,0x96,0xa6,0x80, /* "limit" */ - 0x64,0xc, /* "lpf" */ - 0xd, /* "z" */ - 0x1,0x81,0xab,0x86,0x80, /* "launch" */ - 0x10, /* "d" */ - 0x12,0x7b,0x18, /* "roll" */ - 0x3,0x5,0x2c,0x98,0x4c,0x50, /* "failsafe" */ - 0x1e,0x13, /* "gps" */ - 0x2,0x34, /* "hz" */ - 0x4, /* "i" */ - 0x82,0xf,0x98, /* "pos" */ - 0x2,0xe3,0xb0,0xa0, /* "angle" */ - 0xa2,0x5a,0x50, /* "time" */ - 0x5c, /* "w" */ - 0x18,0xc8, /* "xy" */ - 0x25,0x44, /* "rth" */ - 0x0,0x85,0x9,0x4,0x17,0x10, /* "deadband" */ - 0x7,0xcc,0x9e, /* "gyro" */ - 0x9,0xdd,0x34,0x1a, /* "switch" */ - 0x1,0x4c,0xc0,0xa0, /* "type" */ - 0x21,0x58,0x1c, /* "delay" */ - 0x81,0x2d,0xa8, /* "imu" */ - 0x1a,0x13, /* "mag" */ - 0x82,0x53,0x9a, /* "rssi" */ - 0x41,0x38,0x14,0xa4, /* "speed" */ - 0x5,0x11,0x27,0xd2,0x8c,0x28, /* "throttle" */ - 0x2,0x31, /* "acc" */ - 0x80,0x28,0x48, /* "ahi" */ - 0x2,0xc4,0x9d,0xc0, /* "align" */ - 0x1a,0x2,0xe7,0x15,0x80, /* "channel" */ - 0x1d,0x65,0x22,0xba,0x80, /* "current" */ - 0x61,0x6c,0x56, /* "level" */ - 0x2,0x88,0x90, /* "thr" */ - 0x3,0x5a,0x3c, /* "auto" */ - 0x9,0x71,0x12,0x30,0xd1,0xf2, /* "indicator" */ - 0x3,0x42,0xea,0x85,0x80, /* "manual" */ - 0x6b,0xc8,0x50, /* "mode" */ - 0x4c,0xb2,0xb3, /* "servo" */ - 0xc1,0x42,0xb6,0x0, /* "temp" */ - 0xb0, /* "v" */ - 0x2,0xca,0x26,0x95,0x21, /* "altitude" */ - 0x40,0x20,0xc9,0xe0, /* "baro" */ - 0x14,0x82,0xb4,0xb8,0xe0, /* "braking" */ - 0x2e,0x20,0xf0, /* "expo" */ - 0x20,0x32,0x25,0xc3,0x22, /* "hardware" */ - 0x81,0xaf,0xa3,0xe4, /* "motor" */ - 0x9,0xc, /* "rc" */ - 0x14,0x44,0x8b,0x34,0x3d,0x84, /* "threshold" */ - 0x5,0x84,0x1a, /* "vbat" */ - 0x2,0xc5,0x60, /* "vel" */ - 0x2c,0xf6,0x50,0x27,0x28, /* "voltage" */ - 0x5,0x59,0x4e,0x80, /* "burst" */ - 0x22,0x67,0x40,0xb8,0x65, /* "distance" */ - 0x1,0x32,0xe0,0xb5,0x23,0x98, /* "dynamics" */ - 0x11,0x52, /* "hud" */ - 0x1,0x81,0x71, /* "land" */ - 0x0,0xf3,0x1a,0x65,0xa0, /* "offset" */ - 0x20,0xfb,0x96,0x40, /* "power" */ - 0x9d,0x3,0x49, /* "stats" */ - 0x82,0xb3,0x28, /* "use" */ - 0x2f,0x0, /* "wp" */ - 0x5,0x94, /* "alt" */ - 0x0,0x9e,0xf9,0xd0, /* "boost" */ - 0x3,0x62,0x5a,0x20, /* "climb" */ - 0xd,0xee,0xa4,0x9e,0xc0, /* "control" */ - 0x11,0x49, /* "dji" */ - 0x1,0x32,0xe0, /* "dyn" */ - 0x19,0x2c,0xa1,0x64, /* "filter" */ - 0x7,0x5,0xa5, /* "name" */ - 0x4,0xc6,0x16,0x14, /* "scale" */ - 0x13,0x49,0xa,0x20,0xc8, /* "sidebar" */ - 0x13,0x7d,0x64,0x32, /* "source" */ - 0x82,0x89,0x69,0x5f,0x5a, /* "timeout" */ - 0x3,0x0, /* "x" */ - 0xc8, /* "y" */ - 0x34,0x59,0x3c, /* "zero" */ - 0x1b,0x20, /* "3d" */ - 0x2,0x41, /* "adc" */ - 0x80,0x29,0x94,0xe0,0x52,0x90, /* "airspeed" */ - 0x2,0xd,0x28,0x59,0x64, /* "battery" */ - 0x3,0xb,0x4b,0x20, /* "camera" */ - 0x80,0x61,0x80,0x46,0x9a,0x64, /* "capacity" */ - 0x3,0x20, /* "cd" */ - 0x6,0x56,0x30, /* "cell" */ - 0x3,0x2b,0xa8,0x59, /* "center" */ - 0x0,0x6f,0x6c, /* "comp" */ - 0x0,0x39,0x55,0x33,0x28, /* "cruise" */ - 0x7,0x5a,0x3c,0xc6, /* "cutoff" */ - 0x1,0x6,0xd0, /* "dcm" */ - 0x11,0x33,0xc,0x9a, /* "disarm" */ - 0x2,0x50,0xb2,0x68, /* "dterm" */ - 0xa,0xe2, /* "end" */ - 0x0,0xb3,0x18, /* "esc" */ - 0xc,0x60, /* "ff" */ - 0x24,0x8c,0x28, /* "idle" */ - 0x13,0x42,0xc9,0xa0, /* "iterm" */ - 0x69,0x68,0x59, /* "meter" */ - 0x2,0x17,0x68, /* "pwm" */ - 0x2a,0xe4,0xd0, /* "unit" */ - 0x1,0x18,0xca,0xc0, /* "accel" */ - 0x4,0x63,0x38,0x52,0xe0, /* "accgain" */ - 0x4,0x63,0xd1,0x64,0xf0, /* "acczero" */ - 0x5,0xd4,0x49,0xe4,0x1b,0x26,0x99, /* "antigravity" */ - 0x0,0x6b,0x47,0xd2,0xae,0x28, /* "autotune" */ - 0x4,0x17,0x2c, /* "bank" */ - 0x2,0x29,0x60,0x59, /* "beeper" */ - 0x0,0x4c,0x8,0xd6,0x27,0xe0, /* "blackbox" */ - 0x2,0x78,0x64,0x40, /* "board" */ - 0xc,0x2c, /* "cal" */ - 0x1,0x4,0xd0, /* "dbm" */ - 0x10,0xb4,0x28,0xe8, /* "detect" */ - 0x2,0xb8,0xb2,0x3e, /* "energy" */ - 0x40,0x82,0x1c, /* "hdg" */ - 0x8,0x28,0x48,0x97,0x1c, /* "heading" */ - 0x8,0x7b,0x8, /* "hold" */ - 0x4,0xba,0xc5,0x95,0xa,0x40, /* "inverted" */ - 0x30,0x2e,0x22,0x5c,0x70, /* "landing" */ - 0x34,0x27,0x38,0x52,0xe0, /* "maggain" */ - 0x34,0x27,0xd1,0x64,0xf0, /* "magzero" */ - 0x34,0x29,0x70, /* "main" */ - 0x1a,0x19,0x1d,0x2e, /* "margin" */ - 0x3,0xe0,0x66,0x3e,0xe0, /* "opflow" */ - 0x82,0x68,0x34,0x72,0x88,0x90, /* "pitch2thr" */ - 0x20,0x9a,0x3e,0x80, /* "pitot" */ - 0x84,0x8a,0x44,0x8e,0x8f,0x90, /* "predictor" */ - 0x26,0x39,0x3d,0x8c, /* "scroll" */ - 0x4,0xca,0xe9,0xa6,0x89,0xb2,0x69,0x90, /* "sensitivity" */ - 0x4c,0xb2,0x48,0x59,0x2c, /* "serialrx" */ - 0x2,0x6c,0x7d,0xc8,0xfb,0xb8, /* "slowdown" */ - 0x13,0x6a,0x68,0x80, /* "smith" */ - 0x4e,0xb2,0x30,0x46,0x50, /* "surface" */ - 0x51,0xf4,0xb, /* "total" */ - 0x1,0x48,0x4, /* "tpa" */ - 0x17,0x2a,0x4e,0x8a, /* "weight" */ - 0x0,0x22,0x7c,0xa8, /* "abort" */ - 0x0,0xa6,0x4d,0x79,0xa, /* "airmode" */ - 0x1,0x6,0x80, /* "bat" */ - 0x10,0x6a,0x40, /* "baud" */ - 0xd,0x5,0x1a, /* "check" */ - 0xc0,0x37,0xba,0x80, /* "cont" */ - 0x1b,0xe5,0x22,0x8e,0x89,0x7b, /* "correction" */ - 0x80,0x44,0xc8,0xa3,0xa2,0x5e,0xe0, /* "direction" */ - 0x11,0x33,0x80, /* "disp" */ - 0x8,0x99,0xd0, /* "dist" */ - 0x4,0x4d,0x8a, /* "dive" */ - 0x2,0x4d,0xf,0xa0, /* "dshot" */ - 0xb,0xb, /* "epv" */ - 0x0,0xc1,0x1d,0x1f,0x20, /* "factor" */ - 0x18,0x2c,0x61,0x1f,0x77, /* "falldown" */ - 0x0,0xc9,0x94,0xe8, /* "first" */ - 0x3,0x31,0xf7, /* "flow" */ - 0x1,0x9f,0x60, /* "fov" */ - 0x1c,0x29,0x70, /* "gain" */ - 0xf,0x20,0xd9,0x34,0xc8, /* "gravity" */ - 0x10, /* "h" */ - 0x4,0x5,0x86,0x25,0x60,0xc2,0xe0, /* "halfduplex" */ - 0x8,0x2a,0x4e,0x8a, /* "height" */ - 0x1,0xf,0x69, /* "home" */ - 0x40,0x93,0xb9,0xf2,0x28, /* "ignore" */ - 0x12,0xe1,0xb1,0x2e,0xd,0x12,0xf7, /* "inclination" */ - 0x1,0x2e,0xa1,0x65,0x60,0xb0, /* "interval" */ - 0xb,0x48, /* "ki" */ - 0x17,0x0, /* "kp" */ - 0x31,0xe7, /* "log" */ - 0x3,0x1e,0x9a,0x16,0x40, /* "loiter" */ - 0x63,0xee, /* "low" */ - 0x6,0x40,0xdc, /* "lpf2" */ - 0x3,0x43,0x3a,0x16,0x40, /* "master" */ - 0x68,0x70,0x16,0x50, /* "maxalt" */ - 0xd,0x4b,0x82,0xca, /* "minalt" */ - 0x1,0xa9,0x9c,0xd2,0xf7, /* "mission" */ - 0x1,0xaf,0x21,0x58, /* "model" */ - 0x7,0x3e,0x83,0x40, /* "notch" */ - 0x1e,0xe2, /* "one" */ - 0x82,0x1,0x70, /* "pan" */ - 0x20,0x90, /* "pi" */ - 0x41,0x24,0x9d,0x5a, /* "pidsum" */ - 0x8,0x49,0xe3,0x29,0x2b,0x22, /* "procedure" */ - 0x82,0x12,0x7d,0x1e,0x37,0xb0, /* "protocol" */ - 0x10,0x93,0xec,0x92,0x16,0x40, /* "provider" */ - 0x90,0x48,0x9a,0xcc, /* "radius" */ - 0x12,0xb,0x8e,0x53,0x25,0xc4,0x2c, /* "rangefinder" */ - 0x81,0x22,0xb0,0x38, /* "relax" */ - 0x4,0x8b,0x30, /* "res" */ - 0x48,0xb3,0x2d, /* "reset" */ - 0x1,0x2c, /* "rx" */ - 0x2,0x61,0x31,0x50,0xf6,0x94, /* "safehome" */ - 0x13,0x68,0x65,0x48,0x3e,0x54, /* "smartport" */ - 0x4,0xda,0xf7,0xd1,0x9,0x71, /* "smoothing" */ - 0xc1,0x39,0x61,0x9c, /* "srxl2" */ - 0x4,0xe8,0x91,0xac, /* "stick" */ - 0x13,0xa6,0x58,0x50, /* "style" */ - 0x51,0x12,0x29, /* "three" */ - 0x41,0x44,0x49,0xf7, /* "throw" */ - 0x5,0x1e,0xc2,0xc8,0x2e,0x19, /* "tolerance" */ - 0x41,0x49,0x4,0x6b,0x10,0x46,0xb0, /* "trackback" */ - 0x52,0xef, /* "two" */ - 0x5,0x34, /* "tz" */ - 0xa,0xc2,0x89,0x65, /* "uptilt" */ - 0x1,0x59,0x94,0x60, /* "usec" */ - 0xb4,0xe0,0x40, /* "vspd" */ - 0x5c,0x32,0x72,0x5c,0x70, /* "warning" */ - 0x4,0x63,0x2b,0xb,0x20,0xd1,0xf2, /* "accelerator" */ - 0x0,0x48,0xaa,0xce,0x8d,0x2b,0xa8, /* "adjustment" */ - 0x0,0x91,0x55,0x9d,0x1a,0x57,0x52,0x60, /* "adjustments" */ - 0xb,0x18,0xfb, /* "allow" */ - 0x80,0x30,0x83,0x12,0x52, /* "applied" */ - 0x0,0x32,0x93,0xef,0x30, /* "arrows" */ - 0x6,0x94,0x70, /* "attn" */ - 0x3,0x5a,0x3d,0xa1,0xa2,0x46, /* "automatic" */ - 0x0,0xd6,0x8f,0xa4,0x92,0xd0, /* "autotrim" */ - 0x9,0x21,0x98, /* "bias" */ - 0x4,0xf9,0x10,0xb2,0x29, /* "bordered" */ - 0x0,0x29,0x14,0x2b,0x83,0xd2,0xea, /* "breakpoint" */ - 0x0,0x61,0x62,0x45,0x20,0xd1,0x2f,0x70, /* "calibration" */ - 0x6,0x56,0x32,0x60, /* "cells" */ - 0x1a,0x3,0x20,0x8e,0x85,0x90, /* "character" */ - 0x6,0xd9,0xcc, /* "cmss" */ - 0x3,0x7b,0x5a,0x17,0x10, /* "command" */ - 0x3,0x7b,0x8c,0x93, /* "config" */ - 0x80,0x6f,0x74,0xe8,0x17,0x50, /* "constant" */ - 0x3,0x7b,0xa9,0x27,0xb2,0x41,0xa1, /* "controlrate" */ - 0x40,0x37,0xbe,0x44,0x4b,0x83,0x42, /* "coordinate" */ - 0x80,0x72,0x4d,0x12,0x30,0xb0, /* "critical" */ - 0x3,0x93,0xe7,0x34,0x5,0x32,0x98, /* "crosshairs" */ - 0x7,0x59,0x58,0xa0, /* "curve" */ - 0x27,0x44,0xf7,0xce,0x9d,0x3e,0x64,0xfe,0x90,0xac,0xa0,0x7a,0xc8,0x1b,0xa8,0xd0, /* "d_boost_gyro_delta_lpf_hz" */ - 0x9,0xd1,0x3d,0xf3,0xa7,0x5a,0x1c,0x74,0x34,0xe8,0x46,0x32,0xb0,0xb2,0xd,0x12,0xf7, /* "d_boost_max_at_acceleration" */ - 0x0,0x85,0x15,0x4e, /* "debug" */ - 0x2,0x14,0x65,0x61,0x64,0x1a,0x25,0xee, /* "deceleration" */ - 0x1,0xa,0x34,0xb4,0x2c,0x98, /* "decimals" */ - 0x8,0x51,0xb0, /* "decl" */ - 0x4,0x28,0xd8,0x97,0x6,0x89,0x7b, /* "declination" */ - 0x80,0x42,0x98,0x35,0x65,0x26, /* "defaults" */ - 0x2,0x14,0xcc,0x28,0xe8,0x97,0xb8, /* "deflection" */ - 0x4,0x29,0xe4,0x52,0xcc, /* "degrees" */ - 0x4,0x2b,0x9e,0xd0, /* "denom" */ - 0x10,0xb6,0x48,0xca, /* "device" */ - 0x2,0x24,0xe9,0xa4, /* "digits" */ - 0xc0,0x44,0xcc,0xae,0x38,0x4e,0x50, /* "disengage" */ - 0x11,0x33,0x83,0x3,0x9e,0x99,0xf2,0x19,0x7b,0x3b,0xf4,0x4c,0x4b,0x96, /* "display_force_sw_blink" */ - 0x2,0x29,0x3d,0x1b,0xba,0x16,0x50,0xb2,0x70,0x68,0x97,0x1f,0xa4,0xac,0x83,0x44,0xbd,0xc0, /* "dji_cn_alternating_duration" */ - 0x22,0x93,0xda,0xcc,0xbd,0x70,0x5a,0x5e,0x99,0xf2,0xeb,0x4b,0x39,0x84,0xe5,0x98, /* "dji_use_name_for_messages" */ - 0x8,0xfb,0xb8, /* "down" */ - 0x4,0x9d, /* "dst" */ - 0x0,0x56,0x96,0x47, /* "emerg" */ - 0x1,0x5c,0x11,0x30,0xa4, /* "enabled" */ - 0x1,0x5c,0x67,0xc8,0x65, /* "enforce" */ - 0x1,0x60,0x80, /* "eph" */ - 0x18,0x33,0xa0, /* "fast" */ - 0xc,0x9c,0x14,0x9d,0xba,0x5c,0x7e,0x86,0xb4,0x7f,0x43,0x26, /* "fixed_wing_auto_arm" */ - 0x80,0xcc,0xc,0xb,0x27,0xb8, /* "flaperon" */ - 0x6,0x60,0x61,0x30, /* "flaps" */ - 0x19,0xf2,0x19, /* "force" */ - 0x40,0x68,0x58, /* "fpv" */ - 0x6,0xbf,0x53,0x42,0xc9,0xbd,0x62,0x5a,0x9a,0x76,0x74,0x48,0xd7,0xd8,0x3e,0x69,0xa2,0x5e,0xe0, /* "fw_iterm_limit_stick_position" */ - 0x1a,0xfd,0xa5,0x64,0xee,0x86,0x73,0x4c,0xe9,0xd8,0x26,0x83,0x47,0x4e,0x14,0xb8, /* "fw_turn_assist_pitch_gain" */ - 0x6,0xbf,0x69,0x59,0x3b,0xa1,0x9c,0xd3,0x3a,0x77,0x21,0xbf,0x4e,0x14,0xb8, /* "fw_turn_assist_yaw_gain" */ - 0x6,0xbf,0x72,0x1b,0xf5,0x34,0x2c,0x9b,0xd3,0x48,0xa5,0xd1,0x7a,0x20,0xb9,0x7d,0xb,0x8e,0xc2, /* "fw_yaw_iterm_freeze_bank_angle" */ - 0x80,0xe1,0x62,0x58,0x57, /* "galileo" */ - 0x80,0xe6,0x7c,0x86,0x50, /* "gforce" */ - 0x1e,0x49,0x20, /* "grid" */ - 0xf,0x99,0x3f,0xa1,0x75,0x13,0xd0,0xb1,0x21,0x9a,0x5c,0x7e,0xb2,0x6,0xea,0x34, /* "gyro_anti_aliasing_lpf_hz" */ - 0x3,0xe6,0x4f,0xe8,0x5d,0x44,0xf4,0x2c,0x48,0x66,0x97,0x1f,0xac,0x81,0xbb,0x4c,0xc0,0xa0, /* "gyro_anti_aliasing_lpf_type" */ - 0x40,0x66, /* "has" */ - 0x4,0x24,0xe8, /* "high" */ - 0x2,0x1e,0xd2,0xc1,0xe9,0x75, /* "homepoint" */ - 0x0,0x87,0xb5,0x2e,0x38, /* "homing" */ - 0x10,0xf9,0x27,0x4f,0x70, /* "horizon" */ - 0x10,0xf9,0x27,0x4f,0x75,0x2,0xc0, /* "horizontal" */ - 0x21,0xf6,0x2c, /* "hover" */ - 0x80,0x92, /* "id" */ - 0x1,0x2e,0xd,0xba,0x16,0x31,0xf7,0xe9,0xa,0x12,0x76,0x45,0x1a,0xde,0xe4,0xb8,0xe0, /* "inav_allow_dead_reckoning" */ - 0x4b,0x88,0x5c, /* "index" */ - 0x1,0x2e,0x2c,0xa8,0x90, /* "inertia" */ - 0x81,0x2e,0x4d, /* "init" */ - 0x0,0x97,0x4c, /* "ins" */ - 0xb,0x4b,0x18, /* "kill" */ - 0x6,0x4,0x45,0x60, /* "label" */ - 0x18,0x1c,0xbe,0xb4, /* "layout" */ - 0x3,0xa,0x6a, /* "left" */ - 0x1,0x89,0x72, /* "link" */ - 0xc0,0xc7,0xbe,0x14,0x4b,0x4a, /* "looptime" */ - 0x6,0x94,0x89,0xb, /* "median" */ - 0x80,0xd2,0xce,0x61,0x39, /* "message" */ - 0x40,0xd2,0xd1,0xf,0x20, /* "method" */ - 0x1a,0x92, /* "mid" */ - 0x1,0xa9,0x63,0x12, /* "milli" */ - 0x6,0xa7,0x0, /* "mix" */ - 0x6b,0xc8,0x5e,0xc8,0x2e,0x39,0x7a,0xc7,0x9d,0x23,0xeb,0xe0,0x59,0x6,0x8f,0x90, /* "mode_range_logic_operator" */ - 0x1a,0xf9,0x3d,0xc0, /* "moron" */ - 0x70,0x6d,0xd2,0xe2,0x92,0xf,0x43,0x26,0xa5,0xc7,0xec,0xc2,0x62,0xd3,0x20, /* "nav_extra_arming_safety" */ - 0x70,0x6d,0xd3,0x5f,0xa1,0x63,0x1f,0x7e,0xb4,0x2e,0xa8,0x59,0xda,0x22,0x5d,0x4b,0x87,0x22,0x86,0x65, /* "nav_fw_allow_manual_thr_increase" */ - 0x3,0x83,0x6e,0x9a,0xfd,0x83,0xe7,0xd4,0x10,0xfd,0x82,0x49,0x3a,0xb7,0xac,0x4b,0x53,0x40, /* "nav_fw_pos_hdg_pidsum_limit" */ - 0x38,0x36,0xe9,0xaf,0xd9,0xbc,0x32,0x4b,0x8f,0xd6,0xbe,0x8f,0x97,0x67,0x47,0xc0, /* "nav_fw_soaring_motor_stop" */ - 0xe,0xd,0xba,0x6b,0xf6,0xf0,0xed,0x24,0x11,0xad,0x2e,0x3f,0x42,0x31,0xd6,0x41,0x1e, /* "nav_fw_wp_tracking_accuracy" */ - 0x40,0xe0,0xdb,0xa6,0xbf,0x6f,0xe,0xd2,0x41,0x1a,0xd2,0xe3,0xf5,0xa1,0xc7,0x42,0xe3,0xb0,0xa0, /* "nav_fw_wp_tracking_max_angle" */ - 0x70,0x6d,0xd3,0x5f,0xb7,0x87,0x69,0x59,0x3b,0xb3,0x6b,0xdf,0x44,0x25,0xc7, /* "nav_fw_wp_turn_smoothing" */ - 0x3,0x83,0x6e,0xb4,0x38,0xed,0xb,0x29,0x5,0x2e,0xe9,0x9e,0xc6,0x3e,0xfd,0xb,0x28, /* "nav_max_terrain_follow_alt" */ - 0x7,0x6,0xdd,0x68,0xfa,0x29,0x5,0x69,0x71,0xfa,0x27,0xbe,0x74,0xe9,0x13,0x32,0xb8,0xe1,0x39,0x7b,0x38,0x14,0xa4, /* "nav_mc_braking_boost_disengage_speed" */ - 0x3,0x83,0x6e,0xb4,0x7d,0xb1,0x59,0xdc,0x67,0xa4,0xa1,0x64,0xde,0x86,0x94,0x2b,0xaa,0x1a,0x25,0xee, /* "nav_mc_vel_xy_dterm_attenuation" */ - 0x3,0x83,0x6e,0xb4,0x7d,0xb1,0x59,0xdc,0x67,0xa4,0xa1,0x64,0xde,0x86,0x94,0x2b,0xaa,0x1a,0x25,0xee,0xe9,0x5c,0x40, /* "nav_mc_vel_xy_dterm_attenuation_end" */ - 0x38,0x36,0xeb,0x47,0xdb,0x15,0x9d,0xc6,0x7a,0x4a,0x16,0x4d,0xe8,0x69,0x42,0xba,0xa1,0xa2,0x5e,0xee,0xce,0x81,0x95, /* "nav_mc_vel_xy_dterm_attenuation_start" */ - 0x0,0xe0,0xdb,0xad,0x1f,0x6c,0x56,0x77,0x19,0xe9,0x28,0x59,0x37,0xac,0x81,0xba,0x8d, /* "nav_mc_vel_xy_dterm_lpf_hz" */ - 0x1,0xc1,0xb7,0x5a,0x99,0xcd,0x2f,0x77,0x60,0xc0,0xb9,0xc5,0x97,0x64,0x59,0x96,0x80, /* "nav_mission_planner_reset" */ - 0x70,0x6d,0xd9,0x51,0x1d,0x1b,0x12,0xd1,0x74,0xc9,0x94,0xe9,0xd9,0xd0,0x27,0x2f,0x42,0xca,0x26,0x95,0x21, /* "nav_rth_climb_first_stage_altitude" */ - 0x40,0xe0,0xdb,0xb2,0xa2,0x3a,0x36,0x25,0xa2,0xe9,0x93,0x29,0xd3,0xb3,0xa0,0x4e,0x5e,0xb5,0xe4,0x28, /* "nav_rth_climb_first_stage_mode" */ - 0x1c,0x1b,0x76,0x54,0x47,0x46,0xc4,0xb4,0x5d,0x49,0xdc,0xf9,0x17,0xa5,0x69,0x64,0x70, /* "nav_rth_climb_ignore_emerg" */ - 0x38,0x36,0xed,0x66,0x5e,0xb5,0x24,0xa2,0x25,0xd3,0x3e,0x5d,0xb,0x28,0x87,0xb0,0x80, /* "nav_use_midthr_for_althold" */ - 0x70,0x6d,0xdb,0xc3,0xac,0x78,0x49,0xd7,0xbb,0xa2,0x7b,0xe8, /* "nav_wp_load_on_boot" */ - 0x7,0x6,0xdd,0xbc,0x3a,0xda,0xb2,0x89,0xeb,0x53,0x39,0xa5,0xee,0xea,0x5c,0x42,0xe0, /* "nav_wp_multi_mission_index" */ - 0xe,0x29, /* "neg" */ - 0xc0,0xe2,0xd6,0x92,0xb, /* "neutral" */ - 0x0,0xe7, /* "no" */ - 0x81,0xd5,0x68, /* "num" */ - 0x1e,0x63, /* "off" */ - 0x1,0xee, /* "on" */ - 0x3,0xe6,0x4e,0x8e,0x53,0x37,0x59,0x1e,0x99,0xf2,0x68,0x68, /* "osd_crsf_lq_format" */ - 0x7,0xcc,0x9d,0x2c,0xe8,0x96,0x86,0x89,0x7b,0xa7,0xdb,0xa5,0xc4,0xe8,0xde,0xd8,0x15,0xd3,0xd,0x12,0xf7, /* "osd_estimations_wind_compensation" */ - 0x1,0xf3,0x27,0x4e,0x67,0xc8,0x65,0xe8,0x70,0x99,0xf4,0x2c,0xc,0x9b,0xd6,0x87,0x0, /* "osd_gforce_axis_alarm_max" */ - 0x7c,0xc9,0xd3,0x99,0xf2,0x19,0x7a,0x1c,0x26,0x7d,0xb,0x3,0x26,0xf5,0xa9,0x70, /* "osd_gforce_axis_alarm_min" */ - 0x1f,0x32,0x75,0xf,0x69,0x7b,0x7,0xcd,0x34,0x4b,0xdd,0xd0,0xc9,0xbd,0x98,0xe4,0x52,0xb8, /* "osd_home_position_arm_screen" */ - 0xf,0x99,0x3a,0x8a,0x93,0xb2,0x9,0x3,0x2e,0x85,0x94,0xe9,0x12,0x63,0x16,0x45,0x70,0xcb,0xd2,0x26,0x70,0x60,0x73,0xda,0x25,0xa5, /* "osd_hud_radar_alt_difference_display_time" */ - 0x3,0xe6,0x4e,0xa2,0xa4,0xec,0x82,0x40,0xcb,0xa4,0x4c,0xe8,0x17,0xc,0xbd,0x22,0x67,0x6,0x7,0x3d,0xa2,0x5a,0x50, /* "osd_hud_radar_distance_display_time" */ - 0x3e,0x64,0xea,0x2a,0x4e,0xc8,0x24,0xc,0xbb,0x20,0xb8,0xe5,0xeb,0x43,0x80, /* "osd_hud_radar_range_max" */ - 0x3e,0x64,0xea,0x2a,0x4e,0xc8,0x24,0xc,0xbb,0x20,0xb8,0xe5,0xeb,0x52,0xe0, /* "osd_hud_radar_range_min" */ - 0x3e,0x64,0xeb,0xa,0x6a,0x76,0x69,0x21,0x44,0x19,0x76,0x63,0x93,0xd8,0xce,0xce,0x85,0x80, /* "osd_left_sidebar_scroll_step" */ - 0x1f,0x32,0x75,0xa1,0x47,0x6b,0x32,0x93,0xb0,0x91,0x46,0x99,0xa5,0xee, /* "osd_mah_used_precision" */ - 0x3,0xe6,0x4e,0xc1,0x95,0x9f,0x46,0xf2,0x17,0xa4,0x49,0xd3,0x49, /* "osd_plus_code_digits" */ - 0x81,0xf3,0x27,0x60,0xca,0xcf,0xa3,0x79,0xb,0xd9,0xa1,0xf2,0xa0, /* "osd_plus_code_short" */ - 0x1f,0x32,0x76,0x49,0x3a,0x29,0xd9,0xa4,0x85,0x10,0x65,0xd9,0x8e,0x4f,0x63,0x3b,0x3a,0x16,0x0, /* "osd_right_sidebar_scroll_step" */ - 0x7c,0xc9,0xd9,0xd0,0x34,0x9f,0x60,0x13,0x97,0xa1,0xad,0x1f,0xd9,0xdc,0x30,0xed,0x12,0xd2, /* "osd_stats_page_auto_swap_time" */ - 0x81,0xf3,0x27,0x67,0x74,0xd0,0x68,0xea,0x5c,0x44,0x8c,0x34,0x7c,0xa7,0xd0,0xb1,0x27,0x77,0x58,0x53,0x50, /* "osd_switch_indicators_align_left" */ - 0xf,0x99,0x3b,0x3c,0xce,0x85,0x6f,0x5b,0x33,0xf4,0x89,0x9c,0x18,0x1c,0xf6,0x89,0x69, /* "osd_system_msg_display_time" */ - 0x40,0xfa,0xd2,0x15,0xa0, /* "output" */ - 0x1f,0x62,0xca,0x49,0x21, /* "override" */ - 0x40,0xfb,0x16,0x52,0x49,0xb,0x30, /* "overrides" */ - 0x41,0x24, /* "pid" */ - 0x4,0x13,0x40, /* "pit" */ - 0x41,0x81,0xa1,0x9f,0x26, /* "platform" */ - 0x82,0xf,0x61,0x66, /* "poles" */ - 0x8,0x3e,0x69,0xa2,0x5e,0xe0, /* "position" */ - 0x42,0x45,0xc,0x9a, /* "prearm" */ - 0x8,0x48,0xa3,0x4c,0xd2,0xf7, /* "precision" */ - 0x2,0x12,0x2d,0x92,0x5b, /* "preview" */ - 0x82,0x12,0x79,0x92,0xc2, /* "profile" */ - 0x82,0x15,0x64,0xca, /* "pulse" */ - 0x8,0x5d,0xbc,0x19,0x5d,0x44,0x90,0xa7, /* "pwm2centideg" */ - 0x4,0x6a,0x16,0x26,0x99, /* "quality" */ - 0x4,0x82,0x40,0xc8, /* "radar" */ - 0x12,0x28,0x9e,0xfa, /* "reboot" */ - 0x2,0x45,0x19,0x53,0x62,0xc8, /* "receiver" */ - 0x12,0x28,0xdf,0x62,0xcb,0x20, /* "recovery" */ - 0x91,0x4c,0x59,0x15,0xc3,0x28, /* "reference" */ - 0x24,0x59,0xd0,0x32,0xa0, /* "restart" */ - 0x24,0x5b,0x16,0x53,0x28, /* "reverse" */ - 0x24,0x93,0xa2,0x80, /* "right" */ - 0x93,0x18, /* "rll" */ - 0x9,0x3e,0x81,0xa2,0x5e,0xe0, /* "rotation" */ - 0x49,0xf7, /* "row" */ - 0x4,0xa0,0xd0, /* "rpm" */ - 0x4c,0x26,0x28, /* "safe" */ - 0x26,0x1a,0x4c, /* "sats" */ - 0x13,0x10,0x66, /* "sbas" */ - 0x9,0x8a,0xb3, /* "sbus" */ - 0x4,0xd0,0x93,0x50,0x8f,0xbb, /* "shiftdown" */ - 0x81,0x36,0x3e,0x5, /* "slope" */ - 0x4,0xda,0x16,0x30, /* "small" */ - 0x13,0x6b,0xdf,0x44,0x38,0xb3,0x98, /* "smoothness" */ - 0x26,0xe9, /* "snr" */ - 0x2,0x6f,0xc,0x92,0xe3, /* "soaring" */ - 0x82,0x70,0x4b,0xab,0x0, /* "spinup" */ - 0x4e,0x43, /* "src" */ - 0x4,0xe8,0xf8, /* "stop" */ - 0x2,0x74,0x90, /* "str" */ - 0x27,0x49,0x15,0xc7,0xa2, /* "strength" */ - 0x1,0x3c,0xb8,0x60, /* "sync" */ - 0x9e,0x67,0x42,0xb4, /* "system" */ - 0x14,0xa,0x58, /* "tail" */ - 0xa,0x15,0x85,0x69,0x69,0x2c, /* "telemetry" */ - 0x82,0x89,0x65, /* "tilt" */ - 0x1,0x47,0xb8,0xa0, /* "tone" */ - 0xa3,0xe0,0x91,0xcc, /* "topics" */ - 0x14,0x92, /* "tri" */ - 0x41,0x49,0x25,0xa0, /* "trim" */ - 0xa8,0x98,0xfc, /* "ublox" */ - 0x2,0xae,0xc,0x9a,0x52, /* "unarmed" */ - 0x2,0xae,0x4d,0x26, /* "units" */ - 0xa,0xcc,0x27,0x28, /* "usage" */ - 0x2b,0x32,0xc8, /* "user" */ - 0x16,0x2b,0x1c,0x52, /* "velned" */ - 0x2,0xc5,0x63,0xc6,0x9a,0x64, /* "velocity" */ - 0x16,0x2c,0xa8,0x91,0x85,0x80, /* "vertical" */ - 0xb2,0x48,0x57, /* "video" */ - 0x82,0xe9,0x25,0x10, /* "width" */ - 0xb,0xa5,0xc4,0x1b,0xdb,0x0, /* "windcomp" */ - 0x5d,0x2e,0x25,0x60, /* "windup" */ - 0xb,0xbe,0x4b,0xc,0x9f,0x57,0x12,0x60, /* "workarounds" */ - 0xc6,0x74, /* "xyz" */ - 0x0,0x00 -}; -static const char wordSymbols[] = {'3','2','_',}; -const char * const table_acc_hardware[] = { - "NONE", - "AUTO", - "MPU6000", - "MPU6500", - "MPU9250", - "BMI160", - "ICM20689", - "BMI088", - "ICM42605", - "BMI270", - "FAKE", -}; -const char * const table_airmodeHandlingType[] = { - "STICK_CENTER", - "THROTTLE_THRESHOLD", - "STICK_CENTER_ONCE", -}; -const char * const table_alignment[] = { - "DEFAULT", - "CW0", - "CW90", - "CW180", - "CW270", - "CW0FLIP", - "CW90FLIP", - "CW180FLIP", - "CW270FLIP", -}; -const char * const table_autotune_rate_adjustment[] = { - "FIXED", - "LIMIT", - "AUTO", -}; -const char * const table_aux_operator[] = { - "OR", - "AND", -}; -const char * const table_baro_hardware[] = { - "NONE", - "AUTO", - "BMP085", - "MS5611", - "BMP280", - "MS5607", - "LPS25H", - "SPL06", - "BMP388", - "DPS310", - "B2SMPB", - "MSP", - "FAKE", -}; -const char * const table_bat_capacity_unit[] = { - "MAH", - "MWH", -}; -const char * const table_bat_voltage_source[] = { - "RAW", - "SAG_COMP", -}; -const char * const table_blackbox_device[] = { - "SERIAL", - "SPIFLASH", - "SDCARD", -}; -const char * const table_current_sensor[] = { - "NONE", - "ADC", - "VIRTUAL", - "FAKE", - "ESC", -}; -const char * const table_debug_modes[] = { - "NONE", - "AGL", - "FLOW_RAW", - "FLOW", - "ALWAYS", - "SAG_COMP_VOLTAGE", - "VIBE", - "CRUISE", - "REM_FLIGHT_TIME", - "SMARTAUDIO", - "ACC", - "NAV_YAW", - "PCF8574", - "DYN_GYRO_LPF", - "AUTOLEVEL", - "ALTITUDE", - "AUTOTRIM", - "AUTOTUNE", - "RATE_DYNAMICS", - "LANDING", -}; -const char * const table_direction[] = { - "RIGHT", - "LEFT", - "YAW", -}; -const char * const table_djiOsdTempSource[] = { - "ESC", - "IMU", - "BARO", -}; -const char * const table_djiRssiSource[] = { - "RSSI", - "CRSF_LQ", -}; -const char * const table_failsafe_procedure[] = { - "LAND", - "DROP", - "RTH", - "NONE", -}; -const char * const table_filter_type[] = { - "PT1", - "BIQUAD", -}; -const char * const table_filter_type_full[] = { - "PT1", - "BIQUAD", - "PT2", - "PT3", -}; -const char * const table_gps_dyn_model[] = { - "PEDESTRIAN", - "AIR_1G", - "AIR_4G", -}; -const char * const table_gps_provider[] = { - "NMEA", - "UBLOX", - "UBLOX7", - "MSP", - "FAKE", -}; -const char * const table_gps_sbas_mode[] = { - "AUTO", - "EGNOS", - "WAAS", - "MSAS", - "GAGAN", - "NONE", -}; -const char * const table_gyro_lpf[] = { - "256HZ", - "188HZ", - "98HZ", - "42HZ", - "20HZ", - "10HZ", -}; -const char * const table_imu_inertia_comp_method[] = { - "VELNED", - "TURNRATE", - "ADAPTIVE", -}; -const char * const table_iterm_relax[] = { - "OFF", - "RP", - "RPY", -}; -const char * const table_log_level[] = { - "ERROR", - "WARNING", - "INFO", - "VERBOSE", - "DEBUG", -}; -const char * const table_mag_hardware[] = { - "NONE", - "AUTO", - "HMC5883", - "AK8975", - "MAG3110", - "AK8963", - "IST8310", - "QMC5883", - "MPU9250", - "IST8308", - "LIS3MDL", - "MSP", - "RM3100", - "VCM5883", - "MLX90393", - "FAKE", -}; -const char * const table_motor_pwm_protocol[] = { - "STANDARD", - "ONESHOT125", - "MULTISHOT", - "BRUSHED", - "DSHOT150", - "DSHOT300", - "DSHOT600", -}; -const char * const table_nav_extra_arming_safety[] = { - "ON", - "ALLOW_BYPASS", -}; -const char * const table_nav_fw_wp_turn_smoothing[] = { - "OFF", - "ON", - "ON-CUT", -}; -const char * const table_nav_overrides_motor_stop[] = { - "OFF_ALWAYS", - "OFF", - "AUTO_ONLY", - "ALL_NAV", -}; -const char * const table_nav_rth_allow_landing[] = { - "NEVER", - "ALWAYS", - "FS_ONLY", -}; -const char * const table_nav_rth_alt_mode[] = { - "CURRENT", - "EXTRA", - "FIXED", - "MAX", - "AT_LEAST", - "AT_LEAST_LINEAR_DESCENT", -}; -const char * const table_nav_rth_climb_first[] = { - "OFF", - "ON", - "ON_FW_SPIRAL", -}; -const char * const table_nav_rth_climb_first_stage_modes[] = { - "AT_LEAST", - "EXTRA", -}; -const char * const table_nav_user_control_mode[] = { - "ATTI", - "CRUISE", -}; -const char * const table_nav_wp_mission_restart[] = { - "START", - "RESUME", - "SWITCH", -}; -const char * const table_off_on[] = { - "OFF", - "ON", -}; -const char * const table_opflow_hardware[] = { - "NONE", - "CXOF", - "MSP", - "FAKE", -}; -const char * const table_osdSpeedSource[] = { - "GROUND", - "3D", - "AIR", -}; -const char * const table_osd_ahi_style[] = { - "DEFAULT", - "LINE", -}; -const char * const table_osd_alignment[] = { - "LEFT", - "RIGHT", -}; -const char * const table_osd_crosshairs_style[] = { - "DEFAULT", - "AIRCRAFT", - "TYPE3", - "TYPE4", - "TYPE5", - "TYPE6", - "TYPE7", - "TYPE8", -}; -const char * const table_osd_crsf_lq_format[] = { - "TYPE1", - "TYPE2", - "TYPE3", -}; -const char * const table_osd_plus_code_short[] = { - "0", - "2", - "4", - "6", -}; -const char * const table_osd_sidebar_scroll[] = { - "NONE", - "ALTITUDE", - "SPEED", - "HOME_DISTANCE", -}; -const char * const table_osd_stats_energy_unit[] = { - "MAH", - "WH", -}; -const char * const table_osd_stats_min_voltage_unit[] = { - "BATTERY", - "CELL", -}; -const char * const table_osd_telemetry[] = { - "OFF", - "ON", - "TEST", -}; -const char * const table_osd_unit[] = { - "IMPERIAL", - "METRIC", - "METRIC_MPH", - "UK", - "GA", -}; -const char * const table_osd_video_system[] = { - "AUTO", - "PAL", - "NTSC", - "HDZERO", - "DJIWTF", -}; -const char * const table_output_mode[] = { - "AUTO", - "MOTORS", - "SERVOS", -}; -const char * const table_pidTypeTable[] = { - "NONE", - "PID", - "PIFF", - "AUTO", -}; -const char * const table_pitot_hardware[] = { - "NONE", - "AUTO", - "MS4525", - "ADC", - "VIRTUAL", - "FAKE", - "MSP", -}; -const char * const table_platform_type[] = { - "MULTIROTOR", - "AIRPLANE", - "HELICOPTER", - "TRICOPTER", - "ROVER", - "BOAT", -}; -const char * const table_rangefinder_hardware[] = { - "NONE", - "SRF10", - "VL53L0X", - "MSP", - "BENEWAKE", - "VL53L1X", - "US42", - "TOF10120_I2C", -}; -const char * const table_receiver_type[] = { - "NONE", - "SERIAL", - "MSP", -}; -const char * const table_reset_type[] = { - "NEVER", - "FIRST_ARM", - "EACH_ARM", -}; -const char * const table_rssi_source[] = { - "NONE", - "AUTO", - "ADC", - "CHANNEL", - "PROTOCOL", - "MSP", -}; -const char * const table_rth_trackback_mode[] = { - "OFF", - "ON", - "FS", -}; -const char * const table_safehome_usage_mode[] = { - "OFF", - "RTH", - "RTH_FS", -}; -const char * const table_serial_rx[] = { - "SPEK1024", - "SPEK2048", - "SBUS", - "SUMD", - "IBUS", - "JETIEXBUS", - "CRSF", - "FPORT", - "SBUS_FAST", - "FPORT2", - "SRXL2", - "GHST", - "MAVLINK", -}; -const char * const table_servo_protocol[] = { - "PWM", - "SBUS", - "SBUS_PWM", -}; -const char * const table_tristate[] = { - "AUTO", - "ON", - "OFF", -}; -const char * const table_tz_automatic_dst[] = { - "OFF", - "EU", - "USA", -}; -const char * const table_voltage_sensor[] = { - "NONE", - "ADC", - "ESC", - "FAKE", -}; -static const lookupTableEntry_t settingLookupTables[] = { - { table_acc_hardware, sizeof(table_acc_hardware) / sizeof(char*) }, - { table_airmodeHandlingType, sizeof(table_airmodeHandlingType) / sizeof(char*) }, - { table_alignment, sizeof(table_alignment) / sizeof(char*) }, - { table_autotune_rate_adjustment, sizeof(table_autotune_rate_adjustment) / sizeof(char*) }, - { table_aux_operator, sizeof(table_aux_operator) / sizeof(char*) }, - { table_baro_hardware, sizeof(table_baro_hardware) / sizeof(char*) }, - { table_bat_capacity_unit, sizeof(table_bat_capacity_unit) / sizeof(char*) }, - { table_bat_voltage_source, sizeof(table_bat_voltage_source) / sizeof(char*) }, - { table_blackbox_device, sizeof(table_blackbox_device) / sizeof(char*) }, - { table_current_sensor, sizeof(table_current_sensor) / sizeof(char*) }, - { table_debug_modes, sizeof(table_debug_modes) / sizeof(char*) }, - { table_direction, sizeof(table_direction) / sizeof(char*) }, - { table_djiOsdTempSource, sizeof(table_djiOsdTempSource) / sizeof(char*) }, - { table_djiRssiSource, sizeof(table_djiRssiSource) / sizeof(char*) }, - { table_failsafe_procedure, sizeof(table_failsafe_procedure) / sizeof(char*) }, - { table_filter_type, sizeof(table_filter_type) / sizeof(char*) }, - { table_filter_type_full, sizeof(table_filter_type_full) / sizeof(char*) }, - { table_gps_dyn_model, sizeof(table_gps_dyn_model) / sizeof(char*) }, - { table_gps_provider, sizeof(table_gps_provider) / sizeof(char*) }, - { table_gps_sbas_mode, sizeof(table_gps_sbas_mode) / sizeof(char*) }, - { table_gyro_lpf, sizeof(table_gyro_lpf) / sizeof(char*) }, - { table_imu_inertia_comp_method, sizeof(table_imu_inertia_comp_method) / sizeof(char*) }, - { table_iterm_relax, sizeof(table_iterm_relax) / sizeof(char*) }, - { table_log_level, sizeof(table_log_level) / sizeof(char*) }, - { table_mag_hardware, sizeof(table_mag_hardware) / sizeof(char*) }, - { table_motor_pwm_protocol, sizeof(table_motor_pwm_protocol) / sizeof(char*) }, - { table_nav_extra_arming_safety, sizeof(table_nav_extra_arming_safety) / sizeof(char*) }, - { table_nav_fw_wp_turn_smoothing, sizeof(table_nav_fw_wp_turn_smoothing) / sizeof(char*) }, - { table_nav_overrides_motor_stop, sizeof(table_nav_overrides_motor_stop) / sizeof(char*) }, - { table_nav_rth_allow_landing, sizeof(table_nav_rth_allow_landing) / sizeof(char*) }, - { table_nav_rth_alt_mode, sizeof(table_nav_rth_alt_mode) / sizeof(char*) }, - { table_nav_rth_climb_first, sizeof(table_nav_rth_climb_first) / sizeof(char*) }, - { table_nav_rth_climb_first_stage_modes, sizeof(table_nav_rth_climb_first_stage_modes) / sizeof(char*) }, - { table_nav_user_control_mode, sizeof(table_nav_user_control_mode) / sizeof(char*) }, - { table_nav_wp_mission_restart, sizeof(table_nav_wp_mission_restart) / sizeof(char*) }, - { table_off_on, sizeof(table_off_on) / sizeof(char*) }, - { table_opflow_hardware, sizeof(table_opflow_hardware) / sizeof(char*) }, - { table_osdSpeedSource, sizeof(table_osdSpeedSource) / sizeof(char*) }, - { table_osd_ahi_style, sizeof(table_osd_ahi_style) / sizeof(char*) }, - { table_osd_alignment, sizeof(table_osd_alignment) / sizeof(char*) }, - { table_osd_crosshairs_style, sizeof(table_osd_crosshairs_style) / sizeof(char*) }, - { table_osd_crsf_lq_format, sizeof(table_osd_crsf_lq_format) / sizeof(char*) }, - { table_osd_plus_code_short, sizeof(table_osd_plus_code_short) / sizeof(char*) }, - { table_osd_sidebar_scroll, sizeof(table_osd_sidebar_scroll) / sizeof(char*) }, - { table_osd_stats_energy_unit, sizeof(table_osd_stats_energy_unit) / sizeof(char*) }, - { table_osd_stats_min_voltage_unit, sizeof(table_osd_stats_min_voltage_unit) / sizeof(char*) }, - { table_osd_telemetry, sizeof(table_osd_telemetry) / sizeof(char*) }, - { table_osd_unit, sizeof(table_osd_unit) / sizeof(char*) }, - { table_osd_video_system, sizeof(table_osd_video_system) / sizeof(char*) }, - { table_output_mode, sizeof(table_output_mode) / sizeof(char*) }, - { table_pidTypeTable, sizeof(table_pidTypeTable) / sizeof(char*) }, - { table_pitot_hardware, sizeof(table_pitot_hardware) / sizeof(char*) }, - { table_platform_type, sizeof(table_platform_type) / sizeof(char*) }, - { table_rangefinder_hardware, sizeof(table_rangefinder_hardware) / sizeof(char*) }, - { table_receiver_type, sizeof(table_receiver_type) / sizeof(char*) }, - { table_reset_type, sizeof(table_reset_type) / sizeof(char*) }, - { table_rssi_source, sizeof(table_rssi_source) / sizeof(char*) }, - { table_rth_trackback_mode, sizeof(table_rth_trackback_mode) / sizeof(char*) }, - { table_safehome_usage_mode, sizeof(table_safehome_usage_mode) / sizeof(char*) }, - { table_serial_rx, sizeof(table_serial_rx) / sizeof(char*) }, - { table_servo_protocol, sizeof(table_servo_protocol) / sizeof(char*) }, - { table_tristate, sizeof(table_tristate) / sizeof(char*) }, - { table_tz_automatic_dst, sizeof(table_tz_automatic_dst) / sizeof(char*) }, - { table_voltage_sensor, sizeof(table_voltage_sensor) / sizeof(char*) }, -}; -static const uint32_t settingMinMaxTable[] = { - 0, - 255, - 100, - 1000, - 10, - 1, - 2000, - 5, - 500, - 32767, - -32768, - 10000, - 4, - 65535, - 2, - 20, - 50, - 200, - 30, - 250, - 5000, - 65000, - -1800, - -550, - 15, - 3600, - 3, - 18, - 80, - 180, - 4294967295, - -20, - 60, - 90, - 95, - 1250, - 3000, - 60000, - 9, - 900, - 1500, - 4000, - 8192, - 2147483647, - -800, - -130, - -128, - -1, - 6, - 8, - 25, - 40, - 45, - 120, - 127, - 150, - 175, - 300, - 400, - 450, - 600, - 750, - 800, - 2250, - 9999, - 27000, - 40000, - 500000, - -18000, - -10000, - -1440, - -1000, - -50, - -40, - -36, - -10, - -2, - 11, - 12, - 13, - 16, - 32, - 36, - 48, - 99, - 126, - 128, - 498, - 1440, - 6000, - 9000, - 9990, - 16000, - 18000, - 20000, - 30000, - 32000, - 50000, -}; -typedef uint8_t setting_min_max_idx_t; -#define SETTING_INDEXES_GET_MIN(val) (val->config.minmax.indexes[0]) -#define SETTING_INDEXES_GET_MAX(val) (val->config.minmax.indexes[1]) -static const setting_t settingsTable[] = { - // PG_GYRO_CONFIG - { {167, 2, 0, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 90}, offsetof(gyroConfig_t, looptime) }, - { {30, 57, 14, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GYRO_LPF }, offsetof(gyroConfig_t, gyro_lpf) }, - { {147, 2, 0, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 3}, offsetof(gyroConfig_t, gyro_anti_aliasing_lpf_hz) }, - { {148, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_FILTER_TYPE }, offsetof(gyroConfig_t, gyro_anti_aliasing_lpf_type) }, - { {175, 2, 60, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 86}, offsetof(gyroConfig_t, gyroMovementCalibrationThreshold) }, - { {30, 132, 1, 14, 21, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 8}, offsetof(gyroConfig_t, gyro_main_lpf_hz) }, - { {30, 132, 1, 14, 32, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_FILTER_TYPE }, offsetof(gyroConfig_t, gyro_main_lpf_type) }, - { {30, 72, 79, 14, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(gyroConfig_t, useDynamicLpf) }, - { {30, 79, 14, 10, 21, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {51, 58}, offsetof(gyroConfig_t, gyroDynamicLpfMinHz) }, - { {30, 79, 14, 6, 21, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {51, 3}, offsetof(gyroConfig_t, gyroDynamicLpfMaxHz) }, - { {30, 79, 14, 238, 1, 56}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {5, 4}, offsetof(gyroConfig_t, gyroDynamicLpfCurveExpo) }, - { {160, 2, 30, 121, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(gyroConfig_t, init_gyro_cal_enabled) }, - { {30, 88, 86, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(gyroConfig_t, gyro_zero_cal[X]) }, - { {30, 88, 87, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(gyroConfig_t, gyro_zero_cal[Y]) }, - { {30, 88, 15, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(gyroConfig_t, gyro_zero_cal[Z]) }, - { {161, 2, 166, 1, 230, 1}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 6}, offsetof(gyroConfig_t, gravity_cmss_cal) }, - // PG_ADC_CHANNEL_CONFIG - { {61, 90, 42, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 12}, offsetof(adcChannelConfig_t, adcFunctionChannel[ADC_BATTERY]) }, - { {36, 90, 42, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 12}, offsetof(adcChannelConfig_t, adcFunctionChannel[ADC_RSSI]) }, - { {43, 90, 42, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 12}, offsetof(adcChannelConfig_t, adcFunctionChannel[ADC_CURRENT]) }, - { {91, 90, 42, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 12}, offsetof(adcChannelConfig_t, adcFunctionChannel[ADC_AIRSPEED]) }, - // PG_ACCELEROMETER_CONFIG - { {39, 185, 1, 21, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 1}, offsetof(accelerometerConfig_t, acc_notch_hz) }, - { {39, 185, 1, 100, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {5, 1}, offsetof(accelerometerConfig_t, acc_notch_cutoff) }, - { {39, 57, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_ACC_HARDWARE }, offsetof(accelerometerConfig_t, acc_hardware) }, - { {39, 14, 21, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 17}, offsetof(accelerometerConfig_t, acc_lpf_hz) }, - { {39, 14, 32, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_FILTER_TYPE }, offsetof(accelerometerConfig_t, acc_soft_lpf_type) }, - { {114, 86, 0, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(accelerometerConfig_t, accZero.raw[X]) }, - { {114, 87, 0, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(accelerometerConfig_t, accZero.raw[Y]) }, - { {114, 15, 0, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(accelerometerConfig_t, accZero.raw[Z]) }, - { {113, 86, 0, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {5, 42}, offsetof(accelerometerConfig_t, accGain.raw[X]) }, - { {113, 87, 0, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {5, 42}, offsetof(accelerometerConfig_t, accGain.raw[Y]) }, - { {113, 15, 0, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {5, 42}, offsetof(accelerometerConfig_t, accGain.raw[Z]) }, - // PG_RANGEFINDER_CONFIG - { {194, 1, 57, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_RANGEFINDER_HARDWARE }, offsetof(rangefinderConfig_t, rangefinder_hardware) }, - { {194, 1, 168, 2, 80, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(rangefinderConfig_t, use_median_filtering) }, - // PG_OPFLOW_CONFIG - { {134, 1, 57, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OPFLOW_HARDWARE }, offsetof(opticalFlowConfig_t, opflow_hardware) }, - { {134, 1, 82, 0, 0, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 11}, offsetof(opticalFlowConfig_t, opflow_scale) }, - { {41, 134, 1, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_ALIGNMENT }, offsetof(opticalFlowConfig_t, opflow_align) }, - // PG_COMPASS_CONFIG - { {41, 35, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_ALIGNMENT }, offsetof(compassConfig_t, mag_align) }, - { {35, 57, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_MAG_HARDWARE }, offsetof(compassConfig_t, mag_hardware) }, - { {35, 245, 1, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {68, 93}, offsetof(compassConfig_t, mag_declination) }, - { {131, 1, 86, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(compassConfig_t, magZero.raw[X]) }, - { {131, 1, 87, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(compassConfig_t, magZero.raw[Y]) }, - { {131, 1, 15, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(compassConfig_t, magZero.raw[Z]) }, - { {130, 1, 86, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(compassConfig_t, magGain[X]) }, - { {130, 1, 87, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(compassConfig_t, magGain[Y]) }, - { {130, 1, 15, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(compassConfig_t, magGain[Z]) }, - { {35, 227, 1, 25, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {15, 53}, offsetof(compassConfig_t, magCalibrationTimeLimit) }, - { {41, 35, 18, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {22, 25}, offsetof(compassConfig_t, rollDeciDegrees) }, - { {41, 35, 11, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {22, 25}, offsetof(compassConfig_t, pitchDeciDegrees) }, - { {41, 35, 8, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {22, 25}, offsetof(compassConfig_t, yawDeciDegrees) }, - // PG_BAROMETER_CONFIG - { {54, 57, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BARO_HARDWARE }, offsetof(barometerConfig_t, baro_hardware) }, - { {54, 121, 207, 1, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 3}, offsetof(barometerConfig_t, baro_calibration_tolerance) }, - // PG_PITOTMETER_CONFIG - { {136, 1, 57, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_PITOT_HARDWARE }, offsetof(pitotmeterConfig_t, pitot_hardware) }, - { {136, 1, 14, 172, 2, 21}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 11}, offsetof(pitotmeterConfig_t, pitot_lpf_milli_hz) }, - { {136, 1, 82, 0, 0, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(pitotmeterConfig_t, pitot_scale) }, - // PG_RX_CONFIG - { {236, 2, 32, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_RECEIVER_TYPE }, offsetof(rxConfig_t, receiverType) }, - { {10, 151, 1, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {3, 6}, offsetof(rxConfig_t, mincheck) }, - { {6, 151, 1, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {3, 6}, offsetof(rxConfig_t, maxcheck) }, - { {36, 84, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_RSSI_SOURCE }, offsetof(rxConfig_t, rssi_source) }, - { {36, 42, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 27}, offsetof(rxConfig_t, rssi_channel) }, - { {36, 10, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(rxConfig_t, rssiMin) }, - { {36, 6, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(rxConfig_t, rssiMax) }, - { {249, 2, 133, 3, 173, 1}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {8, 11}, offsetof(rxConfig_t, sbusSyncInterval) }, - { {59, 80, 14, 21, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {24, 19}, offsetof(rxConfig_t, rcFilterFrequency) }, - { {59, 80, 46, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(rxConfig_t, autoSmooth) }, - { {59, 80, 201, 1, 160, 1}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {5, 2}, offsetof(rxConfig_t, autoSmoothFactor) }, - { {140, 1, 192, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_SERIAL_RX }, offsetof(rxConfig_t, serialrx_provider) }, - { {140, 1, 128, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(rxConfig_t, serialrx_inverted) }, - { {202, 1, 111, 156, 2, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 24}, offsetof(rxConfig_t, srxl2_unit_id) }, - { {202, 1, 150, 1, 134, 2}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(rxConfig_t, srxl2_baud_fast) }, - { {198, 1, 10, 212, 1, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {61, 63}, offsetof(rxConfig_t, rx_min_usec) }, - { {198, 1, 6, 212, 1, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {61, 63}, offsetof(rxConfig_t, rx_max_usec) }, - { {140, 1, 168, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_TRISTATE }, offsetof(rxConfig_t, halfDuplex) }, - // PG_BLACKBOX_CONFIG - { {119, 5, 199, 2, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {5, 13}, offsetof(blackboxConfig_t, rate_num) }, - { {119, 5, 249, 1, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {5, 13}, offsetof(blackboxConfig_t, rate_denom) }, - { {119, 250, 1, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BLACKBOX_DEVICE }, offsetof(blackboxConfig_t, device) }, - // PG_MOTOR_CONFIG - { {6, 38, 0, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {3, 6}, offsetof(motorConfig_t, maxthrottle) }, - { {10, 231, 1, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 6}, offsetof(motorConfig_t, mincommand) }, - { {58, 110, 5, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {16, 96}, offsetof(motorConfig_t, motorPwmRate) }, - { {58, 110, 191, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_MOTOR_PWM_PROTOCOL }, offsetof(motorConfig_t, motorPwmProtocol) }, - { {58, 225, 2, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {12, 1}, offsetof(motorConfig_t, motorPoleCount) }, - // PG_FAILSAFE_CONFIG - { {19, 33, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 17}, offsetof(failsafeConfig_t, failsafe_delay) }, - { {19, 237, 2, 33, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 17}, offsetof(failsafeConfig_t, failsafe_recovery_delay) }, - { {19, 200, 2, 33, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 17}, offsetof(failsafeConfig_t, failsafe_off_delay) }, - { {19, 38, 178, 1, 33, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 57}, offsetof(failsafeConfig_t, failsafe_throttle_low_delay) }, - { {19, 190, 1, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_FAILSAFE_PROCEDURE }, offsetof(failsafeConfig_t, failsafe_procedure) }, - { {19, 203, 1, 60, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 8}, offsetof(failsafeConfig_t, failsafe_stick_motion_threshold) }, - { {19, 2, 18, 24, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {44, 62}, offsetof(failsafeConfig_t, failsafe_fw_roll_angle) }, - { {19, 2, 11, 24, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {44, 62}, offsetof(failsafeConfig_t, failsafe_fw_pitch_angle) }, - { {19, 2, 8, 5, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {71, 3}, offsetof(failsafeConfig_t, failsafe_fw_yaw_rate) }, - { {19, 10, 65, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 21}, offsetof(failsafeConfig_t, failsafe_min_distance) }, - { {19, 10, 65, 190, 1, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_FAILSAFE_PROCEDURE }, offsetof(failsafeConfig_t, failsafe_min_distance_procedure) }, - { {19, 183, 1, 33, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {47, 60}, offsetof(failsafeConfig_t, failsafe_mission_delay) }, - // PG_BOARD_ALIGNMENT - { {41, 120, 18, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {22, 25}, offsetof(boardAlignment_t, rollDeciDegrees) }, - { {41, 120, 11, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {22, 25}, offsetof(boardAlignment_t, pitchDeciDegrees) }, - { {41, 120, 8, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {22, 25}, offsetof(boardAlignment_t, yawDeciDegrees) }, - // PG_BATTERY_METERS_CONFIG - { {61, 109, 32, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_VOLTAGE_SENSOR }, offsetof(batteryMetersConfig_t, voltage.type) }, - { {61, 82, 0, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 13}, offsetof(batteryMetersConfig_t, voltage.scale) }, - { {43, 109, 82, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {69, 11}, offsetof(batteryMetersConfig_t, current.scale) }, - { {43, 109, 69, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {10, 9}, offsetof(batteryMetersConfig_t, current.offset) }, - { {43, 109, 32, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_CURRENT_SENSOR }, offsetof(batteryMetersConfig_t, current.type) }, - { {149, 1, 63, 129, 3, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BAT_VOLTAGE_SOURCE }, offsetof(batteryMetersConfig_t, voltageSource) }, - { {99, 70, 0, 0, 0, 0}, VAR_UINT32 | MASTER_VALUE, .config.minmax.indexes = {0, 30}, offsetof(batteryMetersConfig_t, cruise_power) }, - { {107, 70, 0, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 13}, offsetof(batteryMetersConfig_t, idle_power) }, - { {28, 124, 133, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(batteryMetersConfig_t, rth_energy_margin) }, - { {45, 98, 146, 1, 0, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 14}, offsetof(batteryMetersConfig_t, throttle_compensation_weight) }, - // PG_BATTERY_PROFILES - { {149, 1, 228, 1, 0, 0}, VAR_UINT8 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 78}, offsetof(batteryProfile_t, cells) }, - { {61, 96, 123, 63, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {2, 8}, offsetof(batteryProfile_t, voltage.cellDetect) }, - { {61, 6, 96, 63, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {2, 8}, offsetof(batteryProfile_t, voltage.cellMax) }, - { {61, 10, 96, 63, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {2, 8}, offsetof(batteryProfile_t, voltage.cellMin) }, - { {61, 214, 1, 96, 63, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {2, 8}, offsetof(batteryProfile_t, voltage.cellWarning) }, - { {92, 94, 0, 0, 0, 0}, VAR_UINT32 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 30}, offsetof(batteryProfile_t, capacity.value) }, - { {92, 94, 214, 1, 0, 0}, VAR_UINT32 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 30}, offsetof(batteryProfile_t, capacity.warning) }, - { {92, 94, 236, 1, 0, 0}, VAR_UINT32 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 30}, offsetof(batteryProfile_t, capacity.critical) }, - { {92, 94, 111, 0, 0, 0}, VAR_UINT8 | BATTERY_CONFIG_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BAT_CAPACITY_UNIT }, offsetof(batteryProfile_t, capacity.unit) }, - { {234, 1, 230, 2, 0, 0}, VAR_UINT8 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 26}, offsetof(batteryProfile_t, controlRateProfile) }, - { {38, 82, 0, 0, 0, 0}, VAR_FLOAT | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 5}, offsetof(batteryProfile_t, motor.throttleScale) }, - { {38, 107, 0, 0, 0, 0}, VAR_FLOAT | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 18}, offsetof(batteryProfile_t, motor.throttleIdle) }, - { {19, 38, 0, 0, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {3, 6}, offsetof(batteryProfile_t, failsafe_throttle) }, - { {1, 4, 155, 2, 45, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {3, 6}, offsetof(batteryProfile_t, nav.mc.hover_throttle) }, - { {1, 2, 99, 45, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {3, 6}, offsetof(batteryProfile_t, nav.fw.cruise_throttle) }, - { {1, 2, 10, 45, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {3, 6}, offsetof(batteryProfile_t, nav.fw.min_throttle) }, - { {1, 2, 6, 45, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {3, 6}, offsetof(batteryProfile_t, nav.fw.max_throttle) }, - { {1, 2, 135, 1, 0, 0}, VAR_UINT8 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 2}, offsetof(batteryProfile_t, nav.fw.pitch_to_throttle) }, - { {1, 2, 16, 45, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {3, 6}, offsetof(batteryProfile_t, nav.fw.launch_throttle) }, - { {1, 2, 16, 107, 45, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {3, 6}, offsetof(batteryProfile_t, nav.fw.launch_idle_throttle) }, - { {13, 152, 1, 43, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 41}, offsetof(batteryProfile_t, powerLimits.continuousCurrent) }, - { {13, 64, 43, 0, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 41}, offsetof(batteryProfile_t, powerLimits.burstCurrent) }, - { {13, 64, 43, 25, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 36}, offsetof(batteryProfile_t, powerLimits.burstCurrentTime) }, - { {13, 64, 43, 161, 1, 25}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 36}, offsetof(batteryProfile_t, powerLimits.burstCurrentFalldownTime) }, - { {13, 152, 1, 70, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 66}, offsetof(batteryProfile_t, powerLimits.continuousPower) }, - { {13, 64, 70, 0, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 66}, offsetof(batteryProfile_t, powerLimits.burstPower) }, - { {13, 64, 70, 25, 0, 0}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 36}, offsetof(batteryProfile_t, powerLimits.burstPowerTime) }, - { {13, 64, 70, 161, 1, 25}, VAR_UINT16 | BATTERY_CONFIG_VALUE, .config.minmax.indexes = {0, 36}, offsetof(batteryProfile_t, powerLimits.burstPowerFalldownTime) }, - // PG_MIXER_CONFIG - { {58, 154, 1, 128, 1, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(mixerConfig_t, motorDirectionInverted) }, - { {224, 2, 32, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_PLATFORM_TYPE }, offsetof(mixerConfig_t, platformType) }, - { {149, 2, 137, 2, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(mixerConfig_t, hasFlaps) }, - { {184, 1, 229, 2, 32, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {47, 9}, offsetof(mixerConfig_t, appliedMixerPreset) }, - { {219, 2, 49, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OUTPUT_MODE }, offsetof(mixerConfig_t, outputMode) }, - // PG_REVERSIBLE_MOTORS_CONFIG - { {89, 29, 178, 1, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {3, 6}, offsetof(reversibleMotorsConfig_t, deadband_low) }, - { {89, 29, 150, 2, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {3, 6}, offsetof(reversibleMotorsConfig_t, deadband_high) }, - { {89, 197, 2, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {3, 6}, offsetof(reversibleMotorsConfig_t, neutral) }, - // PG_SERVO_CONFIG - { {50, 191, 1, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_SERVO_PROTOCOL }, offsetof(servoConfig_t, servo_protocol) }, - { {50, 97, 231, 2, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {3, 6}, offsetof(servoConfig_t, servoCenterPulse) }, - { {50, 110, 5, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {16, 87}, offsetof(servoConfig_t, servoPwmRate) }, - { {50, 14, 21, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {0, 58}, offsetof(servoConfig_t, servo_lowpass_freq) }, - { {136, 2, 206, 1, 69, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {16, 59}, offsetof(servoConfig_t, flaperon_throw_offset) }, - { {140, 3, 143, 3, 50, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(servoConfig_t, tri_unarmed_servo) }, - { {50, 223, 1, 243, 2, 13}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {5, 32}, offsetof(servoConfig_t, servo_autotrim_rotation_limit) }, - // PG_CONTROL_RATE_PROFILES - { {45, 171, 2, 0, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(controlRateConfig_t, throttle.rcMid8) }, - { {45, 56, 0, 0, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(controlRateConfig_t, throttle.rcExpo8) }, - { {145, 1, 5, 0, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(controlRateConfig_t, throttle.dynPID) }, - { {145, 1, 226, 1, 0, 0}, VAR_UINT16 | CONTROL_RATE_VALUE, .config.minmax.indexes = {3, 6}, offsetof(controlRateConfig_t, throttle.pa_breakpoint) }, - { {2, 145, 1, 25, 233, 1}, VAR_UINT16 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 20}, offsetof(controlRateConfig_t, throttle.fixedWingTauMs) }, - { {59, 56, 0, 0, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(controlRateConfig_t, stabilized.rcExpo8) }, - { {59, 8, 56, 0, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(controlRateConfig_t, stabilized.rcYawExpo8) }, - { {18, 5, 0, 0, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {12, 29}, offsetof(controlRateConfig_t, stabilized.rates[FD_ROLL]) }, - { {11, 5, 0, 0, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {12, 29}, offsetof(controlRateConfig_t, stabilized.rates[FD_PITCH]) }, - { {8, 5, 0, 0, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {5, 29}, offsetof(controlRateConfig_t, stabilized.rates[FD_YAW]) }, - { {48, 59, 56, 0, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(controlRateConfig_t, manual.rcExpo8) }, - { {48, 59, 8, 56, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(controlRateConfig_t, manual.rcYawExpo8) }, - { {48, 18, 5, 0, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(controlRateConfig_t, manual.rates[FD_ROLL]) }, - { {48, 11, 5, 0, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(controlRateConfig_t, manual.rates[FD_PITCH]) }, - { {48, 8, 5, 0, 0, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(controlRateConfig_t, manual.rates[FD_YAW]) }, - { {139, 2, 173, 2, 248, 1}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 16}, offsetof(controlRateConfig_t, misc.fpvCamAngleDegrees) }, - { {5, 66, 97, 139, 1, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {50, 56}, offsetof(controlRateConfig_t, rateDynamics.sensitivityCenter) }, - { {5, 66, 104, 139, 1, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {50, 56}, offsetof(controlRateConfig_t, rateDynamics.sensitivityEnd) }, - { {5, 66, 97, 153, 1, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {4, 34}, offsetof(controlRateConfig_t, rateDynamics.correctionCenter) }, - { {5, 66, 104, 153, 1, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {4, 34}, offsetof(controlRateConfig_t, rateDynamics.correctionEnd) }, - { {5, 66, 97, 146, 1, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 34}, offsetof(controlRateConfig_t, rateDynamics.weightCenter) }, - { {5, 66, 104, 146, 1, 0}, VAR_UINT8 | CONTROL_RATE_VALUE, .config.minmax.indexes = {0, 34}, offsetof(controlRateConfig_t, rateDynamics.weightEnd) }, - // PG_SERIAL_CONFIG - { {235, 2, 229, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {83, 85}, offsetof(serialConfig_t, reboot_character) }, - // PG_IMU_CONFIG - { {34, 101, 175, 1, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 13}, offsetof(imuConfig_t, dcm_kp_acc) }, - { {34, 101, 174, 1, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 13}, offsetof(imuConfig_t, dcm_ki_acc) }, - { {34, 101, 175, 1, 35, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 13}, offsetof(imuConfig_t, dcm_kp_mag) }, - { {34, 101, 174, 1, 35, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 13}, offsetof(imuConfig_t, dcm_ki_mag) }, - { {252, 2, 24, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 29}, offsetof(imuConfig_t, small_angle) }, - { {34, 39, 171, 1, 5, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 18}, offsetof(imuConfig_t, acc_ignore_rate) }, - { {34, 39, 171, 1, 251, 2}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(imuConfig_t, acc_ignore_slope) }, - { {34, 20, 8, 152, 3, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(imuConfig_t, gps_yaw_windcomp) }, - { {34, 159, 2, 98, 170, 2}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_IMU_INERTIA_COMP_METHOD }, offsetof(imuConfig_t, inertia_comp_method) }, - // PG_ARMING_CONFIG - { {135, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(armingConfig_t, fixed_wing_auto_arm) }, - { {102, 162, 2, 31, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(armingConfig_t, disarm_kill_switch) }, - { {31, 102, 33, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 3}, offsetof(armingConfig_t, switchDisarmDelayMs) }, - { {227, 2, 85, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 11}, offsetof(armingConfig_t, prearmTimeoutMs) }, - // PG_GENERAL_SETTINGS - { {219, 1, 246, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 84}, offsetof(generalSettings_t, appliedDefaults) }, - // PG_GPS_CONFIG - { {20, 192, 1, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GPS_PROVIDER }, offsetof(gpsConfig_t, provider) }, - { {20, 248, 2, 49, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GPS_SBAS_MODE }, offsetof(gpsConfig_t, sbasMode) }, - { {20, 79, 184, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GPS_DYN_MODEL }, offsetof(gpsConfig_t, dynModel) }, - { {20, 46, 232, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(gpsConfig_t, autoConfig) }, - { {20, 46, 150, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(gpsConfig_t, autoBaud) }, - { {20, 142, 3, 72, 144, 2}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(gpsConfig_t, ubloxUseGalileo) }, - { {20, 10, 247, 2, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {7, 4}, offsetof(gpsConfig_t, gpsMinSats) }, - // PG_RC_CONTROLS_CONFIG - { {29, 0, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 81}, offsetof(rcControlsConfig_t, deadband) }, - { {8, 29, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(rcControlsConfig_t, yaw_deadband) }, - { {23, 127, 29, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {14, 19}, offsetof(rcControlsConfig_t, pos_hold_deadband) }, - { {77, 29, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {14, 19}, offsetof(rcControlsConfig_t, control_deadband) }, - { {74, 127, 29, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {4, 19}, offsetof(rcControlsConfig_t, alt_hold_deadband) }, - { {89, 29, 38, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 17}, offsetof(rcControlsConfig_t, mid_throttle_deadband) }, - { {148, 1, 32, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_AIRMODEHANDLINGTYPE }, offsetof(rcControlsConfig_t, airmodeHandlingType) }, - { {148, 1, 38, 60, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {3, 6}, offsetof(rcControlsConfig_t, airmodeThrottleThreshold) }, - // PG_PID_PROFILE - { {4, 7, 11, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_PITCH].P) }, - { {4, 22, 11, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_PITCH].I) }, - { {4, 17, 11, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_PITCH].D) }, - { {4, 95, 11, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_PITCH].FF) }, - { {4, 7, 18, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_ROLL].P) }, - { {4, 22, 18, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_ROLL].I) }, - { {4, 17, 18, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_ROLL].D) }, - { {4, 95, 18, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_ROLL].FF) }, - { {4, 7, 8, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_YAW].P) }, - { {4, 22, 8, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_YAW].I) }, - { {4, 17, 8, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_YAW].D) }, - { {4, 95, 8, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_YAW].FF) }, - { {4, 7, 44, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_LEVEL].P) }, - { {4, 22, 44, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_LEVEL].I) }, - { {4, 17, 44, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_LEVEL].D) }, - { {2, 7, 11, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_PITCH].P) }, - { {2, 22, 11, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_PITCH].I) }, - { {2, 17, 11, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_PITCH].D) }, - { {2, 106, 11, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_PITCH].FF) }, - { {2, 7, 18, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_ROLL].P) }, - { {2, 22, 18, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_ROLL].I) }, - { {2, 17, 18, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_ROLL].D) }, - { {2, 106, 18, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_ROLL].FF) }, - { {2, 7, 8, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_YAW].P) }, - { {2, 22, 8, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_YAW].I) }, - { {2, 17, 8, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_YAW].D) }, - { {2, 106, 8, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_YAW].FF) }, - { {2, 7, 44, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_LEVEL].P) }, - { {2, 22, 44, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_LEVEL].I) }, - { {2, 17, 44, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_LEVEL].D) }, - { {6, 24, 172, 1, 242, 2}, VAR_INT16 | PROFILE_VALUE, .config.minmax.indexes = {2, 39}, offsetof(pidProfile_t, max_angle_inclination[FD_ROLL]) }, - { {6, 24, 172, 1, 223, 2}, VAR_INT16 | PROFILE_VALUE, .config.minmax.indexes = {2, 39}, offsetof(pidProfile_t, max_angle_inclination[FD_PITCH]) }, - { {103, 14, 21, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 8}, offsetof(pidProfile_t, dterm_lpf_hz) }, - { {103, 14, 32, 0, 0, 0}, VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_FILTER_TYPE_FULL }, offsetof(pidProfile_t, dterm_lpf_type) }, - { {103, 179, 1, 21, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 8}, offsetof(pidProfile_t, dterm_lpf2_hz) }, - { {103, 179, 1, 32, 0, 0}, VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_FILTER_TYPE_FULL }, offsetof(pidProfile_t, dterm_lpf2_type) }, - { {8, 14, 21, 0, 0, 0}, VAR_UINT8 | PROFILE_VALUE, .config.minmax.indexes = {0, 17}, offsetof(pidProfile_t, yaw_lpf_hz) }, - { {2, 108, 206, 1, 13, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 8}, offsetof(pidProfile_t, fixedWingItermThrowLimit) }, - { {2, 238, 2, 91, 0, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {57, 89}, offsetof(pidProfile_t, fixedWingReferenceAirspeed) }, - { {142, 2, 0, 0, 0, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {0, 14}, offsetof(pidProfile_t, fixedWingCoordinatedYawGain) }, - { {141, 2, 0, 0, 0, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {0, 14}, offsetof(pidProfile_t, fixedWingCoordinatedPitchGain) }, - { {140, 2, 0, 0, 0, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {0, 5}, offsetof(pidProfile_t, fixedWingItermLimitOnStickPosition) }, - { {143, 2, 0, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 33}, offsetof(pidProfile_t, fixedWingYawItermBankFreeze) }, - { {189, 1, 13, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {2, 3}, offsetof(pidProfile_t, pidSumLimit) }, - { {189, 1, 13, 8, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {2, 3}, offsetof(pidProfile_t, pidSumLimitYaw) }, - { {108, 153, 3, 0, 0, 0}, VAR_UINT8 | PROFILE_VALUE, .config.minmax.indexes = {0, 33}, offsetof(pidProfile_t, itermWindupPointPercent) }, - { {5, 112, 13, 18, 11, 0}, VAR_UINT32 | PROFILE_VALUE, .config.minmax.indexes = {0, 67}, offsetof(pidProfile_t, axisAccelerationLimitRollPitch) }, - { {5, 112, 13, 8, 0, 0}, VAR_UINT32 | PROFILE_VALUE, .config.minmax.indexes = {0, 67}, offsetof(pidProfile_t, axisAccelerationLimitYaw) }, - { {126, 127, 5, 13, 0, 0}, VAR_UINT8 | PROFILE_VALUE, .config.minmax.indexes = {4, 19}, offsetof(pidProfile_t, heading_hold_rate_limit) }, - { {1, 4, 23, 15, 7, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_POS_Z].P) }, - { {1, 4, 62, 15, 7, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_VEL_Z].P) }, - { {1, 4, 62, 15, 22, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_VEL_Z].I) }, - { {1, 4, 62, 15, 17, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_VEL_Z].D) }, - { {1, 4, 23, 27, 7, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_POS_XY].P) }, - { {1, 4, 62, 27, 7, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_VEL_XY].P) }, - { {1, 4, 62, 27, 22, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_VEL_XY].I) }, - { {1, 4, 62, 27, 17, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_VEL_XY].D) }, - { {1, 4, 62, 27, 106, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_VEL_XY].FF) }, - { {1, 4, 126, 7, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_mc.pid[PID_HEADING].P) }, - { {188, 2, 0, 0, 0, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(pidProfile_t, navVelXyDTermLpfHz) }, - { {185, 2, 0, 0, 0, 0}, VAR_UINT8 | PROFILE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(pidProfile_t, navVelXyDtermAttenuation) }, - { {187, 2, 0, 0, 0, 0}, VAR_UINT8 | PROFILE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(pidProfile_t, navVelXyDtermAttenuationStart) }, - { {186, 2, 0, 0, 0, 0}, VAR_UINT8 | PROFILE_VALUE, .config.minmax.indexes = {0, 2}, offsetof(pidProfile_t, navVelXyDtermAttenuationEnd) }, - { {1, 2, 23, 15, 7, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_POS_Z].P) }, - { {1, 2, 23, 15, 22, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_POS_Z].I) }, - { {1, 2, 23, 15, 17, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_POS_Z].D) }, - { {1, 2, 23, 27, 7, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_POS_XY].P) }, - { {1, 2, 23, 27, 22, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_POS_XY].I) }, - { {1, 2, 23, 27, 17, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_POS_XY].D) }, - { {1, 2, 126, 7, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_HEADING].P) }, - { {1, 2, 23, 125, 7, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_POS_HEADING].P) }, - { {1, 2, 23, 125, 22, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_POS_HEADING].I) }, - { {1, 2, 23, 125, 17, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {0, 1}, offsetof(pidProfile_t, bank_fw.pid[PID_POS_HEADING].D) }, - { {178, 2, 0, 0, 0, 0}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {2, 3}, offsetof(pidProfile_t, navFwPosHdgPidsumLimit) }, - { {4, 108, 195, 1, 0, 0}, VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_ITERM_RELAX }, offsetof(pidProfile_t, iterm_relax) }, - { {4, 108, 195, 1, 100, 0}, VAR_UINT8 | PROFILE_VALUE, .config.minmax.indexes = {5, 2}, offsetof(pidProfile_t, iterm_relax_cutoff) }, - { {17, 75, 10, 0, 0, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {0, 5}, offsetof(pidProfile_t, dBoostMin) }, - { {17, 75, 6, 0, 0, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {5, 26}, offsetof(pidProfile_t, dBoostMax) }, - { {240, 1, 0, 0, 0, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {3, 92}, offsetof(pidProfile_t, dBoostMaxAtAlleceleration) }, - { {239, 1, 0, 0, 0, 0}, VAR_UINT8 | PROFILE_VALUE, .config.minmax.indexes = {4, 19}, offsetof(pidProfile_t, dBoostGyroDeltaLpfHz) }, - { {115, 165, 1, 0, 0, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {5, 15}, offsetof(pidProfile_t, antigravityGain) }, - { {115, 215, 1, 0, 0, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {5, 15}, offsetof(pidProfile_t, antigravityAccelerator) }, - { {115, 100, 14, 21, 0, 0}, VAR_UINT8 | PROFILE_VALUE, .config.minmax.indexes = {5, 18}, offsetof(pidProfile_t, antigravityCutoff) }, - { {222, 2, 32, 0, 0, 0}, VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_PIDTYPETABLE }, offsetof(pidProfile_t, pidControllerType) }, - { {4, 95, 14, 21, 0, 0}, VAR_UINT8 | PROFILE_VALUE, .config.minmax.indexes = {0, 17}, offsetof(pidProfile_t, controlDerivativeLpfHz) }, - { {2, 44, 11, 141, 3, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {75, 4}, offsetof(pidProfile_t, fixedWingLevelTrim) }, - { {142, 1, 137, 1, 132, 3}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {0, 5}, offsetof(pidProfile_t, smithPredictorStrength) }, - { {142, 1, 137, 1, 33, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {0, 49}, offsetof(pidProfile_t, smithPredictorDelay) }, - { {142, 1, 137, 1, 14, 21}, VAR_UINT16 | PROFILE_VALUE, .config.minmax.indexes = {5, 8}, offsetof(pidProfile_t, smithPredictorFilterHz) }, - { {2, 44, 11, 165, 1, 0}, VAR_FLOAT | PROFILE_VALUE, .config.minmax.indexes = {0, 15}, offsetof(pidProfile_t, fixedWingLevelTrimGain) }, - // PG_PID_AUTOTUNE_CONFIG - { {2, 116, 10, 203, 1, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(pidAutotuneConfig_t, fw_min_stick) }, - { {2, 116, 5, 216, 1, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_AUTOTUNE_RATE_ADJUSTMENT }, offsetof(pidAutotuneConfig_t, fw_rate_adjustment) }, - { {2, 116, 6, 5, 247, 1}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {16, 2}, offsetof(pidAutotuneConfig_t, fw_max_rate_deflection) }, - // PG_POSITION_ESTIMATION_CONFIG - { {9, 46, 35, 244, 1, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(positionEstimationConfig_t, automatic_mag_declination) }, - { {9, 166, 1, 121, 207, 1}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 1}, offsetof(positionEstimationConfig_t, gravity_calibration_tolerance) }, - { {9, 72, 20, 147, 3, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(positionEstimationConfig_t, use_gps_velned) }, - { {9, 72, 20, 198, 2, 54}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(positionEstimationConfig_t, use_gps_no_baro) }, - { {157, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(positionEstimationConfig_t, allow_dead_reckoning) }, - { {9, 197, 1, 53, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_RESET_TYPE }, offsetof(positionEstimationConfig_t, reset_altitude_type) }, - { {9, 197, 1, 170, 1, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_RESET_TYPE }, offsetof(positionEstimationConfig_t, reset_home_type) }, - { {9, 6, 143, 1, 53, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 3}, offsetof(positionEstimationConfig_t, max_surface_altitude) }, - { {9, 26, 15, 143, 1, 7}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(positionEstimationConfig_t, w_z_surface_p) }, - { {9, 26, 15, 143, 1, 52}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(positionEstimationConfig_t, w_z_surface_v) }, - { {9, 26, 27, 163, 1, 7}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(positionEstimationConfig_t, w_xy_flow_p) }, - { {9, 26, 27, 163, 1, 52}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(positionEstimationConfig_t, w_xy_flow_v) }, - { {9, 26, 15, 54, 7, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(positionEstimationConfig_t, w_z_baro_p) }, - { {9, 26, 15, 20, 7, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(positionEstimationConfig_t, w_z_gps_p) }, - { {9, 26, 15, 20, 52, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(positionEstimationConfig_t, w_z_gps_v) }, - { {9, 26, 27, 20, 7, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(positionEstimationConfig_t, w_xy_gps_p) }, - { {9, 26, 27, 20, 52, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(positionEstimationConfig_t, w_xy_gps_v) }, - { {9, 26, 15, 196, 1, 52}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(positionEstimationConfig_t, w_z_res_v) }, - { {9, 26, 27, 196, 1, 52}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(positionEstimationConfig_t, w_xy_res_v) }, - { {9, 26, 155, 3, 39, 7}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 5}, offsetof(positionEstimationConfig_t, w_xyz_acc_p) }, - { {9, 26, 39, 224, 1, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 5}, offsetof(positionEstimationConfig_t, w_acc_bias) }, - { {9, 6, 133, 2, 159, 1}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 64}, offsetof(positionEstimationConfig_t, max_eph_epv) }, - { {9, 54, 159, 1, 0, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 64}, offsetof(positionEstimationConfig_t, baro_epv) }, - // PG_NAV_CONFIG - { {1, 102, 201, 2, 129, 1}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(navConfig_t, general.flags.disarm_on_landing) }, - { {1, 68, 123, 139, 1, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {5, 24}, offsetof(navConfig_t, general.land_detect_sensitivity) }, - { {193, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(navConfig_t, general.flags.use_thr_mid_for_althold) }, - { {176, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_NAV_EXTRA_ARMING_SAFETY }, offsetof(navConfig_t, general.flags.extra_arming_safety) }, - { {1, 146, 3, 77, 49, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_NAV_USER_CONTROL_MODE }, offsetof(navConfig_t, general.flags.user_control_mode) }, - { {1, 226, 2, 85, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(navConfig_t, general.pos_failure_timeout) }, - { {194, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(navConfig_t, general.waypoint_load_on_boot) }, - { {1, 73, 193, 1, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {4, 11}, offsetof(navConfig_t, general.waypoint_radius) }, - { {1, 73, 132, 2, 53, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 6}, offsetof(navConfig_t, general.waypoint_enforce_altitude) }, - { {1, 73, 6, 246, 2, 65}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 40}, offsetof(navConfig_t, general.waypoint_safe_distance) }, - { {1, 73, 183, 1, 239, 2}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_NAV_WP_MISSION_RESTART }, offsetof(navConfig_t, general.flags.waypoint_mission_restart) }, - { {195, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {5, 38}, offsetof(navConfig_t, general.waypoint_multi_mission_index) }, - { {180, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(navConfig_t, fw.wp_tracking_accuracy) }, - { {181, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {18, 28}, offsetof(navConfig_t, fw.wp_tracking_max_angle) }, - { {182, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_NAV_FW_WP_TURN_SMOOTHING }, offsetof(navConfig_t, fw.wp_turn_smoothing) }, - { {1, 46, 37, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {4, 6}, offsetof(navConfig_t, general.auto_speed) }, - { {1, 6, 46, 37, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {4, 6}, offsetof(navConfig_t, general.max_auto_speed) }, - { {1, 46, 76, 5, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {4, 6}, offsetof(navConfig_t, general.max_auto_climb_rate) }, - { {1, 48, 37, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {4, 6}, offsetof(navConfig_t, general.max_manual_speed) }, - { {1, 48, 76, 5, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {4, 6}, offsetof(navConfig_t, general.max_manual_climb_rate) }, - { {1, 68, 182, 1, 213, 1}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {16, 8}, offsetof(navConfig_t, general.land_minalt_vspd) }, - { {1, 68, 181, 1, 213, 1}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {2, 6}, offsetof(navConfig_t, general.land_maxalt_vspd) }, - { {1, 68, 141, 1, 182, 1}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {16, 3}, offsetof(navConfig_t, general.land_slowdown_minalt) }, - { {1, 68, 141, 1, 181, 1}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {8, 41}, offsetof(navConfig_t, general.land_slowdown_maxalt) }, - { {1, 130, 2, 129, 1, 37}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {2, 6}, offsetof(navConfig_t, general.emerg_descent_rate) }, - { {1, 10, 28, 65, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 20}, offsetof(navConfig_t, general.min_rth_distance) }, - { {1, 221, 2, 58, 130, 3}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_NAV_OVERRIDES_MOTOR_STOP }, offsetof(navConfig_t, general.flags.nav_overrides_motor_stop) }, - { {179, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(navConfig_t, general.flags.soaring_motor_stop) }, - { {1, 2, 255, 2, 11, 29}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 24}, offsetof(navConfig_t, fw.soaring_pitch_deadband) }, - { {1, 28, 76, 162, 1, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_NAV_RTH_CLIMB_FIRST }, offsetof(navConfig_t, general.flags.rth_climb_first) }, - { {191, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_NAV_RTH_CLIMB_FIRST_STAGE_MODES }, offsetof(navConfig_t, general.flags.rth_climb_first_stage_mode) }, - { {190, 2, 0, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 21}, offsetof(navConfig_t, general.rth_climb_first_stage_altitude) }, - { {192, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(navConfig_t, general.flags.rth_climb_ignore_emerg) }, - { {1, 28, 135, 3, 162, 1}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(navConfig_t, general.flags.rth_tail_first) }, - { {1, 28, 218, 1, 129, 1}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_NAV_RTH_ALLOW_LANDING }, offsetof(navConfig_t, general.flags.rth_allow_landing) }, - { {1, 28, 74, 49, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_NAV_RTH_ALT_MODE }, offsetof(navConfig_t, general.flags.rth_alt_control_mode) }, - { {1, 28, 74, 77, 220, 2}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(navConfig_t, general.flags.rth_alt_control_override) }, - { {1, 28, 147, 1, 60, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 21}, offsetof(navConfig_t, general.rth_abort_threshold) }, - { {183, 2, 0, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 3}, offsetof(navConfig_t, general.max_terrain_follow_altitude) }, - { {1, 6, 53, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 21}, offsetof(navConfig_t, general.max_altitude) }, - { {1, 28, 53, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 21}, offsetof(navConfig_t, general.rth_altitude) }, - { {1, 28, 170, 1, 53, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 21}, offsetof(navConfig_t, general.rth_home_altitude) }, - { {1, 28, 208, 1, 49, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_RTH_TRACKBACK_MODE }, offsetof(navConfig_t, general.flags.rth_trackback_mode) }, - { {1, 28, 208, 1, 65, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {16, 6}, offsetof(navConfig_t, general.rth_trackback_distance) }, - { {199, 1, 6, 65, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 21}, offsetof(navConfig_t, general.safehome_max_distance) }, - { {199, 1, 145, 3, 49, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_SAFEHOME_USAGE_MODE }, offsetof(navConfig_t, general.flags.safehome_usage_mode) }, - { {189, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(navConfig_t, general.flags.mission_planner_reset) }, - { {1, 4, 117, 24, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {24, 52}, offsetof(navConfig_t, mc.max_bank_angle) }, - { {1, 46, 102, 33, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {2, 11}, offsetof(navConfig_t, general.auto_disarm_delay) }, - { {1, 4, 55, 37, 60, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 3}, offsetof(navConfig_t, mc.braking_speed_threshold) }, - { {1, 4, 55, 252, 1, 37}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 3}, offsetof(navConfig_t, mc.braking_disengage_speed) }, - { {1, 4, 55, 85, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {2, 20}, offsetof(navConfig_t, mc.braking_timeout) }, - { {1, 4, 55, 75, 160, 1}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 17}, offsetof(navConfig_t, mc.braking_boost_factor) }, - { {1, 4, 55, 75, 85, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 20}, offsetof(navConfig_t, mc.braking_boost_timeout) }, - { {1, 4, 55, 75, 37, 60}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {2, 3}, offsetof(navConfig_t, mc.braking_boost_speed_threshold) }, - { {184, 2, 0, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 3}, offsetof(navConfig_t, mc.braking_boost_disengage_speed) }, - { {1, 4, 55, 117, 24, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {24, 32}, offsetof(navConfig_t, mc.braking_bank_angle) }, - { {1, 4, 23, 242, 1, 25}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 1}, offsetof(navConfig_t, mc.posDecelerationTime) }, - { {1, 4, 23, 56, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 1}, offsetof(navConfig_t, mc.posResponseExpo) }, - { {1, 4, 73, 141, 1, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(navConfig_t, mc.slowDownForTurning) }, - { {1, 2, 117, 24, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {7, 28}, offsetof(navConfig_t, fw.max_bank_angle) }, - { {1, 2, 76, 24, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {7, 28}, offsetof(navConfig_t, fw.max_climb_angle) }, - { {1, 2, 157, 1, 24, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {7, 28}, offsetof(navConfig_t, fw.max_dive_angle) }, - { {1, 2, 135, 1, 201, 1}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 38}, offsetof(navConfig_t, fw.pitch_to_throttle_smooth) }, - { {2, 10, 38, 128, 2, 11}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 59}, offsetof(navConfig_t, fw.minThrottleDownPitchAngle) }, - { {1, 2, 135, 1, 60, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 39}, offsetof(navConfig_t, fw.pitch_to_throttle_thresh) }, - { {1, 2, 177, 1, 193, 1}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 95}, offsetof(navConfig_t, fw.loiter_radius) }, - { {2, 177, 1, 154, 1, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_DIRECTION }, offsetof(navConfig_t, fw.loiter_direction) }, - { {1, 2, 99, 37, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 13}, offsetof(navConfig_t, fw.cruise_speed) }, - { {1, 2, 77, 253, 2, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 38}, offsetof(navConfig_t, fw.control_smoothness) }, - { {1, 2, 68, 157, 1, 24}, VAR_INT8 | MASTER_VALUE, .config.minmax.indexes = {31, 15}, offsetof(navConfig_t, fw.land_dive_angle) }, - { {1, 2, 16, 148, 3, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {2, 11}, offsetof(navConfig_t, fw.launch_velocity_thresh) }, - { {1, 2, 16, 112, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {3, 94}, offsetof(navConfig_t, fw.launch_accel_thresh) }, - { {1, 2, 16, 6, 24, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {7, 29}, offsetof(navConfig_t, fw.launch_max_angle) }, - { {1, 2, 16, 123, 25, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {4, 3}, offsetof(navConfig_t, fw.launch_time_thresh) }, - { {1, 2, 16, 107, 58, 33}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 37}, offsetof(navConfig_t, fw.launch_idle_motor_timer) }, - { {1, 2, 16, 58, 33, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 20}, offsetof(navConfig_t, fw.launch_motor_timer) }, - { {1, 2, 16, 128, 3, 25}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 3}, offsetof(navConfig_t, fw.launch_motor_spinup_time) }, - { {1, 2, 16, 104, 25, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 20}, offsetof(navConfig_t, fw.launch_end_time) }, - { {1, 2, 16, 10, 25, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 37}, offsetof(navConfig_t, fw.launch_min_time) }, - { {1, 2, 16, 85, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 37}, offsetof(navConfig_t, fw.launch_timeout) }, - { {1, 2, 16, 6, 53, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 37}, offsetof(navConfig_t, fw.launch_max_altitude) }, - { {1, 2, 16, 76, 24, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {7, 52}, offsetof(navConfig_t, fw.launch_climb_angle) }, - { {1, 2, 16, 48, 38, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(navConfig_t, fw.launch_manual_throttle) }, - { {1, 2, 16, 147, 1, 29}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {14, 19}, offsetof(navConfig_t, fw.launch_abort_deadband) }, - { {1, 2, 99, 8, 5, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 32}, offsetof(navConfig_t, fw.cruise_yaw_rate) }, - { {177, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(navConfig_t, fw.allow_manual_thr_increase) }, - { {1, 72, 2, 8, 77, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(navConfig_t, fw.useFwNavYawControl) }, - { {1, 2, 8, 29, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 33}, offsetof(navConfig_t, fw.yawControlDeadband) }, - // PG_OSD_CONFIG - { {3, 136, 3, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSD_TELEMETRY }, offsetof(osdConfig_t, telemetry) }, - { {3, 150, 3, 134, 3, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSD_VIDEO_SYSTEM }, offsetof(osdConfig_t, video_system) }, - { {3, 244, 2, 250, 2, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 5}, offsetof(osdConfig_t, row_shiftdown) }, - { {3, 144, 3, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSD_UNIT }, offsetof(osdConfig_t, units) }, - { {3, 71, 124, 111, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSD_STATS_ENERGY_UNIT }, offsetof(osdConfig_t, stats_energy_unit) }, - { {3, 71, 10, 63, 111, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSD_STATS_MIN_VOLTAGE_UNIT }, offsetof(osdConfig_t, stats_min_voltage_unit) }, - { {216, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(osdConfig_t, stats_page_auto_swap_time) }, - { {3, 36, 12, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(osdConfig_t, rssi_alarm) }, - { {3, 25, 12, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 60}, offsetof(osdConfig_t, time_alarm) }, - { {3, 74, 12, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 11}, offsetof(osdConfig_t, alt_alarm) }, - { {3, 156, 1, 12, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 97}, offsetof(osdConfig_t, dist_alarm) }, - { {3, 196, 2, 74, 12, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 11}, offsetof(osdConfig_t, neg_alt_alarm) }, - { {3, 43, 12, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 1}, offsetof(osdConfig_t, current_alarm) }, - { {3, 145, 2, 12, 0, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 15}, offsetof(osdConfig_t, gforce_alarm) }, - { {205, 2, 0, 0, 0, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {31, 15}, offsetof(osdConfig_t, gforce_axis_alarm_min) }, - { {204, 2, 0, 0, 0, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {31, 15}, offsetof(osdConfig_t, gforce_axis_alarm_max) }, - { {3, 34, 51, 12, 10, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {23, 35}, offsetof(osdConfig_t, imu_temp_alarm_min) }, - { {3, 34, 51, 12, 6, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {23, 35}, offsetof(osdConfig_t, imu_temp_alarm_max) }, - { {3, 105, 51, 12, 6, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {23, 40}, offsetof(osdConfig_t, esc_temp_alarm_max) }, - { {3, 105, 51, 12, 10, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {23, 40}, offsetof(osdConfig_t, esc_temp_alarm_min) }, - { {3, 54, 51, 12, 10, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {23, 35}, offsetof(osdConfig_t, baro_temp_alarm_min) }, - { {3, 54, 51, 12, 6, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {23, 35}, offsetof(osdConfig_t, baro_temp_alarm_max) }, - { {3, 254, 2, 12, 0, 0}, VAR_INT8 | MASTER_VALUE, .config.minmax.indexes = {31, 4}, offsetof(osdConfig_t, snr_alarm) }, - { {3, 166, 2, 233, 2, 12}, VAR_INT8 | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(osdConfig_t, link_quality_alarm) }, - { {3, 36, 122, 12, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {45, 0}, offsetof(osdConfig_t, rssi_dbm_alarm) }, - { {3, 36, 122, 6, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {72, 0}, offsetof(osdConfig_t, rssi_dbm_max) }, - { {3, 36, 122, 10, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {45, 0}, offsetof(osdConfig_t, rssi_dbm_min) }, - { {3, 51, 163, 2, 41, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSD_ALIGNMENT }, offsetof(osdConfig_t, temp_label_align) }, - { {3, 91, 12, 10, 0, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 65}, offsetof(osdConfig_t, airspeed_alarm_min) }, - { {3, 91, 12, 6, 0, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 65}, offsetof(osdConfig_t, airspeed_alarm_max) }, - { {3, 40, 240, 2, 18, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(osdConfig_t, ahi_reverse_roll) }, - { {3, 40, 6, 11, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {4, 33}, offsetof(osdConfig_t, ahi_max_pitch) }, - { {3, 237, 1, 204, 1, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSD_CROSSHAIRS_STYLE }, offsetof(osdConfig_t, crosshairs_style) }, - { {202, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSD_CRSF_LQ_FORMAT }, offsetof(osdConfig_t, crsf_lq_format) }, - { {3, 153, 2, 69, 0, 0}, VAR_INT8 | MASTER_VALUE, .config.minmax.indexes = {76, 14}, offsetof(osdConfig_t, horizon_offset) }, - { {3, 93, 211, 1, 0, 0}, VAR_INT8 | MASTER_VALUE, .config.minmax.indexes = {73, 28}, offsetof(osdConfig_t, camera_uptilt) }, - { {3, 40, 93, 211, 1, 98}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(osdConfig_t, ahi_camera_uptilt_comp) }, - { {3, 93, 164, 1, 167, 1}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {32, 55}, offsetof(osdConfig_t, camera_fov_h) }, - { {3, 93, 164, 1, 52, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {18, 53}, offsetof(osdConfig_t, camera_fov_v) }, - { {3, 67, 133, 1, 167, 1}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 12}, offsetof(osdConfig_t, hud_margin_h) }, - { {3, 67, 133, 1, 52, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {5, 26}, offsetof(osdConfig_t, hud_margin_v) }, - { {3, 67, 152, 2, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(osdConfig_t, hud_homing) }, - { {3, 67, 151, 2, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(osdConfig_t, hud_homepoint) }, - { {3, 67, 234, 2, 155, 1}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 12}, offsetof(osdConfig_t, hud_radar_disp) }, - { {210, 2, 0, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {5, 18}, offsetof(osdConfig_t, hud_radar_range_min) }, - { {209, 2, 0, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {2, 91}, offsetof(osdConfig_t, hud_radar_range_max) }, - { {207, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(osdConfig_t, hud_radar_alt_difference_display_time) }, - { {208, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {5, 4}, offsetof(osdConfig_t, hud_radar_distance_display_time) }, - { {3, 67, 73, 155, 1, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 26}, offsetof(osdConfig_t, hud_wp_disp) }, - { {3, 165, 2, 83, 138, 1}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSD_SIDEBAR_SCROLL }, offsetof(osdConfig_t, left_sidebar_scroll) }, - { {3, 241, 2, 83, 138, 1}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSD_SIDEBAR_SCROLL }, offsetof(osdConfig_t, right_sidebar_scroll) }, - { {3, 83, 138, 1, 220, 1}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(osdConfig_t, sidebar_scroll_arrows) }, - { {3, 132, 1, 63, 243, 1}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {5, 14}, offsetof(osdConfig_t, main_voltage_decimals) }, - { {3, 235, 1, 251, 1, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {49, 77}, offsetof(osdConfig_t, coordinate_digits) }, - { {203, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(osdConfig_t, estimations_wind_compensation) }, - { {3, 19, 31, 164, 2, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(osdConfig_t, osd_failsafe_switch_layout) }, - { {213, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {4, 79}, offsetof(osdConfig_t, plus_code_digits) }, - { {214, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSD_PLUS_CODE_SHORT }, offsetof(osdConfig_t, plus_code_short) }, - { {3, 40, 204, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSD_AHI_STYLE }, offsetof(osdConfig_t, ahi_style) }, - { {3, 138, 2, 146, 2, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(osdConfig_t, force_grid) }, - { {3, 40, 225, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(osdConfig_t, ahi_bordered) }, - { {3, 40, 151, 3, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 1}, offsetof(osdConfig_t, ahi_width) }, - { {3, 40, 169, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 1}, offsetof(osdConfig_t, ahi_height) }, - { {3, 40, 149, 3, 69, 0}, VAR_INT8 | MASTER_VALUE, .config.minmax.indexes = {46, 54}, offsetof(osdConfig_t, ahi_vertical_offset) }, - { {3, 83, 154, 2, 69, 0}, VAR_INT8 | MASTER_VALUE, .config.minmax.indexes = {46, 54}, offsetof(osdConfig_t, sidebar_horizontal_offset) }, - { {211, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 1}, offsetof(osdConfig_t, left_sidebar_scroll_step) }, - { {215, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 1}, offsetof(osdConfig_t, right_sidebar_scroll_step) }, - { {3, 83, 169, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 7}, offsetof(osdConfig_t, sidebar_height) }, - { {3, 40, 11, 173, 1, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 18}, offsetof(osdConfig_t, ahi_pitch_interval) }, - { {206, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(osdConfig_t, osd_home_position_arm_screen) }, - { {3, 187, 1, 50, 158, 2}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 4}, offsetof(osdConfig_t, pan_servo_index) }, - { {3, 187, 1, 50, 232, 2}, VAR_INT8 | MASTER_VALUE, .config.minmax.indexes = {74, 82}, offsetof(osdConfig_t, pan_servo_pwm2centideg) }, - { {3, 105, 245, 2, 228, 2}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {26, 48}, offsetof(osdConfig_t, esc_rpm_precision) }, - { {212, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {12, 48}, offsetof(osdConfig_t, mAh_used_precision) }, - { {3, 31, 47, 88, 81, 0}, VAR_STRING | MASTER_VALUE, .config.minmax.indexes = {0, 7}, offsetof(osdConfig_t, osd_switch_indicator0_name) }, - { {3, 31, 47, 186, 1, 81}, VAR_STRING | MASTER_VALUE, .config.minmax.indexes = {0, 7}, offsetof(osdConfig_t, osd_switch_indicator1_name) }, - { {3, 31, 47, 209, 1, 81}, VAR_STRING | MASTER_VALUE, .config.minmax.indexes = {0, 7}, offsetof(osdConfig_t, osd_switch_indicator2_name) }, - { {3, 31, 47, 205, 1, 81}, VAR_STRING | MASTER_VALUE, .config.minmax.indexes = {0, 7}, offsetof(osdConfig_t, osd_switch_indicator3_name) }, - { {3, 31, 47, 88, 42, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {7, 27}, offsetof(osdConfig_t, osd_switch_indicator0_channel) }, - { {3, 31, 47, 186, 1, 42}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {7, 27}, offsetof(osdConfig_t, osd_switch_indicator1_channel) }, - { {3, 31, 47, 209, 1, 42}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {7, 27}, offsetof(osdConfig_t, osd_switch_indicator2_channel) }, - { {3, 31, 47, 205, 1, 42}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {7, 27}, offsetof(osdConfig_t, osd_switch_indicator3_channel) }, - { {217, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(osdConfig_t, osd_switch_indicators_align_left) }, - { {218, 2, 0, 0, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {8, 20}, offsetof(osdConfig_t, system_msg_display_time) }, - // PG_OSD_COMMON_CONFIG - { {3, 37, 84, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSDSPEEDSOURCE }, offsetof(osdCommonConfig_t, speedSource) }, - // PG_SYSTEM_CONFIG - { {241, 1, 49, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_DEBUG_MODES }, offsetof(systemConfig_t, debug_mode) }, - { {38, 137, 3, 98, 131, 3}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(systemConfig_t, throttle_tilt_compensation_strength) }, - { {81, 0, 0, 0, 0, 0}, VAR_STRING | MASTER_VALUE, .config.minmax.indexes = {0, 80}, offsetof(systemConfig_t, name) }, - // PG_MODE_ACTIVATION_OPERATOR_CONFIG - { {174, 2, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_AUX_OPERATOR }, offsetof(modeActivationOperatorConfig_t, modeActivationOperator) }, - // PG_STATS_CONFIG - { {71, 0, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(statsConfig_t, stats_enabled) }, - { {71, 144, 1, 25, 0, 0}, VAR_UINT32 | MASTER_VALUE, .config.minmax.indexes = {0, 43}, offsetof(statsConfig_t, stats_total_time) }, - { {71, 144, 1, 156, 1, 0}, VAR_UINT32 | MASTER_VALUE, .config.minmax.indexes = {0, 43}, offsetof(statsConfig_t, stats_total_dist) }, - { {71, 144, 1, 124, 0, 0}, VAR_UINT32 | MASTER_VALUE, .config.minmax.indexes = {0, 43}, offsetof(statsConfig_t, stats_total_energy) }, - // PG_TIME_CONFIG - { {210, 1, 69, 0, 0, 0}, VAR_INT16 | MASTER_VALUE, .config.minmax.indexes = {70, 88}, offsetof(timeConfig_t, tz_offset) }, - { {210, 1, 222, 1, 129, 2}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_TZ_AUTOMATIC_DST }, offsetof(timeConfig_t, tz_automatic_dst) }, - // PG_DISPLAY_CONFIG - { {253, 1, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(displayConfig_t, force_sw_blink) }, - // PG_LOG_CONFIG - { {176, 1, 44, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_LOG_LEVEL }, offsetof(logConfig_t, level) }, - { {176, 1, 139, 3, 0, 0}, VAR_UINT32 | MASTER_VALUE, .config.minmax.indexes = {0, 30}, offsetof(logConfig_t, topics) }, - // PG_SMARTPORT_MASTER_CONFIG - { {200, 1, 180, 1, 168, 1}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(smartportMasterConfig_t, halfDuplex) }, - { {200, 1, 180, 1, 128, 1}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(smartportMasterConfig_t, inverted) }, - // PG_DJI_OSD_CONFIG - { {78, 154, 3, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {0, 1}, offsetof(djiOsdConfig_t, proto_workarounds) }, - { {255, 1, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(djiOsdConfig_t, use_name_for_messages) }, - { {78, 105, 51, 84, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_DJIOSDTEMPSOURCE }, offsetof(djiOsdConfig_t, esc_temperature_source) }, - { {78, 169, 2, 37, 84, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OSDSPEEDSOURCE }, offsetof(djiOsdConfig_t, messageSpeedSource) }, - { {78, 36, 84, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_DJIRSSISOURCE }, offsetof(djiOsdConfig_t, rssi_source) }, - { {78, 72, 217, 1, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(djiOsdConfig_t, useAdjustments) }, - { {254, 1, 0, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {5, 55}, offsetof(djiOsdConfig_t, craftNameAlternatingDuration) }, - // PG_BEEPER_CONFIG - { {158, 1, 118, 131, 2, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(beeperConfig_t, dshot_beeper_enabled) }, - { {158, 1, 118, 138, 3, 0}, VAR_UINT8 | MASTER_VALUE, .config.minmax.indexes = {5, 7}, offsetof(beeperConfig_t, dshot_beeper_tone) }, - { {118, 110, 49, 0, 0, 0}, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, offsetof(beeperConfig_t, pwmMode) }, - // PG_POWER_LIMITS_CONFIG - { {13, 188, 1, 7, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 11}, offsetof(powerLimitsConfig_t, piP) }, - { {13, 188, 1, 22, 0, 0}, VAR_UINT16 | MASTER_VALUE, .config.minmax.indexes = {0, 11}, offsetof(powerLimitsConfig_t, piI) }, - { {13, 221, 1, 80, 100, 0}, VAR_FLOAT | MASTER_VALUE, .config.minmax.indexes = {0, 2}, offsetof(powerLimitsConfig_t, attnFilterCutoff) }, -}; diff --git a/src/main/fc/settings_generated.h b/src/main/fc/settings_generated.h deleted file mode 100644 index 2ad7c90104..0000000000 --- a/src/main/fc/settings_generated.h +++ /dev/null @@ -1,2209 +0,0 @@ -// This file has been automatically generated by utils/settings.rb -// Don't make any modifications to it. They will be lost. - -#pragma once -#define SETTING_MAX_NAME_LENGTH 42 -#define SETTING_MAX_WORD_LENGTH 42 -#define SETTING_ENCODED_NAME_MAX_BYTES 6 -#define SETTINGS_WORDS_BITS_PER_CHAR 5 -#define SETTINGS_TABLE_COUNT 518 -typedef uint16_t setting_offset_t; -#define SETTINGS_PGN_COUNT 41 -typedef int16_t setting_min_t; -typedef uint32_t setting_max_t; -#define SETTING_MIN_MAX_INDEX_BYTES 2 -enum { - TABLE_ACC_HARDWARE, - TABLE_AIRMODEHANDLINGTYPE, - TABLE_ALIGNMENT, - TABLE_AUTOTUNE_RATE_ADJUSTMENT, - TABLE_AUX_OPERATOR, - TABLE_BARO_HARDWARE, - TABLE_BAT_CAPACITY_UNIT, - TABLE_BAT_VOLTAGE_SOURCE, - TABLE_BLACKBOX_DEVICE, - TABLE_CURRENT_SENSOR, - TABLE_DEBUG_MODES, - TABLE_DIRECTION, - TABLE_DJIOSDTEMPSOURCE, - TABLE_DJIRSSISOURCE, - TABLE_FAILSAFE_PROCEDURE, - TABLE_FILTER_TYPE, - TABLE_FILTER_TYPE_FULL, - TABLE_GPS_DYN_MODEL, - TABLE_GPS_PROVIDER, - TABLE_GPS_SBAS_MODE, - TABLE_GYRO_LPF, - TABLE_IMU_INERTIA_COMP_METHOD, - TABLE_ITERM_RELAX, - TABLE_LOG_LEVEL, - TABLE_MAG_HARDWARE, - TABLE_MOTOR_PWM_PROTOCOL, - TABLE_NAV_EXTRA_ARMING_SAFETY, - TABLE_NAV_FW_WP_TURN_SMOOTHING, - TABLE_NAV_OVERRIDES_MOTOR_STOP, - TABLE_NAV_RTH_ALLOW_LANDING, - TABLE_NAV_RTH_ALT_MODE, - TABLE_NAV_RTH_CLIMB_FIRST, - TABLE_NAV_RTH_CLIMB_FIRST_STAGE_MODES, - TABLE_NAV_USER_CONTROL_MODE, - TABLE_NAV_WP_MISSION_RESTART, - TABLE_OFF_ON, - TABLE_OPFLOW_HARDWARE, - TABLE_OSDSPEEDSOURCE, - TABLE_OSD_AHI_STYLE, - TABLE_OSD_ALIGNMENT, - TABLE_OSD_CROSSHAIRS_STYLE, - TABLE_OSD_CRSF_LQ_FORMAT, - TABLE_OSD_PLUS_CODE_SHORT, - TABLE_OSD_SIDEBAR_SCROLL, - TABLE_OSD_STATS_ENERGY_UNIT, - TABLE_OSD_STATS_MIN_VOLTAGE_UNIT, - TABLE_OSD_TELEMETRY, - TABLE_OSD_UNIT, - TABLE_OSD_VIDEO_SYSTEM, - TABLE_OUTPUT_MODE, - TABLE_PIDTYPETABLE, - TABLE_PITOT_HARDWARE, - TABLE_PLATFORM_TYPE, - TABLE_RANGEFINDER_HARDWARE, - TABLE_RECEIVER_TYPE, - TABLE_RESET_TYPE, - TABLE_RSSI_SOURCE, - TABLE_RTH_TRACKBACK_MODE, - TABLE_SAFEHOME_USAGE_MODE, - TABLE_SERIAL_RX, - TABLE_SERVO_PROTOCOL, - TABLE_TRISTATE, - TABLE_TZ_AUTOMATIC_DST, - TABLE_VOLTAGE_SENSOR, - LOOKUP_TABLE_COUNT, -}; -extern const char * const table_acc_hardware[]; -extern const char * const table_airmodeHandlingType[]; -extern const char * const table_alignment[]; -extern const char * const table_autotune_rate_adjustment[]; -extern const char * const table_aux_operator[]; -extern const char * const table_baro_hardware[]; -extern const char * const table_bat_capacity_unit[]; -extern const char * const table_bat_voltage_source[]; -extern const char * const table_blackbox_device[]; -extern const char * const table_current_sensor[]; -extern const char * const table_debug_modes[]; -extern const char * const table_direction[]; -extern const char * const table_djiOsdTempSource[]; -extern const char * const table_djiRssiSource[]; -extern const char * const table_failsafe_procedure[]; -extern const char * const table_filter_type[]; -extern const char * const table_filter_type_full[]; -extern const char * const table_gps_dyn_model[]; -extern const char * const table_gps_provider[]; -extern const char * const table_gps_sbas_mode[]; -extern const char * const table_gyro_lpf[]; -extern const char * const table_imu_inertia_comp_method[]; -extern const char * const table_iterm_relax[]; -extern const char * const table_log_level[]; -extern const char * const table_mag_hardware[]; -extern const char * const table_motor_pwm_protocol[]; -extern const char * const table_nav_extra_arming_safety[]; -extern const char * const table_nav_fw_wp_turn_smoothing[]; -extern const char * const table_nav_overrides_motor_stop[]; -extern const char * const table_nav_rth_allow_landing[]; -extern const char * const table_nav_rth_alt_mode[]; -extern const char * const table_nav_rth_climb_first[]; -extern const char * const table_nav_rth_climb_first_stage_modes[]; -extern const char * const table_nav_user_control_mode[]; -extern const char * const table_nav_wp_mission_restart[]; -extern const char * const table_off_on[]; -extern const char * const table_opflow_hardware[]; -extern const char * const table_osdSpeedSource[]; -extern const char * const table_osd_ahi_style[]; -extern const char * const table_osd_alignment[]; -extern const char * const table_osd_crosshairs_style[]; -extern const char * const table_osd_crsf_lq_format[]; -extern const char * const table_osd_plus_code_short[]; -extern const char * const table_osd_sidebar_scroll[]; -extern const char * const table_osd_stats_energy_unit[]; -extern const char * const table_osd_stats_min_voltage_unit[]; -extern const char * const table_osd_telemetry[]; -extern const char * const table_osd_unit[]; -extern const char * const table_osd_video_system[]; -extern const char * const table_output_mode[]; -extern const char * const table_pidTypeTable[]; -extern const char * const table_pitot_hardware[]; -extern const char * const table_platform_type[]; -extern const char * const table_rangefinder_hardware[]; -extern const char * const table_receiver_type[]; -extern const char * const table_reset_type[]; -extern const char * const table_rssi_source[]; -extern const char * const table_rth_trackback_mode[]; -extern const char * const table_safehome_usage_mode[]; -extern const char * const table_serial_rx[]; -extern const char * const table_servo_protocol[]; -extern const char * const table_tristate[]; -extern const char * const table_tz_automatic_dst[]; -extern const char * const table_voltage_sensor[]; -#define SETTING_CONSTANT_RPYL_PID_MIN 0 -#define SETTING_CONSTANT_RPYL_PID_MAX 255 -#define SETTING_CONSTANT_MANUAL_RATE_MIN 0 -#define SETTING_CONSTANT_MANUAL_RATE_MAX 100 -#define SETTING_CONSTANT_ROLL_PITCH_RATE_MIN 4 -#define SETTING_CONSTANT_ROLL_PITCH_RATE_MAX 180 -#define SETTING_CONSTANT_MAX_CONTROL_RATE_PROFILE_COUNT 3 -#define SETTING_CONSTANT_MAX_BATTERY_PROFILE_COUNT 3 -#define SETTING_LOOPTIME_DEFAULT 1000 -#define SETTING_LOOPTIME 0 -#define SETTING_LOOPTIME_MIN 0 -#define SETTING_LOOPTIME_MAX 9000 -#define SETTING_GYRO_HARDWARE_LPF_DEFAULT 0 -#define SETTING_GYRO_HARDWARE_LPF 1 -#define SETTING_GYRO_HARDWARE_LPF_MIN 0 -#define SETTING_GYRO_HARDWARE_LPF_MAX 0 -#define SETTING_GYRO_ANTI_ALIASING_LPF_HZ_DEFAULT 250 -#define SETTING_GYRO_ANTI_ALIASING_LPF_HZ 2 -#define SETTING_GYRO_ANTI_ALIASING_LPF_HZ_MIN 0 -#define SETTING_GYRO_ANTI_ALIASING_LPF_HZ_MAX 1000 -#define SETTING_GYRO_ANTI_ALIASING_LPF_TYPE_DEFAULT 0 -#define SETTING_GYRO_ANTI_ALIASING_LPF_TYPE 3 -#define SETTING_GYRO_ANTI_ALIASING_LPF_TYPE_MIN 0 -#define SETTING_GYRO_ANTI_ALIASING_LPF_TYPE_MAX 0 -#define SETTING_MORON_THRESHOLD_DEFAULT 32 -#define SETTING_MORON_THRESHOLD 4 -#define SETTING_MORON_THRESHOLD_MIN 0 -#define SETTING_MORON_THRESHOLD_MAX 128 -#define SETTING_GYRO_MAIN_LPF_HZ_DEFAULT 60 -#define SETTING_GYRO_MAIN_LPF_HZ 5 -#define SETTING_GYRO_MAIN_LPF_HZ_MIN 0 -#define SETTING_GYRO_MAIN_LPF_HZ_MAX 500 -#define SETTING_GYRO_MAIN_LPF_TYPE_DEFAULT 1 -#define SETTING_GYRO_MAIN_LPF_TYPE 6 -#define SETTING_GYRO_MAIN_LPF_TYPE_MIN 0 -#define SETTING_GYRO_MAIN_LPF_TYPE_MAX 0 -#define SETTING_GYRO_USE_DYN_LPF_DEFAULT 0 -#define SETTING_GYRO_USE_DYN_LPF 7 -#define SETTING_GYRO_USE_DYN_LPF_MIN 0 -#define SETTING_GYRO_USE_DYN_LPF_MAX 0 -#define SETTING_GYRO_DYN_LPF_MIN_HZ_DEFAULT 200 -#define SETTING_GYRO_DYN_LPF_MIN_HZ 8 -#define SETTING_GYRO_DYN_LPF_MIN_HZ_MIN 40 -#define SETTING_GYRO_DYN_LPF_MIN_HZ_MAX 400 -#define SETTING_GYRO_DYN_LPF_MAX_HZ_DEFAULT 500 -#define SETTING_GYRO_DYN_LPF_MAX_HZ 9 -#define SETTING_GYRO_DYN_LPF_MAX_HZ_MIN 40 -#define SETTING_GYRO_DYN_LPF_MAX_HZ_MAX 1000 -#define SETTING_GYRO_DYN_LPF_CURVE_EXPO_DEFAULT 5 -#define SETTING_GYRO_DYN_LPF_CURVE_EXPO 10 -#define SETTING_GYRO_DYN_LPF_CURVE_EXPO_MIN 1 -#define SETTING_GYRO_DYN_LPF_CURVE_EXPO_MAX 10 -#define SETTING_INIT_GYRO_CAL_DEFAULT 1 -#define SETTING_INIT_GYRO_CAL 11 -#define SETTING_INIT_GYRO_CAL_MIN 0 -#define SETTING_INIT_GYRO_CAL_MAX 0 -#define SETTING_GYRO_ZERO_X_DEFAULT 0 -#define SETTING_GYRO_ZERO_X 12 -#define SETTING_GYRO_ZERO_X_MIN -32768 -#define SETTING_GYRO_ZERO_X_MAX 32767 -#define SETTING_GYRO_ZERO_Y_DEFAULT 0 -#define SETTING_GYRO_ZERO_Y 13 -#define SETTING_GYRO_ZERO_Y_MIN -32768 -#define SETTING_GYRO_ZERO_Y_MAX 32767 -#define SETTING_GYRO_ZERO_Z_DEFAULT 0 -#define SETTING_GYRO_ZERO_Z 14 -#define SETTING_GYRO_ZERO_Z_MIN -32768 -#define SETTING_GYRO_ZERO_Z_MAX 32767 -#define SETTING_INS_GRAVITY_CMSS_DEFAULT 0.0f -#define SETTING_INS_GRAVITY_CMSS 15 -#define SETTING_INS_GRAVITY_CMSS_MIN 0 -#define SETTING_INS_GRAVITY_CMSS_MAX 2000 -#define SETTING_VBAT_ADC_CHANNEL 16 -#define SETTING_VBAT_ADC_CHANNEL_MIN 0 -#define SETTING_VBAT_ADC_CHANNEL_MAX 4 -#define SETTING_RSSI_ADC_CHANNEL 17 -#define SETTING_RSSI_ADC_CHANNEL_MIN 0 -#define SETTING_RSSI_ADC_CHANNEL_MAX 4 -#define SETTING_CURRENT_ADC_CHANNEL 18 -#define SETTING_CURRENT_ADC_CHANNEL_MIN 0 -#define SETTING_CURRENT_ADC_CHANNEL_MAX 4 -#define SETTING_AIRSPEED_ADC_CHANNEL 19 -#define SETTING_AIRSPEED_ADC_CHANNEL_MIN 0 -#define SETTING_AIRSPEED_ADC_CHANNEL_MAX 4 -#define SETTING_ACC_NOTCH_HZ_DEFAULT 0 -#define SETTING_ACC_NOTCH_HZ 20 -#define SETTING_ACC_NOTCH_HZ_MIN 0 -#define SETTING_ACC_NOTCH_HZ_MAX 255 -#define SETTING_ACC_NOTCH_CUTOFF_DEFAULT 1 -#define SETTING_ACC_NOTCH_CUTOFF 21 -#define SETTING_ACC_NOTCH_CUTOFF_MIN 1 -#define SETTING_ACC_NOTCH_CUTOFF_MAX 255 -#define SETTING_ACC_HARDWARE_DEFAULT 1 -#define SETTING_ACC_HARDWARE 22 -#define SETTING_ACC_HARDWARE_MIN 0 -#define SETTING_ACC_HARDWARE_MAX 0 -#define SETTING_ACC_LPF_HZ_DEFAULT 15 -#define SETTING_ACC_LPF_HZ 23 -#define SETTING_ACC_LPF_HZ_MIN 0 -#define SETTING_ACC_LPF_HZ_MAX 200 -#define SETTING_ACC_LPF_TYPE_DEFAULT 1 -#define SETTING_ACC_LPF_TYPE 24 -#define SETTING_ACC_LPF_TYPE_MIN 0 -#define SETTING_ACC_LPF_TYPE_MAX 0 -#define SETTING_ACCZERO_X_DEFAULT 0 -#define SETTING_ACCZERO_X 25 -#define SETTING_ACCZERO_X_MIN -32768 -#define SETTING_ACCZERO_X_MAX 32767 -#define SETTING_ACCZERO_Y_DEFAULT 0 -#define SETTING_ACCZERO_Y 26 -#define SETTING_ACCZERO_Y_MIN -32768 -#define SETTING_ACCZERO_Y_MAX 32767 -#define SETTING_ACCZERO_Z_DEFAULT 0 -#define SETTING_ACCZERO_Z 27 -#define SETTING_ACCZERO_Z_MIN -32768 -#define SETTING_ACCZERO_Z_MAX 32767 -#define SETTING_ACCGAIN_X_DEFAULT 4096 -#define SETTING_ACCGAIN_X 28 -#define SETTING_ACCGAIN_X_MIN 1 -#define SETTING_ACCGAIN_X_MAX 8192 -#define SETTING_ACCGAIN_Y_DEFAULT 4096 -#define SETTING_ACCGAIN_Y 29 -#define SETTING_ACCGAIN_Y_MIN 1 -#define SETTING_ACCGAIN_Y_MAX 8192 -#define SETTING_ACCGAIN_Z_DEFAULT 4096 -#define SETTING_ACCGAIN_Z 30 -#define SETTING_ACCGAIN_Z_MIN 1 -#define SETTING_ACCGAIN_Z_MAX 8192 -#define SETTING_RANGEFINDER_HARDWARE_DEFAULT 0 -#define SETTING_RANGEFINDER_HARDWARE 31 -#define SETTING_RANGEFINDER_HARDWARE_MIN 0 -#define SETTING_RANGEFINDER_HARDWARE_MAX 0 -#define SETTING_RANGEFINDER_MEDIAN_FILTER_DEFAULT 0 -#define SETTING_RANGEFINDER_MEDIAN_FILTER 32 -#define SETTING_RANGEFINDER_MEDIAN_FILTER_MIN 0 -#define SETTING_RANGEFINDER_MEDIAN_FILTER_MAX 0 -#define SETTING_OPFLOW_HARDWARE_DEFAULT 0 -#define SETTING_OPFLOW_HARDWARE 33 -#define SETTING_OPFLOW_HARDWARE_MIN 0 -#define SETTING_OPFLOW_HARDWARE_MAX 0 -#define SETTING_OPFLOW_SCALE_DEFAULT 10.5f -#define SETTING_OPFLOW_SCALE 34 -#define SETTING_OPFLOW_SCALE_MIN 0 -#define SETTING_OPFLOW_SCALE_MAX 10000 -#define SETTING_ALIGN_OPFLOW_DEFAULT 5 -#define SETTING_ALIGN_OPFLOW 35 -#define SETTING_ALIGN_OPFLOW_MIN 0 -#define SETTING_ALIGN_OPFLOW_MAX 0 -#define SETTING_ALIGN_MAG_DEFAULT 0 -#define SETTING_ALIGN_MAG 36 -#define SETTING_ALIGN_MAG_MIN 0 -#define SETTING_ALIGN_MAG_MAX 0 -#define SETTING_MAG_HARDWARE_DEFAULT 1 -#define SETTING_MAG_HARDWARE 37 -#define SETTING_MAG_HARDWARE_MIN 0 -#define SETTING_MAG_HARDWARE_MAX 0 -#define SETTING_MAG_DECLINATION_DEFAULT 0 -#define SETTING_MAG_DECLINATION 38 -#define SETTING_MAG_DECLINATION_MIN -18000 -#define SETTING_MAG_DECLINATION_MAX 18000 -#define SETTING_MAGZERO_X 39 -#define SETTING_MAGZERO_X_MIN -32768 -#define SETTING_MAGZERO_X_MAX 32767 -#define SETTING_MAGZERO_Y 40 -#define SETTING_MAGZERO_Y_MIN -32768 -#define SETTING_MAGZERO_Y_MAX 32767 -#define SETTING_MAGZERO_Z 41 -#define SETTING_MAGZERO_Z_MIN -32768 -#define SETTING_MAGZERO_Z_MAX 32767 -#define SETTING_MAGGAIN_X_DEFAULT 1024 -#define SETTING_MAGGAIN_X 42 -#define SETTING_MAGGAIN_X_MIN -32768 -#define SETTING_MAGGAIN_X_MAX 32767 -#define SETTING_MAGGAIN_Y_DEFAULT 1024 -#define SETTING_MAGGAIN_Y 43 -#define SETTING_MAGGAIN_Y_MIN -32768 -#define SETTING_MAGGAIN_Y_MAX 32767 -#define SETTING_MAGGAIN_Z_DEFAULT 1024 -#define SETTING_MAGGAIN_Z 44 -#define SETTING_MAGGAIN_Z_MIN -32768 -#define SETTING_MAGGAIN_Z_MAX 32767 -#define SETTING_MAG_CALIBRATION_TIME_DEFAULT 30 -#define SETTING_MAG_CALIBRATION_TIME 45 -#define SETTING_MAG_CALIBRATION_TIME_MIN 20 -#define SETTING_MAG_CALIBRATION_TIME_MAX 120 -#define SETTING_ALIGN_MAG_ROLL_DEFAULT 0 -#define SETTING_ALIGN_MAG_ROLL 46 -#define SETTING_ALIGN_MAG_ROLL_MIN -1800 -#define SETTING_ALIGN_MAG_ROLL_MAX 3600 -#define SETTING_ALIGN_MAG_PITCH_DEFAULT 0 -#define SETTING_ALIGN_MAG_PITCH 47 -#define SETTING_ALIGN_MAG_PITCH_MIN -1800 -#define SETTING_ALIGN_MAG_PITCH_MAX 3600 -#define SETTING_ALIGN_MAG_YAW_DEFAULT 0 -#define SETTING_ALIGN_MAG_YAW 48 -#define SETTING_ALIGN_MAG_YAW_MIN -1800 -#define SETTING_ALIGN_MAG_YAW_MAX 3600 -#define SETTING_BARO_HARDWARE_DEFAULT 1 -#define SETTING_BARO_HARDWARE 49 -#define SETTING_BARO_HARDWARE_MIN 0 -#define SETTING_BARO_HARDWARE_MAX 0 -#define SETTING_BARO_CAL_TOLERANCE_DEFAULT 150 -#define SETTING_BARO_CAL_TOLERANCE 50 -#define SETTING_BARO_CAL_TOLERANCE_MIN 0 -#define SETTING_BARO_CAL_TOLERANCE_MAX 1000 -#define SETTING_PITOT_HARDWARE_DEFAULT 0 -#define SETTING_PITOT_HARDWARE 51 -#define SETTING_PITOT_HARDWARE_MIN 0 -#define SETTING_PITOT_HARDWARE_MAX 0 -#define SETTING_PITOT_LPF_MILLI_HZ_DEFAULT 350 -#define SETTING_PITOT_LPF_MILLI_HZ 52 -#define SETTING_PITOT_LPF_MILLI_HZ_MIN 0 -#define SETTING_PITOT_LPF_MILLI_HZ_MAX 10000 -#define SETTING_PITOT_SCALE_DEFAULT 1.0f -#define SETTING_PITOT_SCALE 53 -#define SETTING_PITOT_SCALE_MIN 0 -#define SETTING_PITOT_SCALE_MAX 100 -#define SETTING_RECEIVER_TYPE 54 -#define SETTING_RECEIVER_TYPE_MIN 0 -#define SETTING_RECEIVER_TYPE_MAX 0 -#define SETTING_MIN_CHECK_DEFAULT 1100 -#define SETTING_MIN_CHECK 55 -#define SETTING_MIN_CHECK_MIN 1000 -#define SETTING_MIN_CHECK_MAX 2000 -#define SETTING_MAX_CHECK_DEFAULT 1900 -#define SETTING_MAX_CHECK 56 -#define SETTING_MAX_CHECK_MIN 1000 -#define SETTING_MAX_CHECK_MAX 2000 -#define SETTING_RSSI_SOURCE_DEFAULT 1 -#define SETTING_RSSI_SOURCE 57 -#define SETTING_RSSI_SOURCE_MIN 0 -#define SETTING_RSSI_SOURCE_MAX 0 -#define SETTING_RSSI_CHANNEL_DEFAULT 0 -#define SETTING_RSSI_CHANNEL 58 -#define SETTING_RSSI_CHANNEL_MIN 0 -#define SETTING_RSSI_CHANNEL_MAX 18 -#define SETTING_RSSI_MIN_DEFAULT 0 -#define SETTING_RSSI_MIN 59 -#define SETTING_RSSI_MIN_MIN 0 -#define SETTING_RSSI_MIN_MAX 100 -#define SETTING_RSSI_MAX_DEFAULT 100 -#define SETTING_RSSI_MAX 60 -#define SETTING_RSSI_MAX_MIN 0 -#define SETTING_RSSI_MAX_MAX 100 -#define SETTING_SBUS_SYNC_INTERVAL_DEFAULT 3000 -#define SETTING_SBUS_SYNC_INTERVAL 61 -#define SETTING_SBUS_SYNC_INTERVAL_MIN 500 -#define SETTING_SBUS_SYNC_INTERVAL_MAX 10000 -#define SETTING_RC_FILTER_LPF_HZ_DEFAULT 50 -#define SETTING_RC_FILTER_LPF_HZ 62 -#define SETTING_RC_FILTER_LPF_HZ_MIN 15 -#define SETTING_RC_FILTER_LPF_HZ_MAX 250 -#define SETTING_RC_FILTER_AUTO_DEFAULT 0 -#define SETTING_RC_FILTER_AUTO 63 -#define SETTING_RC_FILTER_AUTO_MIN 0 -#define SETTING_RC_FILTER_AUTO_MAX 0 -#define SETTING_RC_FILTER_SMOOTHING_FACTOR_DEFAULT 30 -#define SETTING_RC_FILTER_SMOOTHING_FACTOR 64 -#define SETTING_RC_FILTER_SMOOTHING_FACTOR_MIN 1 -#define SETTING_RC_FILTER_SMOOTHING_FACTOR_MAX 100 -#define SETTING_SERIALRX_PROVIDER 65 -#define SETTING_SERIALRX_PROVIDER_MIN 0 -#define SETTING_SERIALRX_PROVIDER_MAX 0 -#define SETTING_SERIALRX_INVERTED_DEFAULT 0 -#define SETTING_SERIALRX_INVERTED 66 -#define SETTING_SERIALRX_INVERTED_MIN 0 -#define SETTING_SERIALRX_INVERTED_MAX 0 -#define SETTING_SRXL2_UNIT_ID_DEFAULT 1 -#define SETTING_SRXL2_UNIT_ID 67 -#define SETTING_SRXL2_UNIT_ID_MIN 0 -#define SETTING_SRXL2_UNIT_ID_MAX 15 -#define SETTING_SRXL2_BAUD_FAST_DEFAULT 1 -#define SETTING_SRXL2_BAUD_FAST 68 -#define SETTING_SRXL2_BAUD_FAST_MIN 0 -#define SETTING_SRXL2_BAUD_FAST_MAX 0 -#define SETTING_RX_MIN_USEC_DEFAULT 885 -#define SETTING_RX_MIN_USEC 69 -#define SETTING_RX_MIN_USEC_MIN 750 -#define SETTING_RX_MIN_USEC_MAX 2250 -#define SETTING_RX_MAX_USEC_DEFAULT 2115 -#define SETTING_RX_MAX_USEC 70 -#define SETTING_RX_MAX_USEC_MIN 750 -#define SETTING_RX_MAX_USEC_MAX 2250 -#define SETTING_SERIALRX_HALFDUPLEX_DEFAULT 0 -#define SETTING_SERIALRX_HALFDUPLEX 71 -#define SETTING_SERIALRX_HALFDUPLEX_MIN 0 -#define SETTING_SERIALRX_HALFDUPLEX_MAX 0 -#define SETTING_BLACKBOX_RATE_NUM_DEFAULT 1 -#define SETTING_BLACKBOX_RATE_NUM 72 -#define SETTING_BLACKBOX_RATE_NUM_MIN 1 -#define SETTING_BLACKBOX_RATE_NUM_MAX 65535 -#define SETTING_BLACKBOX_RATE_DENOM_DEFAULT 1 -#define SETTING_BLACKBOX_RATE_DENOM 73 -#define SETTING_BLACKBOX_RATE_DENOM_MIN 1 -#define SETTING_BLACKBOX_RATE_DENOM_MAX 65535 -#define SETTING_BLACKBOX_DEVICE 74 -#define SETTING_BLACKBOX_DEVICE_MIN 0 -#define SETTING_BLACKBOX_DEVICE_MAX 0 -#define SETTING_MAX_THROTTLE_DEFAULT 1850 -#define SETTING_MAX_THROTTLE 75 -#define SETTING_MAX_THROTTLE_MIN 1000 -#define SETTING_MAX_THROTTLE_MAX 2000 -#define SETTING_MIN_COMMAND_DEFAULT 1000 -#define SETTING_MIN_COMMAND 76 -#define SETTING_MIN_COMMAND_MIN 0 -#define SETTING_MIN_COMMAND_MAX 2000 -#define SETTING_MOTOR_PWM_RATE_DEFAULT 16000 -#define SETTING_MOTOR_PWM_RATE 77 -#define SETTING_MOTOR_PWM_RATE_MIN 50 -#define SETTING_MOTOR_PWM_RATE_MAX 32000 -#define SETTING_MOTOR_PWM_PROTOCOL_DEFAULT 1 -#define SETTING_MOTOR_PWM_PROTOCOL 78 -#define SETTING_MOTOR_PWM_PROTOCOL_MIN 0 -#define SETTING_MOTOR_PWM_PROTOCOL_MAX 0 -#define SETTING_MOTOR_POLES_DEFAULT 14 -#define SETTING_MOTOR_POLES 79 -#define SETTING_MOTOR_POLES_MIN 4 -#define SETTING_MOTOR_POLES_MAX 255 -#define SETTING_FAILSAFE_DELAY_DEFAULT 5 -#define SETTING_FAILSAFE_DELAY 80 -#define SETTING_FAILSAFE_DELAY_MIN 0 -#define SETTING_FAILSAFE_DELAY_MAX 200 -#define SETTING_FAILSAFE_RECOVERY_DELAY_DEFAULT 5 -#define SETTING_FAILSAFE_RECOVERY_DELAY 81 -#define SETTING_FAILSAFE_RECOVERY_DELAY_MIN 0 -#define SETTING_FAILSAFE_RECOVERY_DELAY_MAX 200 -#define SETTING_FAILSAFE_OFF_DELAY_DEFAULT 200 -#define SETTING_FAILSAFE_OFF_DELAY 82 -#define SETTING_FAILSAFE_OFF_DELAY_MIN 0 -#define SETTING_FAILSAFE_OFF_DELAY_MAX 200 -#define SETTING_FAILSAFE_THROTTLE_LOW_DELAY_DEFAULT 0 -#define SETTING_FAILSAFE_THROTTLE_LOW_DELAY 83 -#define SETTING_FAILSAFE_THROTTLE_LOW_DELAY_MIN 0 -#define SETTING_FAILSAFE_THROTTLE_LOW_DELAY_MAX 300 -#define SETTING_FAILSAFE_PROCEDURE_DEFAULT 0 -#define SETTING_FAILSAFE_PROCEDURE 84 -#define SETTING_FAILSAFE_PROCEDURE_MIN 0 -#define SETTING_FAILSAFE_PROCEDURE_MAX 0 -#define SETTING_FAILSAFE_STICK_THRESHOLD_DEFAULT 50 -#define SETTING_FAILSAFE_STICK_THRESHOLD 85 -#define SETTING_FAILSAFE_STICK_THRESHOLD_MIN 0 -#define SETTING_FAILSAFE_STICK_THRESHOLD_MAX 500 -#define SETTING_FAILSAFE_FW_ROLL_ANGLE_DEFAULT -200 -#define SETTING_FAILSAFE_FW_ROLL_ANGLE 86 -#define SETTING_FAILSAFE_FW_ROLL_ANGLE_MIN -800 -#define SETTING_FAILSAFE_FW_ROLL_ANGLE_MAX 800 -#define SETTING_FAILSAFE_FW_PITCH_ANGLE_DEFAULT 100 -#define SETTING_FAILSAFE_FW_PITCH_ANGLE 87 -#define SETTING_FAILSAFE_FW_PITCH_ANGLE_MIN -800 -#define SETTING_FAILSAFE_FW_PITCH_ANGLE_MAX 800 -#define SETTING_FAILSAFE_FW_YAW_RATE_DEFAULT -45 -#define SETTING_FAILSAFE_FW_YAW_RATE 88 -#define SETTING_FAILSAFE_FW_YAW_RATE_MIN -1000 -#define SETTING_FAILSAFE_FW_YAW_RATE_MAX 1000 -#define SETTING_FAILSAFE_MIN_DISTANCE_DEFAULT 0 -#define SETTING_FAILSAFE_MIN_DISTANCE 89 -#define SETTING_FAILSAFE_MIN_DISTANCE_MIN 0 -#define SETTING_FAILSAFE_MIN_DISTANCE_MAX 65000 -#define SETTING_FAILSAFE_MIN_DISTANCE_PROCEDURE_DEFAULT 1 -#define SETTING_FAILSAFE_MIN_DISTANCE_PROCEDURE 90 -#define SETTING_FAILSAFE_MIN_DISTANCE_PROCEDURE_MIN 0 -#define SETTING_FAILSAFE_MIN_DISTANCE_PROCEDURE_MAX 0 -#define SETTING_FAILSAFE_MISSION_DELAY_DEFAULT 0 -#define SETTING_FAILSAFE_MISSION_DELAY 91 -#define SETTING_FAILSAFE_MISSION_DELAY_MIN -1 -#define SETTING_FAILSAFE_MISSION_DELAY_MAX 600 -#define SETTING_ALIGN_BOARD_ROLL 92 -#define SETTING_ALIGN_BOARD_ROLL_MIN -1800 -#define SETTING_ALIGN_BOARD_ROLL_MAX 3600 -#define SETTING_ALIGN_BOARD_PITCH 93 -#define SETTING_ALIGN_BOARD_PITCH_MIN -1800 -#define SETTING_ALIGN_BOARD_PITCH_MAX 3600 -#define SETTING_ALIGN_BOARD_YAW 94 -#define SETTING_ALIGN_BOARD_YAW_MIN -1800 -#define SETTING_ALIGN_BOARD_YAW_MAX 3600 -#define SETTING_VBAT_METER_TYPE_DEFAULT 1 -#define SETTING_VBAT_METER_TYPE 95 -#define SETTING_VBAT_METER_TYPE_MIN 0 -#define SETTING_VBAT_METER_TYPE_MAX 0 -#define SETTING_VBAT_SCALE 96 -#define SETTING_VBAT_SCALE_MIN 0 -#define SETTING_VBAT_SCALE_MAX 65535 -#define SETTING_CURRENT_METER_SCALE 97 -#define SETTING_CURRENT_METER_SCALE_MIN -10000 -#define SETTING_CURRENT_METER_SCALE_MAX 10000 -#define SETTING_CURRENT_METER_OFFSET 98 -#define SETTING_CURRENT_METER_OFFSET_MIN -32768 -#define SETTING_CURRENT_METER_OFFSET_MAX 32767 -#define SETTING_CURRENT_METER_TYPE_DEFAULT 1 -#define SETTING_CURRENT_METER_TYPE 99 -#define SETTING_CURRENT_METER_TYPE_MIN 0 -#define SETTING_CURRENT_METER_TYPE_MAX 0 -#define SETTING_BAT_VOLTAGE_SRC_DEFAULT 0 -#define SETTING_BAT_VOLTAGE_SRC 100 -#define SETTING_BAT_VOLTAGE_SRC_MIN 0 -#define SETTING_BAT_VOLTAGE_SRC_MAX 0 -#define SETTING_CRUISE_POWER_DEFAULT 0 -#define SETTING_CRUISE_POWER 101 -#define SETTING_CRUISE_POWER_MIN 0 -#define SETTING_CRUISE_POWER_MAX 4294967295 -#define SETTING_IDLE_POWER_DEFAULT 0 -#define SETTING_IDLE_POWER 102 -#define SETTING_IDLE_POWER_MIN 0 -#define SETTING_IDLE_POWER_MAX 65535 -#define SETTING_RTH_ENERGY_MARGIN_DEFAULT 5 -#define SETTING_RTH_ENERGY_MARGIN 103 -#define SETTING_RTH_ENERGY_MARGIN_MIN 0 -#define SETTING_RTH_ENERGY_MARGIN_MAX 100 -#define SETTING_THR_COMP_WEIGHT_DEFAULT 1 -#define SETTING_THR_COMP_WEIGHT 104 -#define SETTING_THR_COMP_WEIGHT_MIN 0 -#define SETTING_THR_COMP_WEIGHT_MAX 2 -#define SETTING_BAT_CELLS_DEFAULT 0 -#define SETTING_BAT_CELLS 105 -#define SETTING_BAT_CELLS_MIN 0 -#define SETTING_BAT_CELLS_MAX 12 -#define SETTING_VBAT_CELL_DETECT_VOLTAGE_DEFAULT 425 -#define SETTING_VBAT_CELL_DETECT_VOLTAGE 106 -#define SETTING_VBAT_CELL_DETECT_VOLTAGE_MIN 100 -#define SETTING_VBAT_CELL_DETECT_VOLTAGE_MAX 500 -#define SETTING_VBAT_MAX_CELL_VOLTAGE_DEFAULT 420 -#define SETTING_VBAT_MAX_CELL_VOLTAGE 107 -#define SETTING_VBAT_MAX_CELL_VOLTAGE_MIN 100 -#define SETTING_VBAT_MAX_CELL_VOLTAGE_MAX 500 -#define SETTING_VBAT_MIN_CELL_VOLTAGE_DEFAULT 330 -#define SETTING_VBAT_MIN_CELL_VOLTAGE 108 -#define SETTING_VBAT_MIN_CELL_VOLTAGE_MIN 100 -#define SETTING_VBAT_MIN_CELL_VOLTAGE_MAX 500 -#define SETTING_VBAT_WARNING_CELL_VOLTAGE_DEFAULT 350 -#define SETTING_VBAT_WARNING_CELL_VOLTAGE 109 -#define SETTING_VBAT_WARNING_CELL_VOLTAGE_MIN 100 -#define SETTING_VBAT_WARNING_CELL_VOLTAGE_MAX 500 -#define SETTING_BATTERY_CAPACITY_DEFAULT 0 -#define SETTING_BATTERY_CAPACITY 110 -#define SETTING_BATTERY_CAPACITY_MIN 0 -#define SETTING_BATTERY_CAPACITY_MAX 4294967295 -#define SETTING_BATTERY_CAPACITY_WARNING_DEFAULT 0 -#define SETTING_BATTERY_CAPACITY_WARNING 111 -#define SETTING_BATTERY_CAPACITY_WARNING_MIN 0 -#define SETTING_BATTERY_CAPACITY_WARNING_MAX 4294967295 -#define SETTING_BATTERY_CAPACITY_CRITICAL_DEFAULT 0 -#define SETTING_BATTERY_CAPACITY_CRITICAL 112 -#define SETTING_BATTERY_CAPACITY_CRITICAL_MIN 0 -#define SETTING_BATTERY_CAPACITY_CRITICAL_MAX 4294967295 -#define SETTING_BATTERY_CAPACITY_UNIT_DEFAULT 0 -#define SETTING_BATTERY_CAPACITY_UNIT 113 -#define SETTING_BATTERY_CAPACITY_UNIT_MIN 0 -#define SETTING_BATTERY_CAPACITY_UNIT_MAX 0 -#define SETTING_CONTROLRATE_PROFILE_DEFAULT 0 -#define SETTING_CONTROLRATE_PROFILE 114 -#define SETTING_CONTROLRATE_PROFILE_MIN 0 -#define SETTING_CONTROLRATE_PROFILE_MAX 3 -#define SETTING_THROTTLE_SCALE_DEFAULT 1.0f -#define SETTING_THROTTLE_SCALE 115 -#define SETTING_THROTTLE_SCALE_MIN 0 -#define SETTING_THROTTLE_SCALE_MAX 1 -#define SETTING_THROTTLE_IDLE_DEFAULT 15 -#define SETTING_THROTTLE_IDLE 116 -#define SETTING_THROTTLE_IDLE_MIN 0 -#define SETTING_THROTTLE_IDLE_MAX 30 -#define SETTING_FAILSAFE_THROTTLE_DEFAULT 1000 -#define SETTING_FAILSAFE_THROTTLE 117 -#define SETTING_FAILSAFE_THROTTLE_MIN 1000 -#define SETTING_FAILSAFE_THROTTLE_MAX 2000 -#define SETTING_NAV_MC_HOVER_THR_DEFAULT 1500 -#define SETTING_NAV_MC_HOVER_THR 118 -#define SETTING_NAV_MC_HOVER_THR_MIN 1000 -#define SETTING_NAV_MC_HOVER_THR_MAX 2000 -#define SETTING_NAV_FW_CRUISE_THR_DEFAULT 1400 -#define SETTING_NAV_FW_CRUISE_THR 119 -#define SETTING_NAV_FW_CRUISE_THR_MIN 1000 -#define SETTING_NAV_FW_CRUISE_THR_MAX 2000 -#define SETTING_NAV_FW_MIN_THR_DEFAULT 1200 -#define SETTING_NAV_FW_MIN_THR 120 -#define SETTING_NAV_FW_MIN_THR_MIN 1000 -#define SETTING_NAV_FW_MIN_THR_MAX 2000 -#define SETTING_NAV_FW_MAX_THR_DEFAULT 1700 -#define SETTING_NAV_FW_MAX_THR 121 -#define SETTING_NAV_FW_MAX_THR_MIN 1000 -#define SETTING_NAV_FW_MAX_THR_MAX 2000 -#define SETTING_NAV_FW_PITCH2THR_DEFAULT 10 -#define SETTING_NAV_FW_PITCH2THR 122 -#define SETTING_NAV_FW_PITCH2THR_MIN 0 -#define SETTING_NAV_FW_PITCH2THR_MAX 100 -#define SETTING_NAV_FW_LAUNCH_THR_DEFAULT 1700 -#define SETTING_NAV_FW_LAUNCH_THR 123 -#define SETTING_NAV_FW_LAUNCH_THR_MIN 1000 -#define SETTING_NAV_FW_LAUNCH_THR_MAX 2000 -#define SETTING_NAV_FW_LAUNCH_IDLE_THR_DEFAULT 1000 -#define SETTING_NAV_FW_LAUNCH_IDLE_THR 124 -#define SETTING_NAV_FW_LAUNCH_IDLE_THR_MIN 1000 -#define SETTING_NAV_FW_LAUNCH_IDLE_THR_MAX 2000 -#define SETTING_LIMIT_CONT_CURRENT_DEFAULT 0 -#define SETTING_LIMIT_CONT_CURRENT 125 -#define SETTING_LIMIT_CONT_CURRENT_MIN 0 -#define SETTING_LIMIT_CONT_CURRENT_MAX 4000 -#define SETTING_LIMIT_BURST_CURRENT_DEFAULT 0 -#define SETTING_LIMIT_BURST_CURRENT 126 -#define SETTING_LIMIT_BURST_CURRENT_MIN 0 -#define SETTING_LIMIT_BURST_CURRENT_MAX 4000 -#define SETTING_LIMIT_BURST_CURRENT_TIME_DEFAULT 0 -#define SETTING_LIMIT_BURST_CURRENT_TIME 127 -#define SETTING_LIMIT_BURST_CURRENT_TIME_MIN 0 -#define SETTING_LIMIT_BURST_CURRENT_TIME_MAX 3000 -#define SETTING_LIMIT_BURST_CURRENT_FALLDOWN_TIME_DEFAULT 0 -#define SETTING_LIMIT_BURST_CURRENT_FALLDOWN_TIME 128 -#define SETTING_LIMIT_BURST_CURRENT_FALLDOWN_TIME_MIN 0 -#define SETTING_LIMIT_BURST_CURRENT_FALLDOWN_TIME_MAX 3000 -#define SETTING_LIMIT_CONT_POWER_DEFAULT 0 -#define SETTING_LIMIT_CONT_POWER 129 -#define SETTING_LIMIT_CONT_POWER_MIN 0 -#define SETTING_LIMIT_CONT_POWER_MAX 40000 -#define SETTING_LIMIT_BURST_POWER_DEFAULT 0 -#define SETTING_LIMIT_BURST_POWER 130 -#define SETTING_LIMIT_BURST_POWER_MIN 0 -#define SETTING_LIMIT_BURST_POWER_MAX 40000 -#define SETTING_LIMIT_BURST_POWER_TIME_DEFAULT 0 -#define SETTING_LIMIT_BURST_POWER_TIME 131 -#define SETTING_LIMIT_BURST_POWER_TIME_MIN 0 -#define SETTING_LIMIT_BURST_POWER_TIME_MAX 3000 -#define SETTING_LIMIT_BURST_POWER_FALLDOWN_TIME_DEFAULT 0 -#define SETTING_LIMIT_BURST_POWER_FALLDOWN_TIME 132 -#define SETTING_LIMIT_BURST_POWER_FALLDOWN_TIME_MIN 0 -#define SETTING_LIMIT_BURST_POWER_FALLDOWN_TIME_MAX 3000 -#define SETTING_MOTOR_DIRECTION_INVERTED_DEFAULT 0 -#define SETTING_MOTOR_DIRECTION_INVERTED 133 -#define SETTING_MOTOR_DIRECTION_INVERTED_MIN 0 -#define SETTING_MOTOR_DIRECTION_INVERTED_MAX 0 -#define SETTING_PLATFORM_TYPE_DEFAULT 0 -#define SETTING_PLATFORM_TYPE 134 -#define SETTING_PLATFORM_TYPE_MIN 0 -#define SETTING_PLATFORM_TYPE_MAX 0 -#define SETTING_HAS_FLAPS_DEFAULT 0 -#define SETTING_HAS_FLAPS 135 -#define SETTING_HAS_FLAPS_MIN 0 -#define SETTING_HAS_FLAPS_MAX 0 -#define SETTING_MODEL_PREVIEW_TYPE_DEFAULT -1 -#define SETTING_MODEL_PREVIEW_TYPE 136 -#define SETTING_MODEL_PREVIEW_TYPE_MIN -1 -#define SETTING_MODEL_PREVIEW_TYPE_MAX 32767 -#define SETTING_OUTPUT_MODE_DEFAULT 0 -#define SETTING_OUTPUT_MODE 137 -#define SETTING_OUTPUT_MODE_MIN 0 -#define SETTING_OUTPUT_MODE_MAX 0 -#define SETTING_3D_DEADBAND_LOW_DEFAULT 1406 -#define SETTING_3D_DEADBAND_LOW 138 -#define SETTING_3D_DEADBAND_LOW_MIN 1000 -#define SETTING_3D_DEADBAND_LOW_MAX 2000 -#define SETTING_3D_DEADBAND_HIGH_DEFAULT 1514 -#define SETTING_3D_DEADBAND_HIGH 139 -#define SETTING_3D_DEADBAND_HIGH_MIN 1000 -#define SETTING_3D_DEADBAND_HIGH_MAX 2000 -#define SETTING_3D_NEUTRAL_DEFAULT 1460 -#define SETTING_3D_NEUTRAL 140 -#define SETTING_3D_NEUTRAL_MIN 1000 -#define SETTING_3D_NEUTRAL_MAX 2000 -#define SETTING_SERVO_PROTOCOL_DEFAULT 0 -#define SETTING_SERVO_PROTOCOL 141 -#define SETTING_SERVO_PROTOCOL_MIN 0 -#define SETTING_SERVO_PROTOCOL_MAX 0 -#define SETTING_SERVO_CENTER_PULSE_DEFAULT 1500 -#define SETTING_SERVO_CENTER_PULSE 142 -#define SETTING_SERVO_CENTER_PULSE_MIN 1000 -#define SETTING_SERVO_CENTER_PULSE_MAX 2000 -#define SETTING_SERVO_PWM_RATE_DEFAULT 50 -#define SETTING_SERVO_PWM_RATE 143 -#define SETTING_SERVO_PWM_RATE_MIN 50 -#define SETTING_SERVO_PWM_RATE_MAX 498 -#define SETTING_SERVO_LPF_HZ_DEFAULT 20 -#define SETTING_SERVO_LPF_HZ 144 -#define SETTING_SERVO_LPF_HZ_MIN 0 -#define SETTING_SERVO_LPF_HZ_MAX 400 -#define SETTING_FLAPERON_THROW_OFFSET_DEFAULT 200 -#define SETTING_FLAPERON_THROW_OFFSET 145 -#define SETTING_FLAPERON_THROW_OFFSET_MIN 50 -#define SETTING_FLAPERON_THROW_OFFSET_MAX 450 -#define SETTING_TRI_UNARMED_SERVO_DEFAULT 1 -#define SETTING_TRI_UNARMED_SERVO 146 -#define SETTING_TRI_UNARMED_SERVO_MIN 0 -#define SETTING_TRI_UNARMED_SERVO_MAX 0 -#define SETTING_SERVO_AUTOTRIM_ROTATION_LIMIT_DEFAULT 15 -#define SETTING_SERVO_AUTOTRIM_ROTATION_LIMIT 147 -#define SETTING_SERVO_AUTOTRIM_ROTATION_LIMIT_MIN 1 -#define SETTING_SERVO_AUTOTRIM_ROTATION_LIMIT_MAX 60 -#define SETTING_THR_MID_DEFAULT 50 -#define SETTING_THR_MID 148 -#define SETTING_THR_MID_MIN 0 -#define SETTING_THR_MID_MAX 100 -#define SETTING_THR_EXPO_DEFAULT 0 -#define SETTING_THR_EXPO 149 -#define SETTING_THR_EXPO_MIN 0 -#define SETTING_THR_EXPO_MAX 100 -#define SETTING_TPA_RATE_DEFAULT 0 -#define SETTING_TPA_RATE 150 -#define SETTING_TPA_RATE_MIN 0 -#define SETTING_TPA_RATE_MAX 100 -#define SETTING_TPA_BREAKPOINT_DEFAULT 1500 -#define SETTING_TPA_BREAKPOINT 151 -#define SETTING_TPA_BREAKPOINT_MIN 1000 -#define SETTING_TPA_BREAKPOINT_MAX 2000 -#define SETTING_FW_TPA_TIME_CONSTANT_DEFAULT 1500 -#define SETTING_FW_TPA_TIME_CONSTANT 152 -#define SETTING_FW_TPA_TIME_CONSTANT_MIN 0 -#define SETTING_FW_TPA_TIME_CONSTANT_MAX 5000 -#define SETTING_RC_EXPO_DEFAULT 70 -#define SETTING_RC_EXPO 153 -#define SETTING_RC_EXPO_MIN 0 -#define SETTING_RC_EXPO_MAX 100 -#define SETTING_RC_YAW_EXPO_DEFAULT 20 -#define SETTING_RC_YAW_EXPO 154 -#define SETTING_RC_YAW_EXPO_MIN 0 -#define SETTING_RC_YAW_EXPO_MAX 100 -#define SETTING_ROLL_RATE_DEFAULT 20 -#define SETTING_ROLL_RATE 155 -#define SETTING_ROLL_RATE_MIN 4 -#define SETTING_ROLL_RATE_MAX 180 -#define SETTING_PITCH_RATE_DEFAULT 20 -#define SETTING_PITCH_RATE 156 -#define SETTING_PITCH_RATE_MIN 4 -#define SETTING_PITCH_RATE_MAX 180 -#define SETTING_YAW_RATE_DEFAULT 20 -#define SETTING_YAW_RATE 157 -#define SETTING_YAW_RATE_MIN 1 -#define SETTING_YAW_RATE_MAX 180 -#define SETTING_MANUAL_RC_EXPO_DEFAULT 35 -#define SETTING_MANUAL_RC_EXPO 158 -#define SETTING_MANUAL_RC_EXPO_MIN 0 -#define SETTING_MANUAL_RC_EXPO_MAX 100 -#define SETTING_MANUAL_RC_YAW_EXPO_DEFAULT 20 -#define SETTING_MANUAL_RC_YAW_EXPO 159 -#define SETTING_MANUAL_RC_YAW_EXPO_MIN 0 -#define SETTING_MANUAL_RC_YAW_EXPO_MAX 100 -#define SETTING_MANUAL_ROLL_RATE_DEFAULT 100 -#define SETTING_MANUAL_ROLL_RATE 160 -#define SETTING_MANUAL_ROLL_RATE_MIN 0 -#define SETTING_MANUAL_ROLL_RATE_MAX 100 -#define SETTING_MANUAL_PITCH_RATE_DEFAULT 100 -#define SETTING_MANUAL_PITCH_RATE 161 -#define SETTING_MANUAL_PITCH_RATE_MIN 0 -#define SETTING_MANUAL_PITCH_RATE_MAX 100 -#define SETTING_MANUAL_YAW_RATE_DEFAULT 100 -#define SETTING_MANUAL_YAW_RATE 162 -#define SETTING_MANUAL_YAW_RATE_MIN 0 -#define SETTING_MANUAL_YAW_RATE_MAX 100 -#define SETTING_FPV_MIX_DEGREES_DEFAULT 0 -#define SETTING_FPV_MIX_DEGREES 163 -#define SETTING_FPV_MIX_DEGREES_MIN 0 -#define SETTING_FPV_MIX_DEGREES_MAX 50 -#define SETTING_RATE_DYNAMICS_CENTER_SENSITIVITY_DEFAULT 100 -#define SETTING_RATE_DYNAMICS_CENTER_SENSITIVITY 164 -#define SETTING_RATE_DYNAMICS_CENTER_SENSITIVITY_MIN 25 -#define SETTING_RATE_DYNAMICS_CENTER_SENSITIVITY_MAX 175 -#define SETTING_RATE_DYNAMICS_END_SENSITIVITY_DEFAULT 100 -#define SETTING_RATE_DYNAMICS_END_SENSITIVITY 165 -#define SETTING_RATE_DYNAMICS_END_SENSITIVITY_MIN 25 -#define SETTING_RATE_DYNAMICS_END_SENSITIVITY_MAX 175 -#define SETTING_RATE_DYNAMICS_CENTER_CORRECTION_DEFAULT 10 -#define SETTING_RATE_DYNAMICS_CENTER_CORRECTION 166 -#define SETTING_RATE_DYNAMICS_CENTER_CORRECTION_MIN 10 -#define SETTING_RATE_DYNAMICS_CENTER_CORRECTION_MAX 95 -#define SETTING_RATE_DYNAMICS_END_CORRECTION_DEFAULT 10 -#define SETTING_RATE_DYNAMICS_END_CORRECTION 167 -#define SETTING_RATE_DYNAMICS_END_CORRECTION_MIN 10 -#define SETTING_RATE_DYNAMICS_END_CORRECTION_MAX 95 -#define SETTING_RATE_DYNAMICS_CENTER_WEIGHT_DEFAULT 0 -#define SETTING_RATE_DYNAMICS_CENTER_WEIGHT 168 -#define SETTING_RATE_DYNAMICS_CENTER_WEIGHT_MIN 0 -#define SETTING_RATE_DYNAMICS_CENTER_WEIGHT_MAX 95 -#define SETTING_RATE_DYNAMICS_END_WEIGHT_DEFAULT 0 -#define SETTING_RATE_DYNAMICS_END_WEIGHT 169 -#define SETTING_RATE_DYNAMICS_END_WEIGHT_MIN 0 -#define SETTING_RATE_DYNAMICS_END_WEIGHT_MAX 95 -#define SETTING_REBOOT_CHARACTER_DEFAULT 82 -#define SETTING_REBOOT_CHARACTER 170 -#define SETTING_REBOOT_CHARACTER_MIN 48 -#define SETTING_REBOOT_CHARACTER_MAX 126 -#define SETTING_IMU_DCM_KP_DEFAULT 2000 -#define SETTING_IMU_DCM_KP 171 -#define SETTING_IMU_DCM_KP_MIN 0 -#define SETTING_IMU_DCM_KP_MAX 65535 -#define SETTING_IMU_DCM_KI_DEFAULT 50 -#define SETTING_IMU_DCM_KI 172 -#define SETTING_IMU_DCM_KI_MIN 0 -#define SETTING_IMU_DCM_KI_MAX 65535 -#define SETTING_IMU_DCM_KP_MAG_DEFAULT 2000 -#define SETTING_IMU_DCM_KP_MAG 173 -#define SETTING_IMU_DCM_KP_MAG_MIN 0 -#define SETTING_IMU_DCM_KP_MAG_MAX 65535 -#define SETTING_IMU_DCM_KI_MAG_DEFAULT 50 -#define SETTING_IMU_DCM_KI_MAG 174 -#define SETTING_IMU_DCM_KI_MAG_MIN 0 -#define SETTING_IMU_DCM_KI_MAG_MAX 65535 -#define SETTING_SMALL_ANGLE_DEFAULT 25 -#define SETTING_SMALL_ANGLE 175 -#define SETTING_SMALL_ANGLE_MIN 0 -#define SETTING_SMALL_ANGLE_MAX 180 -#define SETTING_IMU_ACC_IGNORE_RATE_DEFAULT 15 -#define SETTING_IMU_ACC_IGNORE_RATE 176 -#define SETTING_IMU_ACC_IGNORE_RATE_MIN 0 -#define SETTING_IMU_ACC_IGNORE_RATE_MAX 30 -#define SETTING_IMU_ACC_IGNORE_SLOPE_DEFAULT 5 -#define SETTING_IMU_ACC_IGNORE_SLOPE 177 -#define SETTING_IMU_ACC_IGNORE_SLOPE_MIN 0 -#define SETTING_IMU_ACC_IGNORE_SLOPE_MAX 10 -#define SETTING_IMU_GPS_YAW_WINDCOMP_DEFAULT 1 -#define SETTING_IMU_GPS_YAW_WINDCOMP 178 -#define SETTING_IMU_GPS_YAW_WINDCOMP_MIN 0 -#define SETTING_IMU_GPS_YAW_WINDCOMP_MAX 0 -#define SETTING_IMU_INERTIA_COMP_METHOD_DEFAULT 0 -#define SETTING_IMU_INERTIA_COMP_METHOD 179 -#define SETTING_IMU_INERTIA_COMP_METHOD_MIN 0 -#define SETTING_IMU_INERTIA_COMP_METHOD_MAX 0 -#define SETTING_FIXED_WING_AUTO_ARM_DEFAULT 0 -#define SETTING_FIXED_WING_AUTO_ARM 180 -#define SETTING_FIXED_WING_AUTO_ARM_MIN 0 -#define SETTING_FIXED_WING_AUTO_ARM_MAX 0 -#define SETTING_DISARM_KILL_SWITCH_DEFAULT 1 -#define SETTING_DISARM_KILL_SWITCH 181 -#define SETTING_DISARM_KILL_SWITCH_MIN 0 -#define SETTING_DISARM_KILL_SWITCH_MAX 0 -#define SETTING_SWITCH_DISARM_DELAY_DEFAULT 250 -#define SETTING_SWITCH_DISARM_DELAY 182 -#define SETTING_SWITCH_DISARM_DELAY_MIN 0 -#define SETTING_SWITCH_DISARM_DELAY_MAX 1000 -#define SETTING_PREARM_TIMEOUT_DEFAULT 10000 -#define SETTING_PREARM_TIMEOUT 183 -#define SETTING_PREARM_TIMEOUT_MIN 0 -#define SETTING_PREARM_TIMEOUT_MAX 10000 -#define SETTING_APPLIED_DEFAULTS_DEFAULT 0 -#define SETTING_APPLIED_DEFAULTS 184 -#define SETTING_APPLIED_DEFAULTS_MIN 0 -#define SETTING_APPLIED_DEFAULTS_MAX 99 -#define SETTING_GPS_PROVIDER_DEFAULT 1 -#define SETTING_GPS_PROVIDER 185 -#define SETTING_GPS_PROVIDER_MIN 0 -#define SETTING_GPS_PROVIDER_MAX 0 -#define SETTING_GPS_SBAS_MODE_DEFAULT 5 -#define SETTING_GPS_SBAS_MODE 186 -#define SETTING_GPS_SBAS_MODE_MIN 0 -#define SETTING_GPS_SBAS_MODE_MAX 0 -#define SETTING_GPS_DYN_MODEL_DEFAULT 1 -#define SETTING_GPS_DYN_MODEL 187 -#define SETTING_GPS_DYN_MODEL_MIN 0 -#define SETTING_GPS_DYN_MODEL_MAX 0 -#define SETTING_GPS_AUTO_CONFIG_DEFAULT 1 -#define SETTING_GPS_AUTO_CONFIG 188 -#define SETTING_GPS_AUTO_CONFIG_MIN 0 -#define SETTING_GPS_AUTO_CONFIG_MAX 0 -#define SETTING_GPS_AUTO_BAUD_DEFAULT 1 -#define SETTING_GPS_AUTO_BAUD 189 -#define SETTING_GPS_AUTO_BAUD_MIN 0 -#define SETTING_GPS_AUTO_BAUD_MAX 0 -#define SETTING_GPS_UBLOX_USE_GALILEO_DEFAULT 0 -#define SETTING_GPS_UBLOX_USE_GALILEO 190 -#define SETTING_GPS_UBLOX_USE_GALILEO_MIN 0 -#define SETTING_GPS_UBLOX_USE_GALILEO_MAX 0 -#define SETTING_GPS_MIN_SATS_DEFAULT 6 -#define SETTING_GPS_MIN_SATS 191 -#define SETTING_GPS_MIN_SATS_MIN 5 -#define SETTING_GPS_MIN_SATS_MAX 10 -#define SETTING_DEADBAND_DEFAULT 5 -#define SETTING_DEADBAND 192 -#define SETTING_DEADBAND_MIN 0 -#define SETTING_DEADBAND_MAX 32 -#define SETTING_YAW_DEADBAND_DEFAULT 5 -#define SETTING_YAW_DEADBAND 193 -#define SETTING_YAW_DEADBAND_MIN 0 -#define SETTING_YAW_DEADBAND_MAX 100 -#define SETTING_POS_HOLD_DEADBAND_DEFAULT 10 -#define SETTING_POS_HOLD_DEADBAND 194 -#define SETTING_POS_HOLD_DEADBAND_MIN 2 -#define SETTING_POS_HOLD_DEADBAND_MAX 250 -#define SETTING_CONTROL_DEADBAND_DEFAULT 10 -#define SETTING_CONTROL_DEADBAND 195 -#define SETTING_CONTROL_DEADBAND_MIN 2 -#define SETTING_CONTROL_DEADBAND_MAX 250 -#define SETTING_ALT_HOLD_DEADBAND_DEFAULT 50 -#define SETTING_ALT_HOLD_DEADBAND 196 -#define SETTING_ALT_HOLD_DEADBAND_MIN 10 -#define SETTING_ALT_HOLD_DEADBAND_MAX 250 -#define SETTING_3D_DEADBAND_THROTTLE_DEFAULT 50 -#define SETTING_3D_DEADBAND_THROTTLE 197 -#define SETTING_3D_DEADBAND_THROTTLE_MIN 0 -#define SETTING_3D_DEADBAND_THROTTLE_MAX 200 -#define SETTING_AIRMODE_TYPE_DEFAULT 0 -#define SETTING_AIRMODE_TYPE 198 -#define SETTING_AIRMODE_TYPE_MIN 0 -#define SETTING_AIRMODE_TYPE_MAX 0 -#define SETTING_AIRMODE_THROTTLE_THRESHOLD_DEFAULT 1150 -#define SETTING_AIRMODE_THROTTLE_THRESHOLD 199 -#define SETTING_AIRMODE_THROTTLE_THRESHOLD_MIN 1000 -#define SETTING_AIRMODE_THROTTLE_THRESHOLD_MAX 2000 -#define SETTING_MC_P_PITCH_DEFAULT 40 -#define SETTING_MC_P_PITCH 200 -#define SETTING_MC_P_PITCH_MIN 0 -#define SETTING_MC_P_PITCH_MAX 255 -#define SETTING_MC_I_PITCH_DEFAULT 30 -#define SETTING_MC_I_PITCH 201 -#define SETTING_MC_I_PITCH_MIN 0 -#define SETTING_MC_I_PITCH_MAX 255 -#define SETTING_MC_D_PITCH_DEFAULT 23 -#define SETTING_MC_D_PITCH 202 -#define SETTING_MC_D_PITCH_MIN 0 -#define SETTING_MC_D_PITCH_MAX 255 -#define SETTING_MC_CD_PITCH_DEFAULT 60 -#define SETTING_MC_CD_PITCH 203 -#define SETTING_MC_CD_PITCH_MIN 0 -#define SETTING_MC_CD_PITCH_MAX 255 -#define SETTING_MC_P_ROLL_DEFAULT 40 -#define SETTING_MC_P_ROLL 204 -#define SETTING_MC_P_ROLL_MIN 0 -#define SETTING_MC_P_ROLL_MAX 255 -#define SETTING_MC_I_ROLL_DEFAULT 30 -#define SETTING_MC_I_ROLL 205 -#define SETTING_MC_I_ROLL_MIN 0 -#define SETTING_MC_I_ROLL_MAX 255 -#define SETTING_MC_D_ROLL_DEFAULT 23 -#define SETTING_MC_D_ROLL 206 -#define SETTING_MC_D_ROLL_MIN 0 -#define SETTING_MC_D_ROLL_MAX 255 -#define SETTING_MC_CD_ROLL_DEFAULT 60 -#define SETTING_MC_CD_ROLL 207 -#define SETTING_MC_CD_ROLL_MIN 0 -#define SETTING_MC_CD_ROLL_MAX 255 -#define SETTING_MC_P_YAW_DEFAULT 85 -#define SETTING_MC_P_YAW 208 -#define SETTING_MC_P_YAW_MIN 0 -#define SETTING_MC_P_YAW_MAX 255 -#define SETTING_MC_I_YAW_DEFAULT 45 -#define SETTING_MC_I_YAW 209 -#define SETTING_MC_I_YAW_MIN 0 -#define SETTING_MC_I_YAW_MAX 255 -#define SETTING_MC_D_YAW_DEFAULT 0 -#define SETTING_MC_D_YAW 210 -#define SETTING_MC_D_YAW_MIN 0 -#define SETTING_MC_D_YAW_MAX 255 -#define SETTING_MC_CD_YAW_DEFAULT 60 -#define SETTING_MC_CD_YAW 211 -#define SETTING_MC_CD_YAW_MIN 0 -#define SETTING_MC_CD_YAW_MAX 255 -#define SETTING_MC_P_LEVEL_DEFAULT 20 -#define SETTING_MC_P_LEVEL 212 -#define SETTING_MC_P_LEVEL_MIN 0 -#define SETTING_MC_P_LEVEL_MAX 255 -#define SETTING_MC_I_LEVEL_DEFAULT 15 -#define SETTING_MC_I_LEVEL 213 -#define SETTING_MC_I_LEVEL_MIN 0 -#define SETTING_MC_I_LEVEL_MAX 255 -#define SETTING_MC_D_LEVEL_DEFAULT 75 -#define SETTING_MC_D_LEVEL 214 -#define SETTING_MC_D_LEVEL_MIN 0 -#define SETTING_MC_D_LEVEL_MAX 255 -#define SETTING_FW_P_PITCH_DEFAULT 5 -#define SETTING_FW_P_PITCH 215 -#define SETTING_FW_P_PITCH_MIN 0 -#define SETTING_FW_P_PITCH_MAX 255 -#define SETTING_FW_I_PITCH_DEFAULT 7 -#define SETTING_FW_I_PITCH 216 -#define SETTING_FW_I_PITCH_MIN 0 -#define SETTING_FW_I_PITCH_MAX 255 -#define SETTING_FW_D_PITCH_DEFAULT 0 -#define SETTING_FW_D_PITCH 217 -#define SETTING_FW_D_PITCH_MIN 0 -#define SETTING_FW_D_PITCH_MAX 255 -#define SETTING_FW_FF_PITCH_DEFAULT 50 -#define SETTING_FW_FF_PITCH 218 -#define SETTING_FW_FF_PITCH_MIN 0 -#define SETTING_FW_FF_PITCH_MAX 255 -#define SETTING_FW_P_ROLL_DEFAULT 5 -#define SETTING_FW_P_ROLL 219 -#define SETTING_FW_P_ROLL_MIN 0 -#define SETTING_FW_P_ROLL_MAX 255 -#define SETTING_FW_I_ROLL_DEFAULT 7 -#define SETTING_FW_I_ROLL 220 -#define SETTING_FW_I_ROLL_MIN 0 -#define SETTING_FW_I_ROLL_MAX 255 -#define SETTING_FW_D_ROLL_DEFAULT 0 -#define SETTING_FW_D_ROLL 221 -#define SETTING_FW_D_ROLL_MIN 0 -#define SETTING_FW_D_ROLL_MAX 255 -#define SETTING_FW_FF_ROLL_DEFAULT 50 -#define SETTING_FW_FF_ROLL 222 -#define SETTING_FW_FF_ROLL_MIN 0 -#define SETTING_FW_FF_ROLL_MAX 255 -#define SETTING_FW_P_YAW_DEFAULT 6 -#define SETTING_FW_P_YAW 223 -#define SETTING_FW_P_YAW_MIN 0 -#define SETTING_FW_P_YAW_MAX 255 -#define SETTING_FW_I_YAW_DEFAULT 10 -#define SETTING_FW_I_YAW 224 -#define SETTING_FW_I_YAW_MIN 0 -#define SETTING_FW_I_YAW_MAX 255 -#define SETTING_FW_D_YAW_DEFAULT 0 -#define SETTING_FW_D_YAW 225 -#define SETTING_FW_D_YAW_MIN 0 -#define SETTING_FW_D_YAW_MAX 255 -#define SETTING_FW_FF_YAW_DEFAULT 60 -#define SETTING_FW_FF_YAW 226 -#define SETTING_FW_FF_YAW_MIN 0 -#define SETTING_FW_FF_YAW_MAX 255 -#define SETTING_FW_P_LEVEL_DEFAULT 20 -#define SETTING_FW_P_LEVEL 227 -#define SETTING_FW_P_LEVEL_MIN 0 -#define SETTING_FW_P_LEVEL_MAX 255 -#define SETTING_FW_I_LEVEL_DEFAULT 5 -#define SETTING_FW_I_LEVEL 228 -#define SETTING_FW_I_LEVEL_MIN 0 -#define SETTING_FW_I_LEVEL_MAX 255 -#define SETTING_FW_D_LEVEL_DEFAULT 75 -#define SETTING_FW_D_LEVEL 229 -#define SETTING_FW_D_LEVEL_MIN 0 -#define SETTING_FW_D_LEVEL_MAX 255 -#define SETTING_MAX_ANGLE_INCLINATION_RLL_DEFAULT 300 -#define SETTING_MAX_ANGLE_INCLINATION_RLL 230 -#define SETTING_MAX_ANGLE_INCLINATION_RLL_MIN 100 -#define SETTING_MAX_ANGLE_INCLINATION_RLL_MAX 900 -#define SETTING_MAX_ANGLE_INCLINATION_PIT_DEFAULT 300 -#define SETTING_MAX_ANGLE_INCLINATION_PIT 231 -#define SETTING_MAX_ANGLE_INCLINATION_PIT_MIN 100 -#define SETTING_MAX_ANGLE_INCLINATION_PIT_MAX 900 -#define SETTING_DTERM_LPF_HZ_DEFAULT 110 -#define SETTING_DTERM_LPF_HZ 232 -#define SETTING_DTERM_LPF_HZ_MIN 0 -#define SETTING_DTERM_LPF_HZ_MAX 500 -#define SETTING_DTERM_LPF_TYPE_DEFAULT 2 -#define SETTING_DTERM_LPF_TYPE 233 -#define SETTING_DTERM_LPF_TYPE_MIN 0 -#define SETTING_DTERM_LPF_TYPE_MAX 0 -#define SETTING_DTERM_LPF2_HZ_DEFAULT 0 -#define SETTING_DTERM_LPF2_HZ 234 -#define SETTING_DTERM_LPF2_HZ_MIN 0 -#define SETTING_DTERM_LPF2_HZ_MAX 500 -#define SETTING_DTERM_LPF2_TYPE_DEFAULT 0 -#define SETTING_DTERM_LPF2_TYPE 235 -#define SETTING_DTERM_LPF2_TYPE_MIN 0 -#define SETTING_DTERM_LPF2_TYPE_MAX 0 -#define SETTING_YAW_LPF_HZ_DEFAULT 0 -#define SETTING_YAW_LPF_HZ 236 -#define SETTING_YAW_LPF_HZ_MIN 0 -#define SETTING_YAW_LPF_HZ_MAX 200 -#define SETTING_FW_ITERM_THROW_LIMIT_DEFAULT 165 -#define SETTING_FW_ITERM_THROW_LIMIT 237 -#define SETTING_FW_ITERM_THROW_LIMIT_MIN 0 -#define SETTING_FW_ITERM_THROW_LIMIT_MAX 500 -#define SETTING_FW_REFERENCE_AIRSPEED_DEFAULT 1500 -#define SETTING_FW_REFERENCE_AIRSPEED 238 -#define SETTING_FW_REFERENCE_AIRSPEED_MIN 300 -#define SETTING_FW_REFERENCE_AIRSPEED_MAX 6000 -#define SETTING_FW_TURN_ASSIST_YAW_GAIN_DEFAULT 1 -#define SETTING_FW_TURN_ASSIST_YAW_GAIN 239 -#define SETTING_FW_TURN_ASSIST_YAW_GAIN_MIN 0 -#define SETTING_FW_TURN_ASSIST_YAW_GAIN_MAX 2 -#define SETTING_FW_TURN_ASSIST_PITCH_GAIN_DEFAULT 1 -#define SETTING_FW_TURN_ASSIST_PITCH_GAIN 240 -#define SETTING_FW_TURN_ASSIST_PITCH_GAIN_MIN 0 -#define SETTING_FW_TURN_ASSIST_PITCH_GAIN_MAX 2 -#define SETTING_FW_ITERM_LIMIT_STICK_POSITION_DEFAULT 0.5f -#define SETTING_FW_ITERM_LIMIT_STICK_POSITION 241 -#define SETTING_FW_ITERM_LIMIT_STICK_POSITION_MIN 0 -#define SETTING_FW_ITERM_LIMIT_STICK_POSITION_MAX 1 -#define SETTING_FW_YAW_ITERM_FREEZE_BANK_ANGLE_DEFAULT 0 -#define SETTING_FW_YAW_ITERM_FREEZE_BANK_ANGLE 242 -#define SETTING_FW_YAW_ITERM_FREEZE_BANK_ANGLE_MIN 0 -#define SETTING_FW_YAW_ITERM_FREEZE_BANK_ANGLE_MAX 90 -#define SETTING_PIDSUM_LIMIT_DEFAULT 500 -#define SETTING_PIDSUM_LIMIT 243 -#define SETTING_PIDSUM_LIMIT_MIN 100 -#define SETTING_PIDSUM_LIMIT_MAX 1000 -#define SETTING_PIDSUM_LIMIT_YAW_DEFAULT 350 -#define SETTING_PIDSUM_LIMIT_YAW 244 -#define SETTING_PIDSUM_LIMIT_YAW_MIN 100 -#define SETTING_PIDSUM_LIMIT_YAW_MAX 1000 -#define SETTING_ITERM_WINDUP_DEFAULT 50 -#define SETTING_ITERM_WINDUP 245 -#define SETTING_ITERM_WINDUP_MIN 0 -#define SETTING_ITERM_WINDUP_MAX 90 -#define SETTING_RATE_ACCEL_LIMIT_ROLL_PITCH_DEFAULT 0 -#define SETTING_RATE_ACCEL_LIMIT_ROLL_PITCH 246 -#define SETTING_RATE_ACCEL_LIMIT_ROLL_PITCH_MIN 0 -#define SETTING_RATE_ACCEL_LIMIT_ROLL_PITCH_MAX 500000 -#define SETTING_RATE_ACCEL_LIMIT_YAW_DEFAULT 10000 -#define SETTING_RATE_ACCEL_LIMIT_YAW 247 -#define SETTING_RATE_ACCEL_LIMIT_YAW_MIN 0 -#define SETTING_RATE_ACCEL_LIMIT_YAW_MAX 500000 -#define SETTING_HEADING_HOLD_RATE_LIMIT_DEFAULT 90 -#define SETTING_HEADING_HOLD_RATE_LIMIT 248 -#define SETTING_HEADING_HOLD_RATE_LIMIT_MIN 10 -#define SETTING_HEADING_HOLD_RATE_LIMIT_MAX 250 -#define SETTING_NAV_MC_POS_Z_P_DEFAULT 50 -#define SETTING_NAV_MC_POS_Z_P 249 -#define SETTING_NAV_MC_POS_Z_P_MIN 0 -#define SETTING_NAV_MC_POS_Z_P_MAX 255 -#define SETTING_NAV_MC_VEL_Z_P_DEFAULT 100 -#define SETTING_NAV_MC_VEL_Z_P 250 -#define SETTING_NAV_MC_VEL_Z_P_MIN 0 -#define SETTING_NAV_MC_VEL_Z_P_MAX 255 -#define SETTING_NAV_MC_VEL_Z_I_DEFAULT 50 -#define SETTING_NAV_MC_VEL_Z_I 251 -#define SETTING_NAV_MC_VEL_Z_I_MIN 0 -#define SETTING_NAV_MC_VEL_Z_I_MAX 255 -#define SETTING_NAV_MC_VEL_Z_D_DEFAULT 10 -#define SETTING_NAV_MC_VEL_Z_D 252 -#define SETTING_NAV_MC_VEL_Z_D_MIN 0 -#define SETTING_NAV_MC_VEL_Z_D_MAX 255 -#define SETTING_NAV_MC_POS_XY_P_DEFAULT 65 -#define SETTING_NAV_MC_POS_XY_P 253 -#define SETTING_NAV_MC_POS_XY_P_MIN 0 -#define SETTING_NAV_MC_POS_XY_P_MAX 255 -#define SETTING_NAV_MC_VEL_XY_P_DEFAULT 40 -#define SETTING_NAV_MC_VEL_XY_P 254 -#define SETTING_NAV_MC_VEL_XY_P_MIN 0 -#define SETTING_NAV_MC_VEL_XY_P_MAX 255 -#define SETTING_NAV_MC_VEL_XY_I_DEFAULT 15 -#define SETTING_NAV_MC_VEL_XY_I 255 -#define SETTING_NAV_MC_VEL_XY_I_MIN 0 -#define SETTING_NAV_MC_VEL_XY_I_MAX 255 -#define SETTING_NAV_MC_VEL_XY_D_DEFAULT 100 -#define SETTING_NAV_MC_VEL_XY_D 256 -#define SETTING_NAV_MC_VEL_XY_D_MIN 0 -#define SETTING_NAV_MC_VEL_XY_D_MAX 255 -#define SETTING_NAV_MC_VEL_XY_FF_DEFAULT 40 -#define SETTING_NAV_MC_VEL_XY_FF 257 -#define SETTING_NAV_MC_VEL_XY_FF_MIN 0 -#define SETTING_NAV_MC_VEL_XY_FF_MAX 255 -#define SETTING_NAV_MC_HEADING_P_DEFAULT 60 -#define SETTING_NAV_MC_HEADING_P 258 -#define SETTING_NAV_MC_HEADING_P_MIN 0 -#define SETTING_NAV_MC_HEADING_P_MAX 255 -#define SETTING_NAV_MC_VEL_XY_DTERM_LPF_HZ_DEFAULT 2 -#define SETTING_NAV_MC_VEL_XY_DTERM_LPF_HZ 259 -#define SETTING_NAV_MC_VEL_XY_DTERM_LPF_HZ_MIN 0 -#define SETTING_NAV_MC_VEL_XY_DTERM_LPF_HZ_MAX 100 -#define SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_DEFAULT 90 -#define SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION 260 -#define SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_MIN 0 -#define SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_MAX 100 -#define SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_START_DEFAULT 10 -#define SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_START 261 -#define SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_START_MIN 0 -#define SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_START_MAX 100 -#define SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_END_DEFAULT 60 -#define SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_END 262 -#define SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_END_MIN 0 -#define SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_END_MAX 100 -#define SETTING_NAV_FW_POS_Z_P_DEFAULT 40 -#define SETTING_NAV_FW_POS_Z_P 263 -#define SETTING_NAV_FW_POS_Z_P_MIN 0 -#define SETTING_NAV_FW_POS_Z_P_MAX 255 -#define SETTING_NAV_FW_POS_Z_I_DEFAULT 5 -#define SETTING_NAV_FW_POS_Z_I 264 -#define SETTING_NAV_FW_POS_Z_I_MIN 0 -#define SETTING_NAV_FW_POS_Z_I_MAX 255 -#define SETTING_NAV_FW_POS_Z_D_DEFAULT 10 -#define SETTING_NAV_FW_POS_Z_D 265 -#define SETTING_NAV_FW_POS_Z_D_MIN 0 -#define SETTING_NAV_FW_POS_Z_D_MAX 255 -#define SETTING_NAV_FW_POS_XY_P_DEFAULT 75 -#define SETTING_NAV_FW_POS_XY_P 266 -#define SETTING_NAV_FW_POS_XY_P_MIN 0 -#define SETTING_NAV_FW_POS_XY_P_MAX 255 -#define SETTING_NAV_FW_POS_XY_I_DEFAULT 5 -#define SETTING_NAV_FW_POS_XY_I 267 -#define SETTING_NAV_FW_POS_XY_I_MIN 0 -#define SETTING_NAV_FW_POS_XY_I_MAX 255 -#define SETTING_NAV_FW_POS_XY_D_DEFAULT 8 -#define SETTING_NAV_FW_POS_XY_D 268 -#define SETTING_NAV_FW_POS_XY_D_MIN 0 -#define SETTING_NAV_FW_POS_XY_D_MAX 255 -#define SETTING_NAV_FW_HEADING_P_DEFAULT 60 -#define SETTING_NAV_FW_HEADING_P 269 -#define SETTING_NAV_FW_HEADING_P_MIN 0 -#define SETTING_NAV_FW_HEADING_P_MAX 255 -#define SETTING_NAV_FW_POS_HDG_P_DEFAULT 30 -#define SETTING_NAV_FW_POS_HDG_P 270 -#define SETTING_NAV_FW_POS_HDG_P_MIN 0 -#define SETTING_NAV_FW_POS_HDG_P_MAX 255 -#define SETTING_NAV_FW_POS_HDG_I_DEFAULT 2 -#define SETTING_NAV_FW_POS_HDG_I 271 -#define SETTING_NAV_FW_POS_HDG_I_MIN 0 -#define SETTING_NAV_FW_POS_HDG_I_MAX 255 -#define SETTING_NAV_FW_POS_HDG_D_DEFAULT 0 -#define SETTING_NAV_FW_POS_HDG_D 272 -#define SETTING_NAV_FW_POS_HDG_D_MIN 0 -#define SETTING_NAV_FW_POS_HDG_D_MAX 255 -#define SETTING_NAV_FW_POS_HDG_PIDSUM_LIMIT_DEFAULT 350 -#define SETTING_NAV_FW_POS_HDG_PIDSUM_LIMIT 273 -#define SETTING_NAV_FW_POS_HDG_PIDSUM_LIMIT_MIN 100 -#define SETTING_NAV_FW_POS_HDG_PIDSUM_LIMIT_MAX 1000 -#define SETTING_MC_ITERM_RELAX_DEFAULT 1 -#define SETTING_MC_ITERM_RELAX 274 -#define SETTING_MC_ITERM_RELAX_MIN 0 -#define SETTING_MC_ITERM_RELAX_MAX 0 -#define SETTING_MC_ITERM_RELAX_CUTOFF_DEFAULT 15 -#define SETTING_MC_ITERM_RELAX_CUTOFF 275 -#define SETTING_MC_ITERM_RELAX_CUTOFF_MIN 1 -#define SETTING_MC_ITERM_RELAX_CUTOFF_MAX 100 -#define SETTING_D_BOOST_MIN_DEFAULT 0.5f -#define SETTING_D_BOOST_MIN 276 -#define SETTING_D_BOOST_MIN_MIN 0 -#define SETTING_D_BOOST_MIN_MAX 1 -#define SETTING_D_BOOST_MAX_DEFAULT 1.25f -#define SETTING_D_BOOST_MAX 277 -#define SETTING_D_BOOST_MAX_MIN 1 -#define SETTING_D_BOOST_MAX_MAX 3 -#define SETTING_D_BOOST_MAX_AT_ACCELERATION_DEFAULT 7500 -#define SETTING_D_BOOST_MAX_AT_ACCELERATION 278 -#define SETTING_D_BOOST_MAX_AT_ACCELERATION_MIN 1000 -#define SETTING_D_BOOST_MAX_AT_ACCELERATION_MAX 16000 -#define SETTING_D_BOOST_GYRO_DELTA_LPF_HZ_DEFAULT 80 -#define SETTING_D_BOOST_GYRO_DELTA_LPF_HZ 279 -#define SETTING_D_BOOST_GYRO_DELTA_LPF_HZ_MIN 10 -#define SETTING_D_BOOST_GYRO_DELTA_LPF_HZ_MAX 250 -#define SETTING_ANTIGRAVITY_GAIN_DEFAULT 1 -#define SETTING_ANTIGRAVITY_GAIN 280 -#define SETTING_ANTIGRAVITY_GAIN_MIN 1 -#define SETTING_ANTIGRAVITY_GAIN_MAX 20 -#define SETTING_ANTIGRAVITY_ACCELERATOR_DEFAULT 1 -#define SETTING_ANTIGRAVITY_ACCELERATOR 281 -#define SETTING_ANTIGRAVITY_ACCELERATOR_MIN 1 -#define SETTING_ANTIGRAVITY_ACCELERATOR_MAX 20 -#define SETTING_ANTIGRAVITY_CUTOFF_LPF_HZ_DEFAULT 15 -#define SETTING_ANTIGRAVITY_CUTOFF_LPF_HZ 282 -#define SETTING_ANTIGRAVITY_CUTOFF_LPF_HZ_MIN 1 -#define SETTING_ANTIGRAVITY_CUTOFF_LPF_HZ_MAX 30 -#define SETTING_PID_TYPE_DEFAULT 3 -#define SETTING_PID_TYPE 283 -#define SETTING_PID_TYPE_MIN 0 -#define SETTING_PID_TYPE_MAX 0 -#define SETTING_MC_CD_LPF_HZ_DEFAULT 30 -#define SETTING_MC_CD_LPF_HZ 284 -#define SETTING_MC_CD_LPF_HZ_MIN 0 -#define SETTING_MC_CD_LPF_HZ_MAX 200 -#define SETTING_FW_LEVEL_PITCH_TRIM_DEFAULT 0 -#define SETTING_FW_LEVEL_PITCH_TRIM 285 -#define SETTING_FW_LEVEL_PITCH_TRIM_MIN -10 -#define SETTING_FW_LEVEL_PITCH_TRIM_MAX 10 -#define SETTING_SMITH_PREDICTOR_STRENGTH_DEFAULT 0.5f -#define SETTING_SMITH_PREDICTOR_STRENGTH 286 -#define SETTING_SMITH_PREDICTOR_STRENGTH_MIN 0 -#define SETTING_SMITH_PREDICTOR_STRENGTH_MAX 1 -#define SETTING_SMITH_PREDICTOR_DELAY_DEFAULT 0 -#define SETTING_SMITH_PREDICTOR_DELAY 287 -#define SETTING_SMITH_PREDICTOR_DELAY_MIN 0 -#define SETTING_SMITH_PREDICTOR_DELAY_MAX 8 -#define SETTING_SMITH_PREDICTOR_LPF_HZ_DEFAULT 50 -#define SETTING_SMITH_PREDICTOR_LPF_HZ 288 -#define SETTING_SMITH_PREDICTOR_LPF_HZ_MIN 1 -#define SETTING_SMITH_PREDICTOR_LPF_HZ_MAX 500 -#define SETTING_FW_LEVEL_PITCH_GAIN_DEFAULT 5 -#define SETTING_FW_LEVEL_PITCH_GAIN 289 -#define SETTING_FW_LEVEL_PITCH_GAIN_MIN 0 -#define SETTING_FW_LEVEL_PITCH_GAIN_MAX 20 -#define SETTING_FW_AUTOTUNE_MIN_STICK_DEFAULT 50 -#define SETTING_FW_AUTOTUNE_MIN_STICK 290 -#define SETTING_FW_AUTOTUNE_MIN_STICK_MIN 0 -#define SETTING_FW_AUTOTUNE_MIN_STICK_MAX 100 -#define SETTING_FW_AUTOTUNE_RATE_ADJUSTMENT_DEFAULT 2 -#define SETTING_FW_AUTOTUNE_RATE_ADJUSTMENT 291 -#define SETTING_FW_AUTOTUNE_RATE_ADJUSTMENT_MIN 0 -#define SETTING_FW_AUTOTUNE_RATE_ADJUSTMENT_MAX 0 -#define SETTING_FW_AUTOTUNE_MAX_RATE_DEFLECTION_DEFAULT 80 -#define SETTING_FW_AUTOTUNE_MAX_RATE_DEFLECTION 292 -#define SETTING_FW_AUTOTUNE_MAX_RATE_DEFLECTION_MIN 50 -#define SETTING_FW_AUTOTUNE_MAX_RATE_DEFLECTION_MAX 100 -#define SETTING_INAV_AUTO_MAG_DECL_DEFAULT 1 -#define SETTING_INAV_AUTO_MAG_DECL 293 -#define SETTING_INAV_AUTO_MAG_DECL_MIN 0 -#define SETTING_INAV_AUTO_MAG_DECL_MAX 0 -#define SETTING_INAV_GRAVITY_CAL_TOLERANCE_DEFAULT 5 -#define SETTING_INAV_GRAVITY_CAL_TOLERANCE 294 -#define SETTING_INAV_GRAVITY_CAL_TOLERANCE_MIN 0 -#define SETTING_INAV_GRAVITY_CAL_TOLERANCE_MAX 255 -#define SETTING_INAV_USE_GPS_VELNED_DEFAULT 1 -#define SETTING_INAV_USE_GPS_VELNED 295 -#define SETTING_INAV_USE_GPS_VELNED_MIN 0 -#define SETTING_INAV_USE_GPS_VELNED_MAX 0 -#define SETTING_INAV_USE_GPS_NO_BARO_DEFAULT 0 -#define SETTING_INAV_USE_GPS_NO_BARO 296 -#define SETTING_INAV_USE_GPS_NO_BARO_MIN 0 -#define SETTING_INAV_USE_GPS_NO_BARO_MAX 0 -#define SETTING_INAV_ALLOW_DEAD_RECKONING_DEFAULT 0 -#define SETTING_INAV_ALLOW_DEAD_RECKONING 297 -#define SETTING_INAV_ALLOW_DEAD_RECKONING_MIN 0 -#define SETTING_INAV_ALLOW_DEAD_RECKONING_MAX 0 -#define SETTING_INAV_RESET_ALTITUDE_DEFAULT 1 -#define SETTING_INAV_RESET_ALTITUDE 298 -#define SETTING_INAV_RESET_ALTITUDE_MIN 0 -#define SETTING_INAV_RESET_ALTITUDE_MAX 0 -#define SETTING_INAV_RESET_HOME_DEFAULT 1 -#define SETTING_INAV_RESET_HOME 299 -#define SETTING_INAV_RESET_HOME_MIN 0 -#define SETTING_INAV_RESET_HOME_MAX 0 -#define SETTING_INAV_MAX_SURFACE_ALTITUDE_DEFAULT 200 -#define SETTING_INAV_MAX_SURFACE_ALTITUDE 300 -#define SETTING_INAV_MAX_SURFACE_ALTITUDE_MIN 0 -#define SETTING_INAV_MAX_SURFACE_ALTITUDE_MAX 1000 -#define SETTING_INAV_W_Z_SURFACE_P_DEFAULT 3.5f -#define SETTING_INAV_W_Z_SURFACE_P 301 -#define SETTING_INAV_W_Z_SURFACE_P_MIN 0 -#define SETTING_INAV_W_Z_SURFACE_P_MAX 100 -#define SETTING_INAV_W_Z_SURFACE_V_DEFAULT 6.1f -#define SETTING_INAV_W_Z_SURFACE_V 302 -#define SETTING_INAV_W_Z_SURFACE_V_MIN 0 -#define SETTING_INAV_W_Z_SURFACE_V_MAX 100 -#define SETTING_INAV_W_XY_FLOW_P_DEFAULT 1.0f -#define SETTING_INAV_W_XY_FLOW_P 303 -#define SETTING_INAV_W_XY_FLOW_P_MIN 0 -#define SETTING_INAV_W_XY_FLOW_P_MAX 100 -#define SETTING_INAV_W_XY_FLOW_V_DEFAULT 2.0f -#define SETTING_INAV_W_XY_FLOW_V 304 -#define SETTING_INAV_W_XY_FLOW_V_MIN 0 -#define SETTING_INAV_W_XY_FLOW_V_MAX 100 -#define SETTING_INAV_W_Z_BARO_P_DEFAULT 0.35f -#define SETTING_INAV_W_Z_BARO_P 305 -#define SETTING_INAV_W_Z_BARO_P_MIN 0 -#define SETTING_INAV_W_Z_BARO_P_MAX 10 -#define SETTING_INAV_W_Z_GPS_P_DEFAULT 0.2f -#define SETTING_INAV_W_Z_GPS_P 306 -#define SETTING_INAV_W_Z_GPS_P_MIN 0 -#define SETTING_INAV_W_Z_GPS_P_MAX 10 -#define SETTING_INAV_W_Z_GPS_V_DEFAULT 0.1f -#define SETTING_INAV_W_Z_GPS_V 307 -#define SETTING_INAV_W_Z_GPS_V_MIN 0 -#define SETTING_INAV_W_Z_GPS_V_MAX 10 -#define SETTING_INAV_W_XY_GPS_P_DEFAULT 1.0f -#define SETTING_INAV_W_XY_GPS_P 308 -#define SETTING_INAV_W_XY_GPS_P_MIN 0 -#define SETTING_INAV_W_XY_GPS_P_MAX 10 -#define SETTING_INAV_W_XY_GPS_V_DEFAULT 2.0f -#define SETTING_INAV_W_XY_GPS_V 309 -#define SETTING_INAV_W_XY_GPS_V_MIN 0 -#define SETTING_INAV_W_XY_GPS_V_MAX 10 -#define SETTING_INAV_W_Z_RES_V_DEFAULT 0.5f -#define SETTING_INAV_W_Z_RES_V 310 -#define SETTING_INAV_W_Z_RES_V_MIN 0 -#define SETTING_INAV_W_Z_RES_V_MAX 10 -#define SETTING_INAV_W_XY_RES_V_DEFAULT 0.5f -#define SETTING_INAV_W_XY_RES_V 311 -#define SETTING_INAV_W_XY_RES_V_MIN 0 -#define SETTING_INAV_W_XY_RES_V_MAX 10 -#define SETTING_INAV_W_XYZ_ACC_P_DEFAULT 1.0f -#define SETTING_INAV_W_XYZ_ACC_P 312 -#define SETTING_INAV_W_XYZ_ACC_P_MIN 0 -#define SETTING_INAV_W_XYZ_ACC_P_MAX 1 -#define SETTING_INAV_W_ACC_BIAS_DEFAULT 0.01f -#define SETTING_INAV_W_ACC_BIAS 313 -#define SETTING_INAV_W_ACC_BIAS_MIN 0 -#define SETTING_INAV_W_ACC_BIAS_MAX 1 -#define SETTING_INAV_MAX_EPH_EPV_DEFAULT 1000 -#define SETTING_INAV_MAX_EPH_EPV 314 -#define SETTING_INAV_MAX_EPH_EPV_MIN 0 -#define SETTING_INAV_MAX_EPH_EPV_MAX 9999 -#define SETTING_INAV_BARO_EPV_DEFAULT 100 -#define SETTING_INAV_BARO_EPV 315 -#define SETTING_INAV_BARO_EPV_MIN 0 -#define SETTING_INAV_BARO_EPV_MAX 9999 -#define SETTING_NAV_DISARM_ON_LANDING_DEFAULT 0 -#define SETTING_NAV_DISARM_ON_LANDING 316 -#define SETTING_NAV_DISARM_ON_LANDING_MIN 0 -#define SETTING_NAV_DISARM_ON_LANDING_MAX 0 -#define SETTING_NAV_LAND_DETECT_SENSITIVITY_DEFAULT 5 -#define SETTING_NAV_LAND_DETECT_SENSITIVITY 317 -#define SETTING_NAV_LAND_DETECT_SENSITIVITY_MIN 1 -#define SETTING_NAV_LAND_DETECT_SENSITIVITY_MAX 15 -#define SETTING_NAV_USE_MIDTHR_FOR_ALTHOLD_DEFAULT 0 -#define SETTING_NAV_USE_MIDTHR_FOR_ALTHOLD 318 -#define SETTING_NAV_USE_MIDTHR_FOR_ALTHOLD_MIN 0 -#define SETTING_NAV_USE_MIDTHR_FOR_ALTHOLD_MAX 0 -#define SETTING_NAV_EXTRA_ARMING_SAFETY_DEFAULT 0 -#define SETTING_NAV_EXTRA_ARMING_SAFETY 319 -#define SETTING_NAV_EXTRA_ARMING_SAFETY_MIN 0 -#define SETTING_NAV_EXTRA_ARMING_SAFETY_MAX 0 -#define SETTING_NAV_USER_CONTROL_MODE_DEFAULT 0 -#define SETTING_NAV_USER_CONTROL_MODE 320 -#define SETTING_NAV_USER_CONTROL_MODE_MIN 0 -#define SETTING_NAV_USER_CONTROL_MODE_MAX 0 -#define SETTING_NAV_POSITION_TIMEOUT_DEFAULT 5 -#define SETTING_NAV_POSITION_TIMEOUT 321 -#define SETTING_NAV_POSITION_TIMEOUT_MIN 0 -#define SETTING_NAV_POSITION_TIMEOUT_MAX 10 -#define SETTING_NAV_WP_LOAD_ON_BOOT_DEFAULT 0 -#define SETTING_NAV_WP_LOAD_ON_BOOT 322 -#define SETTING_NAV_WP_LOAD_ON_BOOT_MIN 0 -#define SETTING_NAV_WP_LOAD_ON_BOOT_MAX 0 -#define SETTING_NAV_WP_RADIUS_DEFAULT 100 -#define SETTING_NAV_WP_RADIUS 323 -#define SETTING_NAV_WP_RADIUS_MIN 10 -#define SETTING_NAV_WP_RADIUS_MAX 10000 -#define SETTING_NAV_WP_ENFORCE_ALTITUDE_DEFAULT 0 -#define SETTING_NAV_WP_ENFORCE_ALTITUDE 324 -#define SETTING_NAV_WP_ENFORCE_ALTITUDE_MIN 0 -#define SETTING_NAV_WP_ENFORCE_ALTITUDE_MAX 2000 -#define SETTING_NAV_WP_MAX_SAFE_DISTANCE_DEFAULT 100 -#define SETTING_NAV_WP_MAX_SAFE_DISTANCE 325 -#define SETTING_NAV_WP_MAX_SAFE_DISTANCE_MIN 0 -#define SETTING_NAV_WP_MAX_SAFE_DISTANCE_MAX 1500 -#define SETTING_NAV_WP_MISSION_RESTART_DEFAULT 1 -#define SETTING_NAV_WP_MISSION_RESTART 326 -#define SETTING_NAV_WP_MISSION_RESTART_MIN 0 -#define SETTING_NAV_WP_MISSION_RESTART_MAX 0 -#define SETTING_NAV_WP_MULTI_MISSION_INDEX_DEFAULT 1 -#define SETTING_NAV_WP_MULTI_MISSION_INDEX 327 -#define SETTING_NAV_WP_MULTI_MISSION_INDEX_MIN 1 -#define SETTING_NAV_WP_MULTI_MISSION_INDEX_MAX 9 -#define SETTING_NAV_FW_WP_TRACKING_ACCURACY_DEFAULT 0 -#define SETTING_NAV_FW_WP_TRACKING_ACCURACY 328 -#define SETTING_NAV_FW_WP_TRACKING_ACCURACY_MIN 0 -#define SETTING_NAV_FW_WP_TRACKING_ACCURACY_MAX 10 -#define SETTING_NAV_FW_WP_TRACKING_MAX_ANGLE_DEFAULT 60 -#define SETTING_NAV_FW_WP_TRACKING_MAX_ANGLE 329 -#define SETTING_NAV_FW_WP_TRACKING_MAX_ANGLE_MIN 30 -#define SETTING_NAV_FW_WP_TRACKING_MAX_ANGLE_MAX 80 -#define SETTING_NAV_FW_WP_TURN_SMOOTHING_DEFAULT 0 -#define SETTING_NAV_FW_WP_TURN_SMOOTHING 330 -#define SETTING_NAV_FW_WP_TURN_SMOOTHING_MIN 0 -#define SETTING_NAV_FW_WP_TURN_SMOOTHING_MAX 0 -#define SETTING_NAV_AUTO_SPEED_DEFAULT 300 -#define SETTING_NAV_AUTO_SPEED 331 -#define SETTING_NAV_AUTO_SPEED_MIN 10 -#define SETTING_NAV_AUTO_SPEED_MAX 2000 -#define SETTING_NAV_MAX_AUTO_SPEED_DEFAULT 1000 -#define SETTING_NAV_MAX_AUTO_SPEED 332 -#define SETTING_NAV_MAX_AUTO_SPEED_MIN 10 -#define SETTING_NAV_MAX_AUTO_SPEED_MAX 2000 -#define SETTING_NAV_AUTO_CLIMB_RATE_DEFAULT 500 -#define SETTING_NAV_AUTO_CLIMB_RATE 333 -#define SETTING_NAV_AUTO_CLIMB_RATE_MIN 10 -#define SETTING_NAV_AUTO_CLIMB_RATE_MAX 2000 -#define SETTING_NAV_MANUAL_SPEED_DEFAULT 500 -#define SETTING_NAV_MANUAL_SPEED 334 -#define SETTING_NAV_MANUAL_SPEED_MIN 10 -#define SETTING_NAV_MANUAL_SPEED_MAX 2000 -#define SETTING_NAV_MANUAL_CLIMB_RATE_DEFAULT 200 -#define SETTING_NAV_MANUAL_CLIMB_RATE 335 -#define SETTING_NAV_MANUAL_CLIMB_RATE_MIN 10 -#define SETTING_NAV_MANUAL_CLIMB_RATE_MAX 2000 -#define SETTING_NAV_LAND_MINALT_VSPD_DEFAULT 50 -#define SETTING_NAV_LAND_MINALT_VSPD 336 -#define SETTING_NAV_LAND_MINALT_VSPD_MIN 50 -#define SETTING_NAV_LAND_MINALT_VSPD_MAX 500 -#define SETTING_NAV_LAND_MAXALT_VSPD_DEFAULT 200 -#define SETTING_NAV_LAND_MAXALT_VSPD 337 -#define SETTING_NAV_LAND_MAXALT_VSPD_MIN 100 -#define SETTING_NAV_LAND_MAXALT_VSPD_MAX 2000 -#define SETTING_NAV_LAND_SLOWDOWN_MINALT_DEFAULT 500 -#define SETTING_NAV_LAND_SLOWDOWN_MINALT 338 -#define SETTING_NAV_LAND_SLOWDOWN_MINALT_MIN 50 -#define SETTING_NAV_LAND_SLOWDOWN_MINALT_MAX 1000 -#define SETTING_NAV_LAND_SLOWDOWN_MAXALT_DEFAULT 2000 -#define SETTING_NAV_LAND_SLOWDOWN_MAXALT 339 -#define SETTING_NAV_LAND_SLOWDOWN_MAXALT_MIN 500 -#define SETTING_NAV_LAND_SLOWDOWN_MAXALT_MAX 4000 -#define SETTING_NAV_EMERG_LANDING_SPEED_DEFAULT 500 -#define SETTING_NAV_EMERG_LANDING_SPEED 340 -#define SETTING_NAV_EMERG_LANDING_SPEED_MIN 100 -#define SETTING_NAV_EMERG_LANDING_SPEED_MAX 2000 -#define SETTING_NAV_MIN_RTH_DISTANCE_DEFAULT 500 -#define SETTING_NAV_MIN_RTH_DISTANCE 341 -#define SETTING_NAV_MIN_RTH_DISTANCE_MIN 0 -#define SETTING_NAV_MIN_RTH_DISTANCE_MAX 5000 -#define SETTING_NAV_OVERRIDES_MOTOR_STOP_DEFAULT 3 -#define SETTING_NAV_OVERRIDES_MOTOR_STOP 342 -#define SETTING_NAV_OVERRIDES_MOTOR_STOP_MIN 0 -#define SETTING_NAV_OVERRIDES_MOTOR_STOP_MAX 0 -#define SETTING_NAV_FW_SOARING_MOTOR_STOP_DEFAULT 0 -#define SETTING_NAV_FW_SOARING_MOTOR_STOP 343 -#define SETTING_NAV_FW_SOARING_MOTOR_STOP_MIN 0 -#define SETTING_NAV_FW_SOARING_MOTOR_STOP_MAX 0 -#define SETTING_NAV_FW_SOARING_PITCH_DEADBAND_DEFAULT 5 -#define SETTING_NAV_FW_SOARING_PITCH_DEADBAND 344 -#define SETTING_NAV_FW_SOARING_PITCH_DEADBAND_MIN 0 -#define SETTING_NAV_FW_SOARING_PITCH_DEADBAND_MAX 15 -#define SETTING_NAV_RTH_CLIMB_FIRST_DEFAULT 1 -#define SETTING_NAV_RTH_CLIMB_FIRST 345 -#define SETTING_NAV_RTH_CLIMB_FIRST_MIN 0 -#define SETTING_NAV_RTH_CLIMB_FIRST_MAX 0 -#define SETTING_NAV_RTH_CLIMB_FIRST_STAGE_MODE_DEFAULT 0 -#define SETTING_NAV_RTH_CLIMB_FIRST_STAGE_MODE 346 -#define SETTING_NAV_RTH_CLIMB_FIRST_STAGE_MODE_MIN 0 -#define SETTING_NAV_RTH_CLIMB_FIRST_STAGE_MODE_MAX 0 -#define SETTING_NAV_RTH_CLIMB_FIRST_STAGE_ALTITUDE_DEFAULT 0 -#define SETTING_NAV_RTH_CLIMB_FIRST_STAGE_ALTITUDE 347 -#define SETTING_NAV_RTH_CLIMB_FIRST_STAGE_ALTITUDE_MIN 0 -#define SETTING_NAV_RTH_CLIMB_FIRST_STAGE_ALTITUDE_MAX 65000 -#define SETTING_NAV_RTH_CLIMB_IGNORE_EMERG_DEFAULT 0 -#define SETTING_NAV_RTH_CLIMB_IGNORE_EMERG 348 -#define SETTING_NAV_RTH_CLIMB_IGNORE_EMERG_MIN 0 -#define SETTING_NAV_RTH_CLIMB_IGNORE_EMERG_MAX 0 -#define SETTING_NAV_RTH_TAIL_FIRST_DEFAULT 0 -#define SETTING_NAV_RTH_TAIL_FIRST 349 -#define SETTING_NAV_RTH_TAIL_FIRST_MIN 0 -#define SETTING_NAV_RTH_TAIL_FIRST_MAX 0 -#define SETTING_NAV_RTH_ALLOW_LANDING_DEFAULT 1 -#define SETTING_NAV_RTH_ALLOW_LANDING 350 -#define SETTING_NAV_RTH_ALLOW_LANDING_MIN 0 -#define SETTING_NAV_RTH_ALLOW_LANDING_MAX 0 -#define SETTING_NAV_RTH_ALT_MODE_DEFAULT 4 -#define SETTING_NAV_RTH_ALT_MODE 351 -#define SETTING_NAV_RTH_ALT_MODE_MIN 0 -#define SETTING_NAV_RTH_ALT_MODE_MAX 0 -#define SETTING_NAV_RTH_ALT_CONTROL_OVERRIDE_DEFAULT 0 -#define SETTING_NAV_RTH_ALT_CONTROL_OVERRIDE 352 -#define SETTING_NAV_RTH_ALT_CONTROL_OVERRIDE_MIN 0 -#define SETTING_NAV_RTH_ALT_CONTROL_OVERRIDE_MAX 0 -#define SETTING_NAV_RTH_ABORT_THRESHOLD_DEFAULT 50000 -#define SETTING_NAV_RTH_ABORT_THRESHOLD 353 -#define SETTING_NAV_RTH_ABORT_THRESHOLD_MIN 0 -#define SETTING_NAV_RTH_ABORT_THRESHOLD_MAX 65000 -#define SETTING_NAV_MAX_TERRAIN_FOLLOW_ALT_DEFAULT 100 -#define SETTING_NAV_MAX_TERRAIN_FOLLOW_ALT 354 -#define SETTING_NAV_MAX_TERRAIN_FOLLOW_ALT_MIN 0 -#define SETTING_NAV_MAX_TERRAIN_FOLLOW_ALT_MAX 1000 -#define SETTING_NAV_MAX_ALTITUDE_DEFAULT 0 -#define SETTING_NAV_MAX_ALTITUDE 355 -#define SETTING_NAV_MAX_ALTITUDE_MIN 0 -#define SETTING_NAV_MAX_ALTITUDE_MAX 65000 -#define SETTING_NAV_RTH_ALTITUDE_DEFAULT 1000 -#define SETTING_NAV_RTH_ALTITUDE 356 -#define SETTING_NAV_RTH_ALTITUDE_MIN 0 -#define SETTING_NAV_RTH_ALTITUDE_MAX 65000 -#define SETTING_NAV_RTH_HOME_ALTITUDE_DEFAULT 0 -#define SETTING_NAV_RTH_HOME_ALTITUDE 357 -#define SETTING_NAV_RTH_HOME_ALTITUDE_MIN 0 -#define SETTING_NAV_RTH_HOME_ALTITUDE_MAX 65000 -#define SETTING_NAV_RTH_TRACKBACK_MODE_DEFAULT 0 -#define SETTING_NAV_RTH_TRACKBACK_MODE 358 -#define SETTING_NAV_RTH_TRACKBACK_MODE_MIN 0 -#define SETTING_NAV_RTH_TRACKBACK_MODE_MAX 0 -#define SETTING_NAV_RTH_TRACKBACK_DISTANCE_DEFAULT 500 -#define SETTING_NAV_RTH_TRACKBACK_DISTANCE 359 -#define SETTING_NAV_RTH_TRACKBACK_DISTANCE_MIN 50 -#define SETTING_NAV_RTH_TRACKBACK_DISTANCE_MAX 2000 -#define SETTING_SAFEHOME_MAX_DISTANCE_DEFAULT 20000 -#define SETTING_SAFEHOME_MAX_DISTANCE 360 -#define SETTING_SAFEHOME_MAX_DISTANCE_MIN 0 -#define SETTING_SAFEHOME_MAX_DISTANCE_MAX 65000 -#define SETTING_SAFEHOME_USAGE_MODE_DEFAULT 1 -#define SETTING_SAFEHOME_USAGE_MODE 361 -#define SETTING_SAFEHOME_USAGE_MODE_MIN 0 -#define SETTING_SAFEHOME_USAGE_MODE_MAX 0 -#define SETTING_NAV_MISSION_PLANNER_RESET_DEFAULT 1 -#define SETTING_NAV_MISSION_PLANNER_RESET 362 -#define SETTING_NAV_MISSION_PLANNER_RESET_MIN 0 -#define SETTING_NAV_MISSION_PLANNER_RESET_MAX 0 -#define SETTING_NAV_MC_BANK_ANGLE_DEFAULT 30 -#define SETTING_NAV_MC_BANK_ANGLE 363 -#define SETTING_NAV_MC_BANK_ANGLE_MIN 15 -#define SETTING_NAV_MC_BANK_ANGLE_MAX 45 -#define SETTING_NAV_AUTO_DISARM_DELAY_DEFAULT 2000 -#define SETTING_NAV_AUTO_DISARM_DELAY 364 -#define SETTING_NAV_AUTO_DISARM_DELAY_MIN 100 -#define SETTING_NAV_AUTO_DISARM_DELAY_MAX 10000 -#define SETTING_NAV_MC_BRAKING_SPEED_THRESHOLD_DEFAULT 100 -#define SETTING_NAV_MC_BRAKING_SPEED_THRESHOLD 365 -#define SETTING_NAV_MC_BRAKING_SPEED_THRESHOLD_MIN 0 -#define SETTING_NAV_MC_BRAKING_SPEED_THRESHOLD_MAX 1000 -#define SETTING_NAV_MC_BRAKING_DISENGAGE_SPEED_DEFAULT 75 -#define SETTING_NAV_MC_BRAKING_DISENGAGE_SPEED 366 -#define SETTING_NAV_MC_BRAKING_DISENGAGE_SPEED_MIN 0 -#define SETTING_NAV_MC_BRAKING_DISENGAGE_SPEED_MAX 1000 -#define SETTING_NAV_MC_BRAKING_TIMEOUT_DEFAULT 2000 -#define SETTING_NAV_MC_BRAKING_TIMEOUT 367 -#define SETTING_NAV_MC_BRAKING_TIMEOUT_MIN 100 -#define SETTING_NAV_MC_BRAKING_TIMEOUT_MAX 5000 -#define SETTING_NAV_MC_BRAKING_BOOST_FACTOR_DEFAULT 100 -#define SETTING_NAV_MC_BRAKING_BOOST_FACTOR 368 -#define SETTING_NAV_MC_BRAKING_BOOST_FACTOR_MIN 0 -#define SETTING_NAV_MC_BRAKING_BOOST_FACTOR_MAX 200 -#define SETTING_NAV_MC_BRAKING_BOOST_TIMEOUT_DEFAULT 750 -#define SETTING_NAV_MC_BRAKING_BOOST_TIMEOUT 369 -#define SETTING_NAV_MC_BRAKING_BOOST_TIMEOUT_MIN 0 -#define SETTING_NAV_MC_BRAKING_BOOST_TIMEOUT_MAX 5000 -#define SETTING_NAV_MC_BRAKING_BOOST_SPEED_THRESHOLD_DEFAULT 150 -#define SETTING_NAV_MC_BRAKING_BOOST_SPEED_THRESHOLD 370 -#define SETTING_NAV_MC_BRAKING_BOOST_SPEED_THRESHOLD_MIN 100 -#define SETTING_NAV_MC_BRAKING_BOOST_SPEED_THRESHOLD_MAX 1000 -#define SETTING_NAV_MC_BRAKING_BOOST_DISENGAGE_SPEED_DEFAULT 100 -#define SETTING_NAV_MC_BRAKING_BOOST_DISENGAGE_SPEED 371 -#define SETTING_NAV_MC_BRAKING_BOOST_DISENGAGE_SPEED_MIN 0 -#define SETTING_NAV_MC_BRAKING_BOOST_DISENGAGE_SPEED_MAX 1000 -#define SETTING_NAV_MC_BRAKING_BANK_ANGLE_DEFAULT 40 -#define SETTING_NAV_MC_BRAKING_BANK_ANGLE 372 -#define SETTING_NAV_MC_BRAKING_BANK_ANGLE_MIN 15 -#define SETTING_NAV_MC_BRAKING_BANK_ANGLE_MAX 60 -#define SETTING_NAV_MC_POS_DECELERATION_TIME_DEFAULT 120 -#define SETTING_NAV_MC_POS_DECELERATION_TIME 373 -#define SETTING_NAV_MC_POS_DECELERATION_TIME_MIN 0 -#define SETTING_NAV_MC_POS_DECELERATION_TIME_MAX 255 -#define SETTING_NAV_MC_POS_EXPO_DEFAULT 10 -#define SETTING_NAV_MC_POS_EXPO 374 -#define SETTING_NAV_MC_POS_EXPO_MIN 0 -#define SETTING_NAV_MC_POS_EXPO_MAX 255 -#define SETTING_NAV_MC_WP_SLOWDOWN_DEFAULT 1 -#define SETTING_NAV_MC_WP_SLOWDOWN 375 -#define SETTING_NAV_MC_WP_SLOWDOWN_MIN 0 -#define SETTING_NAV_MC_WP_SLOWDOWN_MAX 0 -#define SETTING_NAV_FW_BANK_ANGLE_DEFAULT 35 -#define SETTING_NAV_FW_BANK_ANGLE 376 -#define SETTING_NAV_FW_BANK_ANGLE_MIN 5 -#define SETTING_NAV_FW_BANK_ANGLE_MAX 80 -#define SETTING_NAV_FW_CLIMB_ANGLE_DEFAULT 20 -#define SETTING_NAV_FW_CLIMB_ANGLE 377 -#define SETTING_NAV_FW_CLIMB_ANGLE_MIN 5 -#define SETTING_NAV_FW_CLIMB_ANGLE_MAX 80 -#define SETTING_NAV_FW_DIVE_ANGLE_DEFAULT 15 -#define SETTING_NAV_FW_DIVE_ANGLE 378 -#define SETTING_NAV_FW_DIVE_ANGLE_MIN 5 -#define SETTING_NAV_FW_DIVE_ANGLE_MAX 80 -#define SETTING_NAV_FW_PITCH2THR_SMOOTHING_DEFAULT 6 -#define SETTING_NAV_FW_PITCH2THR_SMOOTHING 379 -#define SETTING_NAV_FW_PITCH2THR_SMOOTHING_MIN 0 -#define SETTING_NAV_FW_PITCH2THR_SMOOTHING_MAX 9 -#define SETTING_FW_MIN_THROTTLE_DOWN_PITCH_DEFAULT 0 -#define SETTING_FW_MIN_THROTTLE_DOWN_PITCH 380 -#define SETTING_FW_MIN_THROTTLE_DOWN_PITCH_MIN 0 -#define SETTING_FW_MIN_THROTTLE_DOWN_PITCH_MAX 450 -#define SETTING_NAV_FW_PITCH2THR_THRESHOLD_DEFAULT 50 -#define SETTING_NAV_FW_PITCH2THR_THRESHOLD 381 -#define SETTING_NAV_FW_PITCH2THR_THRESHOLD_MIN 0 -#define SETTING_NAV_FW_PITCH2THR_THRESHOLD_MAX 900 -#define SETTING_NAV_FW_LOITER_RADIUS_DEFAULT 7500 -#define SETTING_NAV_FW_LOITER_RADIUS 382 -#define SETTING_NAV_FW_LOITER_RADIUS_MIN 0 -#define SETTING_NAV_FW_LOITER_RADIUS_MAX 30000 -#define SETTING_FW_LOITER_DIRECTION_DEFAULT 0 -#define SETTING_FW_LOITER_DIRECTION 383 -#define SETTING_FW_LOITER_DIRECTION_MIN 0 -#define SETTING_FW_LOITER_DIRECTION_MAX 0 -#define SETTING_NAV_FW_CRUISE_SPEED_DEFAULT 0 -#define SETTING_NAV_FW_CRUISE_SPEED 384 -#define SETTING_NAV_FW_CRUISE_SPEED_MIN 0 -#define SETTING_NAV_FW_CRUISE_SPEED_MAX 65535 -#define SETTING_NAV_FW_CONTROL_SMOOTHNESS_DEFAULT 0 -#define SETTING_NAV_FW_CONTROL_SMOOTHNESS 385 -#define SETTING_NAV_FW_CONTROL_SMOOTHNESS_MIN 0 -#define SETTING_NAV_FW_CONTROL_SMOOTHNESS_MAX 9 -#define SETTING_NAV_FW_LAND_DIVE_ANGLE_DEFAULT 2 -#define SETTING_NAV_FW_LAND_DIVE_ANGLE 386 -#define SETTING_NAV_FW_LAND_DIVE_ANGLE_MIN -20 -#define SETTING_NAV_FW_LAND_DIVE_ANGLE_MAX 20 -#define SETTING_NAV_FW_LAUNCH_VELOCITY_DEFAULT 300 -#define SETTING_NAV_FW_LAUNCH_VELOCITY 387 -#define SETTING_NAV_FW_LAUNCH_VELOCITY_MIN 100 -#define SETTING_NAV_FW_LAUNCH_VELOCITY_MAX 10000 -#define SETTING_NAV_FW_LAUNCH_ACCEL_DEFAULT 1863 -#define SETTING_NAV_FW_LAUNCH_ACCEL 388 -#define SETTING_NAV_FW_LAUNCH_ACCEL_MIN 1000 -#define SETTING_NAV_FW_LAUNCH_ACCEL_MAX 20000 -#define SETTING_NAV_FW_LAUNCH_MAX_ANGLE_DEFAULT 45 -#define SETTING_NAV_FW_LAUNCH_MAX_ANGLE 389 -#define SETTING_NAV_FW_LAUNCH_MAX_ANGLE_MIN 5 -#define SETTING_NAV_FW_LAUNCH_MAX_ANGLE_MAX 180 -#define SETTING_NAV_FW_LAUNCH_DETECT_TIME_DEFAULT 40 -#define SETTING_NAV_FW_LAUNCH_DETECT_TIME 390 -#define SETTING_NAV_FW_LAUNCH_DETECT_TIME_MIN 10 -#define SETTING_NAV_FW_LAUNCH_DETECT_TIME_MAX 1000 -#define SETTING_NAV_FW_LAUNCH_IDLE_MOTOR_DELAY_DEFAULT 0 -#define SETTING_NAV_FW_LAUNCH_IDLE_MOTOR_DELAY 391 -#define SETTING_NAV_FW_LAUNCH_IDLE_MOTOR_DELAY_MIN 0 -#define SETTING_NAV_FW_LAUNCH_IDLE_MOTOR_DELAY_MAX 60000 -#define SETTING_NAV_FW_LAUNCH_MOTOR_DELAY_DEFAULT 500 -#define SETTING_NAV_FW_LAUNCH_MOTOR_DELAY 392 -#define SETTING_NAV_FW_LAUNCH_MOTOR_DELAY_MIN 0 -#define SETTING_NAV_FW_LAUNCH_MOTOR_DELAY_MAX 5000 -#define SETTING_NAV_FW_LAUNCH_SPINUP_TIME_DEFAULT 100 -#define SETTING_NAV_FW_LAUNCH_SPINUP_TIME 393 -#define SETTING_NAV_FW_LAUNCH_SPINUP_TIME_MIN 0 -#define SETTING_NAV_FW_LAUNCH_SPINUP_TIME_MAX 1000 -#define SETTING_NAV_FW_LAUNCH_END_TIME_DEFAULT 3000 -#define SETTING_NAV_FW_LAUNCH_END_TIME 394 -#define SETTING_NAV_FW_LAUNCH_END_TIME_MIN 0 -#define SETTING_NAV_FW_LAUNCH_END_TIME_MAX 5000 -#define SETTING_NAV_FW_LAUNCH_MIN_TIME_DEFAULT 0 -#define SETTING_NAV_FW_LAUNCH_MIN_TIME 395 -#define SETTING_NAV_FW_LAUNCH_MIN_TIME_MIN 0 -#define SETTING_NAV_FW_LAUNCH_MIN_TIME_MAX 60000 -#define SETTING_NAV_FW_LAUNCH_TIMEOUT_DEFAULT 5000 -#define SETTING_NAV_FW_LAUNCH_TIMEOUT 396 -#define SETTING_NAV_FW_LAUNCH_TIMEOUT_MIN 0 -#define SETTING_NAV_FW_LAUNCH_TIMEOUT_MAX 60000 -#define SETTING_NAV_FW_LAUNCH_MAX_ALTITUDE_DEFAULT 0 -#define SETTING_NAV_FW_LAUNCH_MAX_ALTITUDE 397 -#define SETTING_NAV_FW_LAUNCH_MAX_ALTITUDE_MIN 0 -#define SETTING_NAV_FW_LAUNCH_MAX_ALTITUDE_MAX 60000 -#define SETTING_NAV_FW_LAUNCH_CLIMB_ANGLE_DEFAULT 18 -#define SETTING_NAV_FW_LAUNCH_CLIMB_ANGLE 398 -#define SETTING_NAV_FW_LAUNCH_CLIMB_ANGLE_MIN 5 -#define SETTING_NAV_FW_LAUNCH_CLIMB_ANGLE_MAX 45 -#define SETTING_NAV_FW_LAUNCH_MANUAL_THROTTLE_DEFAULT 0 -#define SETTING_NAV_FW_LAUNCH_MANUAL_THROTTLE 399 -#define SETTING_NAV_FW_LAUNCH_MANUAL_THROTTLE_MIN 0 -#define SETTING_NAV_FW_LAUNCH_MANUAL_THROTTLE_MAX 0 -#define SETTING_NAV_FW_LAUNCH_ABORT_DEADBAND_DEFAULT 100 -#define SETTING_NAV_FW_LAUNCH_ABORT_DEADBAND 400 -#define SETTING_NAV_FW_LAUNCH_ABORT_DEADBAND_MIN 2 -#define SETTING_NAV_FW_LAUNCH_ABORT_DEADBAND_MAX 250 -#define SETTING_NAV_FW_CRUISE_YAW_RATE_DEFAULT 20 -#define SETTING_NAV_FW_CRUISE_YAW_RATE 401 -#define SETTING_NAV_FW_CRUISE_YAW_RATE_MIN 0 -#define SETTING_NAV_FW_CRUISE_YAW_RATE_MAX 60 -#define SETTING_NAV_FW_ALLOW_MANUAL_THR_INCREASE_DEFAULT 0 -#define SETTING_NAV_FW_ALLOW_MANUAL_THR_INCREASE 402 -#define SETTING_NAV_FW_ALLOW_MANUAL_THR_INCREASE_MIN 0 -#define SETTING_NAV_FW_ALLOW_MANUAL_THR_INCREASE_MAX 0 -#define SETTING_NAV_USE_FW_YAW_CONTROL_DEFAULT 0 -#define SETTING_NAV_USE_FW_YAW_CONTROL 403 -#define SETTING_NAV_USE_FW_YAW_CONTROL_MIN 0 -#define SETTING_NAV_USE_FW_YAW_CONTROL_MAX 0 -#define SETTING_NAV_FW_YAW_DEADBAND_DEFAULT 0 -#define SETTING_NAV_FW_YAW_DEADBAND 404 -#define SETTING_NAV_FW_YAW_DEADBAND_MIN 0 -#define SETTING_NAV_FW_YAW_DEADBAND_MAX 90 -#define SETTING_OSD_TELEMETRY_DEFAULT 0 -#define SETTING_OSD_TELEMETRY 405 -#define SETTING_OSD_TELEMETRY_MIN 0 -#define SETTING_OSD_TELEMETRY_MAX 0 -#define SETTING_OSD_VIDEO_SYSTEM_DEFAULT 0 -#define SETTING_OSD_VIDEO_SYSTEM 406 -#define SETTING_OSD_VIDEO_SYSTEM_MIN 0 -#define SETTING_OSD_VIDEO_SYSTEM_MAX 0 -#define SETTING_OSD_ROW_SHIFTDOWN_DEFAULT 0 -#define SETTING_OSD_ROW_SHIFTDOWN 407 -#define SETTING_OSD_ROW_SHIFTDOWN_MIN 0 -#define SETTING_OSD_ROW_SHIFTDOWN_MAX 1 -#define SETTING_OSD_UNITS_DEFAULT 1 -#define SETTING_OSD_UNITS 408 -#define SETTING_OSD_UNITS_MIN 0 -#define SETTING_OSD_UNITS_MAX 0 -#define SETTING_OSD_STATS_ENERGY_UNIT_DEFAULT 0 -#define SETTING_OSD_STATS_ENERGY_UNIT 409 -#define SETTING_OSD_STATS_ENERGY_UNIT_MIN 0 -#define SETTING_OSD_STATS_ENERGY_UNIT_MAX 0 -#define SETTING_OSD_STATS_MIN_VOLTAGE_UNIT_DEFAULT 0 -#define SETTING_OSD_STATS_MIN_VOLTAGE_UNIT 410 -#define SETTING_OSD_STATS_MIN_VOLTAGE_UNIT_MIN 0 -#define SETTING_OSD_STATS_MIN_VOLTAGE_UNIT_MAX 0 -#define SETTING_OSD_STATS_PAGE_AUTO_SWAP_TIME_DEFAULT 3 -#define SETTING_OSD_STATS_PAGE_AUTO_SWAP_TIME 411 -#define SETTING_OSD_STATS_PAGE_AUTO_SWAP_TIME_MIN 0 -#define SETTING_OSD_STATS_PAGE_AUTO_SWAP_TIME_MAX 10 -#define SETTING_OSD_RSSI_ALARM_DEFAULT 20 -#define SETTING_OSD_RSSI_ALARM 412 -#define SETTING_OSD_RSSI_ALARM_MIN 0 -#define SETTING_OSD_RSSI_ALARM_MAX 100 -#define SETTING_OSD_TIME_ALARM_DEFAULT 10 -#define SETTING_OSD_TIME_ALARM 413 -#define SETTING_OSD_TIME_ALARM_MIN 0 -#define SETTING_OSD_TIME_ALARM_MAX 600 -#define SETTING_OSD_ALT_ALARM_DEFAULT 100 -#define SETTING_OSD_ALT_ALARM 414 -#define SETTING_OSD_ALT_ALARM_MIN 0 -#define SETTING_OSD_ALT_ALARM_MAX 10000 -#define SETTING_OSD_DIST_ALARM_DEFAULT 1000 -#define SETTING_OSD_DIST_ALARM 415 -#define SETTING_OSD_DIST_ALARM_MIN 0 -#define SETTING_OSD_DIST_ALARM_MAX 50000 -#define SETTING_OSD_NEG_ALT_ALARM_DEFAULT 5 -#define SETTING_OSD_NEG_ALT_ALARM 416 -#define SETTING_OSD_NEG_ALT_ALARM_MIN 0 -#define SETTING_OSD_NEG_ALT_ALARM_MAX 10000 -#define SETTING_OSD_CURRENT_ALARM_DEFAULT 0 -#define SETTING_OSD_CURRENT_ALARM 417 -#define SETTING_OSD_CURRENT_ALARM_MIN 0 -#define SETTING_OSD_CURRENT_ALARM_MAX 255 -#define SETTING_OSD_GFORCE_ALARM_DEFAULT 5 -#define SETTING_OSD_GFORCE_ALARM 418 -#define SETTING_OSD_GFORCE_ALARM_MIN 0 -#define SETTING_OSD_GFORCE_ALARM_MAX 20 -#define SETTING_OSD_GFORCE_AXIS_ALARM_MIN_DEFAULT -5 -#define SETTING_OSD_GFORCE_AXIS_ALARM_MIN 419 -#define SETTING_OSD_GFORCE_AXIS_ALARM_MIN_MIN -20 -#define SETTING_OSD_GFORCE_AXIS_ALARM_MIN_MAX 20 -#define SETTING_OSD_GFORCE_AXIS_ALARM_MAX_DEFAULT 5 -#define SETTING_OSD_GFORCE_AXIS_ALARM_MAX 420 -#define SETTING_OSD_GFORCE_AXIS_ALARM_MAX_MIN -20 -#define SETTING_OSD_GFORCE_AXIS_ALARM_MAX_MAX 20 -#define SETTING_OSD_IMU_TEMP_ALARM_MIN_DEFAULT -200 -#define SETTING_OSD_IMU_TEMP_ALARM_MIN 421 -#define SETTING_OSD_IMU_TEMP_ALARM_MIN_MIN -550 -#define SETTING_OSD_IMU_TEMP_ALARM_MIN_MAX 1250 -#define SETTING_OSD_IMU_TEMP_ALARM_MAX_DEFAULT 600 -#define SETTING_OSD_IMU_TEMP_ALARM_MAX 422 -#define SETTING_OSD_IMU_TEMP_ALARM_MAX_MIN -550 -#define SETTING_OSD_IMU_TEMP_ALARM_MAX_MAX 1250 -#define SETTING_OSD_ESC_TEMP_ALARM_MAX_DEFAULT 900 -#define SETTING_OSD_ESC_TEMP_ALARM_MAX 423 -#define SETTING_OSD_ESC_TEMP_ALARM_MAX_MIN -550 -#define SETTING_OSD_ESC_TEMP_ALARM_MAX_MAX 1500 -#define SETTING_OSD_ESC_TEMP_ALARM_MIN_DEFAULT -200 -#define SETTING_OSD_ESC_TEMP_ALARM_MIN 424 -#define SETTING_OSD_ESC_TEMP_ALARM_MIN_MIN -550 -#define SETTING_OSD_ESC_TEMP_ALARM_MIN_MAX 1500 -#define SETTING_OSD_BARO_TEMP_ALARM_MIN_DEFAULT -200 -#define SETTING_OSD_BARO_TEMP_ALARM_MIN 425 -#define SETTING_OSD_BARO_TEMP_ALARM_MIN_MIN -550 -#define SETTING_OSD_BARO_TEMP_ALARM_MIN_MAX 1250 -#define SETTING_OSD_BARO_TEMP_ALARM_MAX_DEFAULT 600 -#define SETTING_OSD_BARO_TEMP_ALARM_MAX 426 -#define SETTING_OSD_BARO_TEMP_ALARM_MAX_MIN -550 -#define SETTING_OSD_BARO_TEMP_ALARM_MAX_MAX 1250 -#define SETTING_OSD_SNR_ALARM_DEFAULT 4 -#define SETTING_OSD_SNR_ALARM 427 -#define SETTING_OSD_SNR_ALARM_MIN -20 -#define SETTING_OSD_SNR_ALARM_MAX 10 -#define SETTING_OSD_LINK_QUALITY_ALARM_DEFAULT 70 -#define SETTING_OSD_LINK_QUALITY_ALARM 428 -#define SETTING_OSD_LINK_QUALITY_ALARM_MIN 0 -#define SETTING_OSD_LINK_QUALITY_ALARM_MAX 100 -#define SETTING_OSD_RSSI_DBM_ALARM_DEFAULT 0 -#define SETTING_OSD_RSSI_DBM_ALARM 429 -#define SETTING_OSD_RSSI_DBM_ALARM_MIN -130 -#define SETTING_OSD_RSSI_DBM_ALARM_MAX 0 -#define SETTING_OSD_RSSI_DBM_MAX_DEFAULT -30 -#define SETTING_OSD_RSSI_DBM_MAX 430 -#define SETTING_OSD_RSSI_DBM_MAX_MIN -50 -#define SETTING_OSD_RSSI_DBM_MAX_MAX 0 -#define SETTING_OSD_RSSI_DBM_MIN_DEFAULT -120 -#define SETTING_OSD_RSSI_DBM_MIN 431 -#define SETTING_OSD_RSSI_DBM_MIN_MIN -130 -#define SETTING_OSD_RSSI_DBM_MIN_MAX 0 -#define SETTING_OSD_TEMP_LABEL_ALIGN_DEFAULT 0 -#define SETTING_OSD_TEMP_LABEL_ALIGN 432 -#define SETTING_OSD_TEMP_LABEL_ALIGN_MIN 0 -#define SETTING_OSD_TEMP_LABEL_ALIGN_MAX 0 -#define SETTING_OSD_AIRSPEED_ALARM_MIN_DEFAULT 0 -#define SETTING_OSD_AIRSPEED_ALARM_MIN 433 -#define SETTING_OSD_AIRSPEED_ALARM_MIN_MIN 0 -#define SETTING_OSD_AIRSPEED_ALARM_MIN_MAX 27000 -#define SETTING_OSD_AIRSPEED_ALARM_MAX_DEFAULT 0 -#define SETTING_OSD_AIRSPEED_ALARM_MAX 434 -#define SETTING_OSD_AIRSPEED_ALARM_MAX_MIN 0 -#define SETTING_OSD_AIRSPEED_ALARM_MAX_MAX 27000 -#define SETTING_OSD_AHI_REVERSE_ROLL_DEFAULT 0 -#define SETTING_OSD_AHI_REVERSE_ROLL 435 -#define SETTING_OSD_AHI_REVERSE_ROLL_MIN 0 -#define SETTING_OSD_AHI_REVERSE_ROLL_MAX 0 -#define SETTING_OSD_AHI_MAX_PITCH_DEFAULT 20 -#define SETTING_OSD_AHI_MAX_PITCH 436 -#define SETTING_OSD_AHI_MAX_PITCH_MIN 10 -#define SETTING_OSD_AHI_MAX_PITCH_MAX 90 -#define SETTING_OSD_CROSSHAIRS_STYLE_DEFAULT 0 -#define SETTING_OSD_CROSSHAIRS_STYLE 437 -#define SETTING_OSD_CROSSHAIRS_STYLE_MIN 0 -#define SETTING_OSD_CROSSHAIRS_STYLE_MAX 0 -#define SETTING_OSD_CRSF_LQ_FORMAT_DEFAULT 0 -#define SETTING_OSD_CRSF_LQ_FORMAT 438 -#define SETTING_OSD_CRSF_LQ_FORMAT_MIN 0 -#define SETTING_OSD_CRSF_LQ_FORMAT_MAX 0 -#define SETTING_OSD_HORIZON_OFFSET_DEFAULT 0 -#define SETTING_OSD_HORIZON_OFFSET 439 -#define SETTING_OSD_HORIZON_OFFSET_MIN -2 -#define SETTING_OSD_HORIZON_OFFSET_MAX 2 -#define SETTING_OSD_CAMERA_UPTILT_DEFAULT 0 -#define SETTING_OSD_CAMERA_UPTILT 440 -#define SETTING_OSD_CAMERA_UPTILT_MIN -40 -#define SETTING_OSD_CAMERA_UPTILT_MAX 80 -#define SETTING_OSD_AHI_CAMERA_UPTILT_COMP_DEFAULT 0 -#define SETTING_OSD_AHI_CAMERA_UPTILT_COMP 441 -#define SETTING_OSD_AHI_CAMERA_UPTILT_COMP_MIN 0 -#define SETTING_OSD_AHI_CAMERA_UPTILT_COMP_MAX 0 -#define SETTING_OSD_CAMERA_FOV_H_DEFAULT 135 -#define SETTING_OSD_CAMERA_FOV_H 442 -#define SETTING_OSD_CAMERA_FOV_H_MIN 60 -#define SETTING_OSD_CAMERA_FOV_H_MAX 150 -#define SETTING_OSD_CAMERA_FOV_V_DEFAULT 85 -#define SETTING_OSD_CAMERA_FOV_V 443 -#define SETTING_OSD_CAMERA_FOV_V_MIN 30 -#define SETTING_OSD_CAMERA_FOV_V_MAX 120 -#define SETTING_OSD_HUD_MARGIN_H_DEFAULT 3 -#define SETTING_OSD_HUD_MARGIN_H 444 -#define SETTING_OSD_HUD_MARGIN_H_MIN 0 -#define SETTING_OSD_HUD_MARGIN_H_MAX 4 -#define SETTING_OSD_HUD_MARGIN_V_DEFAULT 3 -#define SETTING_OSD_HUD_MARGIN_V 445 -#define SETTING_OSD_HUD_MARGIN_V_MIN 1 -#define SETTING_OSD_HUD_MARGIN_V_MAX 3 -#define SETTING_OSD_HUD_HOMING_DEFAULT 0 -#define SETTING_OSD_HUD_HOMING 446 -#define SETTING_OSD_HUD_HOMING_MIN 0 -#define SETTING_OSD_HUD_HOMING_MAX 0 -#define SETTING_OSD_HUD_HOMEPOINT_DEFAULT 0 -#define SETTING_OSD_HUD_HOMEPOINT 447 -#define SETTING_OSD_HUD_HOMEPOINT_MIN 0 -#define SETTING_OSD_HUD_HOMEPOINT_MAX 0 -#define SETTING_OSD_HUD_RADAR_DISP_DEFAULT 0 -#define SETTING_OSD_HUD_RADAR_DISP 448 -#define SETTING_OSD_HUD_RADAR_DISP_MIN 0 -#define SETTING_OSD_HUD_RADAR_DISP_MAX 4 -#define SETTING_OSD_HUD_RADAR_RANGE_MIN_DEFAULT 3 -#define SETTING_OSD_HUD_RADAR_RANGE_MIN 449 -#define SETTING_OSD_HUD_RADAR_RANGE_MIN_MIN 1 -#define SETTING_OSD_HUD_RADAR_RANGE_MIN_MAX 30 -#define SETTING_OSD_HUD_RADAR_RANGE_MAX_DEFAULT 4000 -#define SETTING_OSD_HUD_RADAR_RANGE_MAX 450 -#define SETTING_OSD_HUD_RADAR_RANGE_MAX_MIN 100 -#define SETTING_OSD_HUD_RADAR_RANGE_MAX_MAX 9990 -#define SETTING_OSD_HUD_RADAR_ALT_DIFFERENCE_DISPLAY_TIME_DEFAULT 3 -#define SETTING_OSD_HUD_RADAR_ALT_DIFFERENCE_DISPLAY_TIME 451 -#define SETTING_OSD_HUD_RADAR_ALT_DIFFERENCE_DISPLAY_TIME_MIN 0 -#define SETTING_OSD_HUD_RADAR_ALT_DIFFERENCE_DISPLAY_TIME_MAX 10 -#define SETTING_OSD_HUD_RADAR_DISTANCE_DISPLAY_TIME_DEFAULT 3 -#define SETTING_OSD_HUD_RADAR_DISTANCE_DISPLAY_TIME 452 -#define SETTING_OSD_HUD_RADAR_DISTANCE_DISPLAY_TIME_MIN 1 -#define SETTING_OSD_HUD_RADAR_DISTANCE_DISPLAY_TIME_MAX 10 -#define SETTING_OSD_HUD_WP_DISP_DEFAULT 0 -#define SETTING_OSD_HUD_WP_DISP 453 -#define SETTING_OSD_HUD_WP_DISP_MIN 0 -#define SETTING_OSD_HUD_WP_DISP_MAX 3 -#define SETTING_OSD_LEFT_SIDEBAR_SCROLL_DEFAULT 0 -#define SETTING_OSD_LEFT_SIDEBAR_SCROLL 454 -#define SETTING_OSD_LEFT_SIDEBAR_SCROLL_MIN 0 -#define SETTING_OSD_LEFT_SIDEBAR_SCROLL_MAX 0 -#define SETTING_OSD_RIGHT_SIDEBAR_SCROLL_DEFAULT 0 -#define SETTING_OSD_RIGHT_SIDEBAR_SCROLL 455 -#define SETTING_OSD_RIGHT_SIDEBAR_SCROLL_MIN 0 -#define SETTING_OSD_RIGHT_SIDEBAR_SCROLL_MAX 0 -#define SETTING_OSD_SIDEBAR_SCROLL_ARROWS_DEFAULT 0 -#define SETTING_OSD_SIDEBAR_SCROLL_ARROWS 456 -#define SETTING_OSD_SIDEBAR_SCROLL_ARROWS_MIN 0 -#define SETTING_OSD_SIDEBAR_SCROLL_ARROWS_MAX 0 -#define SETTING_OSD_MAIN_VOLTAGE_DECIMALS_DEFAULT 1 -#define SETTING_OSD_MAIN_VOLTAGE_DECIMALS 457 -#define SETTING_OSD_MAIN_VOLTAGE_DECIMALS_MIN 1 -#define SETTING_OSD_MAIN_VOLTAGE_DECIMALS_MAX 2 -#define SETTING_OSD_COORDINATE_DIGITS_DEFAULT 9 -#define SETTING_OSD_COORDINATE_DIGITS 458 -#define SETTING_OSD_COORDINATE_DIGITS_MIN 8 -#define SETTING_OSD_COORDINATE_DIGITS_MAX 11 -#define SETTING_OSD_ESTIMATIONS_WIND_COMPENSATION_DEFAULT 1 -#define SETTING_OSD_ESTIMATIONS_WIND_COMPENSATION 459 -#define SETTING_OSD_ESTIMATIONS_WIND_COMPENSATION_MIN 0 -#define SETTING_OSD_ESTIMATIONS_WIND_COMPENSATION_MAX 0 -#define SETTING_OSD_FAILSAFE_SWITCH_LAYOUT_DEFAULT 0 -#define SETTING_OSD_FAILSAFE_SWITCH_LAYOUT 460 -#define SETTING_OSD_FAILSAFE_SWITCH_LAYOUT_MIN 0 -#define SETTING_OSD_FAILSAFE_SWITCH_LAYOUT_MAX 0 -#define SETTING_OSD_PLUS_CODE_DIGITS_DEFAULT 11 -#define SETTING_OSD_PLUS_CODE_DIGITS 461 -#define SETTING_OSD_PLUS_CODE_DIGITS_MIN 10 -#define SETTING_OSD_PLUS_CODE_DIGITS_MAX 13 -#define SETTING_OSD_PLUS_CODE_SHORT_DEFAULT 0 -#define SETTING_OSD_PLUS_CODE_SHORT 462 -#define SETTING_OSD_PLUS_CODE_SHORT_MIN 0 -#define SETTING_OSD_PLUS_CODE_SHORT_MAX 0 -#define SETTING_OSD_AHI_STYLE_DEFAULT 0 -#define SETTING_OSD_AHI_STYLE 463 -#define SETTING_OSD_AHI_STYLE_MIN 0 -#define SETTING_OSD_AHI_STYLE_MAX 0 -#define SETTING_OSD_FORCE_GRID_DEFAULT 0 -#define SETTING_OSD_FORCE_GRID 464 -#define SETTING_OSD_FORCE_GRID_MIN 0 -#define SETTING_OSD_FORCE_GRID_MAX 0 -#define SETTING_OSD_AHI_BORDERED_DEFAULT 0 -#define SETTING_OSD_AHI_BORDERED 465 -#define SETTING_OSD_AHI_BORDERED_MIN 0 -#define SETTING_OSD_AHI_BORDERED_MAX 0 -#define SETTING_OSD_AHI_WIDTH_DEFAULT 132 -#define SETTING_OSD_AHI_WIDTH 466 -#define SETTING_OSD_AHI_WIDTH_MIN 0 -#define SETTING_OSD_AHI_WIDTH_MAX 255 -#define SETTING_OSD_AHI_HEIGHT_DEFAULT 162 -#define SETTING_OSD_AHI_HEIGHT 467 -#define SETTING_OSD_AHI_HEIGHT_MIN 0 -#define SETTING_OSD_AHI_HEIGHT_MAX 255 -#define SETTING_OSD_AHI_VERTICAL_OFFSET_DEFAULT -18 -#define SETTING_OSD_AHI_VERTICAL_OFFSET 468 -#define SETTING_OSD_AHI_VERTICAL_OFFSET_MIN -128 -#define SETTING_OSD_AHI_VERTICAL_OFFSET_MAX 127 -#define SETTING_OSD_SIDEBAR_HORIZONTAL_OFFSET_DEFAULT 0 -#define SETTING_OSD_SIDEBAR_HORIZONTAL_OFFSET 469 -#define SETTING_OSD_SIDEBAR_HORIZONTAL_OFFSET_MIN -128 -#define SETTING_OSD_SIDEBAR_HORIZONTAL_OFFSET_MAX 127 -#define SETTING_OSD_LEFT_SIDEBAR_SCROLL_STEP_DEFAULT 0 -#define SETTING_OSD_LEFT_SIDEBAR_SCROLL_STEP 470 -#define SETTING_OSD_LEFT_SIDEBAR_SCROLL_STEP_MIN 0 -#define SETTING_OSD_LEFT_SIDEBAR_SCROLL_STEP_MAX 255 -#define SETTING_OSD_RIGHT_SIDEBAR_SCROLL_STEP_DEFAULT 0 -#define SETTING_OSD_RIGHT_SIDEBAR_SCROLL_STEP 471 -#define SETTING_OSD_RIGHT_SIDEBAR_SCROLL_STEP_MIN 0 -#define SETTING_OSD_RIGHT_SIDEBAR_SCROLL_STEP_MAX 255 -#define SETTING_OSD_SIDEBAR_HEIGHT_DEFAULT 3 -#define SETTING_OSD_SIDEBAR_HEIGHT 472 -#define SETTING_OSD_SIDEBAR_HEIGHT_MIN 0 -#define SETTING_OSD_SIDEBAR_HEIGHT_MAX 5 -#define SETTING_OSD_AHI_PITCH_INTERVAL_DEFAULT 0 -#define SETTING_OSD_AHI_PITCH_INTERVAL 473 -#define SETTING_OSD_AHI_PITCH_INTERVAL_MIN 0 -#define SETTING_OSD_AHI_PITCH_INTERVAL_MAX 30 -#define SETTING_OSD_HOME_POSITION_ARM_SCREEN_DEFAULT 1 -#define SETTING_OSD_HOME_POSITION_ARM_SCREEN 474 -#define SETTING_OSD_HOME_POSITION_ARM_SCREEN_MIN 0 -#define SETTING_OSD_HOME_POSITION_ARM_SCREEN_MAX 0 -#define SETTING_OSD_PAN_SERVO_INDEX_DEFAULT 0 -#define SETTING_OSD_PAN_SERVO_INDEX 475 -#define SETTING_OSD_PAN_SERVO_INDEX_MIN 0 -#define SETTING_OSD_PAN_SERVO_INDEX_MAX 10 -#define SETTING_OSD_PAN_SERVO_PWM2CENTIDEG_DEFAULT 0 -#define SETTING_OSD_PAN_SERVO_PWM2CENTIDEG 476 -#define SETTING_OSD_PAN_SERVO_PWM2CENTIDEG_MIN -36 -#define SETTING_OSD_PAN_SERVO_PWM2CENTIDEG_MAX 36 -#define SETTING_OSD_ESC_RPM_PRECISION_DEFAULT 3 -#define SETTING_OSD_ESC_RPM_PRECISION 477 -#define SETTING_OSD_ESC_RPM_PRECISION_MIN 3 -#define SETTING_OSD_ESC_RPM_PRECISION_MAX 6 -#define SETTING_OSD_MAH_USED_PRECISION_DEFAULT 4 -#define SETTING_OSD_MAH_USED_PRECISION 478 -#define SETTING_OSD_MAH_USED_PRECISION_MIN 4 -#define SETTING_OSD_MAH_USED_PRECISION_MAX 6 -#define SETTING_OSD_SWITCH_INDICATOR_ZERO_NAME_DEFAULT { 70, 76, 65, 80, 0 } -#define SETTING_OSD_SWITCH_INDICATOR_ZERO_NAME 479 -#define SETTING_OSD_SWITCH_INDICATOR_ZERO_NAME_MIN 0 -#define SETTING_OSD_SWITCH_INDICATOR_ZERO_NAME_MAX 5 -#define SETTING_OSD_SWITCH_INDICATOR_ONE_NAME_DEFAULT { 71, 69, 65, 82, 0 } -#define SETTING_OSD_SWITCH_INDICATOR_ONE_NAME 480 -#define SETTING_OSD_SWITCH_INDICATOR_ONE_NAME_MIN 0 -#define SETTING_OSD_SWITCH_INDICATOR_ONE_NAME_MAX 5 -#define SETTING_OSD_SWITCH_INDICATOR_TWO_NAME_DEFAULT { 67, 65, 77, 0 } -#define SETTING_OSD_SWITCH_INDICATOR_TWO_NAME 481 -#define SETTING_OSD_SWITCH_INDICATOR_TWO_NAME_MIN 0 -#define SETTING_OSD_SWITCH_INDICATOR_TWO_NAME_MAX 5 -#define SETTING_OSD_SWITCH_INDICATOR_THREE_NAME_DEFAULT { 76, 73, 71, 84, 0 } -#define SETTING_OSD_SWITCH_INDICATOR_THREE_NAME 482 -#define SETTING_OSD_SWITCH_INDICATOR_THREE_NAME_MIN 0 -#define SETTING_OSD_SWITCH_INDICATOR_THREE_NAME_MAX 5 -#define SETTING_OSD_SWITCH_INDICATOR_ZERO_CHANNEL_DEFAULT 5 -#define SETTING_OSD_SWITCH_INDICATOR_ZERO_CHANNEL 483 -#define SETTING_OSD_SWITCH_INDICATOR_ZERO_CHANNEL_MIN 5 -#define SETTING_OSD_SWITCH_INDICATOR_ZERO_CHANNEL_MAX 18 -#define SETTING_OSD_SWITCH_INDICATOR_ONE_CHANNEL_DEFAULT 5 -#define SETTING_OSD_SWITCH_INDICATOR_ONE_CHANNEL 484 -#define SETTING_OSD_SWITCH_INDICATOR_ONE_CHANNEL_MIN 5 -#define SETTING_OSD_SWITCH_INDICATOR_ONE_CHANNEL_MAX 18 -#define SETTING_OSD_SWITCH_INDICATOR_TWO_CHANNEL_DEFAULT 5 -#define SETTING_OSD_SWITCH_INDICATOR_TWO_CHANNEL 485 -#define SETTING_OSD_SWITCH_INDICATOR_TWO_CHANNEL_MIN 5 -#define SETTING_OSD_SWITCH_INDICATOR_TWO_CHANNEL_MAX 18 -#define SETTING_OSD_SWITCH_INDICATOR_THREE_CHANNEL_DEFAULT 5 -#define SETTING_OSD_SWITCH_INDICATOR_THREE_CHANNEL 486 -#define SETTING_OSD_SWITCH_INDICATOR_THREE_CHANNEL_MIN 5 -#define SETTING_OSD_SWITCH_INDICATOR_THREE_CHANNEL_MAX 18 -#define SETTING_OSD_SWITCH_INDICATORS_ALIGN_LEFT_DEFAULT 1 -#define SETTING_OSD_SWITCH_INDICATORS_ALIGN_LEFT 487 -#define SETTING_OSD_SWITCH_INDICATORS_ALIGN_LEFT_MIN 0 -#define SETTING_OSD_SWITCH_INDICATORS_ALIGN_LEFT_MAX 0 -#define SETTING_OSD_SYSTEM_MSG_DISPLAY_TIME_DEFAULT 1000 -#define SETTING_OSD_SYSTEM_MSG_DISPLAY_TIME 488 -#define SETTING_OSD_SYSTEM_MSG_DISPLAY_TIME_MIN 500 -#define SETTING_OSD_SYSTEM_MSG_DISPLAY_TIME_MAX 5000 -#define SETTING_OSD_SPEED_SOURCE_DEFAULT 0 -#define SETTING_OSD_SPEED_SOURCE 489 -#define SETTING_OSD_SPEED_SOURCE_MIN 0 -#define SETTING_OSD_SPEED_SOURCE_MAX 0 -#define SETTING_DEBUG_MODE_DEFAULT 0 -#define SETTING_DEBUG_MODE 490 -#define SETTING_DEBUG_MODE_MIN 0 -#define SETTING_DEBUG_MODE_MAX 0 -#define SETTING_THROTTLE_TILT_COMP_STR_DEFAULT 0 -#define SETTING_THROTTLE_TILT_COMP_STR 491 -#define SETTING_THROTTLE_TILT_COMP_STR_MIN 0 -#define SETTING_THROTTLE_TILT_COMP_STR_MAX 100 -#define SETTING_NAME_DEFAULT { 0 } -#define SETTING_NAME 492 -#define SETTING_NAME_MIN 0 -#define SETTING_NAME_MAX 16 -#define SETTING_MODE_RANGE_LOGIC_OPERATOR_DEFAULT 0 -#define SETTING_MODE_RANGE_LOGIC_OPERATOR 493 -#define SETTING_MODE_RANGE_LOGIC_OPERATOR_MIN 0 -#define SETTING_MODE_RANGE_LOGIC_OPERATOR_MAX 0 -#define SETTING_STATS_DEFAULT 0 -#define SETTING_STATS 494 -#define SETTING_STATS_MIN 0 -#define SETTING_STATS_MAX 0 -#define SETTING_STATS_TOTAL_TIME_DEFAULT 0 -#define SETTING_STATS_TOTAL_TIME 495 -#define SETTING_STATS_TOTAL_TIME_MIN 0 -#define SETTING_STATS_TOTAL_TIME_MAX 2147483647 -#define SETTING_STATS_TOTAL_DIST_DEFAULT 0 -#define SETTING_STATS_TOTAL_DIST 496 -#define SETTING_STATS_TOTAL_DIST_MIN 0 -#define SETTING_STATS_TOTAL_DIST_MAX 2147483647 -#define SETTING_STATS_TOTAL_ENERGY_DEFAULT 0 -#define SETTING_STATS_TOTAL_ENERGY 497 -#define SETTING_STATS_TOTAL_ENERGY_MIN 0 -#define SETTING_STATS_TOTAL_ENERGY_MAX 2147483647 -#define SETTING_TZ_OFFSET_DEFAULT 0 -#define SETTING_TZ_OFFSET 498 -#define SETTING_TZ_OFFSET_MIN -1440 -#define SETTING_TZ_OFFSET_MAX 1440 -#define SETTING_TZ_AUTOMATIC_DST_DEFAULT 0 -#define SETTING_TZ_AUTOMATIC_DST 499 -#define SETTING_TZ_AUTOMATIC_DST_MIN 0 -#define SETTING_TZ_AUTOMATIC_DST_MAX 0 -#define SETTING_DISPLAY_FORCE_SW_BLINK_DEFAULT 0 -#define SETTING_DISPLAY_FORCE_SW_BLINK 500 -#define SETTING_DISPLAY_FORCE_SW_BLINK_MIN 0 -#define SETTING_DISPLAY_FORCE_SW_BLINK_MAX 0 -#define SETTING_LOG_LEVEL_DEFAULT 0 -#define SETTING_LOG_LEVEL 501 -#define SETTING_LOG_LEVEL_MIN 0 -#define SETTING_LOG_LEVEL_MAX 0 -#define SETTING_LOG_TOPICS_DEFAULT 0 -#define SETTING_LOG_TOPICS 502 -#define SETTING_LOG_TOPICS_MIN 0 -#define SETTING_LOG_TOPICS_MAX 4294967295 -#define SETTING_SMARTPORT_MASTER_HALFDUPLEX_DEFAULT 1 -#define SETTING_SMARTPORT_MASTER_HALFDUPLEX 503 -#define SETTING_SMARTPORT_MASTER_HALFDUPLEX_MIN 0 -#define SETTING_SMARTPORT_MASTER_HALFDUPLEX_MAX 0 -#define SETTING_SMARTPORT_MASTER_INVERTED_DEFAULT 0 -#define SETTING_SMARTPORT_MASTER_INVERTED 504 -#define SETTING_SMARTPORT_MASTER_INVERTED_MIN 0 -#define SETTING_SMARTPORT_MASTER_INVERTED_MAX 0 -#define SETTING_DJI_WORKAROUNDS_DEFAULT 1 -#define SETTING_DJI_WORKAROUNDS 505 -#define SETTING_DJI_WORKAROUNDS_MIN 0 -#define SETTING_DJI_WORKAROUNDS_MAX 255 -#define SETTING_DJI_USE_NAME_FOR_MESSAGES_DEFAULT 1 -#define SETTING_DJI_USE_NAME_FOR_MESSAGES 506 -#define SETTING_DJI_USE_NAME_FOR_MESSAGES_MIN 0 -#define SETTING_DJI_USE_NAME_FOR_MESSAGES_MAX 0 -#define SETTING_DJI_ESC_TEMP_SOURCE_DEFAULT 0 -#define SETTING_DJI_ESC_TEMP_SOURCE 507 -#define SETTING_DJI_ESC_TEMP_SOURCE_MIN 0 -#define SETTING_DJI_ESC_TEMP_SOURCE_MAX 0 -#define SETTING_DJI_MESSAGE_SPEED_SOURCE_DEFAULT 1 -#define SETTING_DJI_MESSAGE_SPEED_SOURCE 508 -#define SETTING_DJI_MESSAGE_SPEED_SOURCE_MIN 0 -#define SETTING_DJI_MESSAGE_SPEED_SOURCE_MAX 0 -#define SETTING_DJI_RSSI_SOURCE_DEFAULT 0 -#define SETTING_DJI_RSSI_SOURCE 509 -#define SETTING_DJI_RSSI_SOURCE_MIN 0 -#define SETTING_DJI_RSSI_SOURCE_MAX 0 -#define SETTING_DJI_USE_ADJUSTMENTS_DEFAULT 0 -#define SETTING_DJI_USE_ADJUSTMENTS 510 -#define SETTING_DJI_USE_ADJUSTMENTS_MIN 0 -#define SETTING_DJI_USE_ADJUSTMENTS_MAX 0 -#define SETTING_DJI_CN_ALTERNATING_DURATION_DEFAULT 30 -#define SETTING_DJI_CN_ALTERNATING_DURATION 511 -#define SETTING_DJI_CN_ALTERNATING_DURATION_MIN 1 -#define SETTING_DJI_CN_ALTERNATING_DURATION_MAX 150 -#define SETTING_DSHOT_BEEPER_ENABLED_DEFAULT 1 -#define SETTING_DSHOT_BEEPER_ENABLED 512 -#define SETTING_DSHOT_BEEPER_ENABLED_MIN 0 -#define SETTING_DSHOT_BEEPER_ENABLED_MAX 0 -#define SETTING_DSHOT_BEEPER_TONE_DEFAULT 1 -#define SETTING_DSHOT_BEEPER_TONE 513 -#define SETTING_DSHOT_BEEPER_TONE_MIN 1 -#define SETTING_DSHOT_BEEPER_TONE_MAX 5 -#define SETTING_BEEPER_PWM_MODE_DEFAULT 0 -#define SETTING_BEEPER_PWM_MODE 514 -#define SETTING_BEEPER_PWM_MODE_MIN 0 -#define SETTING_BEEPER_PWM_MODE_MAX 0 -#define SETTING_LIMIT_PI_P_DEFAULT 100 -#define SETTING_LIMIT_PI_P 515 -#define SETTING_LIMIT_PI_P_MIN 0 -#define SETTING_LIMIT_PI_P_MAX 10000 -#define SETTING_LIMIT_PI_I_DEFAULT 100 -#define SETTING_LIMIT_PI_I 516 -#define SETTING_LIMIT_PI_I_MIN 0 -#define SETTING_LIMIT_PI_I_MAX 10000 -#define SETTING_LIMIT_ATTN_FILTER_CUTOFF_DEFAULT 1.2f -#define SETTING_LIMIT_ATTN_FILTER_CUTOFF 517 -#define SETTING_LIMIT_ATTN_FILTER_CUTOFF_MIN 0 -#define SETTING_LIMIT_ATTN_FILTER_CUTOFF_MAX 100 From 1af0e6116b4f88c96e214feb0ed3b4e1ac1fce28 Mon Sep 17 00:00:00 2001 From: Scavanger Date: Tue, 24 Jan 2023 23:14:11 -0300 Subject: [PATCH 013/130] Fix tests --- CMakeLists.txt | 5 ----- cmake/settings.cmake | 5 +++++ 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 6e6a6462f9..4ce4d50b9b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -59,11 +59,6 @@ set(CMAKE_CXX_STANDARD 11) set(CMAKE_CXX_EXTENSIONS ON) set(CMAKE_CXX_STANDARD_REQUIRED ON) -find_program(RUBY_EXECUTABLE ruby) -if (NOT RUBY_EXECUTABLE) - message(FATAL_ERROR "Could not find ruby") -endif() - if(CMAKE_BUILD_TYPE STREQUAL "Release" OR CMAKE_BUILD_TYPE STREQUAL "RelWithDebInfo") set(IS_RELEASE_BUILD ON) endif() diff --git a/cmake/settings.cmake b/cmake/settings.cmake index ba83773704..979b5e1722 100644 --- a/cmake/settings.cmake +++ b/cmake/settings.cmake @@ -29,6 +29,11 @@ function(enable_settings exe name) ${ARGN} ) + find_program(RUBY_EXECUTABLE ruby) + if (NOT RUBY_EXECUTABLE) + message(FATAL_ERROR "Could not find ruby") + endif() + if(host STREQUAL TOOLCHAIN) set(USE_HOST_GCC "-g") endif() From 0e796a7e103c9219439198257c9b936caf87a45e Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Fri, 15 Jul 2022 08:14:06 +0100 Subject: [PATCH 014/130] ESP32 Radar: Replace side arrows with cardinal indicator The 1-3 arrows that hang off the side of the ESP32 Radar POIs are not intuitive for finding your flying buddies. This PR replaces the 1-3 arrows with a compass style cardinal indicator. This will point in the direction of the other craft. It is displayed on the right of the POI, to be distinct from the relative heading arrow. --- src/main/drivers/osd_symbols.h | 6 ++-- src/main/io/osd_grid.c | 8 ++--- src/main/io/osd_hud.c | 63 +++++++++++++++++++++++++++------- 3 files changed, 58 insertions(+), 19 deletions(-) diff --git a/src/main/drivers/osd_symbols.h b/src/main/drivers/osd_symbols.h index adcb595ce2..e6167e25f2 100644 --- a/src/main/drivers/osd_symbols.h +++ b/src/main/drivers/osd_symbols.h @@ -44,8 +44,8 @@ #define SYM_DBM 0x13 // 019 dBm #define SYM_SNR 0x14 // 020 SNR -#define SYM_AH_DECORATION_UP 0x15 // 021 Arrow up AHI -#define SYM_AH_DECORATION_DOWN 0x16 // 022 Arrow down AHI +#define SYM_AH_DIRECTION_UP 0x15 // 021 Arrow up AHI +#define SYM_AH_DIRECTION_DOWN 0x16 // 022 Arrow down AHI #define SYM_DIRECTION 0x17 // 023 to 030, directional little arrows #define SYM_VOLT 0x1F // 031 VOLTS @@ -252,6 +252,8 @@ #define SYM_HUD_ARROWS_D2 0x1B8 // 440 2 arrows down #define SYM_HUD_ARROWS_D3 0x1B9 // 441 3 arrows down +#define SYM_HUD_CARDINAL 0x1BA // 442-453 Cardinal direction in 30 degree segments + #else #define TEMP_SENSOR_SYM_COUNT 0 diff --git a/src/main/io/osd_grid.c b/src/main/io/osd_grid.c index 9e79194498..5d7e8736d9 100644 --- a/src/main/io/osd_grid.c +++ b/src/main/io/osd_grid.c @@ -315,16 +315,16 @@ void osdGridDrawSidebars(displayPort_t *display) // Arrows if (osdConfig()->sidebar_scroll_arrows) { displayWriteChar(display, elemPosX - hudwidth, elemPosY - hudheight - 1, - left.arrow == OSD_SIDEBAR_ARROW_UP ? SYM_AH_DECORATION_UP : SYM_BLANK); + left.arrow == OSD_SIDEBAR_ARROW_UP ? SYM_AH_DIRECTION_UP : SYM_BLANK); displayWriteChar(display, elemPosX + hudwidth, elemPosY - hudheight - 1, - right.arrow == OSD_SIDEBAR_ARROW_UP ? SYM_AH_DECORATION_UP : SYM_BLANK); + right.arrow == OSD_SIDEBAR_ARROW_UP ? SYM_AH_DIRECTION_UP : SYM_BLANK); displayWriteChar(display, elemPosX - hudwidth, elemPosY + hudheight + 1, - left.arrow == OSD_SIDEBAR_ARROW_DOWN ? SYM_AH_DECORATION_DOWN : SYM_BLANK); + left.arrow == OSD_SIDEBAR_ARROW_DOWN ? SYM_AH_DIRECTION_DOWN : SYM_BLANK); displayWriteChar(display, elemPosX + hudwidth, elemPosY + hudheight + 1, - right.arrow == OSD_SIDEBAR_ARROW_DOWN ? SYM_AH_DECORATION_DOWN : SYM_BLANK); + right.arrow == OSD_SIDEBAR_ARROW_DOWN ? SYM_AH_DIRECTION_DOWN : SYM_BLANK); } // Draw AH sides diff --git a/src/main/io/osd_hud.c b/src/main/io/osd_hud.c index 7c900c7e6b..db16ee4239 100644 --- a/src/main/io/osd_hud.c +++ b/src/main/io/osd_hud.c @@ -117,7 +117,7 @@ int8_t radarGetNearestPOI(void) * Display a POI as a 3D-marker on the hud * Distance (m), Direction (°), Altitude (relative, m, negative means below), Heading (°), * Type = 0 : Home point - * Type = 1 : Radar POI, P1: Heading, P2: Signal + * Type = 1 : Radar POI, P1: Relative heading, P2: Signal, P3 Cardinal direction * Type = 2 : Waypoint, P1: WP number, P2: 1=WP+1, 2=WP+2, 3=WP+3 */ void osdHudDrawPoi(uint32_t poiDistance, int16_t poiDirection, int32_t poiAltitude, uint8_t poiType, uint16_t poiSymbol, int16_t poiP1, int16_t poiP2) @@ -176,13 +176,23 @@ void osdHudDrawPoi(uint32_t poiDistance, int16_t poiDirection, int32_t poiAltitu } } - if (error_x > 0 ) { - d = SYM_HUD_ARROWS_R3 - constrain((180 - error_x) / 45, 0, 2); + if (poiType == 1) { // POI from the ESP radar + d = constrain(((error_x + 180) / 30), 0, 12); + if (d == 12) { + d = 0; // Directly behind + } + + d = SYM_HUD_CARDINAL + d; osdHudWrite(poi_x + 2, poi_y, d, 1); - } - else { - d = SYM_HUD_ARROWS_L3 - constrain((180 + error_x) / 45, 0, 2); - osdHudWrite(poi_x - 2, poi_y, d, 1); + } else { + if (error_x > 0 ) { + d = SYM_HUD_ARROWS_R3 - constrain((180 - error_x) / 45, 0, 2); + osdHudWrite(poi_x + 2, poi_y, d, 1); + } + else { + d = SYM_HUD_ARROWS_L3 - constrain((180 + error_x) / 45, 0, 2); + osdHudWrite(poi_x - 2, poi_y, d, 1); + } } } @@ -205,7 +215,7 @@ void osdHudDrawPoi(uint32_t poiDistance, int16_t poiDirection, int32_t poiAltitu if (poiType > 0 && ((millis() / 1000) % (osdConfig()->hud_radar_alt_difference_display_time + osdConfig()->hud_radar_distance_display_time) < (osdConfig()->hud_radar_alt_difference_display_time % (osdConfig()->hud_radar_alt_difference_display_time + osdConfig()->hud_radar_distance_display_time))) ) { // For Radar and WPs, display the difference in altitude, then distance. Time is pilot defined - altc = constrain(poiAltitude, -99 , 99); + altc = poiAltitude; switch ((osd_unit_e)osdConfig()->units) { case OSD_UNIT_UK: @@ -214,7 +224,7 @@ void osdHudDrawPoi(uint32_t poiDistance, int16_t poiDirection, int32_t poiAltitu FALLTHROUGH; case OSD_UNIT_IMPERIAL: // Convert to feet - altc = constrain(CENTIMETERS_TO_FEET(poiAltitude * 100), -99, 99); + altc = CENTIMETERS_TO_FEET(poiAltitude * 100); break; default: FALLTHROUGH; @@ -225,24 +235,48 @@ void osdHudDrawPoi(uint32_t poiDistance, int16_t poiDirection, int32_t poiAltitu break; } + if (poiType == 1) { + altc = constrain(altc, -999 , 999); + } else { + altc = constrain(altc, -99 , 99); + } + tfp_sprintf(buff, "%3d", altc); - buff[0] = (poiAltitude >= 0) ? SYM_DIRECTION : SYM_DIRECTION+4; + buff[0] = (poiAltitude >= 0) ? SYM_AH_DIRECTION_UP : SYM_AH_DIRECTION_DOWN; } else { // Display the distance by default switch ((osd_unit_e)osdConfig()->units) { case OSD_UNIT_UK: FALLTHROUGH; case OSD_UNIT_IMPERIAL: - osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(poiDistance * 100), FEET_PER_MILE, 0, 3, 3); + { + if (poiType == 1) { + osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(poiDistance * 100), FEET_PER_MILE, 0, 4, 4); + } else { + osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(poiDistance * 100), FEET_PER_MILE, 0, 3, 3); + } + } break; case OSD_UNIT_GA: - osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(poiDistance * 100), FEET_PER_NAUTICALMILE, 0, 3, 3); + { + if (poiType == 1) { + osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(poiDistance * 100), FEET_PER_NAUTICALMILE, 0, 4, 4); + } else { + osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(poiDistance * 100), FEET_PER_NAUTICALMILE, 0, 3, 3); + } + } break; default: FALLTHROUGH; case OSD_UNIT_METRIC_MPH: FALLTHROUGH; case OSD_UNIT_METRIC: - osdFormatCentiNumber(buff, poiDistance * 100, METERS_PER_KILOMETER, 0, 3, 3); + { + if (poiType == 1) { + osdFormatCentiNumber(buff, poiDistance * 100, METERS_PER_KILOMETER, 0, 4, 4); + } else { + osdFormatCentiNumber(buff, poiDistance * 100, METERS_PER_KILOMETER, 0, 3, 3); + } + } break; } } @@ -250,6 +284,9 @@ void osdHudDrawPoi(uint32_t poiDistance, int16_t poiDirection, int32_t poiAltitu osdHudWrite(poi_x - 1, poi_y + 1, buff[0], 1); osdHudWrite(poi_x , poi_y + 1, buff[1], 1); osdHudWrite(poi_x + 1, poi_y + 1, buff[2], 1); + if (poiType == 1) { + osdHudWrite(poi_x + 2, poi_y + 1, buff[3], 1); + } } /* From 8112c8d5fa505e87edf030f3e9ed54f71ba1e945 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Fri, 15 Jul 2022 18:42:17 +0100 Subject: [PATCH 015/130] Improvements - Renamed `osdPanServoHomeDirectionOffset` to `osdGetPanServoOffset` as the function does not reference home direction. So it can be used elsewhere. - Added pan servo offset to POIs. - Made cardinal always visible for ESP32 Radar. --- src/main/io/osd.c | 4 ++-- src/main/io/osd.h | 2 ++ src/main/io/osd_hud.c | 9 +++++++-- 3 files changed, 11 insertions(+), 4 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index eed14a2764..25a9b56e5f 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1170,7 +1170,7 @@ int16_t osdGetHeading(void) return attitude.values.yaw; } -int16_t osdPanServoHomeDirectionOffset(void) +int16_t osdGetPanServoOffset(void) { int8_t servoIndex = osdConfig()->pan_servo_index; int16_t servoPosition = servo[servoIndex]; @@ -1767,7 +1767,7 @@ static bool osdDrawSingleElement(uint8_t item) { int16_t panHomeDirOffset = 0; if (!(osdConfig()->pan_servo_pwm2centideg == 0)){ - panHomeDirOffset = osdPanServoHomeDirectionOffset(); + panHomeDirOffset = osdGetPanServoOffset(); } int16_t flightDirection = STATE(AIRPLANE) ? CENTIDEGREES_TO_DEGREES(posControl.actualState.cog) : DECIDEGREES_TO_DEGREES(osdGetHeading()); int homeDirection = GPS_directionToHome - flightDirection + panHomeDirOffset; diff --git a/src/main/io/osd.h b/src/main/io/osd.h index 9cb4eaabd8..a90c7dd232 100644 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -482,6 +482,8 @@ void osdFormatVelocityStr(char* buff, int32_t vel, bool _3D, bool _max); // Returns a heading angle in degrees normalized to [0, 360). int osdGetHeadingAngle(int angle); +int16_t osdGetPanServoOffset(void); + /** * @brief Get the OSD system message * @param buff pointer to the message buffer diff --git a/src/main/io/osd_hud.c b/src/main/io/osd_hud.c index db16ee4239..981858b4d7 100644 --- a/src/main/io/osd_hud.c +++ b/src/main/io/osd_hud.c @@ -137,6 +137,10 @@ void osdHudDrawPoi(uint32_t poiDistance, int16_t poiDirection, int32_t poiAltitu osdCrosshairPosition(¢er_x, ¢er_y); + if (!(osdConfig()->pan_servo_pwm2centideg == 0)){ + poiDistance = poiDistance + osdGetPanServoOffset(); + } + int16_t error_x = hudWrap180(poiDirection - DECIDEGREES_TO_DEGREES(osdGetHeading())); if ((error_x > -(osdConfig()->camera_fov_h / 2)) && (error_x < osdConfig()->camera_fov_h / 2)) { // POI might be in sight, extra geometry needed @@ -161,8 +165,9 @@ void osdHudDrawPoi(uint32_t poiDistance, int16_t poiDirection, int32_t poiAltitu } // Out-of-sight arrows and stacking + // Always show with ESP32 Radar - if (poi_is_oos) { + if (poi_is_oos || poiType == 1) { uint16_t d; uint16_t c; @@ -208,7 +213,7 @@ void osdHudDrawPoi(uint32_t poiDistance, int16_t poiDirection, int32_t poiAltitu else if (poiType == 2) { // Waypoint, osdHudWrite(poi_x - 1, poi_y, SYM_HUD_ARROWS_U1 + poiP2, 1); osdHudWrite(poi_x + 1, poi_y, poiP1, 1); - } + } // Distance From 285fa9ba40b987ba8cb0c4a1d9fb657324364d03 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Sat, 16 Jul 2022 22:50:22 +0100 Subject: [PATCH 016/130] Updates after flight test --- src/main/io/osd_hud.c | 21 +++++++++++---------- 1 file changed, 11 insertions(+), 10 deletions(-) diff --git a/src/main/io/osd_hud.c b/src/main/io/osd_hud.c index 981858b4d7..c9944bf71c 100644 --- a/src/main/io/osd_hud.c +++ b/src/main/io/osd_hud.c @@ -127,7 +127,7 @@ void osdHudDrawPoi(uint32_t poiDistance, int16_t poiDirection, int32_t poiAltitu uint8_t center_x; uint8_t center_y; bool poi_is_oos = 0; - char buff[3]; + char buff[4]; int altc = 0; uint8_t minX = osdConfig()->hud_margin_h + 2; @@ -149,8 +149,7 @@ void osdHudDrawPoi(uint32_t poiDistance, int16_t poiDirection, int32_t poiAltitu if (poi_x < minX || poi_x > maxX ) { // In camera view, but out of the hud area poi_is_oos = 1; - } - else { // POI is on sight, compute the vertical + } else { // POI is on sight, compute the vertical float poi_angle = atan2_approx(-poiAltitude, poiDistance); poi_angle = RADIANS_TO_DEGREES(poi_angle); int16_t plane_angle = attitude.values.pitch / 10; @@ -159,8 +158,7 @@ void osdHudDrawPoi(uint32_t poiDistance, int16_t poiDirection, int32_t poiAltitu float scaled_y = sin_approx(DEGREES_TO_RADIANS(error_y)) / sin_approx(DEGREES_TO_RADIANS(osdConfig()->camera_fov_v / 2)); poi_y = constrain(center_y + (osdGetDisplayPort()->rows / 2) * scaled_y, minY, maxY - 1); } - } - else { + } else { poi_is_oos = 1; // POI is out of camera view for sure } @@ -171,8 +169,10 @@ void osdHudDrawPoi(uint32_t poiDistance, int16_t poiDirection, int32_t poiAltitu uint16_t d; uint16_t c; - poi_x = (error_x > 0 ) ? maxX : minX; - poi_y = center_y - 1; + if (poi_is_oos) { + poi_x = (error_x > 0 ) ? maxX : minX; + poi_y = center_y - 1; + } if (displayReadCharWithAttr(osdGetDisplayPort(), poi_x, poi_y, &c, NULL) && c != SYM_BLANK) { poi_y = center_y - 3; @@ -241,12 +241,13 @@ void osdHudDrawPoi(uint32_t poiDistance, int16_t poiDirection, int32_t poiAltitu } if (poiType == 1) { - altc = constrain(altc, -999 , 999); + altc = ABS(constrain(altc, -999, 999)); + tfp_sprintf(buff+1, "%3d", altc); } else { - altc = constrain(altc, -99 , 99); + altc = constrain(altc, -99, 99); + tfp_sprintf(buff, "%3d", altc); } - tfp_sprintf(buff, "%3d", altc); buff[0] = (poiAltitude >= 0) ? SYM_AH_DIRECTION_UP : SYM_AH_DIRECTION_DOWN; } else { // Display the distance by default switch ((osd_unit_e)osdConfig()->units) { From 01bb69bb525414e85bb7702eb7258d9ecb73d932 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Mon, 18 Jul 2022 20:37:11 +0100 Subject: [PATCH 017/130] Added OSD symbol for pan servo offset --- src/main/drivers/osd_symbols.h | 3 +++ src/main/io/osd.c | 10 ++++++++++ src/main/io/osd.h | 1 + 3 files changed, 14 insertions(+) diff --git a/src/main/drivers/osd_symbols.h b/src/main/drivers/osd_symbols.h index e6167e25f2..8b65c0d55f 100644 --- a/src/main/drivers/osd_symbols.h +++ b/src/main/drivers/osd_symbols.h @@ -254,6 +254,9 @@ #define SYM_HUD_CARDINAL 0x1BA // 442-453 Cardinal direction in 30 degree segments +#define SYM_SERVO_PAN_IS_CENTRED 0x1C6 // 454 Pan servo is centred +#define SYM_SERVO_PAN_IS_OFFSET 0x1C7 // 455 Pan servo is offset + #else #define TEMP_SENSOR_SYM_COUNT 0 diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 25a9b56e5f..0655b64fce 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -2482,6 +2482,16 @@ static bool osdDrawSingleElement(uint8_t item) osdDisplaySwitchIndicator(osdConfig()->osd_switch_indicator3_name, rxGetChannelValue(osdConfig()->osd_switch_indicator3_channel - 1), buff); break; + case OSD_PAN_SERVO_CENTRED: + { + if (osdGetPanServoOffset() != 0) { + displayWriteChar(osdDisplayPort, elemPosX, elemPosY, SYM_SERVO_PAN_IS_OFFSET); + } else { + displayWriteChar(osdDisplayPort, elemPosX, elemPosY, SYM_SERVO_PAN_IS_CENTRED); + } + } + break; + case OSD_ACTIVE_PROFILE: tfp_sprintf(buff, "%c%u", SYM_PROFILE, (getConfigProfile() + 1)); displayWrite(osdDisplayPort, elemPosX, elemPosY, buff); diff --git a/src/main/io/osd.h b/src/main/io/osd.h index a90c7dd232..59adc7c2e4 100644 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -271,6 +271,7 @@ typedef enum { OSD_GROUND_COURSE, // 140 OSD_CROSS_TRACK_ERROR, OSD_PILOT_NAME, + OSD_PAN_SERVO_CENTRED, OSD_ITEM_COUNT // MUST BE LAST } osd_items_e; From 10ebb5c16daa768690f41cc6ef868727f26dcc86 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Tue, 19 Jul 2022 22:56:13 +0100 Subject: [PATCH 018/130] Added customisations and options --- docs/Settings.md | 20 ++++++++++++++++ src/main/drivers/osd_symbols.h | 3 ++- src/main/fc/settings.yaml | 13 ++++++++++ src/main/io/osd.c | 43 ++++++++++++++++++++++++++++++++-- src/main/io/osd.h | 2 ++ 5 files changed, 78 insertions(+), 3 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index fa30e623d8..b962828558 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -4392,6 +4392,26 @@ Index of the pan servo to adjust osd home heading direction based on camera pan. --- +### osd_pan_servo_indicator_show_degrees + +Show the degress of offset from centre on the pan servo OSD display element. + +| Default | Min | Max | +| --- | --- | --- | +| OFF | OFF | ON | + +--- + +### osd_pan_servo_offcentre_warning + +Degrees around the pan servo centre that it is assumed camera is wanted to be facing forwards; but isn't at 0. If in this range and not 0 for longer than 10 seconds, the pan servo offset OSD element will blink. + +| Default | Min | Max | +| --- | --- | --- | +| 10 | 0 | 45 | + +--- + ### osd_pan_servo_pwm2centideg Centidegrees of pan servo rotation us PWM signal. A servo with 180 degrees of rotation from 1000 to 2000 us PWM typically needs `18` for this setting. Change sign to inverse direction. diff --git a/src/main/drivers/osd_symbols.h b/src/main/drivers/osd_symbols.h index 8b65c0d55f..57acdf384e 100644 --- a/src/main/drivers/osd_symbols.h +++ b/src/main/drivers/osd_symbols.h @@ -255,7 +255,8 @@ #define SYM_HUD_CARDINAL 0x1BA // 442-453 Cardinal direction in 30 degree segments #define SYM_SERVO_PAN_IS_CENTRED 0x1C6 // 454 Pan servo is centred -#define SYM_SERVO_PAN_IS_OFFSET 0x1C7 // 455 Pan servo is offset +#define SYM_SERVO_PAN_IS_OFFSET_L 0x1C7 // 455 Pan servo is offset left +#define SYM_SERVO_PAN_IS_OFFSET_R 0x1C8 // 456 Pan servo is offset right #else diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index a089c01859..38398dc730 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -3456,6 +3456,19 @@ groups: min: -36 max: 36 + - name: osd_pan_servo_offcentre_warning + description: Degrees either side of the pan servo centre; where it is assumed camera is wanted to be facing forwards, but isn't at 0. If in this range and not 0 for longer than 10 seconds, the pan servo offset OSD element will blink. + field: pan_servo_offcentre_warning + min: 0 + max: 45 + default_value: 10 + + - name: osd_pan_servo_indicator_show_degrees + description: Show the degress of offset from centre on the pan servo OSD display element. + field: pan_servo_indicator_show_degrees + type: bool + default_value: OFF + - name: osd_esc_rpm_precision description: Number of characters used to display the RPM value. field: esc_rpm_precision diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 0655b64fce..4c4622f9c1 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -2484,11 +2484,48 @@ static bool osdDrawSingleElement(uint8_t item) case OSD_PAN_SERVO_CENTRED: { - if (osdGetPanServoOffset() != 0) { - displayWriteChar(osdDisplayPort, elemPosX, elemPosY, SYM_SERVO_PAN_IS_OFFSET); + int16_t panOffset = osdGetPanServoOffset(); + const timeMs_t panServoTimeNow = millis(); + static timeMs_t panServoTimeOffCentre = 0; + + if (panOffset < 0) { + if (osdConfig()->pan_servo_offcentre_warning != 0 && panOffset >= -osdConfig()->pan_servo_offcentre_warning) { + if (panServoTimeOffCentre == 0) { + panServoTimeOffCentre = panServoTimeNow; + } else if (panServoTimeNow >= (panServoTimeOffCentre + 10000 )) { + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + } else { + panServoTimeOffCentre = 0; + } + + if (osdConfig()->pan_servo_indicator_show_degrees) { + tfp_sprintf(buff, "%3d%c", -panOffset, SYM_DEGREES); + displayWriteWithAttr(osdDisplayPort, elemPosX+1, elemPosY, buff, elemAttr); + } + displayWriteCharWithAttr(osdDisplayPort, elemPosX, elemPosY, SYM_SERVO_PAN_IS_OFFSET_L, elemAttr); + } else if (panOffset > 0) { + if (osdConfig()->pan_servo_offcentre_warning != 0 && panOffset <= osdConfig()->pan_servo_offcentre_warning) { + if (panServoTimeOffCentre == 0) { + panServoTimeOffCentre = panServoTimeNow; + } else if (panServoTimeNow >= (panServoTimeOffCentre + 10000 )) { + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + } else { + panServoTimeOffCentre = 0; + } + + if (osdConfig()->pan_servo_indicator_show_degrees) { + tfp_sprintf(buff, "%3d%c", panOffset, SYM_DEGREES); + displayWriteWithAttr(osdDisplayPort, elemPosX+1, elemPosY, buff, elemAttr); + } + displayWriteCharWithAttr(osdDisplayPort, elemPosX, elemPosY, SYM_SERVO_PAN_IS_OFFSET_R, elemAttr); } else { + panServoTimeOffCentre = 0; displayWriteChar(osdDisplayPort, elemPosX, elemPosY, SYM_SERVO_PAN_IS_CENTRED); } + + return true; } break; @@ -3493,6 +3530,8 @@ PG_RESET_TEMPLATE(osdConfig_t, osdConfig, .osd_home_position_arm_screen = SETTING_OSD_HOME_POSITION_ARM_SCREEN_DEFAULT, .pan_servo_index = SETTING_OSD_PAN_SERVO_INDEX_DEFAULT, .pan_servo_pwm2centideg = SETTING_OSD_PAN_SERVO_PWM2CENTIDEG_DEFAULT, + .pan_servo_offcentre_warning = SETTING_OSD_PAN_SERVO_OFFCENTRE_WARNING_DEFAULT, + .pan_servo_indicator_show_degrees = SETTING_OSD_PAN_SERVO_INDICATOR_SHOW_DEGREES_DEFAULT, .esc_rpm_precision = SETTING_OSD_ESC_RPM_PRECISION_DEFAULT, .mAh_used_precision = SETTING_OSD_MAH_USED_PRECISION_DEFAULT, .osd_switch_indicator0_name = SETTING_OSD_SWITCH_INDICATOR_ZERO_NAME_DEFAULT, diff --git a/src/main/io/osd.h b/src/main/io/osd.h index 59adc7c2e4..b7af9af3e0 100644 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -428,6 +428,8 @@ typedef struct osdConfig_s { bool osd_home_position_arm_screen; uint8_t pan_servo_index; // Index of the pan servo used for home direction offset int8_t pan_servo_pwm2centideg; // Centidegrees of servo rotation per us pwm + uint8_t pan_servo_offcentre_warning; // Degrees around the centre, that is assumed camera is wanted to be facing forwards, but isn't centred + bool pan_servo_indicator_show_degrees; // Show the degrees of offset for the pan servo uint8_t crsf_lq_format; uint8_t sidebar_height; // sidebar height in rows, 0 turns off sidebars leaving only level indicator arrows uint8_t telemetry; // use telemetry on displayed pixel line 0 From a29726c364aa4e0322bf46824975173df7efc0e3 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Wed, 20 Jul 2022 06:54:02 +0100 Subject: [PATCH 019/130] Updated docs --- docs/Settings.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/Settings.md b/docs/Settings.md index b962828558..432fb99641 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -4404,7 +4404,7 @@ Show the degress of offset from centre on the pan servo OSD display element. ### osd_pan_servo_offcentre_warning -Degrees around the pan servo centre that it is assumed camera is wanted to be facing forwards; but isn't at 0. If in this range and not 0 for longer than 10 seconds, the pan servo offset OSD element will blink. +Degrees either side of the pan servo centre; where it is assumed camera is wanted to be facing forwards, but isn't at 0. If in this range and not 0 for longer than 10 seconds, the pan servo offset OSD element will blink. | Default | Min | Max | | --- | --- | --- | From 8c46e5aa05fe6a472e9e5081014b135ee8b4fa8a Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Wed, 20 Jul 2022 07:27:18 +0100 Subject: [PATCH 020/130] PG bump --- src/main/io/osd.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 4c4622f9c1..c669b96ee3 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -201,7 +201,7 @@ static bool osdDisplayHasCanvas; #define AH_MAX_PITCH_DEFAULT 20 // Specify default maximum AHI pitch value displayed (degrees) -PG_REGISTER_WITH_RESET_TEMPLATE(osdConfig_t, osdConfig, PG_OSD_CONFIG, 7); +PG_REGISTER_WITH_RESET_TEMPLATE(osdConfig_t, osdConfig, PG_OSD_CONFIG, 8); PG_REGISTER_WITH_RESET_FN(osdLayoutsConfig_t, osdLayoutsConfig, PG_OSD_LAYOUTS_CONFIG, 1); void osdStartedSaveProcess() { From 88b17e3628baa6e0c6c66d6f55da91397387f028 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Wed, 20 Jul 2022 08:36:01 +0100 Subject: [PATCH 021/130] Update settings.yaml --- src/main/fc/settings.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 38398dc730..7418a057c8 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -3457,7 +3457,7 @@ groups: max: 36 - name: osd_pan_servo_offcentre_warning - description: Degrees either side of the pan servo centre; where it is assumed camera is wanted to be facing forwards, but isn't at 0. If in this range and not 0 for longer than 10 seconds, the pan servo offset OSD element will blink. + description: Degrees either side of the pan servo centre; where it is assumed camera is wanted to be facing forwards, but isn't at 0. If in this range and not 0 for longer than 10 seconds, the pan servo offset OSD element will blink. 0 means the warning is disabled. field: pan_servo_offcentre_warning min: 0 max: 45 From 7649c5f429735656ccb202f3f6bf13eae6952db4 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Wed, 20 Jul 2022 21:10:45 +0100 Subject: [PATCH 022/130] Updated the `osd_pan_servo_index` max to 16 Updated the `osd_pan_servo_index` max to 16. There are flight controllers now that have 12 PWM outputs. This now matches `MAX_SUPPORTED_SERVOS`. --- docs/Settings.md | 6 +++--- src/main/fc/settings.yaml | 4 ++-- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index 432fb99641..5b899a1215 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -4384,11 +4384,11 @@ Value below which (negative altitude) to make the OSD relative altitude indicato ### osd_pan_servo_index -Index of the pan servo to adjust osd home heading direction based on camera pan. Note that this feature does not work with continiously rotating servos. +Index of the pan servo, used to adjust osd home heading direction based on camera pan. Note that this feature does not work with continiously rotating servos. | Default | Min | Max | | --- | --- | --- | -| 0 | 0 | 10 | +| 0 | 0 | 16 | --- @@ -4404,7 +4404,7 @@ Show the degress of offset from centre on the pan servo OSD display element. ### osd_pan_servo_offcentre_warning -Degrees either side of the pan servo centre; where it is assumed camera is wanted to be facing forwards, but isn't at 0. If in this range and not 0 for longer than 10 seconds, the pan servo offset OSD element will blink. +Degrees either side of the pan servo centre; where it is assumed camera is wanted to be facing forwards, but isn't at 0. If in this range and not 0 for longer than 10 seconds, the pan servo offset OSD element will blink. 0 means the warning is disabled. | Default | Min | Max | | --- | --- | --- | diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 7418a057c8..77074db6c8 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -3443,10 +3443,10 @@ groups: description: Should home position coordinates be displayed on the arming screen. - name: osd_pan_servo_index - description: Index of the pan servo to adjust osd home heading direction based on camera pan. Note that this feature does not work with continiously rotating servos. + description: Index of the pan servo, used to adjust osd home heading direction based on camera pan. Note that this feature does not work with continiously rotating servos. field: pan_servo_index min: 0 - max: 10 + max: 16 default_value: 0 - name: osd_pan_servo_pwm2centideg From 64b23db33c17132994b0b0fb8ed8b7d85b0ce579 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Fri, 22 Jul 2022 19:00:33 +0100 Subject: [PATCH 023/130] Fixed a miscopy/paste --- src/main/io/osd_hud.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/io/osd_hud.c b/src/main/io/osd_hud.c index c9944bf71c..ee352cde78 100644 --- a/src/main/io/osd_hud.c +++ b/src/main/io/osd_hud.c @@ -138,7 +138,7 @@ void osdHudDrawPoi(uint32_t poiDistance, int16_t poiDirection, int32_t poiAltitu osdCrosshairPosition(¢er_x, ¢er_y); if (!(osdConfig()->pan_servo_pwm2centideg == 0)){ - poiDistance = poiDistance + osdGetPanServoOffset(); + poiDirection = poiDirection + osdGetPanServoOffset(); } int16_t error_x = hudWrap180(poiDirection - DECIDEGREES_TO_DEGREES(osdGetHeading())); From 40cce65c10eee9d83ac13fab6a2fe9307bbd5384 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Sun, 2 Oct 2022 18:50:18 +0100 Subject: [PATCH 024/130] Fixed incorrect degrees in centre position --- src/main/io/osd.c | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index c669b96ee3..fbe200efa6 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -2522,6 +2522,11 @@ static bool osdDrawSingleElement(uint8_t item) displayWriteCharWithAttr(osdDisplayPort, elemPosX, elemPosY, SYM_SERVO_PAN_IS_OFFSET_R, elemAttr); } else { panServoTimeOffCentre = 0; + + if (osdConfig()->pan_servo_indicator_show_degrees) { + tfp_sprintf(buff, "%3d%c", panOffset, SYM_DEGREES); + displayWriteWithAttr(osdDisplayPort, elemPosX+1, elemPosY, buff, elemAttr); + } displayWriteChar(osdDisplayPort, elemPosX, elemPosY, SYM_SERVO_PAN_IS_CENTRED); } From 3b13709fe87c7066d9a834b5c493c3821323bc5c Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Fri, 20 Jan 2023 08:32:12 +0000 Subject: [PATCH 025/130] Reverse pan direction of offset OSD element - Fix bug from merge with master - Reverse pan offset direction arrow --- src/main/io/osd.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index fbe200efa6..23f7621d2d 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -2503,7 +2503,7 @@ static bool osdDrawSingleElement(uint8_t item) tfp_sprintf(buff, "%3d%c", -panOffset, SYM_DEGREES); displayWriteWithAttr(osdDisplayPort, elemPosX+1, elemPosY, buff, elemAttr); } - displayWriteCharWithAttr(osdDisplayPort, elemPosX, elemPosY, SYM_SERVO_PAN_IS_OFFSET_L, elemAttr); + displayWriteCharWithAttr(osdDisplayPort, elemPosX, elemPosY, SYM_SERVO_PAN_IS_OFFSET_R, elemAttr); } else if (panOffset > 0) { if (osdConfig()->pan_servo_offcentre_warning != 0 && panOffset <= osdConfig()->pan_servo_offcentre_warning) { if (panServoTimeOffCentre == 0) { @@ -2519,7 +2519,7 @@ static bool osdDrawSingleElement(uint8_t item) tfp_sprintf(buff, "%3d%c", panOffset, SYM_DEGREES); displayWriteWithAttr(osdDisplayPort, elemPosX+1, elemPosY, buff, elemAttr); } - displayWriteCharWithAttr(osdDisplayPort, elemPosX, elemPosY, SYM_SERVO_PAN_IS_OFFSET_R, elemAttr); + displayWriteCharWithAttr(osdDisplayPort, elemPosX, elemPosY, SYM_SERVO_PAN_IS_OFFSET_L, elemAttr); } else { panServoTimeOffCentre = 0; @@ -3041,10 +3041,10 @@ static bool osdDrawSingleElement(uint8_t item) float verticalWindSpeed; verticalWindSpeed = -getEstimatedWindSpeed(Z); //from NED to NEU if (verticalWindSpeed < 0) { - buff[1] = SYM_AH_DECORATION_DOWN; + buff[1] = SYM_AH_DIRECTION_DOWN; verticalWindSpeed = -verticalWindSpeed; } else { - buff[1] = SYM_AH_DECORATION_UP; + buff[1] = SYM_AH_DIRECTION_UP; } osdFormatWindSpeedStr(buff + 2, verticalWindSpeed, valid); break; From e97c7a6d9148f633870295e4f21cbc744f783874 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Thu, 2 Feb 2023 19:16:40 +0100 Subject: [PATCH 026/130] Add a mapping for 3D kph and mph symbols --- src/main/io/displayport_msp_bf_compat.c | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/src/main/io/displayport_msp_bf_compat.c b/src/main/io/displayport_msp_bf_compat.c index 29a85b6718..b6b1fe9d81 100644 --- a/src/main/io/displayport_msp_bf_compat.c +++ b/src/main/io/displayport_msp_bf_compat.c @@ -228,12 +228,6 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) case SYM_WIND_VERTICAL: return BF_SYM_WIND_VERTICAL; - case SYM_3D_KMH: - return BF_SYM_3D_KMH; - - case SYM_3D_MPH: - return BF_SYM_3D_MPH; - case SYM_3D_KT: return BF_SYM_3D_KT; @@ -242,6 +236,12 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) return BF_SYM_AIR; */ + case SYM_3D_KMH: + return BF_SYM_KPH; + + case SYM_3D_MPH: + return BF_SYM_MPH; + case SYM_RPM: return BF_SYM_RPM; From f3de64444a09d41534acf5342bd41bd85e4f0d0e Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Tue, 7 Feb 2023 14:05:59 +0000 Subject: [PATCH 027/130] osd batt cleanup --- src/main/io/osd.c | 14 +++++--- src/main/sensors/battery.c | 65 +++++++++++++++++++++++--------------- src/main/sensors/battery.h | 1 + 3 files changed, 51 insertions(+), 29 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index eed14a2764..ba0c538f02 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1045,8 +1045,11 @@ static void osdFormatBatteryChargeSymbol(char *buff) static void osdUpdateBatteryCapacityOrVoltageTextAttributes(textAttributes_t *attr) { - if ((getBatteryState() != BATTERY_NOT_PRESENT) && ((batteryUsesCapacityThresholds() && (getBatteryRemainingCapacity() <= currentBatteryProfile->capacity.warning - currentBatteryProfile->capacity.critical)) || ((!batteryUsesCapacityThresholds()) && (getBatteryVoltage() <= getBatteryWarningVoltage())))) + const batteryState_e batteryState = getBatteryState(); + + if (batteryState == BATTERY_WARNING || batteryState == BATTERY_CRITICAL) { TEXT_ATTRIBUTES_ADD_BLINK(*attr); + } } void osdCrosshairPosition(uint8_t *x, uint8_t *y) @@ -1448,8 +1451,10 @@ static void osdDisplayBatteryVoltage(uint8_t elemPosX, uint8_t elemPosY, uint16_ osdFormatCentiNumber(buff, voltage, 0, decimals, 0, digits); buff[digits] = SYM_VOLT; buff[digits+1] = '\0'; - if ((getBatteryState() != BATTERY_NOT_PRESENT) && (getBatteryVoltage() <= getBatteryWarningVoltage())) + const batteryState_e batteryVoltageState = checkBatteryVoltageState(); + if (batteryVoltageState == BATTERY_CRITICAL || batteryVoltageState == BATTERY_WARNING) { TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } displayWriteWithAttr(osdDisplayPort, elemPosX + 1, elemPosY, buff, elemAttr); } @@ -1679,8 +1684,9 @@ static bool osdDrawSingleElement(uint8_t item) buff[4] = currentBatteryProfile->capacity.unit == BAT_CAPACITY_UNIT_MAH ? SYM_MAH : SYM_WH; buff[5] = '\0'; - if ((getBatteryState() != BATTERY_NOT_PRESENT) && batteryUsesCapacityThresholds() && (getBatteryRemainingCapacity() <= currentBatteryProfile->capacity.warning - currentBatteryProfile->capacity.critical)) - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + if (batteryUsesCapacityThresholds()) { + osdUpdateBatteryCapacityOrVoltageTextAttributes(&elemAttr); + } break; diff --git a/src/main/sensors/battery.c b/src/main/sensors/battery.c index 9652e15c4f..6646f8f57d 100644 --- a/src/main/sensors/battery.c +++ b/src/main/sensors/battery.c @@ -305,6 +305,44 @@ static void updateBatteryVoltage(timeUs_t timeDelta, bool justConnected) } } +batteryState_e checkBatteryVoltageState(void) +{ + uint16_t stateVoltage = getBatteryVoltage(); + switch (batteryState) + { + case BATTERY_OK: + if (stateVoltage <= (batteryWarningVoltage - VBATT_HYSTERESIS)) { + return BATTERY_WARNING; + } + break; + case BATTERY_WARNING: + if (stateVoltage <= (batteryCriticalVoltage - VBATT_HYSTERESIS)) { + return BATTERY_CRITICAL; + } else if (stateVoltage > (batteryWarningVoltage + VBATT_HYSTERESIS)){ + return BATTERY_OK; + } + break; + case BATTERY_CRITICAL: + if (stateVoltage > (batteryCriticalVoltage + VBATT_HYSTERESIS)) { + return BATTERY_WARNING; + } + break; + default: + break; + } + + return batteryState; +} + +static void checkBatteryCapacityState(void) +{ + if (batteryRemainingCapacity == 0) { + batteryState = BATTERY_CRITICAL; + } else if (batteryRemainingCapacity <= currentBatteryProfile->capacity.warning - currentBatteryProfile->capacity.critical) { + batteryState = BATTERY_WARNING; + } +} + void batteryUpdate(timeUs_t timeDelta) { /* battery has just been connected*/ @@ -367,32 +405,9 @@ void batteryUpdate(timeUs_t timeDelta) } if (batteryUseCapacityThresholds) { - if (batteryRemainingCapacity == 0) - batteryState = BATTERY_CRITICAL; - else if (batteryRemainingCapacity <= currentBatteryProfile->capacity.warning - currentBatteryProfile->capacity.critical) - batteryState = BATTERY_WARNING; + checkBatteryCapacityState(); } else { - uint16_t stateVoltage = getBatteryVoltage(); - switch (batteryState) - { - case BATTERY_OK: - if (stateVoltage <= (batteryWarningVoltage - VBATT_HYSTERESIS)) - batteryState = BATTERY_WARNING; - break; - case BATTERY_WARNING: - if (stateVoltage <= (batteryCriticalVoltage - VBATT_HYSTERESIS)) { - batteryState = BATTERY_CRITICAL; - } else if (stateVoltage > (batteryWarningVoltage + VBATT_HYSTERESIS)){ - batteryState = BATTERY_OK; - } - break; - case BATTERY_CRITICAL: - if (stateVoltage > (batteryCriticalVoltage + VBATT_HYSTERESIS)) - batteryState = BATTERY_WARNING; - break; - default: - break; - } + batteryState = checkBatteryVoltageState(); } // handle beeper diff --git a/src/main/sensors/battery.h b/src/main/sensors/battery.h index 549515f13b..4e2e4b47e1 100644 --- a/src/main/sensors/battery.h +++ b/src/main/sensors/battery.h @@ -63,6 +63,7 @@ typedef enum { uint16_t batteryAdcToVoltage(uint16_t src); batteryState_e getBatteryState(void); +batteryState_e checkBatteryVoltageState(void); bool batteryWasFullWhenPluggedIn(void); bool batteryUsesCapacityThresholds(void); void batteryInit(void); From d4cdab469eb124b5283b77f0f3a028f277cfe1ad Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Tue, 7 Feb 2023 21:08:12 +0100 Subject: [PATCH 028/130] Initial test setup --- src/test/unit/CMakeLists.txt | 4 ++++ src/test/unit/osd_unittest.cc | 23 +++++++++++++++++++++++ 2 files changed, 27 insertions(+) create mode 100644 src/test/unit/osd_unittest.cc diff --git a/src/test/unit/CMakeLists.txt b/src/test/unit/CMakeLists.txt index a7a20a5324..f2c8424717 100644 --- a/src/test/unit/CMakeLists.txt +++ b/src/test/unit/CMakeLists.txt @@ -34,6 +34,9 @@ set_property(SOURCE time_unittest.cc PROPERTY depends "drivers/time.c") set_property(SOURCE circular_queue_unittest.cc PROPERTY depends "common/circular_queue.c") +set_property(SOURCE osd_unittest.cc PROPERTY depends "io/osd.c") +#set_property(SOURCE osd_unittest.cc PROPERTY definitions USE_OSD) + function(unit_test src) get_filename_component(basename ${src} NAME) string(REPLACE ".cc" "" name ${basename} ) @@ -54,6 +57,7 @@ function(unit_test src) target_compile_definitions(${name} PRIVATE ${test_definitions}) target_compile_options(${name} PRIVATE -pthread -Wall -Wextra -Wno-extern-c-compat -ggdb3 -O0) enable_settings(${name} ${gen_name} OUTPUTS setting_files SETTINGS_CXX g++) + #enable_settings(${name} ${gen_name} OUTPUTS setting_files SETTINGS_CC gcc) target_sources(${name} PRIVATE ${setting_files}) target_link_libraries(${name} gtest_main) gtest_discover_tests(${name}) diff --git a/src/test/unit/osd_unittest.cc b/src/test/unit/osd_unittest.cc new file mode 100644 index 0000000000..0ad2849aac --- /dev/null +++ b/src/test/unit/osd_unittest.cc @@ -0,0 +1,23 @@ +#include "gtest/gtest.h" +#include "unittest_macros.h" + +#include +#include + +extern "C" { +#include "io/osd.h" +}; + + +TEST(OSDTest, TestCentiNumber) +{ + //bool osdFormatCentiNumber(char *buff, int32_t centivalue, uint32_t scale, int maxDecimals, int maxScaledDecimals, int length); + char buf[10] = ""; + + osdFormatCentiNumber(buf, 10000, 1, 2, 2, 5); + + std::cout << buf << std::endl; + + EXPECT_EQ(1, 1); + +} \ No newline at end of file From 445b4e86651c610adc02aa74a04e537150f99fab Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Tue, 7 Feb 2023 21:25:45 +0100 Subject: [PATCH 029/130] Move format centi function to a separate ifdef --- src/main/io/osd.c | 195 ++++++++++++++++++----------------- src/test/unit/CMakeLists.txt | 3 +- 2 files changed, 101 insertions(+), 97 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index eed14a2764..2941f2868e 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -240,102 +240,7 @@ bool osdDisplayIsHD(void) return false; } -/** - * Formats a number given in cents, to support non integer values - * without using floating point math. Value is always right aligned - * and spaces are inserted before the number to always yield a string - * of the same length. If the value doesn't fit into the provided length - * it will be divided by scale and true will be returned. - */ -bool osdFormatCentiNumber(char *buff, int32_t centivalue, uint32_t scale, int maxDecimals, int maxScaledDecimals, int length) -{ - char *ptr = buff; - char *dec; - int decimals = maxDecimals; - bool negative = false; - bool scaled = false; - bool explicitDecimal = isBfCompatibleVideoSystem(osdConfig()); - buff[length] = '\0'; - - if (centivalue < 0) { - negative = true; - centivalue = -centivalue; - length--; - } - - int32_t integerPart = centivalue / 100; - // 3 decimal digits - int32_t millis = (centivalue % 100) * 10; - - int digits = digitCount(integerPart); - int remaining = length - digits; - if (explicitDecimal) { - remaining--; - } - - if (remaining < 0 && scale > 0) { - // Reduce by scale - scaled = true; - decimals = maxScaledDecimals; - integerPart = integerPart / scale; - // Multiply by 10 to get 3 decimal digits - millis = ((centivalue % (100 * scale)) * 10) / scale; - digits = digitCount(integerPart); - remaining = length - digits; - if (explicitDecimal) { - remaining--; - } - } - - // 3 decimals at most - decimals = MIN(remaining, MIN(decimals, 3)); - remaining -= decimals; - - // Done counting. Time to write the characters. - - // Write spaces at the start - while (remaining > 0) { - *ptr = SYM_BLANK; - ptr++; - remaining--; - } - - // Write the minus sign if required - if (negative) { - *ptr = '-'; - ptr++; - } - // Now write the digits. - ui2a(integerPart, 10, 0, ptr); - ptr += digits; - - if (decimals > 0) { - if (explicitDecimal) { - *ptr = '.'; - ptr++; - } else { - *(ptr - 1) += SYM_ZERO_HALF_TRAILING_DOT - '0'; - } - dec = ptr; - int factor = 3; // we're getting the decimal part in millis first - while (decimals < factor) { - factor--; - millis /= 10; - } - int decimalDigits = digitCount(millis); - while (decimalDigits < decimals) { - decimalDigits++; - *ptr = '0'; - ptr++; - } - ui2a(millis, 10, 0, ptr); - if (!explicitDecimal) { - *dec += SYM_ZERO_HALF_LEADING_DOT - '0'; - } - } - return scaled; -} /* * Aligns text to the left side. Adds spaces at the end to keep string length unchanged. @@ -4676,3 +4581,103 @@ textAttributes_t osdGetSystemMessage(char *buff, size_t buff_size, bool isCenter } #endif // OSD + +#if defined(USE_OSD) || defined (OSD_UNIT_TEST) +/** + * Formats a number given in cents, to support non integer values + * without using floating point math. Value is always right aligned + * and spaces are inserted before the number to always yield a string + * of the same length. If the value doesn't fit into the provided length + * it will be divided by scale and true will be returned. + */ +bool osdFormatCentiNumber(char *buff, int32_t centivalue, uint32_t scale, int maxDecimals, int maxScaledDecimals, int length) +{ + char *ptr = buff; + char *dec; + int decimals = maxDecimals; + bool negative = false; + bool scaled = false; + bool explicitDecimal = isBfCompatibleVideoSystem(osdConfig()); + + buff[length] = '\0'; + + if (centivalue < 0) { + negative = true; + centivalue = -centivalue; + length--; + } + + int32_t integerPart = centivalue / 100; + // 3 decimal digits + int32_t millis = (centivalue % 100) * 10; + + int digits = digitCount(integerPart); + int remaining = length - digits; + if (explicitDecimal) { + remaining--; + } + + if (remaining < 0 && scale > 0) { + // Reduce by scale + scaled = true; + decimals = maxScaledDecimals; + integerPart = integerPart / scale; + // Multiply by 10 to get 3 decimal digits + millis = ((centivalue % (100 * scale)) * 10) / scale; + digits = digitCount(integerPart); + remaining = length - digits; + if (explicitDecimal) { + remaining--; + } + } + + // 3 decimals at most + decimals = MIN(remaining, MIN(decimals, 3)); + remaining -= decimals; + + // Done counting. Time to write the characters. + + // Write spaces at the start + while (remaining > 0) { + *ptr = SYM_BLANK; + ptr++; + remaining--; + } + + // Write the minus sign if required + if (negative) { + *ptr = '-'; + ptr++; + } + // Now write the digits. + ui2a(integerPart, 10, 0, ptr); + ptr += digits; + + if (decimals > 0) { + if (explicitDecimal) { + *ptr = '.'; + ptr++; + } else { + *(ptr - 1) += SYM_ZERO_HALF_TRAILING_DOT - '0'; + } + dec = ptr; + int factor = 3; // we're getting the decimal part in millis first + while (decimals < factor) { + factor--; + millis /= 10; + } + int decimalDigits = digitCount(millis); + while (decimalDigits < decimals) { + decimalDigits++; + *ptr = '0'; + ptr++; + } + ui2a(millis, 10, 0, ptr); + if (!explicitDecimal) { + *dec += SYM_ZERO_HALF_LEADING_DOT - '0'; + } + } + return scaled; +} + +#endif \ No newline at end of file diff --git a/src/test/unit/CMakeLists.txt b/src/test/unit/CMakeLists.txt index f2c8424717..ea26b42e6f 100644 --- a/src/test/unit/CMakeLists.txt +++ b/src/test/unit/CMakeLists.txt @@ -35,7 +35,7 @@ set_property(SOURCE time_unittest.cc PROPERTY depends "drivers/time.c") set_property(SOURCE circular_queue_unittest.cc PROPERTY depends "common/circular_queue.c") set_property(SOURCE osd_unittest.cc PROPERTY depends "io/osd.c") -#set_property(SOURCE osd_unittest.cc PROPERTY definitions USE_OSD) +set_property(SOURCE osd_unittest.cc PROPERTY definitions OSD_UNIT_TEST) function(unit_test src) get_filename_component(basename ${src} NAME) @@ -57,7 +57,6 @@ function(unit_test src) target_compile_definitions(${name} PRIVATE ${test_definitions}) target_compile_options(${name} PRIVATE -pthread -Wall -Wextra -Wno-extern-c-compat -ggdb3 -O0) enable_settings(${name} ${gen_name} OUTPUTS setting_files SETTINGS_CXX g++) - #enable_settings(${name} ${gen_name} OUTPUTS setting_files SETTINGS_CC gcc) target_sources(${name} PRIVATE ${setting_files}) target_link_libraries(${name} gtest_main) gtest_discover_tests(${name}) From 92ec1dbb321630eef2ae0c1384f7b089584570a4 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Tue, 7 Feb 2023 21:34:33 +0100 Subject: [PATCH 030/130] Change ifdef for easier unit testing --- src/main/drivers/osd_symbols.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/drivers/osd_symbols.h b/src/main/drivers/osd_symbols.h index adcb595ce2..aba95f544b 100644 --- a/src/main/drivers/osd_symbols.h +++ b/src/main/drivers/osd_symbols.h @@ -21,7 +21,7 @@ #pragma once -#ifdef USE_OSD +#if defined(USE_OSD) || defined(OSD_UNIT_TEST) #define SYM_RSSI 0x01 // 001 Icon RSSI #define SYM_LQ 0x02 // 002 LQ From 6665b6a7c004c0a3a8c8a79dda7cc7a1184b3ab9 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Tue, 7 Feb 2023 22:28:38 +0100 Subject: [PATCH 031/130] Tests are running --- src/main/io/displayport_msp_bf_compat.h | 4 ++ src/main/io/osd.c | 39 ++++++++++++------- src/test/unit/CMakeLists.txt | 4 +- src/test/unit/osd_unittest.cc | 52 +++++++++++++++++++++++-- 4 files changed, 79 insertions(+), 20 deletions(-) diff --git a/src/main/io/displayport_msp_bf_compat.h b/src/main/io/displayport_msp_bf_compat.h index b7fe270700..4bfe84dc0f 100644 --- a/src/main/io/displayport_msp_bf_compat.h +++ b/src/main/io/displayport_msp_bf_compat.h @@ -28,5 +28,9 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page); #define isBfCompatibleVideoSystem(osdConfigPtr) (osdConfigPtr->video_system == VIDEO_SYSTEM_BFCOMPAT) #else #define getBfCharacter(x, page) (x) +#ifdef OSD_UNIT_TEST +#define isBfCompatibleVideoSystem(osdConfigPtr) (true) +#else #define isBfCompatibleVideoSystem(osdConfigPtr) (false) +#endif #endif \ No newline at end of file diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 2941f2868e..f10c8ac031 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -33,6 +33,17 @@ FILE_COMPILE_FOR_SPEED +#include "drivers/osd_symbols.h" +#include "common/maths.h" +#include "io/displayport_msp_bf_compat.h" +#include "config/parameter_group.h" +#include "config/parameter_group_ids.h" +#include "common/typeconversion.h" + +//PG_REGISTER_WITH_RESET_TEMPLATE(osdConfig_t, osdConfig, PG_OSD_CONFIG, 7); +//PG_REGISTER_WITH_RESET_FN(osdLayoutsConfig_t, osdLayoutsConfig, PG_OSD_LAYOUTS_CONFIG, 1); + + #ifdef USE_OSD #include "build/debug.h" @@ -50,7 +61,6 @@ FILE_COMPILE_FOR_SPEED #include "common/printf.h" #include "common/string_light.h" #include "common/time.h" -#include "common/typeconversion.h" #include "common/utils.h" #include "config/feature.h" @@ -60,7 +70,6 @@ FILE_COMPILE_FOR_SPEED #include "drivers/display.h" #include "drivers/display_canvas.h" #include "drivers/display_font_metadata.h" -#include "drivers/osd_symbols.h" #include "drivers/time.h" #include "drivers/vtx_common.h" @@ -69,7 +78,6 @@ FILE_COMPILE_FOR_SPEED #include "io/osd.h" #include "io/osd_common.h" #include "io/osd_hud.h" -#include "io/displayport_msp_bf_compat.h" #include "io/vtx.h" #include "io/vtx_string.h" @@ -213,18 +221,7 @@ void osdShowEEPROMSavedNotification() { notify_settings_saved = millis() + 5000; } -static int digitCount(int32_t value) -{ - int digits = 1; - while(1) { - value = value / 10; - if (value == 0) { - break; - } - digits++; - } - return digits; -} + bool osdDisplayIsPAL(void) { @@ -4583,6 +4580,18 @@ textAttributes_t osdGetSystemMessage(char *buff, size_t buff_size, bool isCenter #endif // OSD #if defined(USE_OSD) || defined (OSD_UNIT_TEST) +static int digitCount(int32_t value) +{ + int digits = 1; + while(1) { + value = value / 10; + if (value == 0) { + break; + } + digits++; + } + return digits; +} /** * Formats a number given in cents, to support non integer values * without using floating point math. Value is always right aligned diff --git a/src/test/unit/CMakeLists.txt b/src/test/unit/CMakeLists.txt index ea26b42e6f..374e9d0bb2 100644 --- a/src/test/unit/CMakeLists.txt +++ b/src/test/unit/CMakeLists.txt @@ -34,8 +34,8 @@ set_property(SOURCE time_unittest.cc PROPERTY depends "drivers/time.c") set_property(SOURCE circular_queue_unittest.cc PROPERTY depends "common/circular_queue.c") -set_property(SOURCE osd_unittest.cc PROPERTY depends "io/osd.c") -set_property(SOURCE osd_unittest.cc PROPERTY definitions OSD_UNIT_TEST) +set_property(SOURCE osd_unittest.cc PROPERTY depends "io/osd.c" "io/displayport_msp_osd.c" "common/typeconversion.c") +set_property(SOURCE osd_unittest.cc PROPERTY definitions OSD_UNIT_TEST USE_MSP_DISPLAYPORT DISABLE_MSP_BF_COMPAT) function(unit_test src) get_filename_component(basename ${src} NAME) diff --git a/src/test/unit/osd_unittest.cc b/src/test/unit/osd_unittest.cc index 0ad2849aac..2918eb3106 100644 --- a/src/test/unit/osd_unittest.cc +++ b/src/test/unit/osd_unittest.cc @@ -12,11 +12,57 @@ extern "C" { TEST(OSDTest, TestCentiNumber) { //bool osdFormatCentiNumber(char *buff, int32_t centivalue, uint32_t scale, int maxDecimals, int maxScaledDecimals, int length); - char buf[10] = ""; + char buf[11] = "0123456789"; - osdFormatCentiNumber(buf, 10000, 1, 2, 2, 5); + osdFormatCentiNumber(buf, 12345, 1, 2, 3, 5); + std::cout << "'" << buf << "'" << std::endl; + EXPECT_FALSE(strcmp(buf, "123.4")); - std::cout << buf << std::endl; + memset(buf, 0, 11); + osdFormatCentiNumber(buf, 12345, 1, 2, 2, 6); + std::cout << "'" << buf << "'" << std::endl; + EXPECT_FALSE(strcmp(buf, "123.45")); + + memset(buf, 0, 11); + osdFormatCentiNumber(buf, 12345, 1, 2, 2, 4); + std::cout << "'" << buf << "'" << std::endl; + EXPECT_FALSE(strcmp(buf, "123")); + + memset(buf, 0, 11); + osdFormatCentiNumber(buf, 12345, 1, 2, 2, 3); + std::cout << "'" << buf << "'" << std::endl; + EXPECT_FALSE(strcmp(buf, "123")); + + memset(buf, 0, 11); + osdFormatCentiNumber(buf, 12345, 1, 2, 2, 1); + std::cout << "'" << buf << "'" << std::endl; + EXPECT_FALSE(strcmp(buf, "123")); + std::cout << "'" << buf << "'" << std::endl; + + memset(buf, 0, 11); + osdFormatCentiNumber(buf, -12345, 1, 2, 2, 5); + std::cout << "'" << buf << "'" << std::endl; + EXPECT_FALSE(strcmp(buf, "-123")); + + memset(buf, 0, 11); + osdFormatCentiNumber(buf, -12345, 1, 2, 2, 6); + std::cout << "'" << buf << "'" << std::endl; + EXPECT_FALSE(strcmp(buf, "-123.4")); + + memset(buf, 0, 11); + osdFormatCentiNumber(buf, -12345, 1, 2, 2, 4); + std::cout << "'" << buf << "'" << std::endl; + EXPECT_FALSE(strcmp(buf, "-123")); + + memset(buf, 0, 11); + osdFormatCentiNumber(buf, -12345, 1, 2, 2, 3); + std::cout << "'" << buf << "'" << std::endl; + EXPECT_FALSE(strcmp(buf, "-123")); + + memset(buf, 0, 11); + osdFormatCentiNumber(buf, -12345, 1, 2, 2, 1); + std::cout << "'" << buf << "'" << std::endl; + EXPECT_FALSE(strcmp(buf, "-123")); EXPECT_EQ(1, 1); From ad219fa0927b2fa414901a0f367543234cc408d8 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Tue, 7 Feb 2023 23:03:31 +0100 Subject: [PATCH 032/130] Unit tests to valid issue --- src/test/unit/osd_unittest.cc | 42 ++++++++++++++++++----------------- 1 file changed, 22 insertions(+), 20 deletions(-) diff --git a/src/test/unit/osd_unittest.cc b/src/test/unit/osd_unittest.cc index 2918eb3106..6a8aa6f091 100644 --- a/src/test/unit/osd_unittest.cc +++ b/src/test/unit/osd_unittest.cc @@ -14,56 +14,58 @@ TEST(OSDTest, TestCentiNumber) //bool osdFormatCentiNumber(char *buff, int32_t centivalue, uint32_t scale, int maxDecimals, int maxScaledDecimals, int length); char buf[11] = "0123456789"; - osdFormatCentiNumber(buf, 12345, 1, 2, 3, 5); + osdFormatCentiNumber(buf, 12345, 1, 2, 3, 7); std::cout << "'" << buf << "'" << std::endl; - EXPECT_FALSE(strcmp(buf, "123.4")); + EXPECT_FALSE(strcmp(buf, " 123.45")); memset(buf, 0, 11); osdFormatCentiNumber(buf, 12345, 1, 2, 2, 6); std::cout << "'" << buf << "'" << std::endl; EXPECT_FALSE(strcmp(buf, "123.45")); + memset(buf, 0, 11); + osdFormatCentiNumber(buf, 12345, 1, 2, 2, 5); + std::cout << "'" << buf << "'" << std::endl; + EXPECT_FALSE(strcmp(buf, "123.4")); + memset(buf, 0, 11); osdFormatCentiNumber(buf, 12345, 1, 2, 2, 4); std::cout << "'" << buf << "'" << std::endl; - EXPECT_FALSE(strcmp(buf, "123")); + EXPECT_FALSE(strcmp(buf, " 123")); // this should be causing #8769 memset(buf, 0, 11); osdFormatCentiNumber(buf, 12345, 1, 2, 2, 3); std::cout << "'" << buf << "'" << std::endl; EXPECT_FALSE(strcmp(buf, "123")); - - memset(buf, 0, 11); - osdFormatCentiNumber(buf, 12345, 1, 2, 2, 1); - std::cout << "'" << buf << "'" << std::endl; - EXPECT_FALSE(strcmp(buf, "123")); std::cout << "'" << buf << "'" << std::endl; memset(buf, 0, 11); - osdFormatCentiNumber(buf, -12345, 1, 2, 2, 5); + osdFormatCentiNumber(buf, -12345, 1, 2, 2, 8); std::cout << "'" << buf << "'" << std::endl; - EXPECT_FALSE(strcmp(buf, "-123")); + EXPECT_FALSE(strcmp(buf, " -123.45")); + + + + memset(buf, 0, 11); + osdFormatCentiNumber(buf, -12345, 1, 2, 2, 7); + std::cout << "'" << buf << "'" << std::endl; + EXPECT_FALSE(strcmp(buf, "-123.45")); memset(buf, 0, 11); osdFormatCentiNumber(buf, -12345, 1, 2, 2, 6); std::cout << "'" << buf << "'" << std::endl; EXPECT_FALSE(strcmp(buf, "-123.4")); + memset(buf, 0, 11); + osdFormatCentiNumber(buf, -12345, 1, 2, 2, 5); + std::cout << "'" << buf << "'" << std::endl; + EXPECT_FALSE(strcmp(buf, " -123")); + memset(buf, 0, 11); osdFormatCentiNumber(buf, -12345, 1, 2, 2, 4); std::cout << "'" << buf << "'" << std::endl; EXPECT_FALSE(strcmp(buf, "-123")); - memset(buf, 0, 11); - osdFormatCentiNumber(buf, -12345, 1, 2, 2, 3); - std::cout << "'" << buf << "'" << std::endl; - EXPECT_FALSE(strcmp(buf, "-123")); - - memset(buf, 0, 11); - osdFormatCentiNumber(buf, -12345, 1, 2, 2, 1); - std::cout << "'" << buf << "'" << std::endl; - EXPECT_FALSE(strcmp(buf, "-123")); - EXPECT_EQ(1, 1); } \ No newline at end of file From 24bbe6e347facd4bda02a4e5418668dc74f59080 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Tue, 7 Feb 2023 23:32:13 +0100 Subject: [PATCH 033/130] Handle special case when only . is left to keep numbers aligned to the right. --- src/main/io/osd.c | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index f10c8ac031..2cfd2045bb 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -4645,7 +4645,6 @@ bool osdFormatCentiNumber(char *buff, int32_t centivalue, uint32_t scale, int ma remaining -= decimals; // Done counting. Time to write the characters. - // Write spaces at the start while (remaining > 0) { *ptr = SYM_BLANK; @@ -4653,6 +4652,15 @@ bool osdFormatCentiNumber(char *buff, int32_t centivalue, uint32_t scale, int ma remaining--; } + if(explicitDecimal && decimals == 0) + { + if ((digits + 1) == length) { + *ptr = SYM_BLANK; + ptr++; + remaining--; + } + } + // Write the minus sign if required if (negative) { *ptr = '-'; From bd3caf65dec892dd3f54b0ccd9f0177572324fc7 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Tue, 7 Feb 2023 23:36:20 +0100 Subject: [PATCH 034/130] Add comment --- src/main/io/osd.c | 1 + 1 file changed, 1 insertion(+) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 2cfd2045bb..577e7785d6 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -4652,6 +4652,7 @@ bool osdFormatCentiNumber(char *buff, int32_t centivalue, uint32_t scale, int ma remaining--; } + // Keep number right aligned and correct length if(explicitDecimal && decimals == 0) { if ((digits + 1) == length) { From 595b17b2fd5e20bf2fd1552fe2ac63df75b404be Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Tue, 7 Feb 2023 23:40:47 +0100 Subject: [PATCH 035/130] formatting changes --- src/main/io/osd.c | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 577e7785d6..6809f06c37 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -4653,8 +4653,7 @@ bool osdFormatCentiNumber(char *buff, int32_t centivalue, uint32_t scale, int ma } // Keep number right aligned and correct length - if(explicitDecimal && decimals == 0) - { + if(explicitDecimal && decimals == 0) { if ((digits + 1) == length) { *ptr = SYM_BLANK; ptr++; From f727232a195a67591926174c821f60ad2f27e5c8 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Tue, 7 Feb 2023 23:50:01 +0100 Subject: [PATCH 036/130] Move things around for build. This probably needs some extra refactoring, shuffling for a cleanner look --- src/main/io/osd.c | 26 ++++++++++++++------------ 1 file changed, 14 insertions(+), 12 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 6809f06c37..ed74f698f8 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -43,6 +43,20 @@ FILE_COMPILE_FOR_SPEED //PG_REGISTER_WITH_RESET_TEMPLATE(osdConfig_t, osdConfig, PG_OSD_CONFIG, 7); //PG_REGISTER_WITH_RESET_FN(osdLayoutsConfig_t, osdLayoutsConfig, PG_OSD_LAYOUTS_CONFIG, 1); +#if defined(USE_OSD) || defined (OSD_UNIT_TEST) +static int digitCount(int32_t value) +{ + int digits = 1; + while(1) { + value = value / 10; + if (value == 0) { + break; + } + digits++; + } + return digits; +} +#endif #ifdef USE_OSD @@ -4580,18 +4594,6 @@ textAttributes_t osdGetSystemMessage(char *buff, size_t buff_size, bool isCenter #endif // OSD #if defined(USE_OSD) || defined (OSD_UNIT_TEST) -static int digitCount(int32_t value) -{ - int digits = 1; - while(1) { - value = value / 10; - if (value == 0) { - break; - } - digits++; - } - return digits; -} /** * Formats a number given in cents, to support non integer values * without using floating point math. Value is always right aligned From 14404e0c57aeb8b471f9c24e7ab58761de311e55 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Wed, 8 Feb 2023 09:42:57 +0100 Subject: [PATCH 037/130] Cleanup changes and move testable code to a separate file --- src/main/CMakeLists.txt | 2 + src/main/io/osd.c | 139 ++--------------------------------- src/main/io/osd_utils.c | 126 +++++++++++++++++++++++++++++++ src/main/io/osd_utils.h | 38 ++++++++++ src/test/unit/CMakeLists.txt | 2 +- 5 files changed, 172 insertions(+), 135 deletions(-) create mode 100644 src/main/io/osd_utils.c create mode 100644 src/main/io/osd_utils.h diff --git a/src/main/CMakeLists.txt b/src/main/CMakeLists.txt index 317da760b6..3d38b16943 100644 --- a/src/main/CMakeLists.txt +++ b/src/main/CMakeLists.txt @@ -498,6 +498,8 @@ main_sources(COMMON_SRC io/ledstrip.h io/osd.c io/osd.h + io/osd_utils.c + io/osd_utils.h io/osd_canvas.c io/osd_canvas.h io/osd_common.c diff --git a/src/main/io/osd.c b/src/main/io/osd.c index ed74f698f8..733f3ce561 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -33,31 +33,6 @@ FILE_COMPILE_FOR_SPEED -#include "drivers/osd_symbols.h" -#include "common/maths.h" -#include "io/displayport_msp_bf_compat.h" -#include "config/parameter_group.h" -#include "config/parameter_group_ids.h" -#include "common/typeconversion.h" - -//PG_REGISTER_WITH_RESET_TEMPLATE(osdConfig_t, osdConfig, PG_OSD_CONFIG, 7); -//PG_REGISTER_WITH_RESET_FN(osdLayoutsConfig_t, osdLayoutsConfig, PG_OSD_LAYOUTS_CONFIG, 1); - -#if defined(USE_OSD) || defined (OSD_UNIT_TEST) -static int digitCount(int32_t value) -{ - int digits = 1; - while(1) { - value = value / 10; - if (value == 0) { - break; - } - digits++; - } - return digits; -} -#endif - #ifdef USE_OSD #include "build/debug.h" @@ -75,6 +50,7 @@ static int digitCount(int32_t value) #include "common/printf.h" #include "common/string_light.h" #include "common/time.h" +#include "common/typeconversion.h" #include "common/utils.h" #include "config/feature.h" @@ -84,6 +60,7 @@ static int digitCount(int32_t value) #include "drivers/display.h" #include "drivers/display_canvas.h" #include "drivers/display_font_metadata.h" +#include "drivers/osd_symbols.h" #include "drivers/time.h" #include "drivers/vtx_common.h" @@ -92,6 +69,8 @@ static int digitCount(int32_t value) #include "io/osd.h" #include "io/osd_common.h" #include "io/osd_hud.h" +#include "io/osd_utils.h" +#include "io/displayport_msp_bf_compat.h" #include "io/vtx.h" #include "io/vtx_string.h" @@ -4591,112 +4570,4 @@ textAttributes_t osdGetSystemMessage(char *buff, size_t buff_size, bool isCenter return elemAttr; } -#endif // OSD - -#if defined(USE_OSD) || defined (OSD_UNIT_TEST) -/** - * Formats a number given in cents, to support non integer values - * without using floating point math. Value is always right aligned - * and spaces are inserted before the number to always yield a string - * of the same length. If the value doesn't fit into the provided length - * it will be divided by scale and true will be returned. - */ -bool osdFormatCentiNumber(char *buff, int32_t centivalue, uint32_t scale, int maxDecimals, int maxScaledDecimals, int length) -{ - char *ptr = buff; - char *dec; - int decimals = maxDecimals; - bool negative = false; - bool scaled = false; - bool explicitDecimal = isBfCompatibleVideoSystem(osdConfig()); - - buff[length] = '\0'; - - if (centivalue < 0) { - negative = true; - centivalue = -centivalue; - length--; - } - - int32_t integerPart = centivalue / 100; - // 3 decimal digits - int32_t millis = (centivalue % 100) * 10; - - int digits = digitCount(integerPart); - int remaining = length - digits; - if (explicitDecimal) { - remaining--; - } - - if (remaining < 0 && scale > 0) { - // Reduce by scale - scaled = true; - decimals = maxScaledDecimals; - integerPart = integerPart / scale; - // Multiply by 10 to get 3 decimal digits - millis = ((centivalue % (100 * scale)) * 10) / scale; - digits = digitCount(integerPart); - remaining = length - digits; - if (explicitDecimal) { - remaining--; - } - } - - // 3 decimals at most - decimals = MIN(remaining, MIN(decimals, 3)); - remaining -= decimals; - - // Done counting. Time to write the characters. - // Write spaces at the start - while (remaining > 0) { - *ptr = SYM_BLANK; - ptr++; - remaining--; - } - - // Keep number right aligned and correct length - if(explicitDecimal && decimals == 0) { - if ((digits + 1) == length) { - *ptr = SYM_BLANK; - ptr++; - remaining--; - } - } - - // Write the minus sign if required - if (negative) { - *ptr = '-'; - ptr++; - } - // Now write the digits. - ui2a(integerPart, 10, 0, ptr); - ptr += digits; - - if (decimals > 0) { - if (explicitDecimal) { - *ptr = '.'; - ptr++; - } else { - *(ptr - 1) += SYM_ZERO_HALF_TRAILING_DOT - '0'; - } - dec = ptr; - int factor = 3; // we're getting the decimal part in millis first - while (decimals < factor) { - factor--; - millis /= 10; - } - int decimalDigits = digitCount(millis); - while (decimalDigits < decimals) { - decimalDigits++; - *ptr = '0'; - ptr++; - } - ui2a(millis, 10, 0, ptr); - if (!explicitDecimal) { - *dec += SYM_ZERO_HALF_LEADING_DOT - '0'; - } - } - return scaled; -} - -#endif \ No newline at end of file +#endif // OSD \ No newline at end of file diff --git a/src/main/io/osd_utils.c b/src/main/io/osd_utils.c new file mode 100644 index 0000000000..defb291fc9 --- /dev/null +++ b/src/main/io/osd_utils.c @@ -0,0 +1,126 @@ +#include "io/osd_utils.h" + +#include "drivers/osd_symbols.h" +#include "common/maths.h" +#include "io/displayport_msp_bf_compat.h" +#include "config/parameter_group.h" +#include "config/parameter_group_ids.h" +#include "common/typeconversion.h" + + +FILE_COMPILE_FOR_SPEED + +#if defined(USE_OSD) || defined(OSD_UNIT_TEST) + +int digitCount(int32_t value) +{ + int digits = 1; + while(1) { + value = value / 10; + if (value == 0) { + break; + } + digits++; + } + return digits; +} + + +bool osdFormatCentiNumber(char *buff, int32_t centivalue, uint32_t scale, int maxDecimals, int maxScaledDecimals, int length) +{ + char *ptr = buff; + char *dec; + int decimals = maxDecimals; + bool negative = false; + bool scaled = false; + bool explicitDecimal = isBfCompatibleVideoSystem(osdConfig()); + + buff[length] = '\0'; + + if (centivalue < 0) { + negative = true; + centivalue = -centivalue; + length--; + } + + int32_t integerPart = centivalue / 100; + // 3 decimal digits + int32_t millis = (centivalue % 100) * 10; + + int digits = digitCount(integerPart); + int remaining = length - digits; + if (explicitDecimal) { + remaining--; + } + + if (remaining < 0 && scale > 0) { + // Reduce by scale + scaled = true; + decimals = maxScaledDecimals; + integerPart = integerPart / scale; + // Multiply by 10 to get 3 decimal digits + millis = ((centivalue % (100 * scale)) * 10) / scale; + digits = digitCount(integerPart); + remaining = length - digits; + if (explicitDecimal) { + remaining--; + } + } + + // 3 decimals at most + decimals = MIN(remaining, MIN(decimals, 3)); + remaining -= decimals; + + // Done counting. Time to write the characters. + // Write spaces at the start + while (remaining > 0) { + *ptr = SYM_BLANK; + ptr++; + remaining--; + } + + // Keep number right aligned and correct length + if(explicitDecimal && decimals == 0) { + if ((digits + 1) == length) { + *ptr = SYM_BLANK; + ptr++; + remaining--; + } + } + + // Write the minus sign if required + if (negative) { + *ptr = '-'; + ptr++; + } + // Now write the digits. + ui2a(integerPart, 10, 0, ptr); + ptr += digits; + + if (decimals > 0) { + if (explicitDecimal) { + *ptr = '.'; + ptr++; + } else { + *(ptr - 1) += SYM_ZERO_HALF_TRAILING_DOT - '0'; + } + dec = ptr; + int factor = 3; // we're getting the decimal part in millis first + while (decimals < factor) { + factor--; + millis /= 10; + } + int decimalDigits = digitCount(millis); + while (decimalDigits < decimals) { + decimalDigits++; + *ptr = '0'; + ptr++; + } + ui2a(millis, 10, 0, ptr); + if (!explicitDecimal) { + *dec += SYM_ZERO_HALF_LEADING_DOT - '0'; + } + } + return scaled; +} +#endif \ No newline at end of file diff --git a/src/main/io/osd_utils.h b/src/main/io/osd_utils.h new file mode 100644 index 0000000000..2f9c61a320 --- /dev/null +++ b/src/main/io/osd_utils.h @@ -0,0 +1,38 @@ +/* + * This file is part of INAV + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + +#include +#include + +#include "platform.h" + +#if defined(USE_OSD) || defined(OSD_UNIT_TEST) + +int digitCount(int32_t value); + +/** + * Formats a number given in cents, to support non integer values + * without using floating point math. Value is always right aligned + * and spaces are inserted before the number to always yield a string + * of the same length. If the value doesn't fit into the provided length + * it will be divided by scale and true will be returned. + */ +bool osdFormatCentiNumber(char *buff, int32_t centivalue, uint32_t scale, int maxDecimals, int maxScaledDecimals, int length); + +#endif diff --git a/src/test/unit/CMakeLists.txt b/src/test/unit/CMakeLists.txt index 374e9d0bb2..abb9389fbb 100644 --- a/src/test/unit/CMakeLists.txt +++ b/src/test/unit/CMakeLists.txt @@ -34,7 +34,7 @@ set_property(SOURCE time_unittest.cc PROPERTY depends "drivers/time.c") set_property(SOURCE circular_queue_unittest.cc PROPERTY depends "common/circular_queue.c") -set_property(SOURCE osd_unittest.cc PROPERTY depends "io/osd.c" "io/displayport_msp_osd.c" "common/typeconversion.c") +set_property(SOURCE osd_unittest.cc PROPERTY depends "io/osd_utils.c" "io/displayport_msp_osd.c" "common/typeconversion.c") set_property(SOURCE osd_unittest.cc PROPERTY definitions OSD_UNIT_TEST USE_MSP_DISPLAYPORT DISABLE_MSP_BF_COMPAT) function(unit_test src) From 994e0b206c3e6c00d333015c1f4c620feff67d6d Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Wed, 8 Feb 2023 09:59:37 +0100 Subject: [PATCH 038/130] Cleanup includes --- src/main/io/osd_utils.c | 24 +++++++++++++++++++----- 1 file changed, 19 insertions(+), 5 deletions(-) diff --git a/src/main/io/osd_utils.c b/src/main/io/osd_utils.c index defb291fc9..7e695276f4 100644 --- a/src/main/io/osd_utils.c +++ b/src/main/io/osd_utils.c @@ -1,12 +1,26 @@ +/* + * This file is part of INAV + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + #include "io/osd_utils.h" -#include "drivers/osd_symbols.h" #include "common/maths.h" -#include "io/displayport_msp_bf_compat.h" -#include "config/parameter_group.h" -#include "config/parameter_group_ids.h" #include "common/typeconversion.h" - +#include "drivers/osd_symbols.h" +#include "io/displayport_msp_bf_compat.h" FILE_COMPILE_FOR_SPEED From 7dcf095b7ada7141b2bae7997b96443359437b76 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Wed, 8 Feb 2023 16:53:06 +0100 Subject: [PATCH 039/130] Simplify and fix altitude processing for BF43COMPAT --- src/main/io/displayport_msp_bf_compat.c | 13 +++---- src/main/io/osd.c | 45 +++++++++++++++++++++++-- 2 files changed, 50 insertions(+), 8 deletions(-) diff --git a/src/main/io/displayport_msp_bf_compat.c b/src/main/io/displayport_msp_bf_compat.c index b6b1fe9d81..792ab800dd 100644 --- a/src/main/io/displayport_msp_bf_compat.c +++ b/src/main/io/displayport_msp_bf_compat.c @@ -176,6 +176,13 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) */ case SYM_FT: return BF_SYM_FT; + + case SYM_ALT_FT: + return BF_SYM_FT; + + case SYM_ALT_M: + return BF_SYM_M; + /* case SYM_TRIP_DIST: return BF_SYM_TRIP_DIST; @@ -183,15 +190,9 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) case SYM_TOTAL: return BF_SYM_TOTAL; - case SYM_ALT_M: - return BF_SYM_ALT_M; - case SYM_ALT_KM: return BF_SYM_ALT_KM; - case SYM_ALT_FT: - return BF_SYM_ALT_FT; - case SYM_ALT_KFT: return BF_SYM_ALT_KFT; diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 70a2889116..344c8b1087 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -437,6 +437,37 @@ static void osdFormatWindSpeedStr(char *buff, int32_t ws, bool isValid) } #endif +/* + * This is a simplified altitude conversion code that does not use any scaling + * but is fully compatible with the DJI G2 MSP Displayport OSD implementation. + */ +void osdSimpleAltitudeSymbol(char *buff, int32_t alt) { + + int32_t convertedAltutude; + char suffix; + + switch ((osd_unit_e)osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_GA: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + convertedAltutude = CENTIMETERS_TO_FEET(alt); + suffix = SYM_ALT_FT; + break; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + convertedAltutude = CENTIMETERS_TO_METERS(alt); + suffix = SYM_ALT_M; + break; + } + + tfp_sprintf(buff, "%4d", convertedAltutude); + buff[4] = suffix; + buff[5] = '\0'; +} + /** * Converts altitude into a string based on the current unit system * prefixed by a a symbol to indicate the unit used. @@ -1818,7 +1849,13 @@ static bool osdDrawSingleElement(uint8_t item) case OSD_ALTITUDE: { int32_t alt = osdGetAltitude(); - osdFormatAltitudeSymbol(buff, alt); + + if (isBfCompatibleVideoSystem(osdConfig())) { + osdSimpleAltitudeSymbol(buff, alt); + } else { + osdFormatAltitudeSymbol(buff, alt); + } + uint16_t alt_alarm = osdConfig()->alt_alarm; uint16_t neg_alt_alarm = osdConfig()->neg_alt_alarm; if ((alt_alarm > 0 && CENTIMETERS_TO_METERS(alt) > alt_alarm) || @@ -1832,7 +1869,11 @@ static bool osdDrawSingleElement(uint8_t item) case OSD_ALTITUDE_MSL: { int32_t alt = osdGetAltitudeMsl(); - osdFormatAltitudeSymbol(buff, alt); + if (isBfCompatibleVideoSystem(osdConfig())) { + osdSimpleAltitudeSymbol(buff, alt); + } else { + osdFormatAltitudeSymbol(buff, alt); + } break; } From 4f7dc8e5cc88f341ee38d85bb2aa0a755381446e Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Wed, 8 Feb 2023 18:32:08 +0100 Subject: [PATCH 040/130] Fix casting --- src/main/io/osd.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 344c8b1087..25e9bfd145 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -463,7 +463,7 @@ void osdSimpleAltitudeSymbol(char *buff, int32_t alt) { break; } - tfp_sprintf(buff, "%4d", convertedAltutude); + tfp_sprintf(buff, "%4d", (int) convertedAltutude); buff[4] = suffix; buff[5] = '\0'; } From 3ad11fb3d8db46fa9560f7cd8823dc3ecdb68626 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Wed, 8 Feb 2023 22:29:46 +0000 Subject: [PATCH 041/130] remove unused code --- src/main/sensors/battery.c | 5 ----- src/main/sensors/battery.h | 1 - 2 files changed, 6 deletions(-) diff --git a/src/main/sensors/battery.c b/src/main/sensors/battery.c index 6646f8f57d..168ef81f63 100644 --- a/src/main/sensors/battery.c +++ b/src/main/sensors/battery.c @@ -478,11 +478,6 @@ float calculateThrottleCompensationFactor(void) return 1.0f + ((float)batteryFullVoltage / sagCompensatedVBat - 1.0f) * batteryMetersConfig()->throttle_compensation_weight; } -uint16_t getBatteryWarningVoltage(void) -{ - return batteryWarningVoltage; -} - uint8_t getBatteryCellCount(void) { return batteryCellCount; diff --git a/src/main/sensors/battery.h b/src/main/sensors/battery.h index 4e2e4b47e1..0ecde181b3 100644 --- a/src/main/sensors/battery.h +++ b/src/main/sensors/battery.h @@ -76,7 +76,6 @@ bool isPowerSupplyImpedanceValid(void); uint16_t getBatteryVoltage(void); uint16_t getBatteryRawVoltage(void); uint16_t getBatterySagCompensatedVoltage(void); -uint16_t getBatteryWarningVoltage(void); uint8_t getBatteryCellCount(void); uint16_t getBatteryRawAverageCellVoltage(void); uint16_t getBatteryAverageCellVoltage(void); From c352dcf7802c13e685898a69f4dab739cf487b0d Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Sun, 12 Feb 2023 11:04:03 +0000 Subject: [PATCH 042/130] Update cms.c --- src/main/cms/cms.c | 1 + 1 file changed, 1 insertion(+) diff --git a/src/main/cms/cms.c b/src/main/cms/cms.c index 8341cda584..07ab3219a7 100644 --- a/src/main/cms/cms.c +++ b/src/main/cms/cms.c @@ -875,6 +875,7 @@ long cmsMenuExit(displayPort_t *pDisplay, const void *ptr) setServoOutputEnabled(true); if ((exitType == CMS_EXIT_SAVEREBOOT) || (exitType == CMS_POPUP_SAVEREBOOT)) { + processDelayedSave(); displayClearScreen(pDisplay); displayWrite(pDisplay, 5, 3, "REBOOTING..."); From 389e9e9bc86f46b8abc6cda8d91f2d66dca638b8 Mon Sep 17 00:00:00 2001 From: EMSR Date: Sun, 29 Jan 2023 22:53:45 +0800 Subject: [PATCH 043/130] add at32 bsp driver lib Co-Authored-By: EMSR <10240646+shanggl@users.noreply.github.com> Co-Authored-By: carl <101383042+tcdddd@users.noreply.github.com> Co-Authored-By: Hugo Chiang --- CMakeLists.txt | 1 + board/at32fc.cfg | 9 + cmake/at32-bootloader.cmake | 33 + cmake/at32-stdperiph.cmake | 4 + cmake/at32.cmake | 430 + cmake/at32f4-usb.cmake | 45 + cmake/at32f4.cmake | 114 + dev/svd/AT32F437xx_v2.svd | 58291 ++++++++++++++++ .../inc/at32f435_437_acc.h | 205 + .../inc/at32f435_437_adc.h | 938 + .../inc/at32f435_437_can.h | 1042 + .../inc/at32f435_437_crc.h | 172 + .../inc/at32f435_437_crm.h | 1572 + .../inc/at32f435_437_dac.h | 394 + .../inc/at32f435_437_debug.h | 208 + .../inc/at32f435_437_def.h | 74 + .../inc/at32f435_437_dma.h | 785 + .../inc/at32f435_437_dvp.h | 622 + .../inc/at32f435_437_edma.h | 1064 + .../inc/at32f435_437_emac.h | 1711 + .../inc/at32f435_437_ertc.h | 1209 + .../inc/at32f435_437_exint.h | 234 + .../inc/at32f435_437_flash.h | 724 + .../inc/at32f435_437_gpio.h | 565 + .../inc/at32f435_437_i2c.h | 479 + .../inc/at32f435_437_misc.h | 125 + .../inc/at32f435_437_pwc.h | 232 + .../inc/at32f435_437_qspi.h | 555 + .../inc/at32f435_437_scfg.h | 323 + .../inc/at32f435_437_sdio.h | 624 + .../inc/at32f435_437_spi.h | 505 + .../inc/at32f435_437_tmr.h | 1006 + .../inc/at32f435_437_usart.h | 412 + .../inc/at32f435_437_usb.h | 1423 + .../inc/at32f435_437_wdt.h | 197 + .../inc/at32f435_437_wwdt.h | 158 + .../inc/at32f435_437_xmc.h | 1075 + .../src/at32f435_437_acc.c | 231 + .../src/at32f435_437_adc.c | 1215 + .../src/at32f435_437_can.c | 1148 + .../src/at32f435_437_crc.c | 164 + .../src/at32f435_437_crm.c | 986 + .../src/at32f435_437_dac.c | 454 + .../src/at32f435_437_debug.c | 135 + .../src/at32f435_437_dma.c | 683 + .../src/at32f435_437_dvp.c | 528 + .../src/at32f435_437_edma.c | 931 + .../src/at32f435_437_emac.c | 2309 + .../src/at32f435_437_ertc.c | 1571 + .../src/at32f435_437_exint.c | 236 + .../src/at32f435_437_flash.c | 1158 + .../src/at32f435_437_gpio.c | 523 + .../src/at32f435_437_i2c.c | 748 + .../src/at32f435_437_misc.c | 173 + .../src/at32f435_437_pwc.c | 250 + .../src/at32f435_437_qspi.c | 430 + .../src/at32f435_437_scfg.c | 220 + .../src/at32f435_437_sdio.c | 575 + .../src/at32f435_437_spi.c | 650 + .../src/at32f435_437_tmr.c | 1848 + .../src/at32f435_437_usart.c | 732 + .../src/at32f435_437_usb.c | 1096 + .../src/at32f435_437_wdt.c | 156 + .../src/at32f435_437_wwdt.c | 141 + .../src/at32f435_437_xmc.c | 909 + .../CMSIS/Device/ST/AT32F43x/at32f435_437.h | 783 + .../Device/ST/AT32F43x/at32f435_437_clock.c | 142 + .../Device/ST/AT32F43x/at32f435_437_clock.h | 46 + .../Device/ST/AT32F43x/at32f435_437_conf.h | 249 + .../cm4/core_support/arm_common_tables.h | 517 + .../cm4/core_support/arm_const_structs.h | 76 + .../CMSIS/cm4/core_support/arm_helium_utils.h | 348 + .../Drivers/CMSIS/cm4/core_support/arm_math.h | 8970 +++ .../CMSIS/cm4/core_support/arm_mve_tables.h | 235 + .../CMSIS/cm4/core_support/arm_vec_math.h | 372 + .../CMSIS/cm4/core_support/cmsis_armcc.h | 885 + .../CMSIS/cm4/core_support/cmsis_armclang.h | 1467 + .../cm4/core_support/cmsis_armclang_ltm.h | 1893 + .../CMSIS/cm4/core_support/cmsis_compiler.h | 283 + .../CMSIS/cm4/core_support/cmsis_gcc.h | 2177 + .../CMSIS/cm4/core_support/cmsis_iccarm.h | 968 + .../CMSIS/cm4/core_support/cmsis_version.h | 39 + .../Drivers/CMSIS/cm4/core_support/core_cm4.h | 2129 + .../CMSIS/cm4/core_support/mpu_armv7.h | 275 + .../CMSIS/cm4/core_support/mpu_armv8.h | 352 + .../CMSIS/cm4/core_support/pmu_armv8.h | 337 + .../Class/usbd_class/cdc/cdc_class.c | 439 + .../Class/usbd_class/cdc/cdc_class.h | 117 + .../Class/usbd_class/cdc/cdc_desc.c | 446 + .../Class/usbd_class/cdc/cdc_desc.h | 104 + .../Class/usbd_class/hid_iap/hid_iap_class.c | 342 + .../Class/usbd_class/hid_iap/hid_iap_class.h | 159 + .../Class/usbd_class/hid_iap/hid_iap_desc.c | 468 + .../Class/usbd_class/hid_iap/hid_iap_desc.h | 94 + .../Class/usbd_class/msc/msc_bot_scsi.c | 835 + .../Class/usbd_class/msc/msc_bot_scsi.h | 256 + .../Class/usbd_class/msc/msc_class.c | 298 + .../Class/usbd_class/msc/msc_class.h | 72 + .../Class/usbd_class/msc/msc_desc.c | 404 + .../Class/usbd_class/msc/msc_desc.h | 85 + .../usbh_class/usbh_cdc/usbh_cdc_class.c | 532 + .../usbh_class/usbh_cdc/usbh_cdc_class.h | 284 + .../usbh_class/usbh_hid/usbh_hid_class.c | 453 + .../usbh_class/usbh_hid/usbh_hid_class.h | 148 + .../usbh_class/usbh_hid/usbh_hid_keyboard.c | 255 + .../usbh_class/usbh_hid/usbh_hid_keyboard.h | 84 + .../usbh_class/usbh_hid/usbh_hid_mouse.c | 188 + .../usbh_class/usbh_hid/usbh_hid_mouse.h | 93 + .../usbh_class/usbh_msc/usbh_msc_bot_scsi.c | 671 + .../usbh_class/usbh_msc/usbh_msc_bot_scsi.h | 239 + .../usbh_class/usbh_msc/usbh_msc_class.c | 523 + .../usbh_class/usbh_msc/usbh_msc_class.h | 143 + .../Core/Inc/usb_conf.h | 219 + .../Core/Inc/usb_core.h | 136 + .../Core/Inc/usb_std.h | 385 + .../Core/Inc/usbd_core.h | 187 + .../Core/Inc/usbd_int.h | 82 + .../Core/Inc/usbd_sdr.h | 73 + .../Core/Inc/usbh_core.h | 375 + .../Core/Inc/usbh_ctrl.h | 109 + .../Core/Inc/usbh_int.h | 77 + .../Core/Src/usb_core.c | 188 + .../Core/Src/usbd_core.c | 884 + .../Core/Src/usbd_int.c | 538 + .../Core/Src/usbd_sdr.c | 535 + .../Core/Src/usbh_core.c | 1241 + .../Core/Src/usbh_ctrl.c | 976 + .../Core/Src/usbh_int.c | 529 + src/main/build/build_config.h | 5 +- src/main/navigation/navigation_fw_launch.c | 2 + src/main/platform.h | 13 + src/main/startup/startup_at32f435_437.s | 577 + src/main/target/link/at32_flash_f43xG.ld | 50 + src/main/target/link/at32_flash_f43xM.ld | 50 + src/main/target/link/at32_flash_f43xM_bl.ld | 52 + .../target/link/at32_flash_f43xM_for_bl.ld | 52 + src/main/target/link/at32_flash_f4_split.ld | 267 + src/main/target/system_at32f435_437.c | 186 + src/main/target/system_at32f435_437.h | 77 + 139 files changed, 135899 insertions(+), 1 deletion(-) create mode 100644 board/at32fc.cfg create mode 100644 cmake/at32-bootloader.cmake create mode 100644 cmake/at32-stdperiph.cmake create mode 100644 cmake/at32.cmake create mode 100644 cmake/at32f4-usb.cmake create mode 100644 cmake/at32f4.cmake create mode 100644 dev/svd/AT32F437xx_v2.svd create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_acc.h create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_adc.h create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_can.h create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_crc.h create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_crm.h create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_dac.h create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_debug.h create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_def.h create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_dma.h create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_dvp.h create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_edma.h create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_emac.h create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_ertc.h create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_exint.h create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_flash.h create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_gpio.h create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_i2c.h create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_misc.h create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_pwc.h create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_qspi.h create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_scfg.h create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_sdio.h create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_spi.h create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_tmr.h create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_usart.h create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_usb.h create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_wdt.h create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_wwdt.h create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_xmc.h create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_acc.c create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_adc.c create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_can.c create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_crc.c create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_crm.c create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_dac.c create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_debug.c create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_dma.c create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_dvp.c create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_edma.c create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_emac.c create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_ertc.c create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_exint.c create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_flash.c create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_gpio.c create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_i2c.c create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_misc.c create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_pwc.c create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_qspi.c create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_scfg.c create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_sdio.c create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_spi.c create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_tmr.c create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_usart.c create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_usb.c create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_wdt.c create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_wwdt.c create mode 100644 lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_xmc.c create mode 100644 lib/main/AT32F43x/Drivers/CMSIS/Device/ST/AT32F43x/at32f435_437.h create mode 100644 lib/main/AT32F43x/Drivers/CMSIS/Device/ST/AT32F43x/at32f435_437_clock.c create mode 100644 lib/main/AT32F43x/Drivers/CMSIS/Device/ST/AT32F43x/at32f435_437_clock.h create mode 100644 lib/main/AT32F43x/Drivers/CMSIS/Device/ST/AT32F43x/at32f435_437_conf.h create mode 100644 lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_common_tables.h create mode 100644 lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_const_structs.h create mode 100644 lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_helium_utils.h create mode 100644 lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_math.h create mode 100644 lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_mve_tables.h create mode 100644 lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_vec_math.h create mode 100644 lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_armcc.h create mode 100644 lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_armclang.h create mode 100644 lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_armclang_ltm.h create mode 100644 lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_compiler.h create mode 100644 lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_gcc.h create mode 100644 lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_iccarm.h create mode 100644 lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_version.h create mode 100644 lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/core_cm4.h create mode 100644 lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/mpu_armv7.h create mode 100644 lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/mpu_armv8.h create mode 100644 lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/pmu_armv8.h create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/cdc/cdc_class.c create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/cdc/cdc_class.h create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/cdc/cdc_desc.c create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/cdc/cdc_desc.h create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/hid_iap/hid_iap_class.c create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/hid_iap/hid_iap_class.h create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/hid_iap/hid_iap_desc.c create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/hid_iap/hid_iap_desc.h create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_bot_scsi.c create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_bot_scsi.h create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_class.c create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_class.h create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_desc.c create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_desc.h create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_cdc/usbh_cdc_class.c create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_cdc/usbh_cdc_class.h create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_class.c create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_class.h create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_keyboard.c create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_keyboard.h create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_mouse.c create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_mouse.h create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_msc/usbh_msc_bot_scsi.c create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_msc/usbh_msc_bot_scsi.h create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_msc/usbh_msc_class.c create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_msc/usbh_msc_class.h create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usb_conf.h create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usb_core.h create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usb_std.h create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbd_core.h create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbd_int.h create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbd_sdr.h create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbh_core.h create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbh_ctrl.h create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbh_int.h create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usb_core.c create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbd_core.c create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbd_int.c create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbd_sdr.c create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbh_core.c create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbh_ctrl.c create mode 100644 lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbh_int.c create mode 100644 src/main/startup/startup_at32f435_437.s create mode 100644 src/main/target/link/at32_flash_f43xG.ld create mode 100644 src/main/target/link/at32_flash_f43xM.ld create mode 100644 src/main/target/link/at32_flash_f43xM_bl.ld create mode 100644 src/main/target/link/at32_flash_f43xM_for_bl.ld create mode 100644 src/main/target/link/at32_flash_f4_split.ld create mode 100644 src/main/target/system_at32f435_437.c create mode 100644 src/main/target/system_at32f435_437.h diff --git a/CMakeLists.txt b/CMakeLists.txt index 04623c6774..86715075f5 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -71,6 +71,7 @@ set(COMMON_COMPILE_DEFINITIONS include(openocd) include(svd) include(stm32) +include(at32) add_subdirectory(src) diff --git a/board/at32fc.cfg b/board/at32fc.cfg new file mode 100644 index 0000000000..aeb34d8bc7 --- /dev/null +++ b/board/at32fc.cfg @@ -0,0 +1,9 @@ +# Boardconfig for AT-LINK for AT32F4-FC + +source [find interface/atlink.cfg] + +#transport select hla_swd + +source [find target/at32f437xM.cfg] + +reset_config none separate diff --git a/cmake/at32-bootloader.cmake b/cmake/at32-bootloader.cmake new file mode 100644 index 0000000000..857ae08a52 --- /dev/null +++ b/cmake/at32-bootloader.cmake @@ -0,0 +1,33 @@ +main_sources(BOOTLOADER_SOURCES + common/log.c + common/log.h + common/printf.c + common/printf.h + common/string_light.c + common/string_light.h + common/typeconversion.c + common/typeconversion.h + + drivers/bus.c + drivers/bus_busdev_i2c.c + drivers/bus_busdev_spi.c + drivers/bus_i2c_soft.c + drivers/io.c + drivers/light_led.c + drivers/persistent.c + drivers/rcc.c + drivers/serial.c + drivers/system.c + drivers/time.c + drivers/timer.c + drivers/flash_m25p16.c + drivers/flash_w25n01g.c + drivers/flash.c + + fc/firmware_update_common.c + fc/firmware_update_common.h + + target/common_hardware.c +) + +list(APPEND BOOTLOADER_SOURCES ${MAIN_DIR}/src/bl/bl_main.c) diff --git a/cmake/at32-stdperiph.cmake b/cmake/at32-stdperiph.cmake new file mode 100644 index 0000000000..66ef7b8852 --- /dev/null +++ b/cmake/at32-stdperiph.cmake @@ -0,0 +1,4 @@ +main_sources(AT32_STDPERIPH_SRC + drivers/bus_spi_at32f43x.c + drivers/serial_uart_hal_at32f43x.c +) diff --git a/cmake/at32.cmake b/cmake/at32.cmake new file mode 100644 index 0000000000..2722798669 --- /dev/null +++ b/cmake/at32.cmake @@ -0,0 +1,430 @@ +include(at32-bootloader) +include(at32f4) + +include(CMakeParseArguments) + +option(DEBUG_HARDFAULTS "Enable debugging of hard faults via custom handler") +option(SEMIHOSTING "Enable semihosting") + +message("-- DEBUG_HARDFAULTS: ${DEBUG_HARDFAULTS}, SEMIHOSTING: ${SEMIHOSTING}") + +set(CMSIS_DIR "${MAIN_LIB_DIR}/lib/main/AT32F43x/Drivers/CMSIS") +set(CMSIS_INCLUDE_DIR "${CMSIS_DIR}/cm4/core_support") +# DSP use common +set(CMSIS_DSP_DIR "${MAIN_LIB_DIR}/main/CMSIS/DSP") +set(CMSIS_DSP_INCLUDE_DIR "${CMSIS_DSP_DIR}/Include") + +set(CMSIS_DSP_SRC + BasicMathFunctions/arm_mult_f32.c + TransformFunctions/arm_rfft_fast_f32.c + TransformFunctions/arm_cfft_f32.c + TransformFunctions/arm_rfft_fast_init_f32.c + TransformFunctions/arm_cfft_radix8_f32.c + TransformFunctions/arm_bitreversal2.S + CommonTables/arm_common_tables.c + ComplexMathFunctions/arm_cmplx_mag_f32.c + StatisticsFunctions/arm_max_f32.c +) +list(TRANSFORM CMSIS_DSP_SRC PREPEND "${CMSIS_DSP_DIR}/Source/") + +set(AT32_STARTUP_DIR "${MAIN_SRC_DIR}/startup") + +main_sources(AT32_VCP_SRC + drivers/serial_usb_vcp_at32f43x.c + drivers/usb_io.c +) +# SDCARD not supported yet +main_sources(AT32_SDCARD_SRC + drivers/sdcard/sdcard.c + drivers/sdcard/sdcard_spi.c + drivers/sdcard/sdcard_sdio.c + drivers/sdcard/sdcard_standard.c +) + +# XXX: This code is not STM32 specific +main_sources(AT32_ASYNCFATFS_SRC + io/asyncfatfs/asyncfatfs.c + io/asyncfatfs/fat_standard.c +) + +main_sources(AT32_MSC_SRC + msc/at32_msc_diskio.c + msc/emfat.c + msc/emfat_file.c +) + +set(AT32_INCLUDE_DIRS + "${CMSIS_INCLUDE_DIR}" + "${CMSIS_DSP_INCLUDE_DIR}" + "${MAIN_SRC_DIR}/target" +) + +set(AT32_DEFINITIONS +) +set(AT32_DEFAULT_HSE_MHZ 8) +set(AT32_LINKER_DIR "${MAIN_SRC_DIR}/target/link") +set(AT32_COMPILE_OPTIONS + -ffunction-sections + -fdata-sections + -fno-common +) + +set(AT32_LINK_LIBRARIES + -lm + -lc +) + +if(SEMIHOSTING) + list(APPEND AT32_LINK_LIBRARIES --specs=rdimon.specs -lrdimon) + list(APPEND AT32_DEFINITIONS SEMIHOSTING) +else() + list(APPEND AT32_LINK_LIBRARIES -lnosys) +endif() + +set(AT32_LINK_OPTIONS + #-nostartfiles + --specs=nano.specs + -static + -Wl,-gc-sections + -Wl,-L${AT32_LINKER_DIR} + -Wl,--cref + -Wl,--no-wchar-size-warning + -Wl,--print-memory-usage +) +# Get target features +macro(get_at32_target_features output_var dir target_name) + execute_process(COMMAND "${CMAKE_C_COMPILER}" -E -dD -D${ARGV2} "${ARGV1}/target.h" + ERROR_VARIABLE _errors + RESULT_VARIABLE _result + OUTPUT_STRIP_TRAILING_WHITESPACE + OUTPUT_VARIABLE _contents) + + if(NOT _result EQUAL 0) + message(FATAL_ERROR "error extracting features for AT32 target ${ARGV2}: ${_errors}") + endif() + + string(REGEX MATCH "#define[\t ]+USE_VCP" HAS_VCP ${_contents}) + if(HAS_VCP) + list(APPEND ${ARGV0} VCP) + endif() + string(REGEX MATCH "define[\t ]+USE_FLASHFS" HAS_FLASHFS ${_contents}) + if(HAS_FLASHFS) + list(APPEND ${ARGV0} FLASHFS) + endif() + string(REGEX MATCH "define[\t ]+USE_SDCARD" HAS_SDCARD ${_contents}) + if (HAS_SDCARD) + list(APPEND ${ARGV0} SDCARD) + string(REGEX MATCH "define[\t ]+USE_SDCARD_SDIO" HAS_SDIO ${_contents}) + if (HAS_SDIO) + list(APPEND ${ARGV0} SDIO) + endif() + endif() + if(HAS_FLASHFS OR HAS_SDCARD) + list(APPEND ${ARGV0} MSC) + endif() +endmacro() + +function(get_at32_flash_size out size) + # 4: 16, 6: 32, 8: 64, B: 128, C: 256, D: 384, E: 512, F: 768, G: 1024, H: 1536, I: 2048 KiB + string(TOUPPER ${size} s) + if(${s} STREQUAL "4") + set(${out} 16 PARENT_SCOPE) + return() + endif() + if(${s} STREQUAL "6") + set(${out} 32 PARENT_SCOPE) + return() + endif() + if(${s} STREQUAL "8") + set(${out} 64 PARENT_SCOPE) + return() + endif() + if(${s} STREQUAL "8") + set(${out} 64 PARENT_SCOPE) + return() + endif() + if(${s} STREQUAL "B") + set(${out} 128 PARENT_SCOPE) + return() + endif() + if(${s} STREQUAL "C") + set(${out} 256 PARENT_SCOPE) + return() + endif() + if(${s} STREQUAL "D") + set(${out} 384 PARENT_SCOPE) + return() + endif() + if(${s} STREQUAL "E") + set(${out} 512 PARENT_SCOPE) + return() + endif() + if(${s} STREQUAL "F") + set(${out} 768 PARENT_SCOPE) + return() + endif() + if(${s} STREQUAL "G") + set(${out} 1024 PARENT_SCOPE) + return() + endif() + if(${s} STREQUAL "H") + set(${out} 1536 PARENT_SCOPE) + return() + endif() + if(${s} STREQUAL "I") + set(${out} 2048 PARENT_SCOPE) + return() + endif() +endfunction() + +function(add_hex_target name exe hex) + add_custom_target(${name} ALL + cmake -E env PATH="$ENV{PATH}" + # TODO: Overriding the start address with --set-start 0x08000000 + # seems to be required due to some incorrect assumptions about .hex + # files in the configurator. Verify wether that's the case and fix + # the bug in configurator or delete this comment. + ${CMAKE_OBJCOPY} -Oihex --set-start 0x08000000 $ ${hex} + BYPRODUCTS ${hex} + ) +endfunction() + +function(add_bin_target name exe bin) + add_custom_target(${name} + cmake -E env PATH="$ENV{PATH}" + ${CMAKE_OBJCOPY} -Obinary $ ${bin} + BYPRODUCTS ${bin} + ) +endfunction() + +function(generate_map_file target) + if(CMAKE_VERSION VERSION_LESS 3.15) + set(map "$.map") + else() + set(map "$/$.map") + endif() + target_link_options(${target} PRIVATE "-Wl,-Map,${map}") +endfunction() + +function(set_linker_script target script) + set(script_path ${AT32_LINKER_DIR}/${args_LINKER_SCRIPT}.ld) + if(NOT EXISTS ${script_path}) + message(FATAL_ERROR "linker script ${script_path} doesn't exist") + endif() + set_target_properties(${target} PROPERTIES LINK_DEPENDS ${script_path}) + target_link_options(${elf_target} PRIVATE -T${script_path}) +endfunction() + +function(add_at32_executable) + cmake_parse_arguments( + args + # Boolean arguments + "" + # Single value arguments + "FILENAME;NAME;OPTIMIZATION;OUTPUT_BIN_FILENAME;OUTPUT_HEX_FILENAME;OUTPUT_TARGET_NAME" + # Multi-value arguments + "COMPILE_DEFINITIONS;COMPILE_OPTIONS;INCLUDE_DIRECTORIES;LINK_OPTIONS;LINKER_SCRIPT;SOURCES" + # Start parsing after the known arguments + ${ARGN} + ) + set(elf_target ${args_NAME}.elf) + add_executable(${elf_target}) + target_sources(${elf_target} PRIVATE ${args_SOURCES}) + target_include_directories(${elf_target} PRIVATE ${CMAKE_CURRENT_SOURCE_DIR} ${args_INCLUDE_DIRECTORIES} ${AT32_INCLUDE_DIRS}) + target_compile_definitions(${elf_target} PRIVATE ${args_COMPILE_DEFINITIONS}) + target_compile_options(${elf_target} PRIVATE ${AT32_COMPILE_OPTIONS} ${args_COMPILE_OPTIONS}) + if(WARNINGS_AS_ERRORS) + target_compile_options(${elf_target} PRIVATE -Werror) + endif() + if (IS_RELEASE_BUILD) + target_compile_options(${elf_target} PRIVATE ${args_OPTIMIZATION}) + target_link_options(${elf_target} PRIVATE ${args_OPTIMIZATION}) + endif() + target_link_libraries(${elf_target} PRIVATE ${AT32_LINK_LIBRARIES}) + target_link_options(${elf_target} PRIVATE ${AT32_LINK_OPTIONS} ${args_LINK_OPTIONS}) + generate_map_file(${elf_target}) + set_linker_script(${elf_target} ${args_LINKER_SCRIPT}) + if(args_FILENAME) + set(basename ${CMAKE_BINARY_DIR}/${args_FILENAME}) + set(hex_filename ${basename}.hex) + add_hex_target(${args_NAME} ${elf_target} ${hex_filename}) + set(bin_filename ${basename}.bin) + add_bin_target(${args_NAME}.bin ${elf_target} ${bin_filename}) + endif() + if(args_OUTPUT_BIN_FILENAME) + set(${args_OUTPUT_BIN_FILENAME} ${bin_filename} PARENT_SCOPE) + endif() + if(args_OUTPUT_TARGET_NAME) + set(${args_OUTPUT_TARGET_NAME} ${elf_target} PARENT_SCOPE) + endif() + if(args_OUTPUT_HEX_FILENAME) + set(${args_OUTPUT_HEX_FILENAME} ${hex_filename} PARENT_SCOPE) + endif() +endfunction() + +# Main function of AT32 +function(target_at32) + if(NOT arm-none-eabi STREQUAL TOOLCHAIN) + return() + endif() + # Parse keyword arguments + cmake_parse_arguments( + args + # Boolean arguments + "DISABLE_MSC;BOOTLOADER" + # Single value arguments + "HSE_MHZ;LINKER_SCRIPT;NAME;OPENOCD_TARGET;OPTIMIZATION;STARTUP;SVD" + # Multi-value arguments + "COMPILE_DEFINITIONS;COMPILE_OPTIONS;INCLUDE_DIRECTORIES;LINK_OPTIONS;SOURCES;MSC_SOURCES;MSC_INCLUDE_DIRECTORIES;VCP_SOURCES;VCP_INCLUDE_DIRECTORIES" + # Start parsing after the known arguments + ${ARGN} + ) + set(name ${args_NAME}) + + if (args_HSE_MHZ) + set(hse_mhz ${args_HSE_MHZ}) + else() + set(hse_mhz ${AT32_DEFAULT_HSE_MHZ}) + endif() + + set(target_sources ${AT32_STARTUP_DIR}/${args_STARTUP}) + list(APPEND target_sources ${args_SOURCES}) + file(GLOB target_c_sources "${CMAKE_CURRENT_SOURCE_DIR}/*.c") + file(GLOB target_h_sources "${CMAKE_CURRENT_SOURCE_DIR}/*.h") + list(APPEND target_sources ${target_c_sources} ${target_h_sources}) + + set(target_include_directories ${args_INCLUDE_DIRECTORIES}) + + set(target_definitions ${AT32_DEFINITIONS} ${COMMON_COMPILE_DEFINITIONS}) + + get_at32_target_features(features "${CMAKE_CURRENT_SOURCE_DIR}" ${name}) + set_property(TARGET ${elf_target} PROPERTY FEATURES ${features}) + + if(VCP IN_LIST features) + list(APPEND target_sources ${AT32_VCP_SRC} ${args_VCP_SOURCES}) + list(APPEND target_include_directories ${args_VCP_INCLUDE_DIRECTORIES}) + endif() + if(SDCARD IN_LIST features) + list(APPEND target_sources ${AT32_SDCARD_SRC} ${AT32_ASYNCFATFS_SRC}) + endif() + + set(msc_sources) + if(NOT args_DISABLE_MSC AND MSC IN_LIST features) + list(APPEND target_include_directories ${args_MSC_INCLUDE_DIRECTORIES}) + list(APPEND msc_sources ${AT32_MSC_SRC} ${args_MSC_SOURCES}) + list(APPEND target_definitions USE_USB_MSC) + if(FLASHFS IN_LIST features) + list(APPEND msc_sources ${AT32_MSC_FLASH_SRC}) + endif() + if (SDCARD IN_LIST features) + list(APPEND msc_sources ${AT32_MSC_SDCARD_SRC}) + endif() + endif() + + math(EXPR hse_value "${hse_mhz} * 1000000") + list(APPEND target_definitions "HSE_VALUE=${hse_value}") + if(args_COMPILE_DEFINITIONS) + list(APPEND target_definitions ${args_COMPILE_DEFINITIONS}) + endif() + if(DEBUG_HARDFAULTS) + list(APPEND target_definitions DEBUG_HARDFAULTS) + endif() + + string(TOLOWER ${PROJECT_NAME} lowercase_project_name) + set(binary_name ${lowercase_project_name}_${FIRMWARE_VERSION}_${name}) + if(DEFINED BUILD_SUFFIX AND NOT "" STREQUAL "${BUILD_SUFFIX}") + set(binary_name "${binary_name}_${BUILD_SUFFIX}") + endif() + + # Main firmware + add_at32_executable( + NAME ${name} + FILENAME ${binary_name} + SOURCES ${target_sources} ${msc_sources} ${CMSIS_DSP_SRC} ${COMMON_SRC} + COMPILE_DEFINITIONS ${target_definitions} + COMPILE_OPTIONS ${args_COMPILE_OPTIONS} + INCLUDE_DIRECTORIES ${target_include_directories} + LINK_OPTIONS ${args_LINK_OPTIONS} + LINKER_SCRIPT ${args_LINKER_SCRIPT} + OPTIMIZATION ${args_OPTIMIZATION} + + OUTPUT_BIN_FILENAME main_bin_filename + OUTPUT_HEX_FILENAME main_hex_filename + OUTPUT_TARGET_NAME main_target_name + + ) + + set_property(TARGET ${main_target_name} PROPERTY OPENOCD_TARGET ${args_OPENOCD_TARGET}) + set_property(TARGET ${main_target_name} PROPERTY OPENOCD_DEFAULT_INTERFACE atlink) + set_property(TARGET ${main_target_name} PROPERTY SVD ${args_SVD}) + + setup_firmware_target(${main_target_name} ${name} ${ARGN}) + + if(args_BOOTLOADER) + # Bootloader for the target + set(bl_suffix _bl) + add_at32_executable( + NAME ${name}${bl_suffix} + FILENAME ${binary_name}${bl_suffix} + SOURCES ${target_sources} ${BOOTLOADER_SOURCES} + COMPILE_DEFINITIONS ${target_definitions} BOOTLOADER MSP_FIRMWARE_UPDATE + COMPILE_OPTIONS ${args_COMPILE_OPTIONS} + INCLUDE_DIRECTORIES ${target_include_directories} + LINK_OPTIONS ${args_LINK_OPTIONS} + LINKER_SCRIPT ${args_LINKER_SCRIPT}${bl_suffix} + OPTIMIZATION ${args_OPTIMIZATION} + + OUTPUT_BIN_FILENAME bl_bin_filename + OUTPUT_HEX_FILENAME bl_hex_filename + OUTPUT_TARGET_NAME bl_target_name + ) + setup_executable(${bl_target_name} ${name}) + + # Main firmware, but for running with the bootloader + set(for_bl_suffix _for_bl) + add_at32_executable( + NAME ${name}${for_bl_suffix} + FILENAME ${binary_name}${for_bl_suffix} + SOURCES ${target_sources} ${msc_sources} ${CMSIS_DSP_SRC} ${COMMON_SRC} + COMPILE_DEFINITIONS ${target_definitions} MSP_FIRMWARE_UPDATE + COMPILE_OPTIONS ${args_COMPILE_OPTIONS} + INCLUDE_DIRECTORIES ${target_include_directories} + LINK_OPTIONS ${args_LINK_OPTIONS} + LINKER_SCRIPT ${args_LINKER_SCRIPT}${for_bl_suffix} + OPTIMIZATION ${args_OPTIMIZATION} + + OUTPUT_BIN_FILENAME for_bl_bin_filename + OUTPUT_HEX_FILENAME for_bl_hex_filename + OUTPUT_TARGET_NAME for_bl_target_name + ) + setup_executable(${for_bl_target_name} ${name}) + + # Combined with bootloader and main firmware + set(with_bl_suffix _with_bl) + set(combined_hex ${CMAKE_BINARY_DIR}/${binary_name}${with_bl_suffix}.hex) + set(with_bl_target ${name}${with_bl_suffix}) + add_custom_target(${with_bl_target} + ${CMAKE_SOURCE_DIR}/src/utils/combine_tool ${bl_bin_filename} ${for_bl_bin_filename} ${combined_hex} + BYPRODUCTS ${combined_hex} + ) + add_dependencies(${with_bl_target} ${bl_target_name} ${for_bl_target_name}) + endif() + + # clean_ + set(generator_cmd "") + if (CMAKE_GENERATOR STREQUAL "Unix Makefiles") + set(generator_cmd "make") + elseif(CMAKE_GENERATOR STREQUAL "Ninja") + set(generator_cmd "ninja") + endif() + if (NOT generator_cmd STREQUAL "") + set(clean_target "clean_${name}") + add_custom_target(${clean_target} + WORKING_DIRECTORY ${CMAKE_BINARY_DIR} + COMMAND ${generator_cmd} clean + COMMENT "Removing intermediate files for ${name}") + set_property(TARGET ${clean_target} PROPERTY + EXCLUDE_FROM_ALL 1 + EXCLUDE_FROM_DEFAULT_BUILD 1) + endif() +endfunction() diff --git a/cmake/at32f4-usb.cmake b/cmake/at32f4-usb.cmake new file mode 100644 index 0000000000..1806fcf3f0 --- /dev/null +++ b/cmake/at32f4-usb.cmake @@ -0,0 +1,45 @@ +set(AT32_USBCORE_DIR "${MAIN_LIB_DIR}/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core") +set(AT32_USBCDC_DIR "${MAIN_LIB_DIR}/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/cdc") +set(AT32_USBMSC_DIR "${MAIN_LIB_DIR}/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc") + +set(AT32F4_USB_INCLUDE_DIRS + "${AT32_USBCORE_DIR}/Inc" + "${AT32_USBCDC_DIR}" + "${AT32_USBMSC_DIR}" +) + +set(AT32_USBCORE_SRC + usb_core.c + usbd_core.c + usbd_int.c + usbd_sdr.c +) +list(TRANSFORM AT32_USBCORE_SRC PREPEND "${AT32_USBCORE_DIR}/Src/") + + +set(AT32_USBCDC_SRC + "${AT32_USBCDC_DIR}/cdc_class.c" + "${AT32_USBCDC_DIR}/cdc_desc.c" +) + +main_sources(AT32F4_VCP_SRC + drivers/serial_usb_vcp_at32f43x.c + drivers/usb_io.c +) + +set(AT32F4_USBMSC_SRC + msc_desc.c + msc_class.c + msc_bot_scsi.c +) + +main_sources(AT32F4_MSC_SRC + drivers/usb_msc_at32f43x.c +) + +list(TRANSFORM AT32F4_USBMSC_SRC PREPEND "${AT32_USBMSC_DIR}/") +list(APPEND AT32F4_USBMSC_SRC ${AT32F4_MSC_SRC}) + +list(APPEND AT32F4_USB_SRC ${AT32F4_VCP_SRC}) +list(APPEND AT32F4_USB_SRC ${AT32_USBCORE_SRC}) +list(APPEND AT32F4_USB_SRC ${AT32_USBCDC_SRC}) diff --git a/cmake/at32f4.cmake b/cmake/at32f4.cmake new file mode 100644 index 0000000000..3fb407827b --- /dev/null +++ b/cmake/at32f4.cmake @@ -0,0 +1,114 @@ +include(cortex-m4f) +include(at32-stdperiph) +include(at32f4-usb) + +set(AT32F4_STDPERIPH_DIR "${MAIN_LIB_DIR}/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver") +set(AT32F4_CMSIS_DEVICE_DIR "${MAIN_LIB_DIR}/main/AT32F43x/Drivers/CMSIS/Device/ST/AT32F43x") +set(AT32F4_CMSIS_DRIVERS_DIR "${MAIN_LIB_DIR}/main/AT32F43x/Drivers/CMSIS") + + +set(AT32F4_STDPERIPH_SRC_EXCLUDES + at32f435_437_can.c + at32f435_437_dvp.c + at32f435_437_emac + at32f435_437_xmc.c +) + +set(AT32F4_STDPERIPH_SRC_DIR "${AT32F4_STDPERIPH_DIR}/src") +glob_except(AT32F4_STDPERIPH_SRC "${AT32F4_STDPERIPH_SRC_DIR}/*.c" "${AT32F4_STDPERIPH_SRC_EXCLUDES}") + +list(APPEND AT32F4_STDPERIPH_SRC "${AT32F4_CMSIS_DEVICE_DIR}/at32f435_437_clock.c" ) + +main_sources(AT32F4_SRC + target/system_at32f435_437.c + config/config_streamer_at32f43x.c + config/config_streamer_ram.c + config/config_streamer_extflash.c + drivers/adc_at32f43x.c + drivers/i2c_application.c + drivers/bus_i2c_at32f43x.c + drivers/bus_spi_at32f43x + drivers/serial_uart_hal_at32f43x.c + drivers/serial_uart_at32f43x.c + + drivers/system_at32f43x.c + drivers/timer.c + drivers/timer_impl_stdperiph_at32.c + drivers/timer_at32f43x.c + drivers/uart_inverter.c + drivers/dma_at32f43x.c +) + +set(AT32F4_INCLUDE_DIRS + ${CMSIS_INCLUDE_DIR} + ${CMSIS_DSP_INCLUDE_DIR} + ${AT32F4_CMSIS_DRIVERS_DIR} + ${AT32F4_STDPERIPH_DIR}/inc + ${AT32F4_CMSIS_DEVICE_DIR} + #"${AT32F4_I2C_DIR}" +) + +set(AT32F4_DEFINITIONS + ${CORTEX_M4F_DEFINITIONS} + AT32F43x + USE_STDPERIPH_DRIVER +) + +function(target_at32f43x) + target_at32( + SOURCES ${AT32_STDPERIPH_SRC} ${AT32F4_SRC} + COMPILE_DEFINITIONS ${AT32F4_DEFINITIONS} + COMPILE_OPTIONS ${CORTEX_M4F_COMMON_OPTIONS} ${CORTEX_M4F_COMPILE_OPTIONS} + INCLUDE_DIRECTORIES ${AT32F4_INCLUDE_DIRS} + LINK_OPTIONS ${CORTEX_M4F_COMMON_OPTIONS} ${CORTEX_M4F_LINK_OPTIONS} + + MSC_SOURCES ${AT32F4_USBMSC_SRC} ${AT32F4_MSC_SRC} + VCP_SOURCES ${AT32F4_USB_SRC} ${AT32F4_VCP_SRC} + VCP_INCLUDE_DIRECTORIES ${AT32F4_USB_INCLUDE_DIRS} + + OPTIMIZATION -O2 + + OPENOCD_TARGET at32f437xx + + ${ARGN} + ) +endfunction() + +#target_at32f43x_xMT7 +#target_at32f43x_xGT7 + +set(at32f43x_xMT7_COMPILE_DEFINITIONS + AT32F437VMT7 + MCU_FLASH_SIZE=4032 +) + +function(target_at32f43x_xMT7 name) + target_at32f43x( + NAME ${name} + STARTUP startup_at32f435_437.s + SOURCES ${AT32F4_STDPERIPH_SRC} + COMPILE_DEFINITIONS ${at32f43x_xMT7_COMPILE_DEFINITIONS} + LINKER_SCRIPT at32_flash_f43xM + #BOOTLOADER + SVD at32f43x_xMT7 + ${ARGN} + ) +endfunction() + +set(at32f43x_xGT7_COMPILE_DEFINITIONS + AT32F435RGT7 + MCU_FLASH_SIZE=1024 +) + +function(target_at32f43x_xGT7 name) + target_at32f43x( + NAME ${name} + STARTUP startup_at32f435_437.s + SOURCES ${AT32F4_STDPERIPH_SRC} + COMPILE_DEFINITIONS ${at32f43x_xGT7_COMPILE_DEFINITIONS} + LINKER_SCRIPT at32_flash_f43xG + #BOOTLOADER + SVD at32f43x_xGT7 + ${ARGN} + ) +endfunction() diff --git a/dev/svd/AT32F437xx_v2.svd b/dev/svd/AT32F437xx_v2.svd new file mode 100644 index 0000000000..4f34af9d30 --- /dev/null +++ b/dev/svd/AT32F437xx_v2.svd @@ -0,0 +1,58291 @@ + + + + + + + + Keil + ArteryTek + AT32F437xx_v2 + AT32F437 + 1.0 + ARM 32-bit Cortex-M4 Microcontroller based device, CPU clock up to 288MHz, etc. + + ARM Limited (ARM) is supplying this software for use with Cortex-M\n + processor based microcontroller, but can be equally used for other\n + suitable processor architectures. This file can be freely distributed.\n + Modifications to this file shall be clearly marked.\n + \n + THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED\n + OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF\n + MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE.\n + ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR\n + CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. + + + CM4 + r0p1 + little + false + true + 4 + false + + 8 + 32 + + 32 + read-write + 0x00000000 + 0xFFFFFFFF + + + + XMC + Flexible static memory controller + XMC + 0xA0000000 + + 0x0 + 0x1000 + registers + + + XMC + XMC global interrupt + 48 + + + + BK1CTRL1 + BK1CTRL1 + SRAM/NOR-Flash chip-select control register + 1 + 0x0 + 0x20 + read-write + 0x000030DB + + + MWMC + Memory write mode control + 19 + 1 + + + CRPGS + CRAM page size + 16 + 3 + + + NWASEN + NWAIT in asynchronous transfer enable + 15 + 1 + + + RWTD + Read-write timing different + 14 + 1 + + + NWSEN + NWAIT in synchronous transfer enable + 13 + 1 + + + WEN + Write enable + 12 + 1 + + + NWTCFG + Wait timing configuration + 11 + 1 + + + WRAPEN + Wrapped enable + 10 + 1 + + + NWPOL + NWAIT polarity + 9 + 1 + + + SYNCBEN + Synchronous burst enable + 8 + 1 + + + NOREN + Nor flash access enable + 6 + 1 + + + EXTMDBW + External memory data bus width + 4 + 2 + + + DEV + Memory device type + 2 + 2 + + + ADMUXEN + Address and data multiplexing enable + 1 + 1 + + + EN + Memory bank enable + 0 + 1 + + + + + BK1TMG1 + BK1TMG1 + SRAM/NOR-Flash chip-select timing register + 1 + 0x4 + 0x20 + read-write + 0x0FFFFFFF + + + ASYNCM + Asynchronous mode + 28 + 2 + + + DTLAT + Data latency + 24 + 4 + + + CLKPSC + Clock prescale + 20 + 4 + + + BUSLAT + Bus latency + 16 + 4 + + + DTST + Asynchronous data setup time + 8 + 8 + + + ADDRHT + Address-hold time + 4 + 4 + + + ADDRST + Address setup time + 0 + 4 + + + + + BK1CTRL2 + BK1CTRL2 + SRAM/NOR-Flash chip-select control register + 2 + 0x8 + 0x20 + read-write + 0x000030D2 + + + MWMC + Memory write mode control + 19 + 1 + + + CRPGS + CRAM page size + 16 + 3 + + + NWASEN + NWAIT in asynchronous transfer enable + 15 + 1 + + + RWTD + Read-write timing different + 14 + 1 + + + NWSEN + NWAIT in synchronous transfer enable + 13 + 1 + + + WEN + Write enable + 12 + 1 + + + NWTCFG + Wait timing configuration + 11 + 1 + + + WRAPEN + Wrapped enable + 10 + 1 + + + NWPOL + NWAIT polarity + 9 + 1 + + + SYNCBEN + Synchronous burst enable + 8 + 1 + + + NOREN + Nor flash access enable + 6 + 1 + + + EXTMDBW + External memory data bus width + 4 + 2 + + + DEV + Memory device type + 2 + 2 + + + ADMUXEN + Address and data multiplexing enable + 1 + 1 + + + EN + Memory bank enable + 0 + 1 + + + + + BK1TMG2 + BK1TMG2 + SRAM/NOR-Flash chip-select timing register + 2 + 0xC + 0x20 + read-write + 0x0FFFFFFF + + + ASYNCM + Asynchronous mode + 28 + 2 + + + DTLAT + Data latency + 24 + 4 + + + CLKPSC + Clock prescale + 20 + 4 + + + BUSLAT + Bus latency + 16 + 4 + + + DTST + Asynchronous data setup time + 8 + 8 + + + ADDRHT + Address-hold time + 4 + 4 + + + ADDRST + Address setup time + 0 + 4 + + + + + BK1CTRL3 + BK1CTRL3 + SRAM/NOR-Flash chip-select control register + 3 + 0x10 + 0x20 + read-write + 0x000030D2 + + + MWMC + Memory write mode control + 19 + 1 + + + CRPGS + CRAM page size + 16 + 3 + + + NWASEN + NWAIT in asynchronous transfer enable + 15 + 1 + + + RWTD + Read-write timing different + 14 + 1 + + + NWSEN + NWAIT in synchronous transfer enable + 13 + 1 + + + WEN + Write enable + 12 + 1 + + + NWTCFG + Wait timing configuration + 11 + 1 + + + WRAPEN + Wrapped enable + 10 + 1 + + + NWPOL + NWAIT polarity + 9 + 1 + + + SYNCBEN + Synchronous burst enable + 8 + 1 + + + NOREN + Nor flash access enable + 6 + 1 + + + EXTMDBW + External memory data bus width + 4 + 2 + + + DEV + Memory device type + 2 + 2 + + + ADMUXEN + Address and data multiplexing enable + 1 + 1 + + + EN + Memory bank enable + 0 + 1 + + + + + BK1TMG3 + BK1TMG3 + SRAM/NOR-Flash chip-select timing register + 3 + 0x14 + 0x20 + read-write + 0x0FFFFFFF + + + ASYNCM + Asynchronous mode + 28 + 2 + + + DTLAT + Data latency + 24 + 4 + + + CLKPSC + Clock prescale + 20 + 4 + + + BUSLAT + Bus latency + 16 + 4 + + + DTST + Asynchronous data setup time + 8 + 8 + + + ADDRHT + Address-hold time + 4 + 4 + + + ADDRST + Address setup time + 0 + 4 + + + + + BK1CTRL4 + BK1CTRL4 + SRAM/NOR-Flash chip-select control register + 4 + 0x18 + 0x20 + read-write + 0x000030D2 + + + MWMC + Memory write mode control + 19 + 1 + + + CRPGS + CRAM page size + 16 + 3 + + + NWASEN + NWAIT in asynchronous transfer enable + 15 + 1 + + + RWTD + Read-write timing different + 14 + 1 + + + NWSEN + NWAIT in synchronous transfer enable + 13 + 1 + + + WEN + Write enable + 12 + 1 + + + NWTCFG + Wait timing configuration + 11 + 1 + + + WRAPEN + Wrapped enable + 10 + 1 + + + NWPOL + NWAIT polarity + 9 + 1 + + + SYNCBEN + Synchronous burst enable + 8 + 1 + + + NOREN + Nor flash access enable + 6 + 1 + + + EXTMDBW + External memory data bus width + 4 + 2 + + + DEV + Memory device type + 2 + 2 + + + ADMUXEN + Address and data multiplexing enable + 1 + 1 + + + EN + Memory bank enable + 0 + 1 + + + + + BK1TMG4 + BK1TMG4 + SRAM/NOR-Flash chip-select timing register + 4 + 0x1C + 0x20 + read-write + 0x0FFFFFFF + + + ASYNCM + Asynchronous mode + 28 + 2 + + + DTLAT + Data latency + 24 + 4 + + + CLKPSC + Clock prescale + 20 + 4 + + + BUSLAT + Bus latency + 16 + 4 + + + DTST + Asynchronous data setup time + 8 + 8 + + + ADDRHT + Address-hold time + 4 + 4 + + + ADDRST + Address setup time + 0 + 4 + + + + + BK2CTRL + BK2CTRL + PC Card/NAND Flash control register + 2 + 0x60 + 0x20 + read-write + 0x00000018 + + + ECCPGS + ECC page size + 17 + 3 + + + TAR + ALE to RE delay + 13 + 4 + + + TCR + CLE to RE delay + 9 + 4 + + + ECCEN + ECC enable + 6 + 1 + + + EXTMDBW + External memory data bus width + 4 + 2 + + + DEV + Memory device type + 3 + 1 + + + EN + Memory bank enable + 2 + 1 + + + NWEN + Wait feature enable + 1 + 1 + + + + + BK2IS + BK2IS + FIFO status and interrupt register + 2 + 0x64 + 0x20 + 0x00000040 + + + FIFOE + FIFO empty + 6 + 1 + read-only + + + FEIEN + Falling edge interrupt enable + 5 + 1 + read-write + + + HLIEN + High-level interrupt enable + 4 + 1 + read-write + + + REIEN + Rising edge interrupt enable + 3 + 1 + read-write + + + FES + Falling edge status + 2 + 1 + read-write + + + HLS + High-level status + 1 + 1 + read-write + + + RES + Rising edge capture status + 0 + 1 + read-write + + + + + BK2TMGRG + BK2TMGRG + Regular memory space timing register + 2 + 0x68 + 0x20 + read-write + 0xFCFCFCFC + + + RGDHIZT + Regular memory databus High resistance time + 24 + 8 + + + RGHT + Regular memory hold time + 16 + 8 + + + RGWT + Regular memory wait time + 8 + 8 + + + RGST + Regular memory setup time + 0 + 8 + + + + + BK2TMGSP + BK2TMGSP + special memory space timing register + 2 + 0x6C + 0x20 + read-write + 0xFCFCFCFC + + + SPDHIZT + special memory databus High resistance time + 24 + 8 + + + SPHT + special memory hold time + 16 + 8 + + + SPWT + special memory wait time + 8 + 8 + + + SPST + special memory setup time + 0 + 8 + + + + + BK2ECC + BK2ECC + ECC result register 2 + 0x74 + 0x20 + read-write + 0x00000000 + + + ECC + ECC result + 0 + 32 + + + + + BK3CTRL + BK3CTRL + PC Card/NAND Flash control register + 3 + 0x80 + 0x20 + read-write + 0x00000018 + + + ECCPGS + ECC page size + 17 + 3 + + + TAR + ALE to RE delay + 13 + 4 + + + TCR + CLE to RE delay + 9 + 4 + + + ECCEN + ECC enable + 6 + 1 + + + EXTMDBW + External memory data bus width + 4 + 2 + + + DEV + Memory device type + 3 + 1 + + + EN + Memory bank enable + 2 + 1 + + + NWEN + Wait feature enable + 1 + 1 + + + + + BK3IS + BK3IS + FIFO status and interrupt register + 3 + 0x84 + 0x20 + 0x00000040 + + + FIFOE + FIFO empty + 6 + 1 + read-only + + + FEIEN + Falling edge interrupt enable + 5 + 1 + read-write + + + HLIEN + High-level interrupt enable + 4 + 1 + read-write + + + REIEN + Rising edge interrupt enable + 3 + 1 + read-write + + + FES + Falling edge status + 2 + 1 + read-write + + + HLS + High-level status + 1 + 1 + read-write + + + RES + Rising edge capture status + 0 + 1 + read-write + + + + + BK3TMGRG + BK3TMGRG + Regular memory space timing register + 3 + 0x88 + 0x20 + read-write + 0xFCFCFCFC + + + RGDHIZT + Regular memory databus High resistance time + 24 + 8 + + + RGHT + Regular memory hold time + 16 + 8 + + + RGWT + Regular memory wait time + 8 + 8 + + + RGST + Regular memory setup time + 0 + 8 + + + + + BK3TMGSP + BK3TMGSP + special memory space timing register + 3 + 0x8C + 0x20 + read-write + 0xFCFCFCFC + + + SPDHIZT + special memory databus High resistance time + 24 + 8 + + + SPHT + special memory hold time + 16 + 8 + + + SPWT + special memory wait time + 8 + 8 + + + SPST + special memory setup time + 0 + 8 + + + + + BK3ECC + BK3ECC + ECC result register 3 + 0x94 + 0x20 + read-write + 0x00000000 + + + ECC + ECC result + 0 + 32 + + + + + BK4CTRL + BK4CTRL + PC Card/NAND Flash control register + 4 + 0xA0 + 0x20 + read-write + 0x00000018 + + + EN + Memory bank enable + 2 + 1 + + + NWEN + Wait feature enable + 1 + 1 + + + + + BK4IS + BK4IS + FIFO status and interrupt register + 4 + 0xA4 + 0x20 + 0x00000040 + + + FIFOE + FIFO empty + 6 + 1 + read-only + + + FEIEN + Falling edge interrupt enable + 5 + 1 + read-write + + + HLIEN + High-level interrupt enable + 4 + 1 + read-write + + + REIEN + Rising edge interrupt enable + 3 + 1 + read-write + + + FES + Falling edge status + 2 + 1 + read-write + + + HLS + High-level status + 1 + 1 + read-write + + + RES + Rising edge capture status + 0 + 1 + read-write + + + + + BK4TMGCM + BK4TMGCM + Regular memory space timing register + 4 + 0xA8 + 0x20 + read-write + 0xFCFCFCFC + + + CMDHIZT + Regular memory databus High resistance time + 24 + 8 + + + CMHT + Regular memory hold time + 16 + 8 + + + CMWT + Regular memory wait time + 8 + 8 + + + CMST + Regular memory setup time + 0 + 8 + + + + + BK4TMGAT + BK4TMGAT + special memory space timing register + 4 + 0xAC + 0x20 + read-write + 0xFCFCFCFC + + + ATDHIZT + special memory databus High resistance time + 24 + 8 + + + ATHT + special memory hold time + 16 + 8 + + + ATWT + special memory wait time + 8 + 8 + + + ATST + special memory setup time + 0 + 8 + + + + + BK4TMGIO + BK4TMGIO + I/O space timing register 4 + 0xB0 + 0x20 + read-write + 0xFCFCFCFC + + + IODHIZT + WRSTP + 24 + 8 + + + IOHT + HLD + 16 + 8 + + + IOWT + OP + 8 + 8 + + + IOST + STP + 0 + 8 + + + + + BK1TMGWR1 + BK1TMGWR1 + SRAM/NOR-Flash write timing registers + 1 + 0x104 + 0x20 + read-write + 0x0FFFFFFF + + + ASYNCM + Asynchronous mode + 28 + 2 + + + BUSLAT + Bus latency + 16 + 4 + + + DTST + Asynchronous data setup time + 8 + 8 + + + ADDRHT + Address-hold time + 4 + 4 + + + ADDRST + Address setup time + 0 + 4 + + + + + BK1TMGWR2 + BK1TMGWR2 + SRAM/NOR-Flash write timing registers + 2 + 0x10C + 0x20 + read-write + 0x0FFFFFFF + + + ASYNCM + Asynchronous mode + 28 + 2 + + + BUSLAT + Bus latency + 16 + 4 + + + DTST + Asynchronous data setup time + 8 + 8 + + + ADDRHT + Address-hold time + 4 + 4 + + + ADDRST + Address setup time + 0 + 4 + + + + + BK1TMGWR3 + BK1TMGWR3 + SRAM/NOR-Flash write timing registers + 3 + 0x114 + 0x20 + read-write + 0x0FFFFFFF + + + ASYNCM + Asynchronous mode + 28 + 2 + + + BUSLAT + Bus latency + 16 + 4 + + + DTST + Asynchronous data setup time + 8 + 8 + + + ADDRHT + Address-hold time + 4 + 4 + + + ADDRST + Address setup time + 0 + 4 + + + + + BK1TMGWR4 + BK1TMGWR4 + SRAM/NOR-Flash write timing registers + 4 + 0x11C + 0x20 + read-write + 0x0FFFFFFF + + + ASYNCM + Asynchronous mode + 28 + 2 + + + BUSLAT + Bus latency + 16 + 4 + + + DTST + Asynchronous data setup time + 8 + 8 + + + ADDRHT + Address-hold time + 4 + 4 + + + ADDRST + Address setup time + 0 + 4 + + + + + CTRL1 + CTRL1 + SDRAM Control Register 1 + 0x140 + 0x20 + read-write + 0x000002D0 + + + CA + Number of column address + bits + 0 + 2 + + + RA + Number of row address bits + 2 + 2 + + + DB + Memory data bus width + 4 + 2 + + + INBK + Number of internal banks + 6 + 1 + + + CAS + CAS latency + 7 + 2 + + + WRP + Write protection + 9 + 1 + + + CLKDIV + Clock division configuration + 10 + 2 + + + BSTR + Burst read + 12 + 1 + + + RD + Read delay + 13 + 2 + + + + + CTRL2 + CTRL2 + SDRAM Control Register 2 + 0x144 + 0x20 + read-write + 0x000002D0 + + + CA + Number of column address + bits + 0 + 2 + + + RA + Number of row address bits + 2 + 2 + + + DB + Memory data bus width + 4 + 2 + + + INBK + Number of internal banks + 6 + 1 + + + CAS + CAS latency + 7 + 2 + + + WRP + Write protection + 9 + 1 + + + CLKDIV + Clock division configuration + 10 + 2 + + + BSTR + Burst read + 12 + 1 + + + RD + Read pipe + 13 + 2 + + + + + TM1 + TM1 + SDRAM Timing register 1 + 0x148 + 0x20 + read-write + 0x0FFFFFFF + + + TMRD + Mode register program to active delay + 0 + 4 + + + TXSR + Exit Self-refresh to active delay + 4 + 4 + + + TRAS + Self refresh time + 8 + 4 + + + TRC + Refresh to active delay + 12 + 4 + + + TWR + Write Recovery delay + 16 + 4 + + + TRP + Precharge to active delay + 20 + 4 + + + TRCD + Row active to Read/Write delay + 24 + 4 + + + + + TM2 + TM2 + SDRAM Timing register 2 + 0x14C + 0x20 + read-write + 0x0FFFFFFF + + + TMRD + Mode register program to active delay + 0 + 4 + + + TXSR + Exit Self-refresh to active delay + 4 + 4 + + + TRAS + Self refresh time + 8 + 4 + + + TRC + Refresh to active delay + 12 + 4 + + + TWR + Write Recovery delay + 16 + 4 + + + TRP + Precharge to active delay + 20 + 4 + + + TRCD + Row active to Read/Write delay + 24 + 4 + + + + + CMD + CMD + SDRAM Command Mode register + 0x150 + 0x20 + 0x00000000 + + + CMD + SDRAM Command + 0 + 3 + write-only + + + BK2 + SDRAM Bank 2 + 3 + 1 + write-only + + + BK1 + SDRAM Bank 1 + 4 + 1 + write-only + + + ART + Auto-refresh times + 5 + 4 + read-write + + + MRD + Mode register data + 9 + 13 + read-write + + + + + RCNT + RCNT + SDRAM Refresh Timer register + 0x154 + 0x20 + 0x00000000 + + + ERRC + error flag clear + 0 + 1 + write-only + + + RC + Refresh Count + 1 + 13 + read-write + + + ERIEN + error Interrupt Enable + 14 + 1 + read-write + + + + + STS + STS + SDRAM Status register + 0x158 + 0x20 + read-only + 0x00000000 + + + ERR + error flag + 0 + 1 + + + BK1STS + Bank 1 Status + 1 + 2 + + + BK2STS + Bank 2 Status + 3 + 2 + + + BUSY + Busy status + 5 + 1 + + + + + EXT1 + EXT1 + externl timeing register 1 + 0x220 + 0x20 + read-write + 0x00000808 + + + BUSLATW2W + Bus turnaround phase for consecutive write duration + 0 + 8 + + + BUSLATR2R + Bus turnaround phase for consecutive read duration + 8 + 8 + + + + + EXT2 + EXT2 + externl timeing register 2 + 0x224 + 0x20 + read-write + 0x00000808 + + + BUSLATW2W + Bus turnaround phase for consecutive write duration + 0 + 8 + + + BUSLATR2R + Bus turnaround phase for consecutive read duration + 8 + 8 + + + + + EXT3 + EXT3 + externl timeing register 3 + 0x228 + 0x20 + read-write + 0x00000808 + + + BUSLATW2W + Bus turnaround phase for consecutive write duration + 0 + 8 + + + BUSLATR2R + Bus turnaround phase for consecutive read duration + 8 + 8 + + + + + EXT4 + EXT4 + externl timeing register 4 + 0x22C + 0x20 + read-write + 0x00000808 + + + BUSLATW2W + Bus turnaround phase for consecutive write duration + 0 + 8 + + + BUSLATR2R + Bus turnaround phase for consecutive read duration + 8 + 8 + + + + + + + PWC + Power control + PWC + 0x40007000 + + 0x0 + 0x400 + registers + + + + CTRL + CTRL + Power control register + (PWC_CTRL) + 0x0 + 0x20 + read-write + 0x00000000 + + + VRSEL + Voltage regulator state select when deepsleep mode + 0 + 1 + + + LPSEL + Low power mode select when Cortex-M4F sleepdeep + 1 + 1 + + + CLSWEF + Clear SWEF flag + 2 + 1 + + + CLSEF + Clear SEF flag + 3 + 1 + + + PVMEN + Power voltage monitoring enable + 4 + 1 + + + PVMSEL + Power voltage monitoring boundary select + 5 + 3 + + + BPWEN + Battery powered domain write enable + 8 + 1 + + + + + CTRLSTS + CTRLSTS + Power control and status register + (PWC_CTRLSTS) + 0x4 + 0x20 + 0x00000000 + + + SWEF + Standby wake-up event flag + 0 + 1 + read-only + + + SEF + Standby mode entry flag + 1 + 1 + read-only + + + PVMOF + Power voltage monitoring output flag + 2 + 1 + read-only + + + SWPEN1 + Standby wake-up pin 1 enable + 8 + 1 + read-write + + + SWPEN2 + Standby wake-up pin 2 enable + 9 + 1 + read-write + + + + + LDOOV + LDOOV + LDO output voltage register + 0x10 + 0x20 + 0x00000000 + + + LDOOVSEL + LDO output voltage select + 0 + 3 + read-write + + + + + + + CRM + Clock and reset management + CRM + 0x40023800 + + 0x0 + 0x400 + registers + + + CRM + CRM global interrupt + 5 + + + + CTRL + CTRL + Clock control register + 0x0 + 0x20 + 0x00000083 + + + HICKEN + High speed internal clock enable + 0 + 1 + read-write + + + HICKSTBL + High speed internal clock ready flag + 1 + 1 + read-only + + + HICKTRIM + High speed internal clock trimming + 2 + 6 + read-write + + + HICKCAL + High speed internal clock calibration + 8 + 8 + read-only + + + HEXTEN + High speed exernal crystal enable + 16 + 1 + read-write + + + HEXTSTBL + High speed exernal crystal ready flag + 17 + 1 + read-only + + + HEXTBYPS + High speed exernal crystal bypass + 18 + 1 + read-write + + + CFDEN + Clock failure detection enable + 19 + 1 + read-write + + + PLLEN + PLL enable + 24 + 1 + read-write + + + PLLSTBL + PLL clock ready flag + 25 + 1 + read-only + + + + + PLLCFG + PLLCFG + PLL configuration register + (CRM_PLLCFG) + 0x4 + 0x20 + 0x00033002 + + + PLL_MS + PLL pre-division + 0 + 4 + read-write + + + PLL_NS + PLL frequency multiplication factor + 6 + 9 + read-write + + + PLL_FR + PLL post-division + 16 + 3 + read-write + + + PLLRCS + PLL reference clock select + 22 + 1 + read-write + + + + + CFG + CFG + Clock configuration register(CRM_CFG) + 0x8 + 0x20 + 0x00000000 + + + SCLKSEL + System clock select + 0 + 2 + read-write + + + SCLKSTS + System Clock select Status + 2 + 2 + read-only + + + AHBDIV + AHB division + 4 + 4 + read-write + + + APB1DIV + APB1 division + 10 + 3 + read-write + + + APB2DIV + APB2 division + 13 + 3 + read-write + + + ERTCDIV + HEXT division for ERTC clock + 16 + 5 + read-write + + + CLKOUT1_SEL + Clock output1 selection + 21 + 2 + read-write + + + CLKOUT1DIV1 + Clock output1 division1 + 24 + 3 + read-write + + + CLKOUT2DIV1 + Clock output2 division1 + 27 + 3 + read-write + + + CLKOUT2_SEL1 + Clock output2 selection1 + 30 + 2 + read-write + + + + + CLKINT + CLKINT + Clock interrupt register + (CRM_CLKINT) + 0xC + 0x20 + 0x00000000 + + + LICKSTBLF + LICK ready interrupt flag + 0 + 1 + read-only + + + LEXTSTBLF + LEXT ready interrupt flag + 1 + 1 + read-only + + + HICKSTBLF + HICK ready interrupt flag + 2 + 1 + read-only + + + HEXTSTBLF + HEXT ready interrupt flag + 3 + 1 + read-only + + + PLLSTBLF + PLL ready interrupt flag + 4 + 1 + read-only + + + CFDF + Clock failure detection interrupt flag + 7 + 1 + read-only + + + LICKSTBLIEN + LICK ready interrupt enable + 8 + 1 + read-write + + + LEXTSTBLIEN + LEXT ready interrupt enable + 9 + 1 + read-write + + + HICKSTBLIEN + HICK ready interrupt enable + 10 + 1 + read-write + + + HEXTSTBLIEN + HEXT ready interrupt enable + 11 + 1 + read-write + + + PLLSTBLIEN + PLL ready interrupt enable + 12 + 1 + read-write + + + LICKSTBLFC + LICK ready interrupt clear + 16 + 1 + write-only + + + LEXTSTBLFC + LEXT ready interrupt clear + 17 + 1 + write-only + + + HICKSTBLFC + HICK ready interrupt clear + 18 + 1 + write-only + + + HEXTSTBLFC + HEXT ready interrupt clear + 19 + 1 + write-only + + + PLLSTBLFC + PLL ready interrupt clear + 20 + 1 + write-only + + + CFDFC + Clock failure detection interrupt clear + 23 + 1 + write-only + + + + + AHBRST1 + AHBRST1 + AHB peripheral reset register1 + (CRM_AHBRST1) + 0x10 + 0x20 + read-write + 0x000000000 + + + GPIOARST + IO port A reset + 0 + 1 + + + GPIOBRST + IO port B reset + 1 + 1 + + + GPIOCRST + IO port C reset + 2 + 1 + + + GPIODRST + IO port D reset + 3 + 1 + + + GPIOERST + IO port E reset + 4 + 1 + + + GPIOFRST + IO port F reset + 5 + 1 + + + GPIOGRST + IO port G reset + 6 + 1 + + + GPIOHRST + IO port H reset + 7 + 1 + + + CRCRST + CRC reset + 12 + 1 + + + EDMARST + EDMA reset + 21 + 1 + + + DMA1RST + DMA1 reset + 22 + 1 + + + DMA2RST + DMA2 reset + 24 + 1 + + + EMACRST + EMAC reset + 25 + 1 + + + OTGFS2RST + OTGFS2 interface reset + 29 + 1 + + + + + AHBRST2 + AHBRST2 + AHB peripheral reset register 2 + (CRM_AHBRST2) + 0x14 + 0x20 + read-write + 0x00000000 + + + DVPRST + DVP reset + 0 + 1 + + + OTGFS1RST + OTGFS1 reset + 7 + 1 + + + SDIO1RST + SDIO1 reset + 15 + 1 + + + + + AHBRST3 + AHBRST3 + AHB peripheral reset register 3 + (CRM_AHBRST3) + 0x18 + 0x20 + read-write + 0x00000000 + + + XMCRST + XMC reset + 0 + 1 + + + QSPI1RST + QSPI1 reset + 1 + 1 + + + QSPI2RST + QSPI2 reset + 14 + 1 + + + SDIO2RST + SDIO2 reset + 15 + 1 + + + + + APB1RST + APB1RST + APB1 peripheral reset register + (CRM_APB1RST) + 0x20 + 0x20 + read-write + 0x00000000 + + + TMR2RST + Timer2 reset + 0 + 1 + + + TMR3RST + Timer3 reset + 1 + 1 + + + TMR4RST + Timer4 reset + 2 + 1 + + + TMR5RST + Timer5 reset + 3 + 1 + + + TMR6RST + Timer6 reset + 4 + 1 + + + TMR7RST + Timer7 reset + 5 + 1 + + + TMR12RST + Timer12 reset + 6 + 1 + + + TMR13RST + Timer13 reset + 7 + 1 + + + TMR14RST + Timer14 reset + 8 + 1 + + + WWDTRST + Window watchdog reset + 11 + 1 + + + SPI2RST + SPI2 reset + 14 + 1 + + + SPI3RST + SPI3 reset + 15 + 1 + + + USART2RST + USART2 reset + 17 + 1 + + + USART3RST + USART3 reset + 18 + 1 + + + UART4RST + UART4 reset + 19 + 1 + + + UART5RST + UART5 reset + 20 + 1 + + + I2C1RST + I2C1 reset + 21 + 1 + + + I2C2RST + I2C2 reset + 22 + 1 + + + I2C3RST + I2C3 reset + 23 + 1 + + + CAN1RST + CAN1 reset + 25 + 1 + + + CAN2RST + CAN2 reset + 26 + 1 + + + PWCRST + PWC reset + 28 + 1 + + + DACRST + DAC reset + 29 + 1 + + + UART7RST + UART7 reset + 30 + 1 + + + UART8RST + UART8 reset + 31 + 1 + + + + + APB2RST + APB2RST + APB2 peripheral reset register + (CRM_APB2RST) + 0x24 + 0x20 + read-write + 0x00000000 + + + TMR1RST + Timer1 reset + 0 + 1 + + + TMR8RST + Timer8 reset + 1 + 1 + + + USART1RST + USART1 reset + 4 + 1 + + + USART6RST + USART6 reset + 5 + 1 + + + ADCRST + ADC reset + 8 + 1 + + + SPI1RST + SPI1 reset + 12 + 1 + + + SPI4RST + SPI4 reset + 13 + 1 + + + SCFGRST + SCFG reset + 14 + 1 + + + TMR9RST + Timer9 reset + 16 + 1 + + + TMR10RST + Timer10 reset + 17 + 1 + + + TMR11RST + Timer 11 reset + 18 + 1 + + + TMR20RST + Timer20 reset + 20 + 1 + + + ACCRST + ACC reset + 29 + 1 + + + + + AHBEN1 + AHBEN1 + AHB Peripheral Clock enable register 1 + (CRM_AHBEN1) + 0x30 + 0x20 + read-write + 0x00000000 + + + GPIOAEN + IO A clock enable + 0 + 1 + + + GPIOBEN + IO B clock enable + 1 + 1 + + + GPIOCEN + IO C clock enable + 2 + 1 + + + GPIODEN + IO D clock enable + 3 + 1 + + + GPIOEEN + IO E clock enable + 4 + 1 + + + GPIOFEN + IO F clock enable + 5 + 1 + + + GPIOGEN + IO G clock enable + 6 + 1 + + + GPIOHEN + IO H clock enable + 7 + 1 + + + CRCEN + CRC clock enable + 12 + 1 + + + EDMAEN + DMA1 clock enable + 21 + 1 + + + DMA1EN + DMA1 clock enable + 22 + 1 + + + DMA2EN + DMA2 clock enable + 24 + 1 + + + EMACEN + EMAC clock enable + 25 + 1 + + + EMACTXEN + EMAC Tx clock enable + 26 + 1 + + + EMACRXEN + EMAC Rx clock enable + 27 + 1 + + + EMACPTPEN + EMAC PTP clock enable + 28 + 1 + + + OTGFS2EN + OTGFS2 clock enable + 29 + 1 + + + + + AHBEN2 + AHBEN2 + AHB peripheral clock enable register 2 + (CRM_AHBEN2) + 0x34 + 0x20 + read-write + 0x00000000 + + + DVPEN + DVP clock enable + 0 + 1 + + + OTGFS1EN + OTGFS1 clock enable + 7 + 1 + + + SDIO1EN + SDIO1 clock enable + 15 + 1 + + + + + AHBEN3 + AHBEN3 + AHB peripheral clock enable register 3 + (CRM_AHBEN3) + 0x38 + 0x20 + read-write + 0x00000000 + + + XMCEN + XMC clock enable + 0 + 1 + + + QSPI1EN + QSPI1 clock enable + 1 + 1 + + + QSPI2EN + QSPI2 clock enable + 14 + 1 + + + SDIO2EN + SDIO 2 clock enable + 15 + 1 + + + + + APB1EN + APB1EN + APB1 peripheral clock enable register + (CRM_APB1EN) + 0x40 + 0x20 + read-write + 0x00000000 + + + TMR2EN + Timer2 clock enable + 0 + 1 + + + TMR3EN + Timer3 clock enable + 1 + 1 + + + TMR4EN + Timer4 clock enable + 2 + 1 + + + TMR5EN + Timer5 clock enable + 3 + 1 + + + TMR6EN + Timer6 clock enable + 4 + 1 + + + TMR7EN + Timer7 clock enable + 5 + 1 + + + TMR12EN + Timer12 clock enable + 6 + 1 + + + TMR13EN + Timer13 clock enable + 7 + 1 + + + TMR14EN + Timer14 clock enable + 8 + 1 + + + WWDTEN + WWDT clock enable + 11 + 1 + + + SPI2EN + SPI2 clock enable + 14 + 1 + + + SPI3EN + SPI3 clock enable + 15 + 1 + + + USART2EN + USART2 clock enable + 17 + 1 + + + USART3EN + USART3 clock enable + 18 + 1 + + + UART4EN + UART4 clock enable + 19 + 1 + + + UART5EN + UART5 clock enable + 20 + 1 + + + I2C1EN + I2C1 clock enable + 21 + 1 + + + I2C2EN + I2C2 clock enable + 22 + 1 + + + I2C3EN + I2C3 clock enable + 23 + 1 + + + CAN1EN + CAN1 clock enable + 25 + 1 + + + CAN2EN + CAN2 clock enable + 26 + 1 + + + PWCEN + PWC clock enable + 28 + 1 + + + DACEN + DAC clock enable + 29 + 1 + + + UART7EN + UART7 clock enable + 30 + 1 + + + UART8EN + UART8 clock enable + 31 + 1 + + + + + APB2EN + APB2EN + APB2 peripheral clock enable register + (CRM_APB2EN) + 0x44 + 0x20 + read-write + 0x00000000 + + + TMR1EN + Timer1 clock enable + 0 + 1 + + + TMR8EN + Timer8 clock enable + 1 + 1 + + + USART1EN + USART1 clock enable + 4 + 1 + + + USART6EN + USART6 clock enable + 5 + 1 + + + ADC1EN + ADC1 clock enable + 8 + 1 + + + ADC2EN + ADC2 clock enable + 9 + 1 + + + ADC3EN + ADC3 clock enable + 10 + 1 + + + SPI1EN + SPI1 clock enable + 12 + 1 + + + SPI4EN + SPI4 clock enable + 13 + 1 + + + SCFGEN + SCFG clock enable + 14 + 1 + + + TMR9EN + Timer9 clock enable + 16 + 1 + + + TMR10EN + Timer10 clock enable + 17 + 1 + + + TMR11EN + Timer11 clock enable + 18 + 1 + + + TMR20EN + Timer20 clock enable + 20 + 1 + + + ACCEN + ACC clock enable + 29 + 1 + + + + + AHBLPEN1 + AHBLPEN1 + AHB Low-power Peripheral Clock enable + register 1 (CRM_AHBLPEN1) + 0x50 + 0x20 + read-write + 0x3E6390FF + + + GPIOALPEN + IO A clock enable during sleep mode + 0 + 1 + + + GPIOBLPEN + IO B clock enable during sleep mode + 1 + 1 + + + GPIOCLPEN + IO C clock enable during sleep mode + 2 + 1 + + + GPIODLPEN + IO D clock enable during sleep mode + 3 + 1 + + + GPIOELPEN + IO E clock enable during sleep mode + 4 + 1 + + + GPIOFLPEN + IO F clock enable during sleep mode + 5 + 1 + + + GPIOGLPEN + IO G clock enable during sleep mode + 6 + 1 + + + GPIOHLPEN + IO H clock enable during sleep mode + 7 + 1 + + + CRCLPEN + CRC clock enable during sleep mode + 12 + 1 + + + FLASHLPEN + Flash clock enable during sleep mode + 15 + 1 + + + SRAM1LPEN + SRAM1 clock enable during sleep mode + 16 + 1 + + + SRAM2LPEN + SRAM2 clock enable during sleep mode + 17 + 1 + + + EDMALPEN + EDMA clock enable during sleep mode + 21 + 1 + + + DMA1LPEN + DMA1 clock enable during sleep mode + 22 + 1 + + + DMA2LPEN + DMA2 clock enable during sleep mode + 24 + 1 + + + EMACLPEN + EMAC clock enable during sleep mode + 25 + 1 + + + EMACTXLPEN + EMAC Tx clock enable during sleep mode + 26 + 1 + + + EMACRXLPEN + EMAC Rx clock enable during sleep mode + 27 + 1 + + + EMACPTPLPEN + EMAC PTP clock enable during sleep mode + 28 + 1 + + + OTGFS2LPEN + OTGFS2 clock enable during sleep mode + 29 + 1 + + + + + AHBLPEN2 + AHBLPEN2 + AHB peripheral Low-power clock + enable register 2 (CRM_AHBLPEN2) + 0x54 + 0x20 + read-write + 0x00008081 + + + DVPLPEN + DVP clock enable during sleep mode + 0 + 1 + + + OTGFS1LPEN + OTGFS1 clock enable during sleep mode + 7 + 1 + + + SDIO1LPEN + SDIO1 clock enable during sleep mode + 15 + 1 + + + + + AHBLPEN3 + AHBLPEN3 + AHB peripheral Low-power clock + enable register 3 (CRM_AHBLPEN3) + 0x58 + 0x20 + read-write + 0x0000C003 + + + XMCLPEN + XMC clock enable during sleep mode + 0 + 1 + + + QSPI1LPEN + QSPI1 clock enable during sleep mode + 1 + 1 + + + QSPI2LPEN + QSPI2 clock enable during sleep mode + 14 + 1 + + + SDIO2LPEN + SDIO2 clock enable during sleep mode + 15 + 1 + + + + + APB1LPEN + APB1LPEN + APB1 peripheral Low-power clock + enable register (CRM_APB1LPEN) + 0x60 + 0x20 + read-write + 0xF6FEE9FF + + + TMR2LPEN + Timer2 clock enable during sleep mode + 0 + 1 + + + TMR3LPEN + Timer3 clock enable during sleep mode + 1 + 1 + + + TMR4LPEN + Timer4 clock enable during sleep mode + 2 + 1 + + + TMR5LPEN + Timer5 clock enable during sleep mode + 3 + 1 + + + TMR6LPEN + Timer6 clock enable during sleep mode + 4 + 1 + + + TMR7LPEN + Timer7 clock enable during sleep mode + 5 + 1 + + + TMR12LPEN + Timer12 clock enable during sleep mode + 6 + 1 + + + TMR13LPEN + Timer13 clock enable during sleep mode + 7 + 1 + + + TMR14LPEN + Timer14 clock enable during sleep mode + 8 + 1 + + + WWDTLPEN + WWDT clock enable during sleep mode + 11 + 1 + + + SPI2LPEN + SPI2 clock enable during sleep mode + 14 + 1 + + + SPI3LPEN + SPI3 clock enable during sleep mode + 15 + 1 + + + USART2LPEN + USART2 clock enable during sleep mode + 17 + 1 + + + USART3LPEN + USART3 clock enable during sleep mode + 18 + 1 + + + UART4LPEN + UART4 clock enable during sleep mode + 19 + 1 + + + UART5LPEN + UART5 clock enable during sleep mode + 20 + 1 + + + I2C1CPEN + I2C1 clock enable during sleep mode + 21 + 1 + + + I2C2CPEN + I2C2 clock enable during sleep mode + 22 + 1 + + + I2C3CPEN + I2C3 clock enable during sleep mode + 23 + 1 + + + CAN1LPEN + CAN1 clock enable during sleep mode + 25 + 1 + + + CAN2LPEN + CAN2 clock enable during sleep mode + 26 + 1 + + + PWCLPEN + PWC clock enable during sleep mode + 28 + 1 + + + DACLPEN + DAC clock enable during sleep mode + 29 + 1 + + + UART7LPEN + UART7 clock enable during sleep mode + 30 + 1 + + + UART8LPEN + UART8 clock enable during sleep mode + 31 + 1 + + + + + APB2LPEN + APB2LPEN + APB2 peripheral Low-power clock + enable register (CRM_APB2LPEN) + 0x64 + 0x20 + read-write + 0x20177733 + + + TMR1LPEN + Timer1 clock enable during sleep mode + 0 + 1 + + + TMR8LPEN + Timer8 clock enable during sleep mode + 1 + 1 + + + USART1LPEN + USART1 clock enable during sleep mode + 4 + 1 + + + USART6LPEN + USART6 clock enable during sleep mode + 5 + 1 + + + ADC1CPEN + ADC1 clock enable during sleep mode + 8 + 1 + + + ADC2CPEN + ADC2 clock enable during sleep mode + 9 + 1 + + + ADC3EN + ADC3 clock enable during sleep mode + 10 + 1 + + + SPI1LPEN + SPI1 clock enable during sleep mode + 12 + 1 + + + SPI4LPEN + SPI4 clock enable during sleep mode + 13 + 1 + + + SCFGLPEN + SCFG clock enable during sleep mode + 14 + 1 + + + TMR9LPEN + Timer9 clock enable during sleep mode + 16 + 1 + + + TMR10LPEN + Timer10 clock enable during sleep mode + 17 + 1 + + + TMR11LPEN + Timer11 clock enable during sleep mode + 18 + 1 + + + TMR20LPEN + Timer20 clock enable during sleep mode + 20 + 1 + + + ACCLPEN + ACC clock enable during sleep mode + 29 + 1 + + + + + BPDC + BPDC + Battery powered domain control register + (CRM_BPDC) + 0x70 + 0x20 + 0x00000000 + + + LEXTEN + Low speed external crystal enable + 0 + 1 + read-write + + + LEXTSTBL + Low speed external crystal ready + 1 + 1 + read-only + + + LEXTBYPS + Low speed external crystal bypass + 2 + 1 + read-write + + + ERTCSEL + ERTC clock source selection + 8 + 2 + read-write + + + ERTCEN + ERTC clock enable + 15 + 1 + read-write + + + BPDRST + Battery powered domain software reset + 16 + 1 + read-write + + + + + CTRLSTS + CTRLSTS + Control/status register + (CRM_CTRLSTS) + 0x74 + 0x20 + 0x0C000000 + + + LICKEN + Low speed internal clock enable + 0 + 1 + read-write + + + LICKSTBL + Low speed internal clock ready + 1 + 1 + read-only + + + RSTFC + Reset reset flag + 24 + 1 + read-write + + + NRSTF + PIN reset flag + 26 + 1 + read-write + + + PORRSTF + POR/LVR reset flag + 27 + 1 + read-write + + + SWRSTF + Software reset flag + 28 + 1 + read-write + + + WDTRSTF + Watchdog timer reset flag + 29 + 1 + read-write + + + WWDTRSTF + Window watchdog timer reset flag + 30 + 1 + read-write + + + LPRSTF + Low-power reset flag + 31 + 1 + read-write + + + + + MISC1 + MISC1 + Miscellaneous register1 + 0xA0 + 0x20 + 0x00000000 + + + HICKCAL_KEY + HICKCAL write key value + 0 + 8 + read-write + + + HICKDIV + HICK 6 divider selection + 12 + 1 + read-write + + + HICK_TO_USB + HICK to usb clock + 13 + 1 + read-write + + + HICK_TO_SCLK + HICK to system clock + 14 + 1 + read-write + + + CLKOUT2_SEL2 + Clock output2 select2 + 16 + 4 + read-write + + + CLKOUT1DIV2 + Clock output1 division2 + 24 + 4 + read-write + + + CLKOUT2DIV2 + Clock output2 division2 + 28 + 4 + read-write + + + + + MISC2 + MISC2 + Miscellaneous register2 + 0xA4 + 0x20 + 0x0000000D + + + AUTO_STEP_EN + AUTO_STEP_EN + 4 + 2 + read-write + + + CLK_TO_TMR + Clock output internal connect to timer10 + 8 + 1 + read-write + + + USBDIV + USB division + 12 + 4 + read-write + + + + + + + GPIOA + General purpose I/Os + GPIO + 0x40020000 + + 0x0 + 0x400 + registers + + + + CFGR + CFGR + GPIO configuration register + 0x0 + 0x20 + read-write + 0x00000000 + + + IOMC15 + GPIOx pin 15 mode configurate + 30 + 2 + + + IOMC14 + GPIOx pin 14 mode configurate + 28 + 2 + + + IOMC13 + GPIOx pin 13 mode configurate + 26 + 2 + + + IOMC12 + GPIOx pin 12 mode configurate + 24 + 2 + + + IOMC11 + GPIOx pin 11 mode configurate + 22 + 2 + + + IOMC10 + GPIOx pin 10 mode configurate + 20 + 2 + + + IOMC9 + GPIOx pin 9 mode configurate + 18 + 2 + + + IOMC8 + GPIOx pin 8 mode configurate + 16 + 2 + + + IOMC7 + GPIOx pin 7 mode configurate + 14 + 2 + + + IOMC6 + GPIOx pin 6 mode configurate + 12 + 2 + + + IOMC5 + GPIOx pin 5 mode configurate + 10 + 2 + + + IOMC4 + GPIOx pin 4 mode configurate + 8 + 2 + + + IOMC3 + GPIOx pin 3 mode configurate + 6 + 2 + + + IOMC2 + GPIOx pin 2 mode configurate + 4 + 2 + + + IOMC1 + GPIOx pin 1 mode configurate + 2 + 2 + + + IOMC0 + GPIOx pin 0 mode configurate + 0 + 2 + + + + + OMODE + OMODE + GPIO output mode register + 0x4 + 0x20 + read-write + 0x00000000 + + + OM15 + GPIOx pin 15 outpu mode configurate + 15 + 1 + + + OM14 + GPIOx pin 14 outpu mode configurate + 14 + 1 + + + OM13 + GPIOx pin 13 outpu mode configurate + 13 + 1 + + + OM12 + GPIOx pin 12 outpu mode configurate + 12 + 1 + + + OM11 + GPIOx pin 11 outpu mode configurate + 11 + 1 + + + OM10 + GPIOx pin 10 outpu mode configurate + 10 + 1 + + + OM9 + GPIOx pin 9 outpu mode configurate + 9 + 1 + + + OM8 + GPIOx pin 8 outpu mode configurate + 8 + 1 + + + OM7 + GPIOx pin 7 outpu mode configurate + 7 + 1 + + + OM6 + GPIOx pin 6 outpu mode configurate + 6 + 1 + + + OM5 + GPIOx pin 5 outpu mode configurate + 5 + 1 + + + OM4 + GPIOx pin 4 outpu mode configurate + 4 + 1 + + + OM3 + GPIOx pin 3 outpu mode configurate + 3 + 1 + + + OM2 + GPIOx pin 2 outpu mode configurate + 2 + 1 + + + OM1 + GPIOx pin 1 outpu mode configurate + 1 + 1 + + + OM0 + GPIOx pin 0 outpu mode configurate + 0 + 1 + + + + + ODRVR + ODRVR + GPIO drive capability register + 0x8 + 0x20 + read-write + 0x00000000 + + + ODRV15 + GPIOx pin 15 output drive capability + 30 + 2 + + + ODRV14 + GPIOx pin 14 output drive capability + 28 + 2 + + + ODRV13 + GPIOx pin 13 output drive capability + 26 + 2 + + + ODRV12 + GPIOx pin 12 output drive capability + 24 + 2 + + + ODRV11 + GPIOx pin 11 output drive capability + 22 + 2 + + + ODRV10 + GPIOx pin 10 output drive capability + 20 + 2 + + + ODRV9 + GPIOx pin 9 output drive capability + 18 + 2 + + + ODRV8 + GPIOx pin 8 output drive capability + 16 + 2 + + + ODRV7 + GPIOx pin 7 output drive capability + 14 + 2 + + + ODRV6 + GPIOx pin 6 output drive capability + 12 + 2 + + + ODRV5 + GPIOx pin 5 output drive capability + 10 + 2 + + + ODRV4 + GPIOx pin 4 output drive capability + 8 + 2 + + + ODRV3 + GPIOx pin 3 output drive capability + 6 + 2 + + + ODRV2 + GPIOx pin 2 output drive capability + 4 + 2 + + + ODRV1 + GPIOx pin 1 output drive capability + 2 + 2 + + + ODRV0 + GPIOx pin 0 output drive capability + 0 + 2 + + + + + PULL + PULL + GPIO pull-up/pull-down register + 0xC + 0x20 + read-write + 0x00000000 + + + PULL15 + GPIOx pin 15 pull configuration + 30 + 2 + + + PULL14 + GPIOx pin 14 pull configuration + 28 + 2 + + + PULL13 + GPIOx pin 13 pull configuration + 26 + 2 + + + PULL12 + GPIOx pin 12 pull configuration + 24 + 2 + + + PULL11 + GPIOx pin 11 pull configuration + 22 + 2 + + + PULL10 + GPIOx pin 10 pull configuration + 20 + 2 + + + PULL9 + GPIOx pin 9 pull configuration + 18 + 2 + + + PULL8 + GPIOx pin 8 pull configuration + 16 + 2 + + + PULL7 + GPIOx pin 7 pull configuration + 14 + 2 + + + PULL6 + GPIOx pin 6 pull configuration + 12 + 2 + + + PULL5 + GPIOx pin 5 pull configuration + 10 + 2 + + + PULL4 + GPIOx pin 4 pull configuration + 8 + 2 + + + PULL3 + GPIOx pin 3 pull configuration + 6 + 2 + + + PULL2 + GPIOx pin 2 pull configuration + 4 + 2 + + + PULL1 + GPIOx pin 1 pull configuration + 2 + 2 + + + PULL0 + GPIOx pin 0 pull configuration + 0 + 2 + + + + + IDT + IDT + GPIO input data register + 0x10 + 0x20 + read-only + 0x00000000 + + + IDT0 + Port input data + 0 + 1 + + + IDT1 + Port input data + 1 + 1 + + + IDT2 + Port input data + 2 + 1 + + + IDT3 + Port input data + 3 + 1 + + + IDT4 + Port input data + 4 + 1 + + + IDT5 + Port input data + 5 + 1 + + + IDT6 + Port input data + 6 + 1 + + + IDT7 + Port input data + 7 + 1 + + + IDT8 + Port input data + 8 + 1 + + + IDT9 + Port input data + 9 + 1 + + + IDT10 + Port input data + 10 + 1 + + + IDT11 + Port input data + 11 + 1 + + + IDT12 + Port input data + 12 + 1 + + + IDT13 + Port input data + 13 + 1 + + + IDT14 + Port input data + 14 + 1 + + + IDT15 + Port input data + 15 + 1 + + + + + ODT + ODT + GPIO output data register + 0x14 + 0x20 + read-write + 0x00000000 + + + ODT0 + Port output data + 0 + 1 + + + ODT1 + Port output data + 1 + 1 + + + ODT2 + Port output data + 2 + 1 + + + ODT3 + Port output data + 3 + 1 + + + ODT4 + Port output data + 4 + 1 + + + ODT5 + Port output data + 5 + 1 + + + ODT6 + Port output data + 6 + 1 + + + ODT7 + Port output data + 7 + 1 + + + ODT8 + Port output data + 8 + 1 + + + ODT9 + Port output data + 9 + 1 + + + ODT10 + Port output data + 10 + 1 + + + ODT11 + Port output data + 11 + 1 + + + ODT12 + Port output data + 12 + 1 + + + ODT13 + Port output data + 13 + 1 + + + ODT14 + Port output data + 14 + 1 + + + ODT15 + Port output data + 15 + 1 + + + + + SCR + SCR + Port bit set/clear register + 0x18 + 0x20 + write-only + 0x00000000 + + + IOSB0 + Set bit 0 + 0 + 1 + + + IOSB1 + Set bit 1 + 1 + 1 + + + IOSB2 + Set bit 1 + 2 + 1 + + + IOSB3 + Set bit 3 + 3 + 1 + + + IOSB4 + Set bit 4 + 4 + 1 + + + IOSB5 + Set bit 5 + 5 + 1 + + + IOSB6 + Set bit 6 + 6 + 1 + + + IOSB7 + Set bit 7 + 7 + 1 + + + IOSB8 + Set bit 8 + 8 + 1 + + + IOSB9 + Set bit 9 + 9 + 1 + + + IOSB10 + Set bit 10 + 10 + 1 + + + IOSB11 + Set bit 11 + 11 + 1 + + + IOSB12 + Set bit 12 + 12 + 1 + + + IOSB13 + Set bit 13 + 13 + 1 + + + IOSB14 + Set bit 14 + 14 + 1 + + + IOSB15 + Set bit 15 + 15 + 1 + + + IOCB0 + Clear bit 0 + 16 + 1 + + + IOCB1 + Clear bit 1 + 17 + 1 + + + IOCB2 + Clear bit 2 + 18 + 1 + + + IOCB3 + Clear bit 3 + 19 + 1 + + + IOCB4 + Clear bit 4 + 20 + 1 + + + IOCB5 + Clear bit 5 + 21 + 1 + + + IOCB6 + Clear bit 6 + 22 + 1 + + + IOCB7 + Clear bit 7 + 23 + 1 + + + IOCB8 + Clear bit 8 + 24 + 1 + + + IOCB9 + Clear bit 9 + 25 + 1 + + + IOCB10 + Clear bit 10 + 26 + 1 + + + IOCB11 + Clear bit 11 + 27 + 1 + + + IOCB12 + Clear bit 12 + 28 + 1 + + + IOCB13 + Clear bit 13 + 29 + 1 + + + IOCB14 + Clear bit 14 + 30 + 1 + + + IOCB15 + Clear bit 15 + 31 + 1 + + + + + WPR + WPR + Port write protect + register + 0x1C + 0x20 + read-write + 0x00000000 + + + WPEN0 + Write protect enable 0 + 0 + 1 + + + WPEN1 + Write protect enable 1 + 1 + 1 + + + WPEN2 + Write protect enable 2 + 2 + 1 + + + WPEN3 + Write protect enable 3 + 3 + 1 + + + WPEN4 + Write protect enable 4 + 4 + 1 + + + WPEN5 + Write protect enable 5 + 5 + 1 + + + WPEN6 + Write protect enable 6 + 6 + 1 + + + WPEN7 + Write protect enable 7 + 7 + 1 + + + WPEN8 + Write protect enable 8 + 8 + 1 + + + WPEN9 + Write protect enable 9 + 9 + 1 + + + WPEN10 + Write protect enable 10 + 10 + 1 + + + WPEN11 + Write protect enable 11 + 11 + 1 + + + WPEN12 + Write protect enable 12 + 12 + 1 + + + WPEN13 + Write protect enable 13 + 13 + 1 + + + WPEN14 + Write protect enable 14 + 14 + 1 + + + WPEN15 + Write protect enable 15 + 15 + 1 + + + WPSEQ + Write protect sequence + 16 + 1 + + + + + MUXL + MUXL + GPIO muxing function low register + 0x20 + 0x20 + read-write + 0x00000000 + + + MUXL7 + GPIOx pin 7 muxing + 28 + 4 + + + MUXL6 + GPIOx pin 6 muxing + 24 + 4 + + + MUXL5 + GPIOx pin 5 muxing + 20 + 4 + + + MUXL4 + GPIOx pin 4 muxing + 16 + 4 + + + MUXL3 + GPIOx pin 3 muxing + 12 + 4 + + + MUXL2 + GPIOx pin 2 muxing + 8 + 4 + + + MUXL1 + GPIOx pin 1 muxing + 4 + 4 + + + MUXL0 + GPIOx pin 0 muxing + 0 + 4 + + + + + MUXH + MUXH + GPIO muxing function high register + 0x24 + 0x20 + read-write + 0x00000000 + + + MUXH15 + GPIOx pin 15 muxing + 28 + 4 + + + MUXH14 + GPIOx pin 14 muxing + 24 + 4 + + + MUXH13 + GPIOx pin 13 muxing + 20 + 4 + + + MUXH12 + GPIOx pin 12 muxing + 16 + 4 + + + MUXH11 + GPIOx pin 11 muxing + 12 + 4 + + + MUXH10 + GPIOx pin 10 muxing + 8 + 4 + + + MUXH9 + GPIOx pin 9 muxing + 4 + 4 + + + MUXH8 + GPIOx pin 8 muxing + 0 + 4 + + + + + CLR + CLR + GPIO bit reset register + 0x28 + 0x20 + write-only + 0x00000000 + + + IOCB0 + Clear bit 0 + 0 + 1 + + + IOCB1 + Clear bit 1 + 1 + 1 + + + IOCB2 + Clear bit 1 + 2 + 1 + + + IOCB3 + Clear bit 3 + 3 + 1 + + + IOCB4 + Clear bit 4 + 4 + 1 + + + IOCB5 + Clear bit 5 + 5 + 1 + + + IOCB6 + Clear bit 6 + 6 + 1 + + + IOCB7 + Clear bit 7 + 7 + 1 + + + IOCB8 + Clear bit 8 + 8 + 1 + + + IOCB9 + Clear bit 9 + 9 + 1 + + + IOCB10 + Clear bit 10 + 10 + 1 + + + IOCB11 + Clear bit 11 + 11 + 1 + + + IOCB12 + Clear bit 12 + 12 + 1 + + + IOCB13 + Clear bit 13 + 13 + 1 + + + IOCB14 + Clear bit 14 + 14 + 1 + + + IOCB15 + Clear bit 15 + 15 + 1 + + + + + HDRV + HDRV + Huge current driver + 0x3C + 0x20 + read-write + 0x00000000 + + + HDRV0 + Port x driver bit y + 0 + 1 + + + HDRV1 + Port x driver bit y + 1 + 1 + + + HDRV2 + Port x driver bit y + 2 + 1 + + + HDRV3 + Port x driver bit y + 3 + 1 + + + HDRV4 + Port x driver bit y + 4 + 1 + + + HDRV5 + Port x driver bit y + 5 + 1 + + + HDRV6 + Port x driver bit y + 6 + 1 + + + HDRV7 + Port x driver bit y + 7 + 1 + + + HDRV8 + Port x driver bit y + 8 + 1 + + + HDRV9 + Port x driver bit y + 9 + 1 + + + HDRV10 + Port x driver bit y + 10 + 1 + + + HDRV11 + Port x driver bit y + 11 + 1 + + + HDRV12 + Port x driver bit y + 12 + 1 + + + HDRV13 + Port x driver bit y + 13 + 1 + + + HDRV14 + Port x driver bit y + 14 + 1 + + + HDRV15 + Port x driver bit y + 15 + 1 + + + + + + + GPIOB + 0x40020400 + + + GPIOC + 0x40020800 + + + GPIOD + 0x40020C00 + + + GPIOE + 0x40021000 + + + GPIOF + 0x40021400 + + + GPIOG + 0x40021800 + + + GPIOH + 0x40021C00 + + + EXINT + EXINT + EXINT + 0x40013C00 + + 0x0 + 0x400 + registers + + + EXINT0 + EXINT Line0 interrupt + 6 + + + EXINT1 + EXINT Line1 interrupt + 7 + + + EXINT2 + EXINT Line2 interrupt + 8 + + + EXINT3 + EXINT Line3 interrupt + 9 + + + EXINT4 + EXINT Line4 interrupt + 10 + + + EXINT9_5 + EXINT Line[9:5] interrupts + 23 + + + EXINT15_10 + EXINT Line[15:10] interrupts + 40 + + + PVM + PVM interrupt connect to EXINT line16 + 1 + + + ERTCALARM + ERTC Alarm interrupt connect to EXINT line17 + 41 + + + OTGFS1_WKUP + OTGFS1_WKUP interrupt connect to EXINT line18 + 42 + + + EMAC_WKUP + EMAC_WKUP interrupt connect to EXINT line19 + 62 + + + OTGFS2_WKUP + OTGFS2_WKUP interrupt connect to EXINT line20 + 76 + + + TAMPER + Tamper interrupt connect to EXINT line21 + 2 + + + ERTC_WKUP + ERTC Global interrupt connect to EXINT line22 + 3 + + + + INTEN + INTEN + Interrupt enable register + 0x0 + 0x20 + read-write + 0x00000000 + + + INTEN0 + Interrupt enable or disable on line 0 + 0 + 1 + + + INTEN1 + Interrupt enable or disable on line 1 + 1 + 1 + + + INTEN2 + Interrupt enable or disable on line 2 + 2 + 1 + + + INTEN3 + Interrupt enable or disable on line 3 + 3 + 1 + + + INTEN4 + Interrupt enable or disable on line 4 + 4 + 1 + + + INTEN5 + Interrupt enable or disable on line 5 + 5 + 1 + + + INTEN6 + Interrupt enable or disable on line 6 + 6 + 1 + + + INTEN7 + Interrupt enable or disable on line 7 + 7 + 1 + + + INTEN8 + Interrupt enable or disable on line 8 + 8 + 1 + + + INTEN9 + Interrupt enable or disable on line 9 + 9 + 1 + + + INTEN10 + Interrupt enable or disable on line 10 + 10 + 1 + + + INTEN11 + Interrupt enable or disable on line 11 + 11 + 1 + + + INTEN12 + Interrupt enable or disable on line 12 + 12 + 1 + + + INTEN13 + Interrupt enable or disable on line 13 + 13 + 1 + + + INTEN14 + Interrupt enable or disable on line 14 + 14 + 1 + + + INTEN15 + Interrupt enable or disable on line 15 + 15 + 1 + + + INTEN16 + Interrupt enable or disable on line 16 + 16 + 1 + + + INTEN17 + Interrupt enable or disable on line 17 + 17 + 1 + + + INTEN18 + Interrupt enable or disable on line 18 + 18 + 1 + + + INTEN19 + Interrupt enable or disable on line 19 + 19 + 1 + + + INTEN20 + Interrupt enable or disable on line 20 + 20 + 1 + + + INTEN21 + Interrupt enable or disable on line 21 + 21 + 1 + + + INTEN22 + Interrupt enable or disable on line 22 + 22 + 1 + + + + + EVTEN + EVTEN + Event enable register + 0x4 + 0x20 + read-write + 0x00000000 + + + EVTEN0 + Event enable or disable on line 0 + 0 + 1 + + + EVTEN1 + Event enable or disable on line 1 + 1 + 1 + + + EVTEN2 + Event enable or disable on line 2 + 2 + 1 + + + EVTEN3 + Event enable or disable on line 3 + 3 + 1 + + + EVTEN4 + Event enable or disable on line 4 + 4 + 1 + + + EVTEN5 + Event enable or disable on line 5 + 5 + 1 + + + EVTEN6 + Event enable or disable on line 6 + 6 + 1 + + + EVTEN7 + Event enable or disable on line 7 + 7 + 1 + + + EVTEN8 + Event enable or disable on line 8 + 8 + 1 + + + EVTEN9 + Event enable or disable on line 9 + 9 + 1 + + + EVTEN10 + Event enable or disable on line 10 + 10 + 1 + + + EVTEN11 + Event enable or disable on line 11 + 11 + 1 + + + EVTEN12 + Event enable or disable on line 12 + 12 + 1 + + + EVTEN13 + Event enable or disable on line 13 + 13 + 1 + + + EVTEN14 + Event enable or disable on line 14 + 14 + 1 + + + EVTEN15 + Event enable or disable on line 15 + 15 + 1 + + + EVTEN16 + Event enable or disable on line 16 + 16 + 1 + + + EVTEN17 + Event enable or disable on line 17 + 17 + 1 + + + EVTEN18 + Event enable or disable on line 18 + 18 + 1 + + + EVTEN19 + Event enable or disable on line 19 + 19 + 1 + + + EVTEN20 + Event enable or disable on line 20 + 20 + 1 + + + EVTEN21 + Event enable or disable on line 21 + 21 + 1 + + + EVTEN22 + Event enable or disable on line 22 + 22 + 1 + + + + + POLCFG1 + POLCFG1 + Rising polarity configuration register + 0x8 + 0x20 + read-write + 0x00000000 + + + RP0 + Rising polarity configuration bit of line 0 + 0 + 1 + + + RP1 + Rising polarity configuration bit of line 1 + 1 + 1 + + + RP2 + Rising polarity configuration bit of line 2 + 2 + 1 + + + RP3 + Rising polarity configuration bit of line 3 + 3 + 1 + + + RP4 + Rising polarity configuration bit of line 4 + 4 + 1 + + + RP5 + Rising polarity configuration bit of line 5 + 5 + 1 + + + RP6 + Rising polarity configuration bit of linee 6 + 6 + 1 + + + RP7 + Rising polarity configuration bit of line 7 + 7 + 1 + + + RP8 + Rising polarity configuration bit of line 8 + 8 + 1 + + + RP9 + Rising polarity configuration bit of line 9 + 9 + 1 + + + RP10 + Rising polarity configuration bit of line 10 + 10 + 1 + + + RP11 + Rising polarity configuration bit of line 11 + 11 + 1 + + + RP12 + Rising polarity configuration bit of line 12 + 12 + 1 + + + RP13 + Rising polarity configuration bit of line 13 + 13 + 1 + + + RP14 + Rising polarity configuration bit of line 14 + 14 + 1 + + + RP15 + Rising polarity configuration bit of line 15 + 15 + 1 + + + RP16 + Rising polarity configuration bit of line 16 + 16 + 1 + + + RP17 + Rising polarity configuration bit of line 17 + 17 + 1 + + + RP18 + Rising polarity configuration bit of line 18 + 18 + 1 + + + RP19 + Rising polarity configuration bit of line 19 + 19 + 1 + + + RP20 + Rising polarity configuration bit of line 20 + 20 + 1 + + + RP21 + Rising polarity configuration bit of line 21 + 21 + 1 + + + RP22 + Rising polarity configuration bit of line 22 + 22 + 1 + + + + + POLCFG2 + POLCFG2 + Falling polarity configuration register + 0xC + 0x20 + read-write + 0x00000000 + + + FP0 + Falling polarity event configuration bit of line 0 + 0 + 1 + + + FP1 + Falling polarity event configuration bit of line 1 + 1 + 1 + + + FP2 + Falling polarity event configuration bit of line 2 + 2 + 1 + + + FP3 + Falling polarity event configuration bit of line 3 + 3 + 1 + + + FP4 + Falling polarity event configuration bit of line 4 + 4 + 1 + + + FP5 + Falling polarity event configuration bit of line 5 + 5 + 1 + + + FP6 + Falling polarity event configuration bit of line 6 + 6 + 1 + + + FP7 + Falling polarity event configuration bit of line 7 + 7 + 1 + + + FP8 + Falling polarity event configuration bit of line 8 + 8 + 1 + + + FP9 + Falling polarity event configuration bit of line 9 + 9 + 1 + + + FP10 + Falling polarity event configuration bit of line 10 + 10 + 1 + + + FP11 + Falling polarity event configuration bit of line 11 + 11 + 1 + + + FP12 + Falling polarity event configuration bit of line 12 + 12 + 1 + + + FP13 + Falling polarity event configuration bit of line 13 + 13 + 1 + + + FP14 + Falling polarity event configuration bit of line 14 + 14 + 1 + + + FP15 + Falling polarity event configuration bit of line 15 + 15 + 1 + + + FP16 + Falling polarity event configuration bit of line 16 + 16 + 1 + + + FP17 + Falling polarity event configuration bit of line 17 + 17 + 1 + + + FP18 + Falling polarity event configuration bit of line 18 + 18 + 1 + + + FP19 + Falling polarity event configuration bit of line 19 + 19 + 1 + + + FP20 + Falling polarity event configuration bit of line 20 + 20 + 1 + + + FP21 + Falling polarity event configuration bit of line 21 + 21 + 1 + + + FP22 + Falling polarity event configuration bit of line 22 + 22 + 1 + + + + + SWTRG + SWTRG + Software triggle register + 0x10 + 0x20 + read-write + 0x00000000 + + + SWT0 + Software triggle on line 0 + 0 + 1 + + + SWT1 + Software triggle on line 1 + 1 + 1 + + + SWT2 + Software triggle on line 2 + 2 + 1 + + + SWT3 + Software triggle on line 3 + 3 + 1 + + + SWT4 + Software triggle on line 4 + 4 + 1 + + + SWT5 + Software triggle on line 5 + 5 + 1 + + + SWT6 + Software triggle on line 6 + 6 + 1 + + + SWT7 + Software triggle on line 7 + 7 + 1 + + + SWT8 + Software triggle on line 8 + 8 + 1 + + + SWT9 + Software triggle on line 9 + 9 + 1 + + + SWT10 + Software triggle on line 10 + 10 + 1 + + + SWT11 + Software triggle on line 11 + 11 + 1 + + + SWT12 + Software triggle on line 12 + 12 + 1 + + + SWT13 + Software triggle on line 13 + 13 + 1 + + + SWT14 + Software triggle on line 14 + 14 + 1 + + + SWT15 + Software triggle on line 15 + 15 + 1 + + + SWT16 + Software triggle on line 16 + 16 + 1 + + + SWT17 + Software triggle on line 17 + 17 + 1 + + + SWT18 + Software triggle on line 18 + 18 + 1 + + + SWT19 + Software triggle on line 19 + 19 + 1 + + + SWT20 + Software triggle on line 20 + 20 + 1 + + + SWT21 + Software triggle on line 21 + 21 + 1 + + + SWT22 + Software triggle on line 22 + 22 + 1 + + + + + INTSTS + INTSTS + Interrupt status register + 0x14 + 0x20 + read-write + 0x00000000 + + + LINE0 + Line 0 state bit + 0 + 1 + + + LINE1 + Line 1 state bit + 1 + 1 + + + LINE2 + Line 2 state bit + 2 + 1 + + + LINE3 + Line 3 state bit + 3 + 1 + + + LINE4 + Line 4 state bit + 4 + 1 + + + LINE5 + Line 5 state bit + 5 + 1 + + + LINE6 + Line 6 state bit + 6 + 1 + + + LINE7 + Line 7 state bit + 7 + 1 + + + LINE8 + Line 8 state bit + 8 + 1 + + + LINE9 + Line 9 state bit + 9 + 1 + + + LINE10 + Line 10 state bit + 10 + 1 + + + LINE11 + Line 11 state bit + 11 + 1 + + + LINE12 + Line 12 state bit + 12 + 1 + + + LINE13 + Line 13 state bit + 13 + 1 + + + LINE14 + Line 14 state bit + 14 + 1 + + + LINE15 + Line 15 state bit + 15 + 1 + + + LINE16 + Line 16 state bit + 16 + 1 + + + LINE17 + Line 17 state bit + 17 + 1 + + + LINE18 + Line 18 state bit + 18 + 1 + + + LINE19 + Line 19 state bit + 19 + 1 + + + LINE20 + Line 20 state bit + 20 + 1 + + + LINE21 + Line 21 state bit + 21 + 1 + + + LINE22 + Line 22 state bit + 22 + 1 + + + + + + + EDMA + EDMA controller + EDMA + 0x40026000 + + 0x0 + 0x400 + registers + + + EDMA_Stream1 + EDMA Stream1 global interrupt + 11 + + + EDMA_Stream2 + EDMA Stream2 global interrupt + 12 + + + EDMA_Stream3 + EDMA Stream3 global interrupt + 13 + + + EDMA_Stream4 + EDMA Stream4 global interrupt + 14 + + + EDMA_Stream5 + EDMA Stream5 global interrupt + 15 + + + EDMA_Stream6 + EDMA Stream6 global interrupt + 16 + + + EDMA_Stream7 + EDMA Stream7 global interrupt + 17 + + + EDMA_Stream8 + EDMA Stream8 global interrupt + 47 + + + + STS1 + STS1 + Interrupt status register1 + 0x0 + 0x20 + read-only + 0x00000000 + + + FDTF4 + Stream 4 Full data transfer interrupt flag + + 27 + 1 + + + HDTF4 + Stream 4 half data transfer interrupt flag + + 26 + 1 + + + DTERRF4 + Stream 4 transfer error interrupt flag + + 25 + 1 + + + DMERRF4 + Stream 4 direct mode error interrupt flag + + 24 + 1 + + + FERRF4 + Stream 4 FIFO error interrupt flag + + 22 + 1 + + + FDTF3 + Stream 3 Full data transfer interrupt flag + + 21 + 1 + + + HDTF3 + Stream 3 half data transfer interrupt flag + + 20 + 1 + + + DTERRF3 + Stream 3 transfer error interrupt flag + + 19 + 1 + + + DMERRF3 + Stream 3 direct mode error interrupt flag + + 18 + 1 + + + FERRF3 + Stream 3 FIFO error interrupt flag + + 16 + 1 + + + FDTF2 + Stream 2 Full data transfer interrupt flag + + 11 + 1 + + + HDTF2 + Stream 2 half data transfer interrupt flag + + 10 + 1 + + + DTERRF2 + Stream 2 transfer error interrupt flag + + 9 + 1 + + + DMERRF2 + Stream 2 direct mode error interrupt flag + + 8 + 1 + + + FERRF2 + Stream 2 FIFO error interrupt flag + + 6 + 1 + + + FDTF1 + Stream 1 Full data transfer interrupt flag + + 5 + 1 + + + HDTF1 + Stream 1 half data transfer interrupt flag + + 4 + 1 + + + DTERRF1 + Stream 1 transfer error interrupt flag + + 3 + 1 + + + DMERRF1 + Stream 1 direct mode error interrupt flag + + 2 + 1 + + + FERRF1 + Stream 1 FIFO error interrupt flag + + 0 + 1 + + + + + STS2 + STS2 + Interrupt status register2 + 0x4 + 0x20 + read-only + 0x00000000 + + + FDTF8 + Stream 8 full data transfer interrupt flag + + 27 + 1 + + + HDTF8 + Stream 8 half data transfer interrupt flag + + 26 + 1 + + + DTERRF8 + Stream 8 transfer error interrupt flag + + 25 + 1 + + + DMERRF8 + Stream 8 direct mode error interrupt flag + + 24 + 1 + + + FERRF8 + Stream 8 FIFO error interrupt flag + + 22 + 1 + + + FDTF7 + Stream 7 full data transfer interrupt flag + + 21 + 1 + + + HDTF7 + Stream 7 half data transfer interrupt flag + + 20 + 1 + + + DTERRF7 + Stream 7 transfer error interrupt flag + + 19 + 1 + + + DMERRF7 + Stream 7 direct mode error interrupt flag + + 18 + 1 + + + FERRF7 + Stream 7 FIFO error interrupt flag + + 16 + 1 + + + FDTF6 + Stream 6 full data transfer interrupt flag + + 11 + 1 + + + HDTF6 + Stream 6 half data transfer interrupt flag + + 10 + 1 + + + DTERRF6 + Stream 6 transfer error interrupt flag + + 9 + 1 + + + DMERRF6 + Stream 6 direct mode error interrupt flag + + 8 + 1 + + + FERRF6 + Stream 6 FIFO error interrupt flag + + 6 + 1 + + + FDTF5 + Stream 5 full data transfer interrupt flag + + 5 + 1 + + + HDTF5 + Stream 5 half data transfer interrupt flag + + 4 + 1 + + + DTERRF5 + Stream 5 transfer error interrupt flag + + 3 + 1 + + + DMERRF5 + Stream 5 direct mode error interrupt flag + + 2 + 1 + + + FERRF5 + Stream 5 FIFO error interrupt flag + + 0 + 1 + + + + + CLR1 + CLR1 + Interrupt flag clear register1 + + 0x8 + 0x20 + read-write + 0x00000000 + + + FDTFC4 + Stream 4 clear full data transfer complete interrupt flag + + 27 + 1 + + + HDTFC4 + Stream 4 clear half data transfer interrupt flag + + 26 + 1 + + + DTERRFC4 + Stream 4 clear transfer error interrupt flag + + 25 + 1 + + + DMERRFC4 + Stream 4 clear direct mode error interrupt flag + + 24 + 1 + + + FERRFC4 + Stream 4 clear FIFO error interrupt flag + + 22 + 1 + + + FDTFC3 + Stream 3 clear full data transfer complete interrupt flag + + 21 + 1 + + + HDTFC3 + Stream 3 clear half data transfer interrupt flag + + 20 + 1 + + + DTERRFC3 + Stream 3 clear transfer error interrupt flag + + 19 + 1 + + + DMERRFC3 + Stream 3 clear direct mode error interrupt flag + + 18 + 1 + + + FERRFC3 + Stream 3 clear FIFO error interrupt flag + + 16 + 1 + + + FDTFC2 + Stream 2 clear full data transfer complete interrupt flag + + 11 + 1 + + + HDTFC2 + Stream 2 clear half data transfer interrupt flag + + 10 + 1 + + + DTERRFC2 + Stream 2 clear transfer error interrupt flag + + 9 + 1 + + + DMERRFC2 + Stream 2 clear direct mode error interrupt flag + + 8 + 1 + + + FERRFC2 + Stream 2 clear FIFO error interrupt flag + + 6 + 1 + + + FDTFC1 + Stream 1 clear full data transfer complete interrupt flag + + 5 + 1 + + + HDTFC1 + Stream 1 clear half data transfer interrupt flag + + 4 + 1 + + + DTERRFC1 + Stream 1 clear transfer error interrupt flag + + 3 + 1 + + + DMERRFC1 + Stream 1 clear direct mode error interrupt flag + + 2 + 1 + + + FERRFC1 + Stream 1 clear FIFO error interrupt flag + + 0 + 1 + + + + + CLR2 + CLR2 + Interrupt flag clear register2 + + 0xC + 0x20 + read-write + 0x00000000 + + + FDTFC8 + Stream 8 clear full data transfer complete interrupt flag + + 27 + 1 + + + HDTFC8 + Stream 8 clear half data transfer interrupt flag + + 26 + 1 + + + DTERRFC8 + Stream 8 clear transfer error interrupt flag + + 25 + 1 + + + DMERRFC8 + Stream 8 clear direct mode error interrupt flag + + 24 + 1 + + + FERRFC8 + Stream 8 clear FIFO error interrupt flag + + 22 + 1 + + + FDTFC7 + Stream 7 clear full data transfer complete interrupt flag + + 21 + 1 + + + HDTFC7 + Stream 7 clear half data transfer interrupt flag + + 20 + 1 + + + DTERRFC7 + Stream 7 clear transfer error interrupt flag + + 19 + 1 + + + DMERRFC7 + Stream 7 clear direct mode error interrupt flag + + 18 + 1 + + + FERRFC7 + Stream 7 clear FIFO error interrupt flag + + 16 + 1 + + + FDTFC6 + Stream 6 clear full data transfer complete interrupt flag + + 11 + 1 + + + HDTFC6 + Stream 6 clear half data transfer interrupt flag + + 10 + 1 + + + DTERRFC6 + Stream 6 clear transfer error interrupt flag + + 9 + 1 + + + DMERRFC6 + Stream 6 clear direct mode error interrupt flag + + 8 + 1 + + + FERRFC6 + Stream 6 clear FIFO error interrupt flag + + 6 + 1 + + + FDTFC5 + Stream 5 clear full data transfer complete interrupt flag + + 5 + 1 + + + HDTFC5 + Stream 5 clear half data transfer interrupt flag + + 4 + 1 + + + DTERRFC5 + Stream 5 clear transfer error interrupt flag + + 3 + 1 + + + DMERRFC5 + Stream 5 clear direct mode error interrupt flag + + 2 + 1 + + + FERRFC5 + Stream 5 clear FIFO error interrupt flag + + 0 + 1 + + + + + S1CTRL + S1CTRL + stream 1 control + register + 0x10 + 0x20 + read-write + 0x00000000 + + + MBURST + Memory burst transmission + + 23 + 2 + + + PBURST + Peripheral burst transmission + + 21 + 2 + + + CM + Current memory (only in double buffer + mode) + 19 + 1 + + + DMM + Double memory mode + 18 + 1 + + + SPL + Stream priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MWIDTH + Memory data width + 13 + 2 + + + PWIDTH + Peripheral data width + 11 + 2 + + + MINCM + Memory increment mode + 10 + 1 + + + PINCM + Peripheral increment mode + 9 + 1 + + + LM + Loop mode + 8 + 1 + + + DTD + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + FDTIEN + Full data transfer complete interrupt + enable + 4 + 1 + + + HDTIEN + Half data transfer interrupt + enable + 3 + 1 + + + DTERRIEN + Transfer error interrupt + enable + 2 + 1 + + + DMERRIEN + Direct mode error interrupt + enable + 1 + 1 + + + SEN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S1DTCNT + S1DTCNT + stream 1 number of data + register + 0x14 + 0x20 + read-write + 0x00000000 + + + CNT + Number of data items to + transfer + 0 + 16 + + + + + S1PADDR + S1PADDR + stream 1 peripheral address + register + 0x18 + 0x20 + read-write + 0x00000000 + + + PADDR + Peripheral address + 0 + 32 + + + + + S1M0ADDR + S1M0ADDR + stream 1 memory 0 address + register + 0x1C + 0x20 + read-write + 0x00000000 + + + M0ADDR + Memory 0 address + 0 + 32 + + + + + S1M1ADDR + S1M1ADDR + stream 1 memory 1 address + register + 0x20 + 0x20 + read-write + 0x00000000 + + + M1ADDR + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S1FCTRL + S1FCTRL + stream 1 FIFO control register + 0x24 + 0x20 + 0x00000021 + + + FERRIEN + FIFO error interrupt + enable + 7 + 1 + read-write + + + FSTS + FIFO status + 3 + 3 + read-only + + + FEN + FIFO mode enable + 2 + 1 + read-write + + + FTHSEL + FIFO threshold selection + 0 + 2 + read-write + + + + + S2CTRL + S2CTRL + stream 2 control + register + 0x28 + 0x20 + read-write + 0x00000000 + + + MBURST + Memory burst transmission + + 23 + 2 + + + PBURST + Peripheral burst transmission + + 21 + 2 + + + CM + Current memory (only in double buffer + mode) + 19 + 1 + + + DMM + Double memory mode + 18 + 1 + + + SPL + Stream priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MWIDTH + Memory data width + 13 + 2 + + + PWIDTH + Peripheral data width + 11 + 2 + + + MINCM + Memory increment mode + 10 + 1 + + + PINCM + Peripheral increment mode + 9 + 1 + + + LM + Loop mode + 8 + 1 + + + DTD + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + FDTIEN + Full data transfer complete interrupt + enable + 4 + 1 + + + HDTIEN + Half data transfer interrupt + enable + 3 + 1 + + + DTERRIEN + Transfer error interrupt + enable + 2 + 1 + + + DMERRIEN + Direct mode error interrupt + enable + 1 + 1 + + + SEN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S2DTCNT + S2DTCNT + stream 2 number of data + register + 0x2C + 0x20 + read-write + 0x00000000 + + + CNT + Number of data items to + transfer + 0 + 16 + + + + + S2PADDR + S2PADDR + stream 2 peripheral address + register + 0x30 + 0x20 + read-write + 0x00000000 + + + PADDR + Peripheral address + 0 + 32 + + + + + S2M0ADDR + S2M0ADDR + stream 2 memory 0 address + register + 0x34 + 0x20 + read-write + 0x00000000 + + + M0ADDR + Memory 0 address + 0 + 32 + + + + + S2M1ADDR + S2M1ADDR + stream 2 memory 1 address + register + 0x38 + 0x20 + read-write + 0x00000000 + + + M1ADDR + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S2FCTRL + S2FCTRL + stream 2 FIFO control register + 0x3C + 0x20 + 0x00000021 + + + FERRIEN + FIFO error interrupt + enable + 7 + 1 + read-write + + + FSTS + FIFO status + 3 + 3 + read-only + + + FEN + FIFO mode enable + 2 + 1 + read-write + + + FTHSEL + FIFO threshold selection + 0 + 2 + read-write + + + + + S3CTRL + S3CTRL + stream 3 control + register + 0x40 + 0x20 + read-write + 0x00000000 + + + MBURST + Memory burst transmission + + 23 + 2 + + + PBURST + Peripheral burst transmission + + 21 + 2 + + + CM + Current memory (only in double buffer + mode) + 19 + 1 + + + DMM + Double memory mode + 18 + 1 + + + SPL + Stream priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MWIDTH + Memory data width + 13 + 2 + + + PWIDTH + Peripheral data width + 11 + 2 + + + MINCM + Memory increment mode + 10 + 1 + + + PINCM + Peripheral increment mode + 9 + 1 + + + LM + Loop mode + 8 + 1 + + + DTD + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + FDTIEN + Full data transfer complete interrupt + enable + 4 + 1 + + + HDTIEN + Half data transfer interrupt + enable + 3 + 1 + + + DTERRIEN + Transfer error interrupt + enable + 2 + 1 + + + DMERRIEN + Direct mode error interrupt + enable + 1 + 1 + + + SEN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S3DTCNT + S3DTCNT + stream 3 number of data + register + 0x44 + 0x20 + read-write + 0x00000000 + + + CNT + Number of data items to + transfer + 0 + 16 + + + + + S3PADDR + S3PADDR + stream 3 peripheral address + register + 0x48 + 0x20 + read-write + 0x00000000 + + + PADDR + Peripheral address + 0 + 32 + + + + + S3M0ADDR + S3M0ADDR + stream 3 memory 0 address + register + 0x4C + 0x20 + read-write + 0x00000000 + + + M0ADDR + Memory 0 address + 0 + 32 + + + + + S3M1ADDR + S3M1ADDR + stream 3 memory 1 address + register + 0x50 + 0x20 + read-write + 0x00000000 + + + M1ADDR + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S3FCTRL + S3FCTRL + stream 3 FIFO control register + 0x54 + 0x20 + 0x00000021 + + + FERRIEN + FIFO error interrupt + enable + 7 + 1 + read-write + + + FSTS + FIFO status + 3 + 3 + read-only + + + FEN + FIFO mode enable + 2 + 1 + read-write + + + FTHSEL + FIFO threshold selection + 0 + 2 + read-write + + + + + S4CTRL + S4CTRL + stream 4 control + register + 0x58 + 0x20 + read-write + 0x00000000 + + + MBURST + Memory burst transmission + + 23 + 2 + + + PBURST + Peripheral burst transmission + + 21 + 2 + + + CM + Current memory (only in double buffer + mode) + 19 + 1 + + + DMM + Double memory mode + 18 + 1 + + + SPL + Stream priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MWIDTH + Memory data width + 13 + 2 + + + PWIDTH + Peripheral data width + 11 + 2 + + + MINCM + Memory increment mode + 10 + 1 + + + PINCM + Peripheral increment mode + 9 + 1 + + + LM + Loop mode + 8 + 1 + + + DTD + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + FDTIEN + Full data transfer complete interrupt + enable + 4 + 1 + + + HDTIEN + Half data transfer interrupt + enable + 3 + 1 + + + DTERRIEN + Transfer error interrupt + enable + 2 + 1 + + + DMERRIEN + Direct mode error interrupt + enable + 1 + 1 + + + SEN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S4DTCNT + S4DTCNT + stream 4 number of data + register + 0x5C + 0x20 + read-write + 0x00000000 + + + CNT + Number of data items to + transfer + 0 + 16 + + + + + S4PADDR + S4PADDR + stream 4 peripheral address + register + 0x60 + 0x20 + read-write + 0x00000000 + + + PADDR + Peripheral address + 0 + 32 + + + + + S4M0ADDR + S4M0ADDR + stream 4 memory 0 address + register + 0x64 + 0x20 + read-write + 0x00000000 + + + M0ADDR + Memory 0 address + 0 + 32 + + + + + S4M1ADDR + S4M1ADDR + stream 4 memory 1 address + register + 0x68 + 0x20 + read-write + 0x00000000 + + + M1ADDR + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S4FCTRL + S4FCTRL + stream 4 FIFO control register + 0x6C + 0x20 + 0x00000021 + + + FERRIEN + FIFO error interrupt + enable + 7 + 1 + read-write + + + FSTS + FIFO status + 3 + 3 + read-only + + + FEN + FIFO mode enable + 2 + 1 + read-write + + + FTHSEL + FIFO threshold selection + 0 + 2 + read-write + + + + + S5CTRL + S5CTRL + stream 5 control + register + 0x70 + 0x20 + read-write + 0x00000000 + + + MBURST + Memory burst transmission + + 23 + 2 + + + PBURST + Peripheral burst transmission + + 21 + 2 + + + CM + Current memory (only in double buffer + mode) + 19 + 1 + + + DMM + Double memory mode + 18 + 1 + + + SPL + Stream priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MWIDTH + Memory data width + 13 + 2 + + + PWIDTH + Peripheral data width + 11 + 2 + + + MINCM + Memory increment mode + 10 + 1 + + + PINCM + Peripheral increment mode + 9 + 1 + + + LM + Loop mode + 8 + 1 + + + DTD + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + FDTIEN + Full data transfer complete interrupt + enable + 4 + 1 + + + HDTIEN + Half data transfer interrupt + enable + 3 + 1 + + + DTERRIEN + Transfer error interrupt + enable + 2 + 1 + + + DMERRIEN + Direct mode error interrupt + enable + 1 + 1 + + + SEN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S5DTCNT + S5DTCNT + stream 5 number of data + register + 0x74 + 0x20 + read-write + 0x00000000 + + + CNT + Number of data items to + transfer + 0 + 16 + + + + + S5PADDR + S5PADDR + stream 5 peripheral address + register + 0x78 + 0x20 + read-write + 0x00000000 + + + PADDR + Peripheral address + 0 + 32 + + + + + S5M0ADDR + S5M0ADDR + stream 5 memory 0 address + register + 0x7C + 0x20 + read-write + 0x00000000 + + + M0ADDR + Memory 0 address + 0 + 32 + + + + + S5M1ADDR + S5M1ADDR + stream 5 memory 1 address + register + 0x80 + 0x20 + read-write + 0x00000000 + + + M1ADDR + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S5FCTRL + S5FCTRL + stream 5 FIFO control register + 0x84 + 0x20 + 0x00000021 + + + FERRIEN + FIFO error interrupt + enable + 7 + 1 + read-write + + + FSTS + FIFO status + 3 + 3 + read-only + + + FEN + FIFO mode enable + 2 + 1 + read-write + + + FTHSEL + FIFO threshold selection + 0 + 2 + read-write + + + + + S6CTRL + S6CTRL + stream 6 control + register + 0x88 + 0x20 + read-write + 0x00000000 + + + MBURST + Memory burst transmission + + 23 + 2 + + + PBURST + Peripheral burst transmission + + 21 + 2 + + + CM + Current memory (only in double buffer + mode) + 19 + 1 + + + DMM + Double memory mode + 18 + 1 + + + SPL + Stream priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MWIDTH + Memory data width + 13 + 2 + + + PWIDTH + Peripheral data width + 11 + 2 + + + MINCM + Memory increment mode + 10 + 1 + + + PINCM + Peripheral increment mode + 9 + 1 + + + LM + Loop mode + 8 + 1 + + + DTD + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + FDTIEN + Full data transfer complete interrupt + enable + 4 + 1 + + + HDTIEN + Half data transfer interrupt + enable + 3 + 1 + + + DTERRIEN + Transfer error interrupt + enable + 2 + 1 + + + DMERRIEN + Direct mode error interrupt + enable + 1 + 1 + + + SEN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S6DTCNT + S6DTCNT + stream 6 number of data + register + 0x8C + 0x20 + read-write + 0x00000000 + + + CNT + Number of data items to + transfer + 0 + 16 + + + + + S6PADDR + S6PADDR + stream 6 peripheral address + register + 0x90 + 0x20 + read-write + 0x00000000 + + + PADDR + Peripheral address + 0 + 32 + + + + + S6M0ADDR + S6M0ADDR + stream 6 memory 0 address + register + 0x94 + 0x20 + read-write + 0x00000000 + + + M0ADDR + Memory 0 address + 0 + 32 + + + + + S6M1ADDR + S6M1ADDR + stream 6 memory 1 address + register + 0x98 + 0x20 + read-write + 0x00000000 + + + M1ADDR + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S6FCTRL + S6FCTRL + stream 6 FIFO control register + 0x9C + 0x20 + 0x00000021 + + + FERRIEN + FIFO error interrupt + enable + 7 + 1 + read-write + + + FSTS + FIFO status + 3 + 3 + read-only + + + FEN + FIFO mode enable + 2 + 1 + read-write + + + FTHSEL + FIFO threshold selection + 0 + 2 + read-write + + + + + S7CTRL + S7CTRL + stream 7 control + register + 0xA0 + 0x20 + read-write + 0x00000000 + + + MBURST + Memory burst transmission + + 23 + 2 + + + PBURST + Peripheral burst transmission + + 21 + 2 + + + CM + Current memory (only in double buffer + mode) + 19 + 1 + + + DMM + Double memory mode + 18 + 1 + + + SPL + Stream priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MWIDTH + Memory data width + 13 + 2 + + + PWIDTH + Peripheral data width + 11 + 2 + + + MINCM + Memory increment mode + 10 + 1 + + + PINCM + Peripheral increment mode + 9 + 1 + + + LM + Loop mode + 8 + 1 + + + DTD + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + FDTIEN + Full data transfer complete interrupt + enable + 4 + 1 + + + HDTIEN + Half data transfer interrupt + enable + 3 + 1 + + + DTERRIEN + Transfer error interrupt + enable + 2 + 1 + + + DMERRIEN + Direct mode error interrupt + enable + 1 + 1 + + + SEN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S7DTCNT + S7DTCNT + stream 7 number of data + register + 0xA4 + 0x20 + read-write + 0x00000000 + + + CNT + Number of data items to + transfer + 0 + 16 + + + + + S7PADDR + S7PADDR + stream 7 peripheral address + register + 0xA8 + 0x20 + read-write + 0x00000000 + + + PADDR + Peripheral address + 0 + 32 + + + + + S7M0ADDR + S7M0ADDR + stream 7 memory 0 address + register + 0xAC + 0x20 + read-write + 0x00000000 + + + M0ADDR + Memory 0 address + 0 + 32 + + + + + S7M1ADDR + S7M1ADDR + stream 7 memory 1 address + register + 0xB0 + 0x20 + read-write + 0x00000000 + + + M1ADDR + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S7FCTRL + S7FCTRL + stream 7 FIFO control register + 0xB4 + 0x20 + 0x00000021 + + + FERRIEN + FIFO error interrupt + enable + 7 + 1 + read-write + + + FSTS + FIFO status + 3 + 3 + read-only + + + FEN + FIFO mode enable + 2 + 1 + read-write + + + FTHSEL + FIFO threshold selection + 0 + 2 + read-write + + + + + S8CTRL + S8CTRL + stream 8 control + register + 0xB8 + 0x20 + read-write + 0x00000000 + + + MBURST + Memory burst transmission + + 23 + 2 + + + PBURST + Peripheral burst transmission + + 21 + 2 + + + CM + Current memory (only in double buffer + mode) + 19 + 1 + + + DMM + Double memory mode + 18 + 1 + + + SPL + Stream priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MWIDTH + Memory data width + 13 + 2 + + + PWIDTH + Peripheral data width + 11 + 2 + + + MINCM + Memory increment mode + 10 + 1 + + + PINCM + Peripheral increment mode + 9 + 1 + + + LM + Loop mode + 8 + 1 + + + DTD + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + FDTIEN + Full data transfer complete interrupt + enable + 4 + 1 + + + HDTIEN + Half data transfer interrupt + enable + 3 + 1 + + + DTERRIEN + Transfer error interrupt + enable + 2 + 1 + + + DMERRIEN + Direct mode error interrupt + enable + 1 + 1 + + + SEN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S8DTCNT + S8DTCNT + stream 8 number of data + register + 0xBC + 0x20 + read-write + 0x00000000 + + + CNT + Number of data items to + transfer + 0 + 16 + + + + + S8PADDR + S8PADDR + stream 8 peripheral address + register + 0xC0 + 0x20 + read-write + 0x00000000 + + + PADDR + Peripheral address + 0 + 32 + + + + + S8M0ADDR + S8M0ADDR + stream 8 memory 0 address + register + 0xC4 + 0x20 + read-write + 0x00000000 + + + M0ADDR + Memory 0 address + 0 + 32 + + + + + S8M1ADDR + S8M1ADDR + stream 8 memory 1 address + register + 0xC8 + 0x20 + read-write + 0x00000000 + + + M1ADDR + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S8FCTRL + S8FCTRL + stream 8 FIFO control register + 0xCC + 0x20 + 0x00000021 + + + FERRIEN + FIFO error interrupt + enable + 7 + 1 + read-write + + + FSTS + FIFO status + 3 + 3 + read-only + + + FEN + FIFO mode enable + 2 + 1 + read-write + + + FTHSEL + FIFO threshold selection + 0 + 2 + read-write + + + + + LLCTRL + LLCTRL + DMA Link List Control Register + 0xD0 + 0x20 + 0x00000000 + + + S1LLEN + Stream 1 link list enable + 0 + 1 + read-write + + + S2LLEN + Stream 2 link list enable + 1 + 1 + read-write + + + S3LLEN + Stream 3 link list enable + 2 + 1 + read-write + + + S4LLEN + Stream 4 link list enable + 3 + 1 + read-write + + + S5LLEN + Stream 5 link list enable + 4 + 1 + read-write + + + S6LLEN + Stream 6 link list enable + 5 + 1 + read-write + + + S7LLEN + Stream 7 link list enable + 6 + 1 + read-write + + + S8LLEN + Stream 8 link list enable + 7 + 1 + read-write + + + + + S1LLP + S1LLP + Stream 1 Link List Pointer + 0xD4 + 0x20 + 0x00000000 + + + LLP + Link list pointer + 0 + 32 + read-write + + + + + S2LLP + S2LLP + Stream 2 Link List Pointer + 0xD8 + 0x20 + 0x00000000 + + + LLP + Link list pointer + 0 + 32 + read-write + + + + + S3LLP + S3LLP + Stream 3 Link List Pointer + 0xDC + 0x20 + 0x00000000 + + + LLP + Link list pointer + 0 + 32 + read-write + + + + + S4LLP + S4LLP + Stream 4 Link List Pointer + 0xE0 + 0x20 + 0x00000000 + + + LLP + Link list pointer + 0 + 32 + read-write + + + + + S5LLP + S5LLP + Stream 5 Link List Pointer + 0xE4 + 0x20 + 0x00000000 + + + LLP + Link list pointer + 0 + 32 + read-write + + + + + S6LLP + S6LLP + Stream 6 Link List Pointer + 0xE8 + 0x20 + 0x00000000 + + + LLP + Link list pointer + 0 + 32 + read-write + + + + + S7LLP + S7LLP + Stream 7 Link List Pointer + 0xEC + 0x20 + 0x00000000 + + + LLP + Link list pointer + 0 + 32 + read-write + + + + + S8LLP + S8LLP + Stream 8 Link List Pointer + 0xF0 + 0x20 + 0x00000000 + + + LLP + Link list pointer + 0 + 32 + read-write + + + + + S2DCTRL + S2DCTRL + EDMA 2D Transfer Control Register + 0xF4 + 0x20 + 0x00000000 + + + S1_2DEN + Stream 1 2D transfer enable + 0 + 1 + read-write + + + S2_2DEN + Stream 2 2D transfer enable + 1 + 1 + read-write + + + S3_2DEN + Stream 3 2D transfer enable + 2 + 1 + read-write + + + S4_2DEN + Stream 4 2D transfer enable + 3 + 1 + read-write + + + S5_2DEN + Stream 5 2D transfer enable + 4 + 1 + read-write + + + S6_2DEN + Stream 6 2D transfer enable + 5 + 1 + read-write + + + S7_2DEN + Stream 7 2D transfer enable + 6 + 1 + read-write + + + S8_2DEN + Stream 8 2D transfer enable + 7 + 1 + read-write + + + + + S1_2DCNT + S1_2DCNT + Stream 1 2D Transfer Count + 0xF8 + 0x20 + 0x00000000 + + + XCONUT + X dimension transfer count + 0 + 16 + read-write + + + YCONUT + Y dimension transfer count + 16 + 16 + read-write + + + + + S1_STRIDE + S1_STRIDE + Stream 1 2D Transfer Stride + 0xFC + 0x20 + 0x00000000 + + + SRCSTD + Source stride + 0 + 16 + read-write + + + DSTSTD + Destination stride + 16 + 16 + read-write + + + + + S2_2DCNT + S2_2DCNT + Stream 2 2D Transfer Count + 0x100 + 0x20 + 0x00000000 + + + XCONUT + X dimension transfer count + 0 + 16 + read-write + + + YCONUT + Y dimension transfer count + 16 + 16 + read-write + + + + + S2_STRIDE + S2_STRIDE + Stream 2 2D Transfer Stride + 0x104 + 0x20 + 0x00000000 + + + SRCSTD + Source stride + 0 + 16 + read-write + + + DSTSTD + Destination stride + 16 + 16 + read-write + + + + + S3_2DCNT + S3_2DCNT + Stream 3 2D Transfer Count + 0x108 + 0x20 + 0x00000000 + + + XCONUT + X dimension transfer count + 0 + 16 + read-write + + + YCONUT + Y dimension transfer count + 16 + 16 + read-write + + + + + S3_STRIDE + S3_STRIDE + Stream 3 2D Transfer Stride + 0x10C + 0x20 + 0x00000000 + + + SRCSTD + Source stride + 0 + 16 + read-write + + + DSTSTD + Destination stride + 16 + 16 + read-write + + + + + S4_2DCNT + S4_2DCNT + Stream 4 2D Transfer Count + 0x110 + 0x20 + 0x00000000 + + + XCONUT + X dimension transfer count + 0 + 16 + read-write + + + YCONUT + Y dimension transfer count + 16 + 16 + read-write + + + + + S4_STRIDE + S4_STRIDE + Stream 4 2D Transfer Stride + 0x114 + 0x20 + 0x00000000 + + + SRCSTD + Source stride + 0 + 16 + read-write + + + DSTSTD + Destination stride + 16 + 16 + read-write + + + + + S5_2DCNT + S5_2DCNT + Stream 5 2D Transfer Count + 0x118 + 0x20 + 0x00000000 + + + XCONUT + X dimension transfer count + 0 + 16 + read-write + + + YCONUT + Y dimension transfer count + 16 + 16 + read-write + + + + + S5_STRIDE + S5_STRIDE + Stream 5 2D Transfer Stride + 0x11C + 0x20 + 0x00000000 + + + SRCSTD + Source stride + 0 + 16 + read-write + + + DSTSTD + Destination stride + 16 + 16 + read-write + + + + + S6_2DCNT + S6_2DCNT + Stream 6 2D Transfer Count + 0x120 + 0x20 + 0x00000000 + + + XCONUT + X dimension transfer count + 0 + 16 + read-write + + + YCONUT + Y dimension transfer count + 16 + 16 + read-write + + + + + S6_STRIDE + S6_STRIDE + Stream 6 2D Transfer Stride + 0x124 + 0x20 + 0x00000000 + + + SRCSTD + Source stride + 0 + 16 + read-write + + + DSTSTD + Destination stride + 16 + 16 + read-write + + + + + S7_2DCNT + S7_2DCNT + Stream 7 2D Transfer Count + 0x128 + 0x20 + 0x00000000 + + + XCONUT + X dimension transfer count + 0 + 16 + read-write + + + YCONUT + Y dimension transfer count + 16 + 16 + read-write + + + + + S7_STRIDE + S7_STRIDE + Stream 7 2D Transfer Stride + 0x12C + 0x20 + 0x00000000 + + + SRCSTD + Source stride + 0 + 16 + read-write + + + DSTSTD + Destination stride + 16 + 16 + read-write + + + + + S8_2DCNT + S8_2DCNT + Stream 8 2D Transfer Count + 0x130 + 0x20 + 0x00000000 + + + XCONUT + X dimension transfer count + 0 + 16 + read-write + + + YCONUT + Y dimension transfer count + 16 + 16 + read-write + + + + + S8_STRIDE + S8_STRIDE + Stream 8 2D Transfer Stride + 0x134 + 0x20 + 0x00000000 + + + SRCSTD + Source stride + 0 + 16 + read-write + + + DSTSTD + Destination stride + 16 + 16 + read-write + + + + + SYNCEN + SYNCEN + Sync Enable + 0x138 + 0x20 + 0x00000000 + + + S1SYNC + Stream 1 sync enable + 0 + 1 + read-write + + + S2SYNC + Stream 2 sync enable + 1 + 1 + read-write + + + S3SYNC + Stream 3 sync enable + 2 + 1 + read-write + + + S4SYNC + Stream 4 sync enable + 3 + 1 + read-write + + + S5SYNC + Stream 5 sync enable + 4 + 1 + read-write + + + S6SYNC + Stream 6 sync enable + 5 + 1 + read-write + + + S7SYNC + Stream 7 sync enable + 6 + 1 + read-write + + + S8SYNC + Stream 8 sync enable + 7 + 1 + read-write + + + + + MUXSEL + MUXSEL + EDMA MUX Table Selection + 0x13C + 0x20 + 0x00000000 + + + TBL_SEL + Multiplexer Table Select + 0 + 1 + read-write + + + + + MUXS1CTRL + MUXS1CTRL + Stream 1 Configuration Register + 0x140 + 0x20 + 0x00000000 + + + REQSEL + DMA request select + 0 + 7 + read-write + + + SYNCOVIEN + Synchronization overrun interrupt enable + 8 + 1 + read-write + + + EVTGEN + Event generation enable + 9 + 1 + read-write + + + SYNCEN + Synchroniztion enable + 16 + 1 + read-write + + + SYNCPOL + Synchronization polarity + 17 + 2 + read-write + + + REQCNT + Number of DMA requests + 19 + 5 + read-write + + + SYNCSEL + Synchronization select + 24 + 5 + read-write + + + + + MUXS2CTRL + MUXS2CTRL + Stream 2 Configuration Register + 0x144 + 0x20 + 0x00000000 + + + REQSEL + DMA request select + 0 + 7 + read-write + + + SYNCOVIEN + Synchronization overrun interrupt enable + 8 + 1 + read-write + + + EVTGEN + Event generation enable + 9 + 1 + read-write + + + SYNCEN + Synchroniztion enable + 16 + 1 + read-write + + + SYNCPOL + Synchronization polarity + 17 + 2 + read-write + + + REQCNT + Number of DMA requests + 19 + 5 + read-write + + + SYNCSEL + Synchronization select + 24 + 5 + read-write + + + + + MUXS3CTRL + MUXS3CTRL + Stream 3 Configuration Register + 0x148 + 0x20 + 0x00000000 + + + REQSEL + DMA request select + 0 + 7 + read-write + + + SYNCOVIEN + Synchronization overrun interrupt enable + 8 + 1 + read-write + + + EVTGEN + Event generation enable + 9 + 1 + read-write + + + SYNCEN + Synchroniztion enable + 16 + 1 + read-write + + + SYNCPOL + Synchronization polarity + 17 + 2 + read-write + + + REQCNT + Number of DMA requests + 19 + 5 + read-write + + + SYNCSEL + Synchronization select + 24 + 5 + read-write + + + + + MUXS4CTRL + MUXS4CTRL + Stream 4 Configuration Register + 0x14C + 0x20 + 0x00000000 + + + REQSEL + DMA request select + 0 + 7 + read-write + + + SYNCOVIEN + Synchronization overrun interrupt enable + 8 + 1 + read-write + + + EVTGEN + Event generation enable + 9 + 1 + read-write + + + SYNCEN + Synchroniztion enable + 16 + 1 + read-write + + + SYNCPOL + Synchronization polarity + 17 + 2 + read-write + + + REQCNT + Number of DMA requests + 19 + 5 + read-write + + + SYNCSEL + Synchronization select + 24 + 5 + read-write + + + + + MUXS5CTRL + MUXS5CTRL + Stream x Configuration Register + 0x150 + 0x20 + 0x00000000 + + + REQSEL + DMA request select + 0 + 7 + read-write + + + SYNCOVIEN + Synchronization overrun interrupt enable + 8 + 1 + read-write + + + EVTGEN + Event generation enable + 9 + 1 + read-write + + + SYNCEN + Synchroniztion enable + 16 + 1 + read-write + + + SYNCPOL + Synchronization polarity + 17 + 2 + read-write + + + REQCNT + Number of DMA requests + 19 + 5 + read-write + + + SYNCSEL + Synchronization select + 24 + 5 + read-write + + + + + MUXS6CTRL + MUXS6CTRL + Stream 6 Configuration Register + 0x154 + 0x20 + 0x00000000 + + + REQSEL + DMA request select + 0 + 7 + read-write + + + SYNCOVIEN + Synchronization overrun interrupt enable + 8 + 1 + read-write + + + EVTGEN + Event generation enable + 9 + 1 + read-write + + + SYNCEN + Synchroniztion enable + 16 + 1 + read-write + + + SYNCPOL + Synchronization polarity + 17 + 2 + read-write + + + REQCNT + Number of DMA requests + 19 + 5 + read-write + + + SYNCSEL + Synchronization select + 24 + 5 + read-write + + + + + MUXS7CTRL + MUXS7CTRL + Stream 7 Configuration Register + 0x158 + 0x20 + 0x00000000 + + + REQSEL + DMA request select + 0 + 7 + read-write + + + SYNCOVIEN + Synchronization overrun interrupt enable + 8 + 1 + read-write + + + EVTGEN + Event generation enable + 9 + 1 + read-write + + + SYNCEN + Synchroniztion enable + 16 + 1 + read-write + + + SYNCPOL + Synchronization polarity + 17 + 2 + read-write + + + REQCNT + Number of DMA requests + 19 + 5 + read-write + + + SYNCSEL + Synchronization select + 24 + 5 + read-write + + + + + MUXS8CTRL + MUXS8CTRL + Stream 8 Configuration Register + 0x15C + 0x20 + 0x00000000 + + + REQSEL + DMA request select + 0 + 7 + read-write + + + SYNCOVIEN + Synchronization overrun interrupt enable + 8 + 1 + read-write + + + EVTGEN + Event generation enable + 9 + 1 + read-write + + + SYNCEN + Synchroniztion enable + 16 + 1 + read-write + + + SYNCPOL + Synchronization polarity + 17 + 2 + read-write + + + REQCNT + Number of DMA requests + 19 + 5 + read-write + + + SYNCSEL + Synchronization select + 24 + 5 + read-write + + + + + MUXG1CTRL + MUXG1CTRL + Generator 1 Configuration Register + 0x160 + 0x20 + 0x00000000 + + + SIGSEL + Signal select + 0 + 5 + read-write + + + TRGOVIEN + Trigger overrun interrupt enable + 8 + 1 + read-write + + + GEN + DMA request generator enable + 16 + 1 + read-write + + + GPOL + DMA request generator trigger polarity + 17 + 2 + read-write + + + GREQCNT + Number of DMA requests to be generated + 19 + 5 + read-write + + + + + MUXG2CTRL + MUXG2CTRL + Generator 2 Configuration Register + 0x164 + 0x20 + 0x00000000 + + + SIGSEL + Signal select + 0 + 5 + read-write + + + TRGOVIEN + Trigger overrun interrupt enable + 8 + 1 + read-write + + + GEN + DMA request generator enable + 16 + 1 + read-write + + + GPOL + DMA request generator trigger polarity + 17 + 2 + read-write + + + GREQCNT + Number of DMA requests to be generated + 19 + 5 + read-write + + + + + MUXG3CTRL + MUXG3CTRL + Generator 3 Configuration Register + 0x168 + 0x20 + 0x00000000 + + + SIGSEL + Signal select + 0 + 5 + read-write + + + TRGOVIEN + Trigger overrun interrupt enable + 8 + 1 + read-write + + + GEN + DMA request generator enable + 16 + 1 + read-write + + + GPOL + DMA request generator trigger polarity + 17 + 2 + read-write + + + GREQCNT + Number of DMA requests to be generated + 19 + 5 + read-write + + + + + MUXG4CTRL + MUXG4CTRL + Generator 4 Configuration Register + 0x16C + 0x20 + 0x00000000 + + + SIGSEL + Signal select + 0 + 5 + read-write + + + TRGOVIEN + Trigger overrun interrupt enable + 8 + 1 + read-write + + + GEN + DMA request generator enable + 16 + 1 + read-write + + + GPOL + DMA request generator trigger polarity + 17 + 2 + read-write + + + GREQCNT + Number of DMA requests to be generated + 19 + 5 + read-write + + + + + MUXSYNCSTS + MUXSYNCSTS + Channel Interrupt Status Register + 0x170 + 0x20 + 0x00000000 + + + SYNCOVF1 + Synchronizaton overrun interrupt flag + 0 + 1 + read-only + + + SYNCOVF2 + Synchronizaton overrun interrupt flag + 1 + 1 + read-only + + + SYNCOVF3 + Synchronizaton overrun interrupt flag + 2 + 1 + read-only + + + SYNCOVF4 + Synchronizaton overrun interrupt flag + 3 + 1 + read-only + + + SYNCOVF5 + Synchronizaton overrun interrupt flag + 4 + 1 + read-only + + + SYNCOVF6 + Synchronizaton overrun interrupt flag + 5 + 1 + read-only + + + SYNCOVF7 + Synchronizaton overrun interrupt flag + 6 + 1 + read-only + + + SYNCOVF8 + Synchronizaton overrun interrupt flag + 7 + 1 + read-only + + + + + MUXSYNCCLR + MUXSYNCCLR + Channel Interrupt Clear Flag Register + 0x174 + 0x20 + 0x00000000 + + + SYNCOVFC1 + Clear synchronizaton overrun interrupt flag + 0 + 1 + read-write + + + SYNCOVFC2 + Clear synchronizaton overrun interrupt flag + 1 + 1 + read-write + + + SYNCOVFC3 + Clear synchronizaton overrun interrupt flag + 2 + 1 + read-write + + + SYNCOVFC4 + Clear synchronizaton overrun interrupt flag + 3 + 1 + read-write + + + SYNCOVFC5 + Clear synchronizaton overrun interrupt flag + 4 + 1 + read-write + + + SYNCOVFC6 + Clear synchronizaton overrun interrupt flag + 5 + 1 + read-write + + + SYNCOVFC7 + Clear synchronizaton overrun interrupt flag + 6 + 1 + read-write + + + SYNCOVFC8 + Clear synchronizaton overrun interrupt flag + 7 + 1 + read-write + + + + + MUXGSTS + MUXGSTS + Generator Interrupt Status Register + 0x178 + 0x20 + 0x00000000 + + + TRGOVF1 + Trigger overrun interrupt flag + 0 + 1 + read-write + + + TRGOVF2 + Trigger overrun interrupt flag + 1 + 1 + read-write + + + TRGOVF3 + Trigger overrun interrupt flag + 2 + 1 + read-write + + + TRGOVF4 + Trigger overrun interrupt flag + 3 + 1 + read-write + + + + + MUXGCLR + MUXGCLR + Generator Interrupt Clear Flag Register + 0x17C + 0x20 + 0x00000000 + + + TRGOVFC1 + Clear trigger overrun interrupt flag + 0 + 1 + read-write + + + + TRGOVFC2 + Clear trigger overrun interrupt flag + 1 + 1 + read-write + + + TRGOVFC3 + Clear trigger overrun interrupt flag + 2 + 1 + read-write + + + TRGOVFC4 + Clear trigger overrun interrupt flag + 3 + 1 + read-write + + + + + + + DMA1 + DMA controller + DMA + 0x40026400 + + 0x0 + 0x200 + registers + + + DMA1_Channel1 + DMA1 Channel1 global interrupt + 56 + + + DMA1_Channel2 + DMA1 Channel2 global interrupt + 57 + + + DMA1_Channel3 + DMA1 Channel3 global interrupt + 58 + + + DMA1_Channel4 + DMA1 Channel4 global interrupt + 59 + + + DMA1_Channel5 + DMA1 Channel5 global interrupt + 60 + + + DMA1_Channel6 + DMA1 Channel6 global interrupt + 68 + + + DMA1_Channel7 + DMA1 Channel7 global interrupt + 69 + + + + STS + STS + DMA interrupt status register + (DMA_STS) + 0x0 + 0x20 + read-only + 0x00000000 + + + GF1 + Channel 1 Global event flag + 0 + 1 + + + FDTF1 + Channel 1 full data transfer event flag + 1 + 1 + + + HDTF1 + Channel 1 half data transfer event flag + 2 + 1 + + + DTERRF1 + Channel 1 data transfer error event flag + 3 + 1 + + + GF2 + Channel 2 Global event flag + 4 + 1 + + + FDTF2 + Channel 2 full data transfer event flag + 5 + 1 + + + HDTF2 + Channel 2 half data transfer event flag + 6 + 1 + + + DTERRF2 + Channel 2 data transfer error event flag + 7 + 1 + + + GF3 + Channel 3 Global event flag + 8 + 1 + + + FDTF3 + Channel 3 full data transfer event flag + 9 + 1 + + + HDTF3 + Channel 3 half data transfer event flag + 10 + 1 + + + DTERRF3 + Channel 3 data transfer error event flag + 11 + 1 + + + GF4 + Channel 4 Global event flag + 12 + 1 + + + FDTF4 + Channel 4 full data transfer event flag + 13 + 1 + + + HDTF4 + Channel 4 half data transfer event flag + 14 + 1 + + + DTERRF4 + Channel 4 data transfer error event flag + 15 + 1 + + + GF5 + Channel 5 Global event flag + 16 + 1 + + + FDTF5 + Channel 5 full data transfer event flag + 17 + 1 + + + HDTF5 + Channel 5 half data transfer event flag + 18 + 1 + + + DTERRF5 + Channel 5 data transfer error event flag + 19 + 1 + + + GF6 + Channel 6 Global event flag + 20 + 1 + + + FDTF6 + Channel 6 full data transfer event flag + 21 + 1 + + + HDTF6 + Channel 6 half data transfer event flag + 22 + 1 + + + DTERRF6 + Channel 6 data transfer error event flag + 23 + 1 + + + GF7 + Channel 7 Global event flag + 24 + 1 + + + FDTF7 + Channel 7 full data transfer event flag + 25 + 1 + + + HDTF7 + Channel 7 half data transfer event flag + 26 + 1 + + + DTERRF7 + Channel 7 data transfer error event flag + 27 + 1 + + + + + CLR + CLR + DMA interrupt flag clear register + (DMA_CLR) + 0x4 + 0x20 + read-write + 0x00000000 + + + GFC1 + Channel 1 Global flag clear + 0 + 1 + + + GFC2 + Channel 2 Global flag clear + 4 + 1 + + + GFC3 + Channel 3 Global flag clear + 8 + 1 + + + GFC4 + Channel 4 Global flag clear + 12 + 1 + + + GFC5 + Channel 5 Global flag clear + 16 + 1 + + + GFC6 + Channel 6 Global flag clear + 20 + 1 + + + GFC7 + Channel 7 Global flag clear + 24 + 1 + + + FDTFC1 + Channel 1 full data transfer flag clear + 1 + 1 + + + FDTFC2 + Channel 2 full data transfer flag clear + 5 + 1 + + + FDTFC3 + Channel 3 full data transfer flag clear + 9 + 1 + + + FDTFC4 + Channel 4 full data transfer flag clear + 13 + 1 + + + FDTFC5 + Channel 5 full data transfer flag clear + 17 + 1 + + + FDTFC6 + Channel 6 full data transfer flag clear + 21 + 1 + + + FDTFC7 + Channel 7 full data transfer flag clear + 25 + 1 + + + HDTFC1 + Channel 1 half data transfer flag clear + 2 + 1 + + + HDTFC2 + Channel 2 half data transfer flag clear + 6 + 1 + + + HDTFC3 + Channel 3 half data transfer flag clear + 10 + 1 + + + HDTFC4 + Channel 4 half data transfer flag clear + 14 + 1 + + + HDTFC5 + Channel 5 half data transfer flag clear + 18 + 1 + + + HDTFC6 + Channel 6 half data transfer flag clear + 22 + 1 + + + HDTFC7 + Channel 7 half data transfer flag clear + 26 + 1 + + + DTERRFC1 + Channel 1 data transfer error flag clear + 3 + 1 + + + DTERRFC2 + Channel 2 data transfer error flag clear + 7 + 1 + + + DTERRFC3 + Channel 3 data transfer error flag clear + 11 + 1 + + + DTERRFC4 + Channel 4 data transfer error flag clear + 15 + 1 + + + DTERRFC5 + Channel 5 data transfer error flag clear + 19 + 1 + + + DTERRFC6 + Channel 6 data transfer error flag clear + 23 + 1 + + + DTERRFC7 + Channel 7 data transfer error flag clear + 27 + 1 + + + + + C1CTRL + C1CTRL + DMA channel configuration register(DMA_C1CTRL) + 0x8 + 0x20 + read-write + 0x00000000 + + + CHEN + Channel enable + 0 + 1 + + + FDTIEN + Transfer complete interrupt enable + 1 + 1 + + + HDTIEN + Half transfer interrupt enable + 2 + 1 + + + DTERRIEN + Transfer error interrupt enable + 3 + 1 + + + DTD + Data transfer direction + 4 + 1 + + + LM + Loop mode + 5 + 1 + + + PINCM + Peripheral increment mode + 6 + 1 + + + MINCM + Memory increment mode + 7 + 1 + + + PWIDTH + Peripheral data bit width + 8 + 2 + + + MWIDTH + Memory data bit width + 10 + 2 + + + CHPL + Channel Priority level + 12 + 2 + + + M2M + Memory to memory mode + 14 + 1 + + + + + C1DTCNT + C1DTCNT + DMA channel 1 number of data to transfer register + 0xC + 0x20 + read-write + 0x00000000 + + + CNT + Number of data to transfer + 0 + 16 + + + + + C1PADDR + C1PADDR + DMA channel 1 peripheral base address register + 0x10 + 0x20 + read-write + 0x00000000 + + + PADDR + Peripheral address + 0 + 32 + + + + + C1MADDR + C1MADDR + DMA channel 1 memory base address register + 0x14 + 0x20 + read-write + 0x00000000 + + + MADDR + Memory address + 0 + 32 + + + + + C2CTRL + C2CTRL + DMA channel configuration register (DMA_C2CTRL) + 0x1C + 0x20 + read-write + 0x00000000 + + + CHEN + Channel enable + 0 + 1 + + + FDTIEN + Transfer complete interrupt enable + 1 + 1 + + + HDTIEN + Half transfer interrupt enable + 2 + 1 + + + DTERRIEN + Transfer error interrupt enable + 3 + 1 + + + DTD + Data transfer direction + 4 + 1 + + + LM + Loop mode + 5 + 1 + + + PINCM + Peripheral increment mode + 6 + 1 + + + MINCM + Memory increment mode + 7 + 1 + + + PWIDTH + Peripheral data bit width + 8 + 2 + + + MWIDTH + Memory data bit width + 10 + 2 + + + CHPL + Channel Priority level + 12 + 2 + + + M2M + Memory to memory mode + 14 + 1 + + + + + C2DTCNT + C2DTCNT + DMA channel 2 number of data to transferregister + 0x20 + 0x20 + read-write + 0x00000000 + + + CNT + Number of data to transfer + 0 + 16 + + + + + C2PADDR + C2PADDR + DMA channel 2 peripheral base address register + 0x24 + 0x20 + read-write + 0x00000000 + + + PADDR + Peripheral address + 0 + 32 + + + + + C2MADDR + C2MADDR + DMA channel 2 memory base address register + 0x28 + 0x20 + read-write + 0x00000000 + + + MADDR + Memory address + 0 + 32 + + + + + C3CTRL + C3CTRL + DMA channel configuration register (DMA_C3CTRL) + 0x30 + 0x20 + read-write + 0x00000000 + + + CHEN + Channel enable + 0 + 1 + + + FDTIEN + Transfer complete interrupt enable + 1 + 1 + + + HDTIEN + Half transfer interrupt enable + 2 + 1 + + + DTERRIEN + Transfer error interrupt enable + 3 + 1 + + + DTD + Data transfer direction + 4 + 1 + + + LM + Loop mode + 5 + 1 + + + PINCM + Peripheral increment mode + 6 + 1 + + + MINCM + Memory increment mode + 7 + 1 + + + PWIDTH + Peripheral data bit width + 8 + 2 + + + MWIDTH + Memory data bit width + 10 + 2 + + + CHPL + Channel Priority level + 12 + 2 + + + M2M + Memory to memory mode + 14 + 1 + + + + + C3DTCNT + C3DTCNT + DMA channel 3 number of data to transfer register + 0x34 + 0x20 + read-write + 0x00000000 + + + CNT + Number of data to transfer + 0 + 16 + + + + + C3PADDR + C3PADDR + DMA channel 3 peripheral base address register + 0x38 + 0x20 + read-write + 0x00000000 + + + PADDR + Peripheral address + 0 + 32 + + + + + C3MADDR + C3MADDR + DMA channel 3 memory base address register + 0x3C + 0x20 + read-write + 0x00000000 + + + MADDR + Memory address + 0 + 32 + + + + + C4CTRL + C4CTRL + DMA channel configuration register (DMA_C4CTRL) + 0x44 + 0x20 + read-write + 0x00000000 + + + CHEN + Channel enable + 0 + 1 + + + FDTIEN + Transfer complete interrupt enable + 1 + 1 + + + HDTIEN + Half transfer interrupt enable + 2 + 1 + + + DTERRIEN + Transfer error interrupt enable + 3 + 1 + + + DTD + Data transfer direction + 4 + 1 + + + LM + Loop mode + 5 + 1 + + + PINCM + Peripheral increment mode + 6 + 1 + + + MINCM + Memory increment mode + 7 + 1 + + + PWIDTH + Peripheral data bit width + 8 + 2 + + + MWIDTH + Memory data bit width + 10 + 2 + + + CHPL + Channel Priority level + 12 + 2 + + + M2M + Memory to memory mode + 14 + 1 + + + + + C4DTCNT + C4DTCNT + DMA channel 4 number of data to transfer register + 0x48 + 0x20 + read-write + 0x00000000 + + + CNT + Number of data to transfer + 0 + 16 + + + + + C4PADDR + C4PADDR + DMA channel 4 peripheral base address register + 0x4C + 0x20 + read-write + 0x00000000 + + + PADDR + Peripheral address + 0 + 32 + + + + + C4MADDR + C4MADDR + DMA channel 4 memory base address register + 0x50 + 0x20 + read-write + 0x00000000 + + + MADDR + Memory address + 0 + 32 + + + + + C5CTRL + C5CTRL + DMA channel configuration register (DMA_C5CTRL) + 0x58 + 0x20 + read-write + 0x00000000 + + + CHEN + Channel enable + 0 + 1 + + + FDTIEN + Transfer complete interrupt enable + 1 + 1 + + + HDTIEN + Half transfer interrupt enable + 2 + 1 + + + DTERRIEN + Transfer error interrupt enable + 3 + 1 + + + DTD + Data transfer direction + 4 + 1 + + + LM + Loop mode + 5 + 1 + + + PINCM + Peripheral increment mode + 6 + 1 + + + MINCM + Memory increment mode + 7 + 1 + + + PWIDTH + Peripheral data bit width + 8 + 2 + + + MWIDTH + Memory data bit width + 10 + 2 + + + CHPL + Channel Priority level + 12 + 2 + + + M2M + Memory to memory mode + 14 + 1 + + + + + C5DTCNT + C5DTCNT + DMA channel 5 number of data to transfer register + 0x5C + 0x20 + read-write + 0x00000000 + + + CNT + Number of data to transfer + 0 + 16 + + + + + C5PADDR + C5PADDR + DMA channel 5 peripheral base address register + 0x60 + 0x20 + read-write + 0x00000000 + + + PADDR + Peripheral address + 0 + 32 + + + + + C5MADDR + C5MADDR + DMA channel 5 memory base address register + 0x64 + 0x20 + read-write + 0x00000000 + + + MADDR + Memory address + 0 + 32 + + + + + C6CTRL + C6CTRL + DMA channel configuration register(DMA_C6CTRL) + 0x6C + 0x20 + read-write + 0x00000000 + + + CHEN + Channel enable + 0 + 1 + + + FDTIEN + Transfer complete interrupt enable + 1 + 1 + + + HDTIEN + Half transfer interrupt enable + 2 + 1 + + + DTERRIEN + Transfer error interrupt enable + 3 + 1 + + + DTD + Data transfer direction + 4 + 1 + + + LM + Loop mode + 5 + 1 + + + PINCM + Peripheral increment mode + 6 + 1 + + + MINCM + Memory increment mode + 7 + 1 + + + PWIDTH + Peripheral data bit width + 8 + 2 + + + MWIDTH + Memory data bit width + 10 + 2 + + + CHPL + Channel Priority level + 12 + 2 + + + M2M + Memory to memory mode + 14 + 1 + + + + + C6DTCNT + C6DTCNT + DMA channel 6 number of data to transfer register + 0x70 + 0x20 + read-write + 0x00000000 + + + CNT + Number of data to transfer + 0 + 16 + + + + + C6PADDR + C6PADDR + DMA channel 6 peripheral address base register + 0x74 + 0x20 + read-write + 0x00000000 + + + PADDR + Peripheral address + 0 + 32 + + + + + C6MADDR + C6MADDR + DMA channel 6 memory address base register + 0x78 + 0x20 + read-write + 0x00000000 + + + MADDR + Memory address + 0 + 32 + + + + + C7CTRL + C7CTRL + DMA channel configuration register(DMA_C7CTRL) + 0x80 + 0x20 + read-write + 0x00000000 + + + CHEN + Channel enable + 0 + 1 + + + FDTIEN + Transfer complete interrupt enable + 1 + 1 + + + HDTIEN + Half transfer interrupt enable + 2 + 1 + + + DTERRIEN + Transfer error interrupt enable + 3 + 1 + + + DTD + Data transfer direction + 4 + 1 + + + LM + Loop mode + 5 + 1 + + + PINCM + Peripheral increment mode + 6 + 1 + + + MINCM + Memory increment mode + 7 + 1 + + + PWIDTH + Peripheral data bit width + 8 + 2 + + + MWIDTH + Memory data bit width + 10 + 2 + + + CHPL + Channel Priority level + 12 + 2 + + + M2M + Memory to memory mode + 14 + 1 + + + + + C7DTCNT + C7DTCNT + DMA channel 7 number of data to transfer register + 0x84 + 0x20 + read-write + 0x00000000 + + + CNT + Number of data to transfer + 0 + 16 + + + + + C7PADDR + C7PADDR + DMA channel 7 peripheral base address register + 0x88 + 0x20 + read-write + 0x00000000 + + + PADDR + Peripheral address + 0 + 32 + + + + + C7MADDR + C7MADDR + DMA channel 7 memory base address register + 0x8C + 0x20 + read-write + 0x00000000 + + + MADDR + Memory address + 0 + 32 + + + + + DMA_MUXSEL + DMA_MUXSEL + DMAMUX Table Selection + 0x100 + 0x20 + 0x00000000 + + + TBL_SEL + Multiplexer Table Select + 0 + 1 + read-write + + + + + MUXC1CTRL + MUXC1CTRL + Channel 1 Configuration Register + 0x104 + 0x20 + 0x00000000 + + + REQSEL + DMA request select + 0 + 7 + read-write + + + SYNCOVIEN + Synchronization overrun interrupt enable + 8 + 1 + read-write + + + EVTGEN + Event generation enable + 9 + 1 + read-write + + + SYNCEN + Synchroniztion enable + 16 + 1 + read-write + + + SYNCPOL + Synchronization polarity + 17 + 2 + read-write + + + REQCNT + Number of DMA requests + 19 + 5 + read-write + + + SYNCSEL + Synchronization Identification + 24 + 5 + read-write + + + + + MUXC2CTRL + MUXC2CTRL + Channel 2 Configuration Register + 0x108 + 0x20 + 0x00000000 + + + REQSEL + DMA request select + 0 + 7 + read-write + + + SYNCOVIEN + Synchronization overrun interrupt enable + 8 + 1 + read-write + + + EVTGEN + Event generation enable + 9 + 1 + read-write + + + SYNCEN + Synchroniztion enable + 16 + 1 + read-write + + + SYNCPOL + Synchronization polarity + 17 + 2 + read-write + + + REQCNT + Number of DMA requests + 19 + 5 + read-write + + + SYNCSEL + Synchronization Identification + 24 + 5 + read-write + + + + + MUXC3CTRL + MUXC3CTRL + Channel 3 Configuration Register + 0x10C + 0x20 + 0x00000000 + + + REQSEL + DMA request select + 0 + 7 + read-write + + + SYNCOVIEN + Synchronization overrun interrupt enable + 8 + 1 + read-write + + + EVTGEN + Event generation enable + 9 + 1 + read-write + + + SYNCEN + Synchroniztion enable + 16 + 1 + read-write + + + SYNCPOL + Synchronization polarity + 17 + 2 + read-write + + + REQCNT + Number of DMA requests + 19 + 5 + read-write + + + SYNCSEL + Synchronization Identification + 24 + 5 + read-write + + + + + MUXC4CTRL + MUXC4CTRL + Channel 4 Configuration Register + 0x110 + 0x20 + 0x00000000 + + + REQSEL + DMA request select + 0 + 7 + read-write + + + SYNCOVIEN + Synchronization overrun interrupt enable + 8 + 1 + read-write + + + EVTGEN + Event generation enable + 9 + 1 + read-write + + + SYNCEN + Synchroniztion enable + 16 + 1 + read-write + + + SYNCPOL + Synchronization polarity + 17 + 2 + read-write + + + REQCNT + Number of DMA requests + 19 + 5 + read-write + + + SYNCSEL + Synchronization Identification + 24 + 5 + read-write + + + + + MUXC5CTRL + MUXC5CTRL + Channel 5 Configuration Register + 0x114 + 0x20 + 0x00000000 + + + REQSEL + DMA request select + 0 + 7 + read-write + + + SYNCOVIEN + Synchronization overrun interrupt enable + 8 + 1 + read-write + + + EVTGEN + Event generation enable + 9 + 1 + read-write + + + SYNCEN + Synchroniztion enable + 16 + 1 + read-write + + + SYNCPOL + Synchronization polarity + 17 + 2 + read-write + + + REQCNT + Number of DMA requests + 19 + 5 + read-write + + + SYNCSEL + Synchronization Identification + 24 + 5 + read-write + + + + + MUXC6CTRL + MUXC6CTRL + Channel 6 Configuration Register + 0x118 + 0x20 + 0x00000000 + + + REQSEL + DMA request select + 0 + 7 + read-write + + + SYNCOVIEN + Synchronization overrun interrupt enable + 8 + 1 + read-write + + + EVTGEN + Event generation enable + 9 + 1 + read-write + + + SYNCEN + Synchroniztion enable + 16 + 1 + read-write + + + SYNCPOL + Synchronization polarity + 17 + 2 + read-write + + + REQCNT + Number of DMA requests + 19 + 5 + read-write + + + SYNCSEL + Synchronization Identification + 24 + 5 + read-write + + + + + MUXC7CTRL + MUXC7CTRL + Channel 7 Configuration Register + 0x11C + 0x20 + 0x00000000 + + + REQSEL + DMA request select + 0 + 7 + read-write + + + SYNCOVIEN + Synchronization overrun interrupt enable + 8 + 1 + read-write + + + EVTGEN + Event generation enable + 9 + 1 + read-write + + + SYNCEN + Synchroniztion enable + 16 + 1 + read-write + + + SYNCPOL + Synchronization polarity + 17 + 2 + read-write + + + REQCNT + Number of DMA requests + 19 + 5 + read-write + + + SYNCSEL + Synchronization Identification + 24 + 5 + read-write + + + + + MUXG1CTRL + MUXG1CTRL + Generator 1 Configuration Register + 0x120 + 0x20 + 0x00000000 + + + SIGSEL + Signal select + 0 + 5 + read-write + + + TRGOVIEN + Trigger overrun interrupt enable + 8 + 1 + read-write + + + GEN + DMA request generator enable + 16 + 1 + read-write + + + GPOL + DMA request generator trigger polarity + 17 + 2 + read-write + + + GREQCNT + Number of DMA requests to be generated + 19 + 5 + read-write + + + + + MUXG2CTRL + MUXG2CTRL + Generator 2 Configuration Register + 0x124 + 0x20 + 0x00000000 + + + SIGSEL + Signal select + 0 + 5 + read-write + + + TRGOVIEN + Trigger overrun interrupt enable + 8 + 1 + read-write + + + GEN + DMA request generator enable + 16 + 1 + read-write + + + GPOL + DMA request generator trigger polarity + 17 + 2 + read-write + + + GREQCNT + Number of DMA requests to be generated + 19 + 5 + read-write + + + + + MUXG3CTRL + MUXG3CTRL + Generator 3 Configuration Register + 0x128 + 0x20 + 0x00000000 + + + SIGSEL + Signal select + 0 + 5 + read-write + + + TRGOVIEN + Trigger overrun interrupt enable + 8 + 1 + read-write + + + GEN + DMA request generator enable + 16 + 1 + read-write + + + GPOL + DMA request generator trigger polarity + 17 + 2 + read-write + + + GREQCNT + Number of DMA requests to be generated + 19 + 5 + read-write + + + + + MUXG4CTRL + MUXG4CTRL + Generator 4 Configuration Register + 0x12C + 0x20 + 0x00000000 + + + SIGSEL + Signal select + 0 + 5 + read-write + + + TRGOVIEN + Trigger overrun interrupt enable + 8 + 1 + read-write + + + GEN + DMA request generator enable + 16 + 1 + read-write + + + GPOL + DMA request generator trigger polarity + 17 + 2 + read-write + + + GREQCNT + Number of DMA requests to be generated + 19 + 5 + read-write + + + + + MUXSYNCSTS + MUXSYNCSTS + Channel Interrupt Status Register + 0x130 + 0x20 + 0x00000000 + + + SYNCOVF1 + Synchronizaton overrun interrupt flag + 0 + 1 + read-only + + + SYNCOVF2 + Synchronizaton overrun interrupt flag + 1 + 1 + read-only + + + SYNCOVF3 + Synchronizaton overrun interrupt flag + 2 + 1 + read-only + + + SYNCOVF4 + Synchronizaton overrun interrupt flag + 3 + 1 + read-only + + + SYNCOVF5 + Synchronizaton overrun interrupt flag + 4 + 1 + read-only + + + SYNCOVF6 + Synchronizaton overrun interrupt flag + 5 + 1 + read-only + + + SYNCOVF7 + Synchronizaton overrun interrupt flag + 6 + 1 + read-only + + + + + MUXSYNCCLR + MUXSYNCCLR + Channel Interrupt Clear Flag Register + 0x134 + 0x20 + 0x00000000 + + + SYNCOVFC1 + Clear synchronizaton overrun interrupt flag + 0 + 1 + read-write + + + SYNCOVFC2 + Clear synchronizaton overrun interrupt flag + 1 + 1 + read-write + + + SYNCOVFC3 + Clear synchronizaton overrun interrupt flag + 2 + 1 + read-write + + + SYNCOVFC4 + Clear synchronizaton overrun interrupt flag + 3 + 1 + read-write + + + SYNCOVFC5 + Clear synchronizaton overrun interrupt flag + 4 + 1 + read-write + + + SYNCOVFC6 + Clear synchronizaton overrun interrupt flag + 5 + 1 + read-write + + + SYNCOVFC7 + Clear synchronizaton overrun interrupt flag + 6 + 1 + read-write + + + + + MUXGSTS + MUXGSTS + Generator Interrupt Status Register + 0x138 + 0x20 + 0x00000000 + + + TRGOVF1 + Trigger overrun interrupt flag + 0 + 1 + read-write + + + TRGOVF2 + Trigger overrun interrupt flag + 1 + 1 + read-write + + + TRGOVF3 + Trigger overrun interrupt flag + 2 + 1 + read-write + + + TRGOVF4 + Trigger overrun interrupt flag + 3 + 1 + read-write + + + + + MUXGCLR + MUXGCLR + Generator Interrupt Clear Flag Register + 0x13C + 0x20 + 0x00000000 + + + TRGOVFC1 + Clear trigger overrun interrupt flag + 0 + 1 + read-write + + + TRGOVFC2 + Clear trigger overrun interrupt flag + 1 + 1 + read-write + + + TRGOVFC3 + Clear trigger overrun interrupt flag + 2 + 1 + read-write + + + TRGOVFC4 + Clear trigger overrun interrupt flag + 3 + 1 + read-write + + + + + + + DMA2 + 0x40026600 + + + SDIO1 + Secure digital input/output + interface + SDIO + 0x4002C400 + + 0x0 + 0x400 + registers + + + SDIO1 + SDIO1 global interrupt + 49 + + + + PWRCTRL + PWRCTRL + Bits 1:0 = PWRCTRL: Power supply control + bits + 0x0 + 0x20 + read-write + 0x00000000 + + + PS + Power switch + 0 + 2 + + + + + CLKCTRL + CLKCTRL + SD clock control register + (SDIO_CLKCTRL) + 0x4 + 0x20 + read-write + 0x00000000 + + + CLKDIV + Clock division + 0 + 8 + + + CLKOEN + Clock output enable + 8 + 1 + + + PWRSVEN + Power saving mode enable + 9 + 1 + + + BYPSEN + Clock divider bypass enable + bit + 10 + 1 + + + BUSWS + Bus width selection + 11 + 2 + + + CLKEDS + SDIO_CK edge selection bit + 13 + 1 + + + HFCEN + Hardware flow control enable + 14 + 1 + + + CLKDIV98 + Clock divide factor bit9 and bit8 + 15 + 2 + + + + + ARGU + ARGU + Bits 31:0 = : Command argument + 0x8 + 0x20 + read-write + 0x00000000 + + + ARGU + Command argument + 0 + 32 + + + + + CMDCTRL + CMDCTRL + SDIO command control register + (SDIO_CMDCTRL) + 0xC + 0x20 + read-write + 0x00000000 + + + CMDIDX + CMDIDX + 0 + 6 + + + RSPWT + Wait for response + 6 + 2 + + + INTWT + CCSM wait for interrupt + 8 + 1 + + + PNDWT + CCSM wait for end of transfer + 9 + 1 + + + CCSMEN + Command channel state machine + 10 + 1 + + + IOSUSP + SD I/O suspend command + 11 + 1 + + + + + RSPCMD + RSPCMD + SDIO command register + 0x10 + 0x20 + read-only + 0x00000000 + + + RSPCMD + RSPCMD + 0 + 6 + + + + + RSP1 + RSP1 + Bits 31:0 = CARDSTATUS1 + 0x14 + 0x20 + read-only + 0x00000000 + + + CARDSTS1 + CARDSTATUS1 + 0 + 32 + + + + + RSP2 + RSP2 + Bits 31:0 = CARDSTATUS2 + 0x18 + 0x20 + read-only + 0x00000000 + + + CARDSTS2 + CARDSTATUS2 + 0 + 32 + + + + + RSP3 + RSP3 + Bits 31:0 = CARDSTATUS3 + 0x1C + 0x20 + read-only + 0x00000000 + + + CARDSTS2 + CARDSTATUS3 + 0 + 32 + + + + + RSP4 + RSP4 + Bits 31:0 = CARDSTATUS4 + 0x20 + 0x20 + read-only + 0x00000000 + + + CARDSTS2 + CARDSTATUS4 + 0 + 32 + + + + + DTTMR + DTTMR + Bits 31:0 = TIMEOUT: Data timeout + period + 0x24 + 0x20 + read-write + 0x00000000 + + + TIMEOUT + Data timeout period + 0 + 32 + + + + + DTLEN + DTLEN + Bits 24:0 = DATALENGTH: Data length + value + 0x28 + 0x20 + read-write + 0x00000000 + + + DTLEN + Data length value + 0 + 25 + + + + + DTCTRL + DTCTRL + SDIO data control register + (SDIO_DCTRL) + 0x2C + 0x20 + read-write + 0x00000000 + + + TFREN + DTEN + 0 + 1 + + + TFRDIR + DTDIR + 1 + 1 + + + TFRMODE + DTMODE + 2 + 1 + + + DMAEN + DMAEN + 3 + 1 + + + BLKSIZE + DBLOCKSIZE + 4 + 4 + + + RDWTSTART + PWSTART + 8 + 1 + + + RDWTSTOP + PWSTOP + 9 + 1 + + + RDWTMODE + RWMOD + 10 + 1 + + + IOEN + SD I/O function enable + 11 + 1 + + + + + DTCNT + DTCNT + Bits 24:0 = DATACOUNT: Data count + value + 0x30 + 0x20 + read-only + 0x00000000 + + + CNT + Data count value + 0 + 25 + + + + + STS + STS + SDIO status register + (SDIO_STA) + 0x34 + 0x20 + read-only + 0x00000000 + + + CMDFAIL + Command crc fail + 0 + 1 + + + DTFAIL + Data crc fail + 1 + 1 + + + CMDTIMEOUT + Command timeout + 2 + 1 + + + DTTIMEOUT + Data timeout + 3 + 1 + + + TXERRU + Tx under run error + 4 + 1 + + + RXERRO + Rx over run error + 5 + 1 + + + CMDRSPCMPL + Command response complete + 6 + 1 + + + CMDCMPL + Command sent + 7 + 1 + + + DTCMPL + Data sent + 8 + 1 + + + SBITERR + Start bit error + 9 + 1 + + + DTBLKCMPL + Data block sent + 10 + 1 + + + DOCMD + Command transfer in progress + 11 + 1 + + + DOTX + Data transmit in progress + 12 + 1 + + + DORX + Data receive in progress + 13 + 1 + + + TXBUFH + Tx buffer half empty + 14 + 1 + + + RXBUFH + Rx buffer half empty + 15 + 1 + + + TXBUFF + Tx buffer full + 16 + 1 + + + RXBUFF + Rx buffer full + 17 + 1 + + + TXBUFE + Tx buffer empty + 18 + 1 + + + RXBUFE + Rx buffer empty + 19 + 1 + + + TXBUF + Tx data vaild + 20 + 1 + + + RXBUF + Rx data vaild + 21 + 1 + + + IOIF + SD I/O interrupt + 22 + 1 + + + + + INTCLR + INTCLR + SDIO interrupt clear register + (SDIO_INTCLR) + 0x38 + 0x20 + read-write + 0x00000000 + + + CMDFAIL + Command crc fail flag clear + 0 + 1 + + + DTFAIL + Data crc fail flag clear + 1 + 1 + + + CMDTIMEOUT + Command timeout flag clear + 2 + 1 + + + DTTIMEOUT + Data timeout flag clear + 3 + 1 + + + TXERRU + Tx under run error flag clear + 4 + 1 + + + RXERRU + Rx over run error flag clear + 5 + 1 + + + CMDRSPCMPL + Command response complete flag clear + 6 + 1 + + + CMDCMPL + Command sent flag clear + 7 + 1 + + + DTCMPL + Data sent flag clear + 8 + 1 + + + SBITERR + Start bit error flag clear + 9 + 1 + + + DTBLKCMPL + Data block sent clear + 10 + 1 + + + IOIF + SD I/O interrupt flag clear + 22 + 1 + + + + + INTEN + INTEN + SDIO mask register (SDIO_MASK) + 0x3C + 0x20 + read-write + 0x00000000 + + + CMDFAILIEN + Command crc fail interrupt enable + 0 + 1 + + + DTFAILIEN + Data crc fail interrupt enable + 1 + 1 + + + CMDTIMEOUTIEN + Command timeout interrupt enable + 2 + 1 + + + DTTIMEOUTIEN + Data timeout interrupt enable + 3 + 1 + + + TXERRUIEN + Tx under run interrupt enable + 4 + 1 + + + RXERRUIEN + Rx over run interrupt enable + 5 + 1 + + + CMDRSPCMPLIEN + Command response complete interrupt enable + 6 + 1 + + + CMDCMPLIEN + Command sent complete interrupt enable + 7 + 1 + + + DTCMPLIEN + Data sent complete interrupt enable + 8 + 1 + + + SBITERRIEN + Start bit error interrupt enable + 9 + 1 + + + DTBLKCMPLIEN + Data block sent complete interrupt enable + 10 + 1 + + + DOCMDIEN + Command acting interrupt enable + 11 + 1 + + + DOTXIEN + Data transmit acting interrupt enable + 12 + 1 + + + DORXIEN + Data receive acting interrupt enable + 13 + 1 + + + TXBUFHIEN + Tx buffer half empty interrupt enable + 14 + 1 + + + RXBUFHIEN + Rx buffer half empty interrupt enable + 15 + 1 + + + TXBUFFIEN + Tx buffer full interrupt enable + 16 + 1 + + + RXBUFFIEN + Rx buffer full interrupt enable + 17 + 1 + + + TXBUFEIEN + Tx buffer empty interrupt enable + 18 + 1 + + + RXBUFEIEN + Rx buffer empty interrupt enable + 19 + 1 + + + TXBUFIEN + Tx buffer data vaild interrupt enable + 20 + 1 + + + RXBUFIEN + Rx buffer data vaild interrupt enable + 21 + 1 + + + IOIFIEN + SD I/O interrupt enable + 22 + 1 + + + + + BUFCNT + BUFCNT + Bits 23:0 = BUFCOUNT: Remaining number of + words to be written to or read from the + FIFO + 0x48 + 0x20 + read-only + 0x00000000 + + + CNT + FIF0COUNT + 0 + 24 + + + + + BUF + BUF + bits 31:0 = Buffer Data: Receive and transmit + buffer data + 0x80 + 0x20 + read-write + 0x00000000 + + + DT + Buffer data + 0 + 32 + + + + + + + SDIO2 + 0x50061000 + + SDIO2 + SDIO2 global interrupt + 102 + + + + ERTC + Real-time clock + ERTC + 0x40002800 + + 0x0 + 0x400 + registers + + + + TIME + TIME + time register + 0x0 + 0x20 + read-write + 0x00000000 + + + AMPM + AM/PM notation + 22 + 1 + + + HT + Hour tens + 20 + 2 + + + HU + Hour units + 16 + 4 + + + MT + Minute tens + 12 + 3 + + + MU + Minute units + 8 + 4 + + + ST + Second tens + 4 + 3 + + + SU + Second units + 0 + 4 + + + + + DATE + DATE + date register + 0x4 + 0x20 + read-write + 0x00002101 + + + YT + Year tens + 20 + 4 + + + YU + Year units + 16 + 4 + + + WK + Week + 13 + 3 + + + MT + Month tens + 12 + 1 + + + MU + Month units + 8 + 4 + + + DT + Date tens + 4 + 2 + + + DU + Date units + 0 + 4 + + + + + CTRL + CTRL + control register + 0x8 + 0x20 + read-write + 0x00000000 + + + CALOEN + Calibration output enable + 23 + 1 + + + OUTSEL + Output source selection + 21 + 2 + + + OUTP + Output polarity + 20 + 1 + + + CALOSEL + Calibration output selection + 19 + 1 + + + BPR + Battery power domain data register + 18 + 1 + + + DEC1H + Decrease 1 hour + 17 + 1 + + + ADD1H + Add 1 hour + 16 + 1 + + + TSIEN + Timestamp interrupt enable + 15 + 1 + + + WATIEN + Wakeup timer interrupt enable + 14 + 1 + + + ALBIEN + Alarm B interrupt enable + 13 + 1 + + + ALAIEN + Alarm A interrupt enable + 12 + 1 + + + TSEN + Timestamp enable + 11 + 1 + + + WATEN + Wakeup timer enable + 10 + 1 + + + ALBEN + Alarm B enable + 9 + 1 + + + ALAEN + Alarm A enable + 8 + 1 + + + CCALEN + Coarse calibration enable + 7 + 1 + + + HM + Hour mode + 6 + 1 + + + DREN + Date/time register direct read enable + 5 + 1 + + + RCDEN + Reference clock detection enable + 4 + 1 + + + TSEDG + Timestamp trigger edge + 3 + 1 + + + WATCLK + Wakeup timer clock selection + 0 + 3 + + + + + STS + STS + initialization and status + register + 0xC + 0x20 + 0x00000007 + + + ALAWF + Alarm A register allows write flag + 0 + 1 + read-only + + + ALBWF + Alarm B register allows write flag + 1 + 1 + read-only + + + WATWF + Wakeup timer register allows write flag + 2 + 1 + read-only + + + TADJF + Time adjustment flag + 3 + 1 + read-write + + + INITF + Calendar initialization flag + 4 + 1 + read-only + + + UPDF + Calendar update flag + 5 + 1 + read-write + + + IMF + Enter initialization mode flag + 6 + 1 + read-only + + + IMEN + Initialization mode enable + 7 + 1 + read-write + + + ALAF + Alarm A flag + 8 + 1 + read-write + + + ALBF + Alarm B flag + 9 + 1 + read-write + + + WATF + Wakeup timer flag + 10 + 1 + read-write + + + TSF + Timestamp flag + 11 + 1 + read-write + + + TSOF + Timestamp overflow flag + 12 + 1 + read-write + + + TP1F + Tamper detection 1 flag + 13 + 1 + read-write + + + TP2F + Tamper detection 2 flag + 14 + 1 + read-write + + + CALUPDF + Calibration value update completed flag + 16 + 1 + read-only + + + + + DIV + DIV + Diveder register + 0x10 + 0x20 + read-write + 0x007F00FF + + + DIVA + Diveder A + 16 + 7 + + + DIVB + Diveder B + 0 + 15 + + + + + WAT + WAT + Wakeup timer register + 0x14 + 0x20 + read-write + 0x0000FFFF + + + VAL + Wakeup timer reload value + 0 + 16 + + + + + CCAL + CCAL + Calibration register + 0x18 + 0x20 + read-write + 0x00000000 + + + CALDIR + Calibration direction + 7 + 1 + + + CALVAL + Calibration value + 0 + 5 + + + + + ALA + ALA + Alarm A register + 0x1C + 0x20 + read-write + 0x00000000 + + + MASK4 + Date/week mask + 31 + 1 + + + WKSEL + Date/week mode select + 30 + 1 + + + DT + Date tens + 28 + 2 + + + DU + Date units + 24 + 4 + + + MASK3 + Hours mask + 23 + 1 + + + AMPM + AM/PM + 22 + 1 + + + HT + Hour tens + 20 + 2 + + + HU + Hour units + 16 + 4 + + + MASK2 + Minutes mask + 15 + 1 + + + MT + Minute tens + 12 + 3 + + + MU + Minute units + 8 + 4 + + + MASK1 + Seconds mask + 7 + 1 + + + ST + Second tens + 4 + 3 + + + SU + Second units + 0 + 4 + + + + + ALB + ALB + Alarm B register + 0x20 + 0x20 + read-write + 0x00000000 + + + MASK4 + Date/week mask + 31 + 1 + + + WKSEL + Date/week mode select + 30 + 1 + + + DT + Date tens + 28 + 2 + + + DU + Date units + 24 + 4 + + + MASK3 + Hours mask + 23 + 1 + + + AMPM + AM/PM + 22 + 1 + + + HT + Hour tens + 20 + 2 + + + HU + Hour units + 16 + 4 + + + MASK2 + Minutes mask + 15 + 1 + + + MT + Minute tens + 12 + 3 + + + MU + Minute units + 8 + 4 + + + MASK1 + Seconds mask + 7 + 1 + + + ST + Second tens + 4 + 3 + + + SU + Second units + 0 + 4 + + + + + WP + WP + write protection register + 0x24 + 0x20 + write-only + 0x00000000 + + + CMD + Command register + 0 + 8 + + + + + SBS + SBS + sub second register + 0x28 + 0x20 + read-only + 0x00000000 + + + SBS + Sub second value + 0 + 16 + + + + + TADJ + TADJ + time adjust register + 0x2C + 0x20 + write-only + 0x00000000 + + + ADD1S + Add 1 second + 31 + 1 + + + DECSBS + Decrease sub-second value + 0 + 15 + + + + + TSTM + TSTM + time stamp time register + 0x30 + 0x20 + read-only + 0x00000000 + + + AMPM + AMPM + 22 + 1 + + + HT + Hour tens + 20 + 2 + + + HU + Hour units + 16 + 4 + + + MT + Minute tens + 12 + 3 + + + MU + Minute units + 8 + 4 + + + ST + Second tens + 4 + 3 + + + SU + Second units + 0 + 4 + + + + + TSDT + TSDT + timestamp date register + 0x34 + 0x20 + read-only + 0x00000000 + + + WK + Week + 13 + 3 + + + MT + Month tens + 12 + 1 + + + MU + Month units + 8 + 4 + + + DT + Date tens + 4 + 2 + + + DU + Date units + 0 + 4 + + + + + TSSBS + TSSBS + timestamp sub second register + 0x38 + 0x20 + read-only + 0x00000000 + + + SBS + Sub second value + 0 + 16 + + + + + SCAL + SCAL + calibration register + 0x3C + 0x20 + read-write + 0x00000000 + + + ADD + Add ERTC clock + 15 + 1 + + + CAL8 + 8-second calibration period + 14 + 1 + + + CAL16 + 16 second calibration period + 13 + 1 + + + DEC + Decrease ERTC clock + 0 + 9 + + + + + TAMP + TAMP + tamper and alternate function configuration + register + 0x40 + 0x20 + read-write + 0x00000000 + + + OUTTYPE + Output type + 18 + 1 + + + TSPIN + Time stamp detection pin selection + 17 + 1 + + + TP1PIN + Tamper detection pin selection + 16 + 1 + + + TPPU + Tamper detection pull-up + 15 + 1 + + + TPPR + Tamper detection pre-charge time + 13 + 2 + + + TPFLT + Tamper detection filter time + 11 + 2 + + + TPFREQ + Tamper detection frequency + 8 + 3 + + + TPTSEN + Tamper detection timestamp enable + 7 + 1 + + + TP2EDG + Tamper detection 2 valid edge + 4 + 1 + + + TP2EN + Tamper detection 2 enable + 3 + 1 + + + TPIEN + Tamper detection interrupt enable + 2 + 1 + + + TP1EDG + Tamper detection 1 valid edge + 1 + 1 + + + TP1EN + Tamper detection 1 enable + 0 + 1 + + + + + ALASBS + ALASBS + alarm A sub second register + 0x44 + 0x20 + read-write + 0x00000000 + + + SBSMSK + Sub-second mask + 24 + 4 + + + SBS + Sub-seconds value + 0 + 15 + + + + + ALBSBS + ALBSBS + alarm B sub second register + 0x48 + 0x20 + read-write + 0x00000000 + + + SBSMSK + Sub-second mask + 24 + 4 + + + SBS + Sub-seconds value + 0 + 15 + + + + + BPR1DT + BPR1DT + Battery powered domain register + 0x50 + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + BPR2DT + BPR2DT + Battery powered domain register + 0x54 + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + BPR3DT + BPR3DT + Battery powered domain register + 0x58 + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + BPR4DT + BPR4DT + Battery powered domain register + 0x5C + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + BPR5DT + BPR5DT + Battery powered domain register + 0x60 + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + BPR6DT + BPR6DT + Battery powered domain register + 0x64 + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + BPR7DT + BPR7DT + Battery powered domain register + 0x68 + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + BPR8DT + BPR8DT + Battery powered domain register + 0x6C + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + BPR9DT + BPR9DT + Battery powered domain register + 0x70 + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + BPR10DT + BPR10DT + Battery powered domain register + 0x74 + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + BPR11DT + BPR11DT + Battery powered domain register + 0x78 + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + BPR12DT + BPR12DT + Battery powered domain register + 0x7C + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + BPR13DT + BPR13DT + Battery powered domain register + 0x80 + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + BPR14DT + BPR14DT + Battery powered domain register + 0x84 + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + BPR15DT + BPR15DT + Battery powered domain register + 0x88 + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + BPR16DT + BPR16DT + Battery powered domain register + 0x8C + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + BPR17DT + BPR17DT + Battery powered domain register + 0x90 + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + BPR18DT + BPR18DT + Battery powered domain register + 0x94 + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + BPR19DT + BPR19DT + Battery powered domain register + 0x98 + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + BPR20DT + BPR20DT + Battery powered domain register + 0x9C + 0x20 + read-write + 0x00000000 + + + DT + Battery powered domain data + 0 + 32 + + + + + + + WDT + Watchdog + WDT + 0x40003000 + + 0x0 + 0x400 + registers + + + + CMD + CMD + Command register + 0x0 + 0x20 + write-only + 0x00000000 + + + CMD + Command register + 0 + 16 + + + + + DIV + DIV + Division register + 0x4 + 0x20 + read-write + 0x00000000 + + + DIV + Division divider + 0 + 3 + + + + + RLD + RLD + Reload register + 0x8 + 0x20 + read-write + 0x00000FFF + + + RLD + Reload value + 0 + 12 + + + + + STS + STS + Status register + 0xC + 0x20 + read-only + 0x00000000 + + + DIVF + Division value update complete flag + 0 + 1 + + + RLDF + Reload value update complete flag + 1 + 1 + + + WINF + Window value update complete flag + 2 + 1 + + + + + WIN + WIN + Window register + 0x10 + 0x20 + read-write + 0x00000FFF + + + WIN + Window value + 0 + 12 + + + + + + + WWDT + Window watchdog + WWDT + 0x40002C00 + + 0x0 + 0x400 + registers + + + WWDT + Window Watchdog interrupt + 0 + + + + CTRL + CTRL + Control register + 0x0 + 0x20 + read-write + 0x0000007F + + + CNT + Decrement counter + 0 + 7 + + + WWDTEN + Window watchdog enable + 7 + 1 + + + + + CFG + CFG + Configuration register + 0x4 + 0x20 + read-write + 0x0000007F + + + WIN + Window value + 0 + 7 + + + DIV + Clock division value + 7 + 2 + + + RLDIEN + Reload counter interrupt + 9 + 1 + + + + + STS + STS + Status register + 0x8 + 0x20 + read-write + 0x00000000 + + + RLDF + Reload counter interrupt flag + 0 + 1 + + + + + + + TMR1 + Advanced timer + TIMER + 0x40010000 + + 0x0 + 0x400 + registers + + + TMR1_BRK_TMR9 + TMR1 brake interrupt and TMR9 global + interrupt + 24 + + + TMR1_OVF_TMR10 + TMR1 overflow interrupt and TMR10 global + interrupt + 25 + + + TMR1_TRG_HALL_TMR11 + TMR1 trigger and HALL interrupts and + TMR11 global interrupt + 26 + + + TMR1_CH + TMR1 channel interrupt + 27 + + + + CTRL1 + CTRL1 + Control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CLKDIV + Clock divider + 8 + 2 + + + PRBEN + Period buffer enable + 7 + 1 + + + TWCMSEL + Two-way count mode + selection + 5 + 2 + + + OWCDIR + One-way count direction + 4 + 1 + + + OCMEN + One cycle mode enable + 3 + 1 + + + OVFS + Overflow event source + 2 + 1 + + + OVFEN + Overflow event enable + 1 + 1 + + + TMREN + TMR enable + 0 + 1 + + + + + CTRL2 + CTRL2 + Control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + TRGOUT2EN + TRGOUT2 enable + 31 + 1 + + + C4IOS + Channel 4 idle output state + 14 + 1 + + + C3CIOS + Channel 3 complementary idle output state + 13 + 1 + + + C3IOS + Channel 3 idle output state + 12 + 1 + + + C2CIOS + Channel 2 complementary idle output state + 11 + 1 + + + C2IOS + Channel 2 idle output state + 10 + 1 + + + C1CIOS + Channel 1 complementary idle output state + 9 + 1 + + + C1IOS + Channel 1 idle output state + 8 + 1 + + + C1INSEL + C1IN selection + 7 + 1 + + + PTOS + Primary TMR output selection + 4 + 3 + + + DRS + DMA request source + 3 + 1 + + + CCFS + Channel control bit flash select + 2 + 1 + + + CBCTRL + Channel buffer control + 0 + 1 + + + + + STCTRL + STCTRL + Subordinate TMR control register + 0x8 + 0x20 + read-write + 0x0000 + + + ESP + External signal polarity + 15 + 1 + + + ECMBEN + External clock mode B enable + 14 + 1 + + + ESDIV + External signal divider + 12 + 2 + + + ESF + External signal filter + 8 + 4 + + + STS + Subordinate TMR synchronization + 7 + 1 + + + STIS + Subordinate TMR input selection + 4 + 3 + + + SMSEL + Subordinate TMR mode selection + 0 + 3 + + + + + IDEN + IDEN + Interrupt/DMA enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDEN + Trigger DMA request enable + 14 + 1 + + + HALLDE + HALL DMA request enable + 13 + 1 + + + C4DEN + Channel 4 DMA request + enable + 12 + 1 + + + C3DEN + Channel 3 DMA request + enable + 11 + 1 + + + C2DEN + Channel 2 DMA request + enable + 10 + 1 + + + C1DEN + Channel 1 DMA request + enable + 9 + 1 + + + OVFDEN + Overflow DMA request enable + 8 + 1 + + + BRKIE + Brake interrupt enable + 7 + 1 + + + TIEN + Trigger interrupt enable + 6 + 1 + + + HALLIEN + HALL interrupt enable + 5 + 1 + + + C4IEN + Channel 4 interrupt + enable + 4 + 1 + + + C3IEN + Channel 3 interrupt + enable + 3 + 1 + + + C2IEN + Channel 2 interrupt + enable + 2 + 1 + + + C1IEN + Channel 1 interrupt + enable + 1 + 1 + + + OVFIEN + Overflow interrupt enable + 0 + 1 + + + + + ISTS + ISTS + Interrupt status register + 0x10 + 0x20 + read-write + 0x0000 + + + C4RF + Channel 4 recapture flag + 12 + 1 + + + C3RF + Channel 3 recapture flag + 11 + 1 + + + C2RF + Channel 2 recapture flag + 10 + 1 + + + C1RF + Channel 1 recapture flag + 9 + 1 + + + BRKIF + Brake interrupt flag + 7 + 1 + + + TRGIF + Trigger interrupt flag + 6 + 1 + + + HALLIF + HALL interrupt flag + 5 + 1 + + + C4IF + Channel 4 interrupt flag + 4 + 1 + + + C3IF + Channel 3 interrupt flag + 3 + 1 + + + C2IF + Channel 2 interrupt flag + 2 + 1 + + + C1IF + Channel 1 interrupt flag + 1 + 1 + + + OVFIF + Overflow interrupt flag + 0 + 1 + + + + + SWEVT + SWEVT + Software event register + 0x14 + 0x20 + read-write + 0x0000 + + + BRKSWTR + Brake event triggered by software + 7 + 1 + + + TRGSWTR + Trigger event triggered by software + 6 + 1 + + + HALLSWTR + HALL event triggered by software + 5 + 1 + + + C4SWTR + Channel 4 event triggered by software + 4 + 1 + + + C3SWTR + Channel 3 event triggered by software + 3 + 1 + + + C2SWTR + Channel 2 event triggered by software + 2 + 1 + + + C1SWTR + Channel 1 event triggered by software + 1 + 1 + + + OVFSWTR + Overflow event triggered by software + 0 + 1 + + + + + CM1_OUTPUT + CM1_OUTPUT + Channel output mode register + 0x18 + 0x20 + read-write + 0x00000000 + + + C2OSEN + Channel 2 output switch enable + 15 + 1 + + + C2OCTRL + Channel 2 output control + 12 + 3 + + + C2OBEN + Channel 2 output buffer enable + 11 + 1 + + + C2OIEN + Channel 2 output immediately enable + 10 + 1 + + + C2C + Channel 2 configure + 8 + 2 + + + C1OSEN + Channel 1 output switch enable + 7 + 1 + + + C1OCTRL + Channel 1 output control + 4 + 3 + + + C1OBEN + Channel 1 output buffer enable + 3 + 1 + + + C1OIEN + Channel 1 output immediately enable + 2 + 1 + + + C1C + Channel 1 configure + 0 + 2 + + + + + CM1_INPUT + CM1_INPUT + Channel input mode register 1 + CM1_OUTPUT + 0x18 + 0x20 + read-write + 0x00000000 + + + C2DF + Channel 2 digital filter + 12 + 4 + + + C2IDIV + Channel 2 input divider + 10 + 2 + + + C2C + Channel 2 configure + 8 + 2 + + + C1DF + Channel 1 digital filter + 4 + 4 + + + C1IDIV + Channel 1 input divider + 2 + 2 + + + C1C + Channel 1 configure + 0 + 2 + + + + + CM2_OUTPUT + CM2_OUTPUT + Channel output mode register 2 + 0x1C + 0x20 + read-write + 0x00000000 + + + C4OSEN + Channel 4 output switch enable + 15 + 1 + + + C4OCTRL + Channel 4 output control + 12 + 3 + + + C4OBEN + Channel 4 output buffer enable + 11 + 1 + + + C4OIEN + Channel 4 output immediately enable + 10 + 1 + + + C4C + Channel 4 configure + 8 + 2 + + + C3OSEN + Channel 3 output switch enable + 7 + 1 + + + C3OCTRL + Channel 3 output control + 4 + 3 + + + C3OBEN + Channel 3 output buffer enable + 3 + 1 + + + C3OIEN + Channel 3 output immediately enable + 2 + 1 + + + C3C + Channel 3 configure + 0 + 2 + + + + + CM2_INPUT + CM2_INPUT + Channel input mode register 2 + CM2_OUTPUT + 0x1C + 0x20 + read-write + 0x00000000 + + + C4DF + Channel 4 digital filter + 12 + 4 + + + C4IDIV + Channel 4 input divider + 10 + 2 + + + C4C + Channel 4 configure + 8 + 2 + + + C3DF + Channel 3 digital filter + 4 + 4 + + + C3IDIV + Channel 3 input divider + 2 + 2 + + + C3C + Channel 3 configure + 0 + 2 + + + + + CCTRL + CCTRL + Channel control + register + 0x20 + 0x20 + read-write + 0x0000 + + + C4P + Channel 4 Polarity + 13 + 1 + + + C4EN + Channel 4 enable + 12 + 1 + + + C3CP + Channel 3 complementary polarity + 11 + 1 + + + C3CEN + Channel 3 complementary enable + 10 + 1 + + + C3P + Channel 3 Polarity + 9 + 1 + + + C3EN + Channel 3 enable + 8 + 1 + + + C2CP + Channel 2 complementary polarity + 7 + 1 + + + C2CEN + Channel 2 complementary enable + 6 + 1 + + + C2P + Channel 2 Polarity + 5 + 1 + + + C2EN + Channel 2 enable + 4 + 1 + + + C1CP + Channel 1 complementary polarity + 3 + 1 + + + C1CEN + Channel 1 complementary enable + 2 + 1 + + + C1P + Channel 1 Polarity + 1 + 1 + + + C1EN + Channel 1 enable + 0 + 1 + + + + + CVAL + CVAL + Counter value + 0x24 + 0x20 + read-write + 0x00000000 + + + CVAL + Counter value + 0 + 16 + + + + + DIV + DIV + Divider value + 0x28 + 0x20 + read-write + 0x0000 + + + DIV + Divider value + 0 + 16 + + + + + PR + PR + Period value + 0x2C + 0x20 + read-write + 0x00000000 + + + PR + Period value + 0 + 16 + + + + + RPR + RPR + Repetition of period value + 0x30 + 0x20 + read-write + 0x0000 + + + RPR + Repetition of period value + 0 + 8 + + + + + C1DT + C1DT + Channel 1 data register + 0x34 + 0x20 + read-write + 0x00000000 + + + C1DT + Channel 1 data register + 0 + 16 + + + + + C2DT + C2DT + Channel 2 data register + 0x38 + 0x20 + read-write + 0x00000000 + + + C2DT + Channel 2 data register + 0 + 16 + + + + + C3DT + C3DT + Channel 3 data register + 0x3C + 0x20 + read-write + 0x00000000 + + + C3DT + Channel 3 data register + 0 + 16 + + + + + C4DT + C4DT + Channel 4 data register + 0x40 + 0x20 + read-write + 0x00000000 + + + C4DT + Channel 4 data register + 0 + 16 + + + + + BRK + BRK + Brake register + 0x44 + 0x20 + read-write + 0x0000 + + + OEN + Output enable + 15 + 1 + + + AOEN + Automatic output enable + 14 + 1 + + + BRKV + Brake input validity + 13 + 1 + + + BRKEN + Brake enable + 12 + 1 + + + FCSOEN + Frozen channel status when + holistic output enable + 11 + 1 + + + FCSODIS + Frozen channel status when + holistic output disable + 10 + 1 + + + WPC + Write protected configuration + 8 + 2 + + + DTC + Dead-time configuration + 0 + 8 + + + + + DMACTRL + DMACTRL + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DTB + DMA transfer bytes + 8 + 5 + + + ADDR + DMA transfer address offset + 0 + 5 + + + + + DMADT + DMADT + DMA data register + 0x4C + 0x20 + read-write + 0x0000 + + + DMADT + DMA data register + 0 + 16 + + + + + CM3_OUTPUT + CM3_OUTPUT + Channel output mode register + 0x70 + 0x20 + read-write + 0x00000000 + + + C5OSEN + Channel 5 output switch enable + 7 + 1 + + + C5OCTRL + Channel 5 output control + 4 + 3 + + + C5OBEN + Channel 5 output buffer enable + 3 + 1 + + + C5OIEN + Channel 5 output immediately enable + 2 + 1 + + + + + C5DT + C5DT + Channel 5 data register + 0x74 + 0x20 + read-write + 0x00000000 + + + C5DT + Channel 5 data register + 0 + 16 + + + + + + + TMR8 + 0x40010400 + + TMR8_BRK_TMR12 + TMR8 brake interrupt and TMR12 global + interrupt + 43 + + + TMR8_OVF_TMR13 + TMR8 overflow interrupt and TMR13 global + interrupt + 44 + + + TMR8_TRG_HALL_TMR14 + TMR8 trigger and HALL interrupts and + TMR14 global interrupt + 45 + + + TMR8_CH + TMR8 channel interrupt + 46 + + + + TMR20 + 0x40014C00 + + TMR20_BRK + TMR20 brake interrupt + 104 + + + TMR20_OVF + TMR20 overflow interrupt + 105 + + + TMR20_TRG_HALL + TMR20 trigger and HALL interrupts + 106 + + + TMR20_CH + TMR20 channel interrupt + 107 + + + + TMR2 + General purpose timer + TIMER + 0x40000000 + + 0x0 + 0x400 + registers + + + TMR2 + TMR2 global interrupt + 28 + + + + CTRL1 + CTRL1 + Control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + PMEN + Plus Mode Enable + 10 + 1 + + + CLKDIV + Clock divider + 8 + 2 + + + PRBEN + Period buffer enable + 7 + 1 + + + TWCMSEL + Two-way count mode + selection + 5 + 2 + + + OWCDIR + One-way count direction + 4 + 1 + + + OCMEN + One cycle mode enable + 3 + 1 + + + OVFS + Overflow event source + 2 + 1 + + + OVFEN + Overflow event enable + 1 + 1 + + + TMREN + TMR enable + 0 + 1 + + + + + CTRL2 + CTRL2 + Control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + C1INSEL + C1IN selection + 7 + 1 + + + PTOS + Primary TMR output selection + 4 + 3 + + + DRS + DMA request source + 3 + 1 + + + + + STCTRL + STCTRL + Subordinate TMR control register + 0x8 + 0x20 + read-write + 0x0000 + + + ESP + External signal polarity + 15 + 1 + + + ECMBEN + External clock mode B enable + 14 + 1 + + + ESDIV + External signal divider + 12 + 2 + + + ESF + External signal filter + 8 + 4 + + + STS + Subordinate TMR synchronization + 7 + 1 + + + STIS + Subordinate TMR input selection + 4 + 3 + + + SMSEL + Subordinate TMR mode selection + 0 + 3 + + + + + IDEN + IDEN + Interrupt/DMA enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDEN + Trigger DMA request enable + 14 + 1 + + + C4DEN + Channel 4 DMA request + enable + 12 + 1 + + + C3DEN + Channel 3 DMA request + enable + 11 + 1 + + + C2DEN + Channel 2 DMA request + enable + 10 + 1 + + + C1DEN + Channel 1 DMA request + enable + 9 + 1 + + + OVFDEN + Overflow DMA request enable + 8 + 1 + + + TIEN + Trigger interrupt enable + 6 + 1 + + + C4IEN + Channel 4 interrupt + enable + 4 + 1 + + + C3IEN + Channel 3 interrupt + enable + 3 + 1 + + + C2IEN + Channel 2 interrupt + enable + 2 + 1 + + + C1IEN + Channel 1 interrupt + enable + 1 + 1 + + + OVFIEN + Overflow interrupt enable + 0 + 1 + + + + + ISTS + ISTS + Interrupt status register + 0x10 + 0x20 + read-write + 0x0000 + + + C4RF + Channel 4 recapture flag + 12 + 1 + + + C3RF + Channel 3 recapture flag + 11 + 1 + + + C2RF + Channel 2 recapture flag + 10 + 1 + + + C1RF + Channel 1 recapture flag + 9 + 1 + + + TRGIF + Trigger interrupt flag + 6 + 1 + + + C4IF + Channel 4 interrupt flag + 4 + 1 + + + C3IF + Channel 3 interrupt flag + 3 + 1 + + + C2IF + Channel 2 interrupt flag + 2 + 1 + + + C1IF + Channel 1 interrupt flag + 1 + 1 + + + OVFIF + Overflow interrupt flag + 0 + 1 + + + + + SWEVT + SWEVT + Software event register + 0x14 + 0x20 + read-write + 0x0000 + + + TRGSWTR + Trigger event triggered by software + 6 + 1 + + + C4SWTR + Channel 4 event triggered by software + 4 + 1 + + + C3SWTR + Channel 3 event triggered by software + 3 + 1 + + + C2SWTR + Channel 2 event triggered by software + 2 + 1 + + + C1SWTR + Channel 1 event triggered by software + 1 + 1 + + + OVFSWTR + Overflow event triggered by software + 0 + 1 + + + + + CM1_OUTPUT + CM1_OUTPUT + Channel output mode register + 0x18 + 0x20 + read-write + 0x00000000 + + + C2OSEN + Channel 2 output switch enable + 15 + 1 + + + C2OCTRL + Channel 2 output control + 12 + 3 + + + C2OBEN + Channel 2 output buffer enable + 11 + 1 + + + C2OIEN + Channel 2 output immediately enable + 10 + 1 + + + C2C + Channel 2 configure + 8 + 2 + + + C1OSEN + Channel 1 output switch enable + 7 + 1 + + + C1OCTRL + Channel 1 output control + 4 + 3 + + + C1OBEN + Channel 1 output buffer enable + 3 + 1 + + + C1OIEN + Channel 1 output immediately enable + 2 + 1 + + + C1C + Channel 1 configure + 0 + 2 + + + + + CM1_INPUT + CM1_INPUT + Channel input mode register 1 + CM1_OUTPUT + 0x18 + 0x20 + read-write + 0x00000000 + + + C2DF + Channel 2 digital filter + 12 + 4 + + + C2IDIV + Channel 2 input divider + 10 + 2 + + + C2C + Channel 2 configure + 8 + 2 + + + C1DF + Channel 1 digital filter + 4 + 4 + + + C1IDIV + Channel 1 input divider + 2 + 2 + + + C1C + Channel 1 configure + 0 + 2 + + + + + CM2_OUTPUT + CM2_OUTPUT + Channel output mode register 2 + 0x1C + 0x20 + read-write + 0x00000000 + + + C4OSEN + Channel 4 output switch enable + 15 + 1 + + + C4OCTRL + Channel 4 output control + 12 + 3 + + + C4OBEN + Channel 4 output buffer enable + 11 + 1 + + + C4OIEN + Channel 4 output immediately enable + 10 + 1 + + + C4C + Channel 4 configure + 8 + 2 + + + C3OSEN + Channel 3 output switch enable + 7 + 1 + + + C3OCTRL + Channel 3 output control + 4 + 3 + + + C3OBEN + Channel 3 output buffer enable + 3 + 1 + + + C3OIEN + Channel 3 output immediately enable + 2 + 1 + + + C3C + Channel 3 configure + 0 + 2 + + + + + CM2_INPUT + CM2_INPUT + Channel input mode register 2 + CM2_OUTPUT + 0x1C + 0x20 + read-write + 0x00000000 + + + C4DF + Channel 4 digital filter + 12 + 4 + + + C4IDIV + Channel 4 input divider + 10 + 2 + + + C4C + Channel 4 configure + 8 + 2 + + + C3DF + Channel 3 digital filter + 4 + 4 + + + C3IDIV + Channel 3 input divider + 2 + 2 + + + C3C + Channel 3 configure + 0 + 2 + + + + + CCTRL + CCTRL + Channel control + register + 0x20 + 0x20 + read-write + 0x0000 + + + C4P + Channel 4 Polarity + 13 + 1 + + + C4EN + Channel 4 enable + 12 + 1 + + + C3P + Channel 3 Polarity + 9 + 1 + + + C3EN + Channel 3 enable + 8 + 1 + + + C2P + Channel 2 Polarity + 5 + 1 + + + C2EN + Channel 2 enable + 4 + 1 + + + C1P + Channel 1 Polarity + 1 + 1 + + + C1EN + Channel 1 enable + 0 + 1 + + + + + CVAL + CVAL + Counter value + 0x24 + 0x20 + read-write + 0x00000000 + + + CVAL + Counter value + 0 + 32 + + + + + DIV + DIV + Divider value + 0x28 + 0x20 + read-write + 0x0000 + + + DIV + Divider value + 0 + 16 + + + + + PR + PR + Period value + 0x2C + 0x20 + read-write + 0x00000000 + + + PR + Period value + 0 + 32 + + + + + C1DT + C1DT + Channel 1 data register + 0x34 + 0x20 + read-write + 0x00000000 + + + C1DT + Channel 1 data register + 0 + 32 + + + + + C2DT + C2DT + Channel 2 data register + 0x38 + 0x20 + read-write + 0x00000000 + + + C2DT + Channel 2 data register + 0 + 32 + + + + + C3DT + C3DT + Channel 3 data register + 0x3C + 0x20 + read-write + 0x00000000 + + + C3DT + Channel 3 data register + 0 + 32 + + + + + C4DT + C4DT + Channel 4 data register + 0x40 + 0x20 + read-write + 0x00000000 + + + C4DT + Channel 4 data register + 0 + 32 + + + + + DMACTRL + DMACTRL + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DTB + DMA transfer bytes + 8 + 5 + + + ADDR + DMA transfer address offset + 0 + 5 + + + + + DMADT + DMADT + DMA data register + 0x4C + 0x20 + read-write + 0x0000 + + + DMADT + DMA data register + 0 + 16 + + + + + TMR2_RMP + TMR2_RMP + TMR2 channel input remap register + 0x50 + 0x20 + read-write + 0x0000 + + + TMR2_CH1_IRMP + TMR2 channel 1 input remap + 10 + 2 + + + + + + + TMR3 + General purpose timer + TIMER + 0x40000400 + + 0x0 + 0x400 + registers + + + TMR3 + TMR3 global interrupt + 29 + + + + CTRL1 + CTRL1 + Control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CLKDIV + Clock divider + 8 + 2 + + + PRBEN + Period buffer enable + 7 + 1 + + + TWCMSEL + Two-way count mode + selection + 5 + 2 + + + OWCDIR + One-way count direction + 4 + 1 + + + OCMEN + One cycle mode enable + 3 + 1 + + + OVFS + Overflow event source + 2 + 1 + + + OVFEN + Overflow event enable + 1 + 1 + + + TMREN + TMR enable + 0 + 1 + + + + + CTRL2 + CTRL2 + Control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + C1INSEL + C1IN selection + 7 + 1 + + + PTOS + Primary TMR output selection + 4 + 3 + + + DRS + DMA request source + 3 + 1 + + + + + STCTRL + STCTRL + Subordinate TMR control register + 0x8 + 0x20 + read-write + 0x0000 + + + ESP + External signal polarity + 15 + 1 + + + ECMBEN + External clock mode B enable + 14 + 1 + + + ESDIV + External signal divider + 12 + 2 + + + ESF + External signal filter + 8 + 4 + + + STS + Subordinate TMR synchronization + 7 + 1 + + + STIS + Subordinate TMR input selection + 4 + 3 + + + SMSEL + Subordinate TMR mode selection + 0 + 3 + + + + + IDEN + IDEN + Interrupt/DMA enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDEN + Trigger DMA request enable + 14 + 1 + + + C4DEN + Channel 4 DMA request + enable + 12 + 1 + + + C3DEN + Channel 3 DMA request + enable + 11 + 1 + + + C2DEN + Channel 2 DMA request + enable + 10 + 1 + + + C1DEN + Channel 1 DMA request + enable + 9 + 1 + + + OVFDEN + Overflow DMA request enable + 8 + 1 + + + TIEN + Trigger interrupt enable + 6 + 1 + + + C4IEN + Channel 4 interrupt + enable + 4 + 1 + + + C3IEN + Channel 3 interrupt + enable + 3 + 1 + + + C2IEN + Channel 2 interrupt + enable + 2 + 1 + + + C1IEN + Channel 1 interrupt + enable + 1 + 1 + + + OVFIEN + Overflow interrupt enable + 0 + 1 + + + + + ISTS + ISTS + Interrupt status register + 0x10 + 0x20 + read-write + 0x0000 + + + C4RF + Channel 4 recapture flag + 12 + 1 + + + C3RF + Channel 3 recapture flag + 11 + 1 + + + C2RF + Channel 2 recapture flag + 10 + 1 + + + C1RF + Channel 1 recapture flag + 9 + 1 + + + TRGIF + Trigger interrupt flag + 6 + 1 + + + C4IF + Channel 4 interrupt flag + 4 + 1 + + + C3IF + Channel 3 interrupt flag + 3 + 1 + + + C2IF + Channel 2 interrupt flag + 2 + 1 + + + C1IF + Channel 1 interrupt flag + 1 + 1 + + + OVFIF + Overflow interrupt flag + 0 + 1 + + + + + SWEVT + SWEVT + Software event register + 0x14 + 0x20 + read-write + 0x0000 + + + TRGSWTR + Trigger event triggered by software + 6 + 1 + + + C4SWTR + Channel 4 event triggered by software + 4 + 1 + + + C3SWTR + Channel 3 event triggered by software + 3 + 1 + + + C2SWTR + Channel 2 event triggered by software + 2 + 1 + + + C1SWTR + Channel 1 event triggered by software + 1 + 1 + + + OVFSWTR + Overflow event triggered by software + 0 + 1 + + + + + CM1_OUTPUT + CM1_OUTPUT + Channel output mode register + 0x18 + 0x20 + read-write + 0x00000000 + + + C2OSEN + Channel 2 output switch enable + 15 + 1 + + + C2OCTRL + Channel 2 output control + 12 + 3 + + + C2OBEN + Channel 2 output buffer enable + 11 + 1 + + + C2OIEN + Channel 2 output immediately enable + 10 + 1 + + + C2C + Channel 2 configure + 8 + 2 + + + C1OSEN + Channel 1 output switch enable + 7 + 1 + + + C1OCTRL + Channel 1 output control + 4 + 3 + + + C1OBEN + Channel 1 output buffer enable + 3 + 1 + + + C1OIEN + Channel 1 output immediately enable + 2 + 1 + + + C1C + Channel 1 configure + 0 + 2 + + + + + CM1_INPUT + CM1_INPUT + Channel input mode register 1 + CM1_OUTPUT + 0x18 + 0x20 + read-write + 0x00000000 + + + C2DF + Channel 2 digital filter + 12 + 4 + + + C2IDIV + Channel 2 input divider + 10 + 2 + + + C2C + Channel 2 configure + 8 + 2 + + + C1DF + Channel 1 digital filter + 4 + 4 + + + C1IDIV + Channel 1 input divider + 2 + 2 + + + C1C + Channel 1 configure + 0 + 2 + + + + + CM2_OUTPUT + CM2_OUTPUT + Channel output mode register 2 + 0x1C + 0x20 + read-write + 0x00000000 + + + C4OSEN + Channel 4 output switch enable + 15 + 1 + + + C4OCTRL + Channel 4 output control + 12 + 3 + + + C4OBEN + Channel 4 output buffer enable + 11 + 1 + + + C4OIEN + Channel 4 output immediately enable + 10 + 1 + + + C4C + Channel 4 configure + 8 + 2 + + + C3OSEN + Channel 3 output switch enable + 7 + 1 + + + C3OCTRL + Channel 3 output control + 4 + 3 + + + C3OBEN + Channel 3 output buffer enable + 3 + 1 + + + C3OIEN + Channel 3 output immediately enable + 2 + 1 + + + C3C + Channel 3 configure + 0 + 2 + + + + + CM2_INPUT + CM2_INPUT + Channel input mode register 2 + CM2_OUTPUT + 0x1C + 0x20 + read-write + 0x00000000 + + + C4DF + Channel 4 digital filter + 12 + 4 + + + C4IDIV + Channel 4 input divider + 10 + 2 + + + C4C + Channel 4 configure + 8 + 2 + + + C3DF + Channel 3 digital filter + 4 + 4 + + + C3IDIV + Channel 3 input divider + 2 + 2 + + + C3C + Channel 3 configure + 0 + 2 + + + + + CCTRL + CCTRL + Channel control + register + 0x20 + 0x20 + read-write + 0x0000 + + + C4P + Channel 4 Polarity + 13 + 1 + + + C4EN + Channel 4 enable + 12 + 1 + + + C3P + Channel 3 Polarity + 9 + 1 + + + C3EN + Channel 3 enable + 8 + 1 + + + C2P + Channel 2 Polarity + 5 + 1 + + + C2EN + Channel 2 enable + 4 + 1 + + + C1P + Channel 1 Polarity + 1 + 1 + + + C1EN + Channel 1 enable + 0 + 1 + + + + + CVAL + CVAL + Counter value + 0x24 + 0x20 + read-write + 0x00000000 + + + CVAL + Counter value + 0 + 16 + + + + + DIV + DIV + Divider value + 0x28 + 0x20 + read-write + 0x0000 + + + DIV + Divider value + 0 + 16 + + + + + PR + PR + Period value + 0x2C + 0x20 + read-write + 0x00000000 + + + PR + Period value + 0 + 16 + + + + + C1DT + C1DT + Channel 1 data register + 0x34 + 0x20 + read-write + 0x00000000 + + + C1DT + Channel 1 data register + 0 + 16 + + + + + C2DT + C2DT + Channel 2 data register + 0x38 + 0x20 + read-write + 0x00000000 + + + C2DT + Channel 2 data register + 0 + 16 + + + + + C3DT + C3DT + Channel 3 data register + 0x3C + 0x20 + read-write + 0x00000000 + + + C3DT + Channel 3 data register + 0 + 16 + + + + + C4DT + C4DT + Channel 4 data register + 0x40 + 0x20 + read-write + 0x00000000 + + + C4DT + Channel 4 data register + 0 + 16 + + + + + DMACTRL + DMACTRL + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DTB + DMA transfer bytes + 8 + 5 + + + ADDR + DMA transfer address offset + 0 + 5 + + + + + DMADT + DMADT + DMA data register + 0x4C + 0x20 + read-write + 0x0000 + + + DMADT + DMA data register + 0 + 16 + + + + + + + TMR4 + 0x40000800 + + TMR4 + TMR4 global interrupt + 30 + + + + TMR5 + General purpose timer + TIMER + 0x40000C00 + + 0x0 + 0x400 + registers + + + TMR5 + TMR5 global interrupt + 50 + + + + CTRL1 + CTRL1 + Control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + PMEN + Plus Mode Enable + 10 + 1 + + + CLKDIV + Clock divider + 8 + 2 + + + PRBEN + Period buffer enable + 7 + 1 + + + TWCMSEL + Two-way count mode + selection + 5 + 2 + + + OWCDIR + One-way count direction + 4 + 1 + + + OCMEN + One cycle mode enable + 3 + 1 + + + OVFS + Overflow event source + 2 + 1 + + + OVFEN + Overflow event enable + 1 + 1 + + + TMREN + TMR enable + 0 + 1 + + + + + CTRL2 + CTRL2 + Control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + C1INSEL + C1IN selection + 7 + 1 + + + PTOS + Primary TMR output selection + 4 + 3 + + + DRS + DMA request source + 3 + 1 + + + + + STCTRL + STCTRL + Subordinate TMR control register + 0x8 + 0x20 + read-write + 0x0000 + + + ESP + External signal polarity + 15 + 1 + + + ECMBEN + External clock mode B enable + 14 + 1 + + + ESDIV + External signal divider + 12 + 2 + + + ESF + External signal filter + 8 + 4 + + + STS + Subordinate TMR synchronization + 7 + 1 + + + STIS + Subordinate TMR input selection + 4 + 3 + + + SMSEL + Subordinate TMR mode selection + 0 + 3 + + + + + IDEN + IDEN + Interrupt/DMA enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDEN + Trigger DMA request enable + 14 + 1 + + + C4DEN + Channel 4 DMA request + enable + 12 + 1 + + + C3DEN + Channel 3 DMA request + enable + 11 + 1 + + + C2DEN + Channel 2 DMA request + enable + 10 + 1 + + + C1DEN + Channel 1 DMA request + enable + 9 + 1 + + + OVFDEN + Overflow DMA request enable + 8 + 1 + + + TIEN + Trigger interrupt enable + 6 + 1 + + + C4IEN + Channel 4 interrupt + enable + 4 + 1 + + + C3IEN + Channel 3 interrupt + enable + 3 + 1 + + + C2IEN + Channel 2 interrupt + enable + 2 + 1 + + + C1IEN + Channel 1 interrupt + enable + 1 + 1 + + + OVFIEN + Overflow interrupt enable + 0 + 1 + + + + + ISTS + ISTS + Interrupt status register + 0x10 + 0x20 + read-write + 0x0000 + + + C4RF + Channel 4 recapture flag + 12 + 1 + + + C3RF + Channel 3 recapture flag + 11 + 1 + + + C2RF + Channel 2 recapture flag + 10 + 1 + + + C1RF + Channel 1 recapture flag + 9 + 1 + + + TRGIF + Trigger interrupt flag + 6 + 1 + + + C4IF + Channel 4 interrupt flag + 4 + 1 + + + C3IF + Channel 3 interrupt flag + 3 + 1 + + + C2IF + Channel 2 interrupt flag + 2 + 1 + + + C1IF + Channel 1 interrupt flag + 1 + 1 + + + OVFIF + Overflow interrupt flag + 0 + 1 + + + + + SWEVT + SWEVT + Software event register + 0x14 + 0x20 + read-write + 0x0000 + + + TRGSWTR + Trigger event triggered by software + 6 + 1 + + + C4SWTR + Channel 4 event triggered by software + 4 + 1 + + + C3SWTR + Channel 3 event triggered by software + 3 + 1 + + + C2SWTR + Channel 2 event triggered by software + 2 + 1 + + + C1SWTR + Channel 1 event triggered by software + 1 + 1 + + + OVFSWTR + Overflow event triggered by software + 0 + 1 + + + + + CM1_OUTPUT + CM1_OUTPUT + Channel output mode register + 0x18 + 0x20 + read-write + 0x00000000 + + + C2OSEN + Channel 2 output switch enable + 15 + 1 + + + C2OCTRL + Channel 2 output control + 12 + 3 + + + C2OBEN + Channel 2 output buffer enable + 11 + 1 + + + C2OIEN + Channel 2 output immediately enable + 10 + 1 + + + C2C + Channel 2 configure + 8 + 2 + + + C1OSEN + Channel 1 output switch enable + 7 + 1 + + + C1OCTRL + Channel 1 output control + 4 + 3 + + + C1OBEN + Channel 1 output buffer enable + 3 + 1 + + + C1OIEN + Channel 1 output immediately enable + 2 + 1 + + + C1C + Channel 1 configure + 0 + 2 + + + + + CM1_INPUT + CM1_INPUT + Channel input mode register 1 + CM1_OUTPUT + 0x18 + 0x20 + read-write + 0x00000000 + + + C2DF + Channel 2 digital filter + 12 + 4 + + + C2IDIV + Channel 2 input divider + 10 + 2 + + + C2C + Channel 2 configure + 8 + 2 + + + C1DF + Channel 1 digital filter + 4 + 4 + + + C1IDIV + Channel 1 input divider + 2 + 2 + + + C1C + Channel 1 configure + 0 + 2 + + + + + CM2_OUTPUT + CM2_OUTPUT + Channel output mode register 2 + 0x1C + 0x20 + read-write + 0x00000000 + + + C4OSEN + Channel 4 output switch enable + 15 + 1 + + + C4OCTRL + Channel 4 output control + 12 + 3 + + + C4OBEN + Channel 4 output buffer enable + 11 + 1 + + + C4OIEN + Channel 4 output immediately enable + 10 + 1 + + + C4C + Channel 4 configure + 8 + 2 + + + C3OSEN + Channel 3 output switch enable + 7 + 1 + + + C3OCTRL + Channel 3 output control + 4 + 3 + + + C3OBEN + Channel 3 output buffer enable + 3 + 1 + + + C3OIEN + Channel 3 output immediately enable + 2 + 1 + + + C3C + Channel 3 configure + 0 + 2 + + + + + CM2_INPUT + CM2_INPUT + Channel input mode register 2 + CM2_OUTPUT + 0x1C + 0x20 + read-write + 0x00000000 + + + C4DF + Channel 4 digital filter + 12 + 4 + + + C4IDIV + Channel 4 input divider + 10 + 2 + + + C4C + Channel 4 configure + 8 + 2 + + + C3DF + Channel 3 digital filter + 4 + 4 + + + C3IDIV + Channel 3 input divider + 2 + 2 + + + C3C + Channel 3 configure + 0 + 2 + + + + + CCTRL + CCTRL + Channel control + register + 0x20 + 0x20 + read-write + 0x0000 + + + C4P + Channel 4 Polarity + 13 + 1 + + + C4EN + Channel 4 enable + 12 + 1 + + + C3P + Channel 3 Polarity + 9 + 1 + + + C3EN + Channel 3 enable + 8 + 1 + + + C2P + Channel 2 Polarity + 5 + 1 + + + C2EN + Channel 2 enable + 4 + 1 + + + C1P + Channel 1 Polarity + 1 + 1 + + + C1EN + Channel 1 enable + 0 + 1 + + + + + CVAL + CVAL + Counter value + 0x24 + 0x20 + read-write + 0x00000000 + + + CVAL + Counter value + 0 + 32 + + + + + DIV + DIV + Divider value + 0x28 + 0x20 + read-write + 0x0000 + + + DIV + Divider value + 0 + 16 + + + + + PR + PR + Period value + 0x2C + 0x20 + read-write + 0x00000000 + + + PR + Period value + 0 + 32 + + + + + C1DT + C1DT + Channel 1 data register + 0x34 + 0x20 + read-write + 0x00000000 + + + C1DT + Channel 1 data register + 0 + 32 + + + + + C2DT + C2DT + Channel 2 data register + 0x38 + 0x20 + read-write + 0x00000000 + + + C2DT + Channel 2 data register + 0 + 32 + + + + + C3DT + C3DT + Channel 3 data register + 0x3C + 0x20 + read-write + 0x00000000 + + + C3DT + Channel 3 data register + 0 + 32 + + + + + C4DT + C4DT + Channel 4 data register + 0x40 + 0x20 + read-write + 0x00000000 + + + C4DT + Channel 4 data register + 0 + 32 + + + + + DMACTRL + DMACTRL + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DTB + DMA transfer bytes + 8 + 5 + + + ADDR + DMA transfer address offset + 0 + 5 + + + + + DMADT + DMADT + DMA data register + 0x4C + 0x20 + read-write + 0x0000 + + + DMADT + DMA data register + 0 + 16 + + + + + TMR5_RMP + TMR5_RMP + TMR5 channel input remap register + 0x50 + 0x20 + read-write + 0x0000 + + + TMR5_CH4_IRMP + TMR5 channel 4 input remap + 6 + 2 + + + + + + + TMR9 + General purpose timer + TIMER + 0x40014000 + + 0x0 + 0x400 + registers + + + TMR1_BRK_TMR9 + TMR1 brake interrupt and TMR9 global + interrupt + 24 + + + + CTRL1 + CTRL1 + Control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CLKDIV + Clock divider + 8 + 2 + + + PRBEN + Period buffer enable + 7 + 1 + + + OCMEN + One cycle mode enable + 3 + 1 + + + OVFS + Overflow event source + 2 + 1 + + + OVFEN + Overflow event enable + 1 + 1 + + + TMREN + TMR enable + 0 + 1 + + + + + STCTRL + STCTRL + Subordinate TMR control register + 0x8 + 0x20 + read-write + 0x0000 + + + STIS + Subordinate TMR input selection + 4 + 3 + + + SMSEL + Subordinate TMR mode selection + 0 + 3 + + + + + IDEN + IDEN + Interrupt/DMA enable register + 0xC + 0x20 + read-write + 0x0000 + + + TIEN + Trigger interrupt enable + 6 + 1 + + + C2IEN + Channel 2 interrupt + enable + 2 + 1 + + + C1IEN + Channel 1 interrupt + enable + 1 + 1 + + + OVFIEN + Overflow interrupt enable + 0 + 1 + + + + + ISTS + ISTS + Interrupt status register + 0x10 + 0x20 + read-write + 0x0000 + + + C2RF + Channel 2 recapture flag + 10 + 1 + + + C1RF + Channel 1 recapture flag + 9 + 1 + + + TRGIF + Trigger interrupt flag + 6 + 1 + + + C2IF + Channel 2 interrupt flag + 2 + 1 + + + C1IF + Channel 1 interrupt flag + 1 + 1 + + + OVFIF + Overflow interrupt flag + 0 + 1 + + + + + SWEVT + SWEVT + Software event register + 0x14 + 0x20 + read-write + 0x0000 + + + TRGSWTR + Trigger event triggered by software + 6 + 1 + + + C2SWTR + Channel 2 event triggered by software + 2 + 1 + + + C1SWTR + Channel 1 event triggered by software + 1 + 1 + + + OVFSWTR + Overflow event triggered by software + 0 + 1 + + + + + CM1_OUTPUT + CM1_OUTPUT + Channel output mode register + 0x18 + 0x20 + read-write + 0x00000000 + + + C2OCTRL + Channel 2 output control + 12 + 3 + + + C2OBEN + Channel 2 output buffer enable + 11 + 1 + + + C2OIEN + Channel 2 output immediately enable + 10 + 1 + + + C2C + Channel 2 configure + 8 + 2 + + + C1OCTRL + Channel 1 output control + 4 + 3 + + + C1OBEN + Channel 1 output buffer enable + 3 + 1 + + + C1OIEN + Channel 1 output immediately enable + 2 + 1 + + + C1C + Channel 1 configure + 0 + 2 + + + + + CM1_INPUT + CM1_INPUT + Channel input mode register 1 + CM1_OUTPUT + 0x18 + 0x20 + read-write + 0x00000000 + + + C2DF + Channel 2 digital filter + 12 + 4 + + + C2IDIV + Channel 2 input divider + 10 + 2 + + + C2C + Channel 2 configure + 8 + 2 + + + C1DF + Channel 1 digital filter + 4 + 4 + + + C1IDIV + Channel 1 input divider + 2 + 2 + + + C1C + Channel 1 configure + 0 + 2 + + + + + CCTRL + CCTRL + Channel control + register + 0x20 + 0x20 + read-write + 0x0000 + + + C2CP + Channel 2 complementary polarity + 7 + 1 + + + C2CEN + Channel 2 complementary enable + 6 + 1 + + + C2P + Channel 2 Polarity + 5 + 1 + + + C2EN + Channel 2 enable + 4 + 1 + + + C1CP + Channel 1 complementary polarity + 3 + 1 + + + C1CEN + Channel 1 complementary enable + 2 + 1 + + + C1P + Channel 1 Polarity + 1 + 1 + + + C1EN + Channel 1 enable + 0 + 1 + + + + + CVAL + CVAL + Counter value + 0x24 + 0x20 + read-write + 0x00000000 + + + CVAL + Counter value + 0 + 16 + + + + + DIV + DIV + Divider value + 0x28 + 0x20 + read-write + 0x0000 + + + DIV + Divider value + 0 + 16 + + + + + PR + PR + Period value + 0x2C + 0x20 + read-write + 0x00000000 + + + PR + Period value + 0 + 16 + + + + + C1DT + C1DT + Channel 1 data register + 0x34 + 0x20 + read-write + 0x00000000 + + + C1DT + Channel 1 data register + 0 + 16 + + + + + C2DT + C2DT + Channel 2 data register + 0x38 + 0x20 + read-write + 0x00000000 + + + C2DT + Channel 2 data register + 0 + 16 + + + + + + + TMR12 + 0x40001800 + + TMR8_BRK_TMR12 + TMR8 brake interrupt and TMR12 global + interrupt + 43 + + + + TMR10 + General purpose timer + TIMER + 0x40014400 + + 0x0 + 0x400 + registers + + + TMR1_OVF_TMR10 + TMR1 overflow interrupt and TMR10 global + interrupt + 25 + + + + CTRL1 + CTRL1 + Control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CLKDIV + Clock divider + 8 + 2 + + + PRBEN + Period buffer enable + 7 + 1 + + + OCMEN + One cycle mode enable + 3 + 1 + + + OVFS + Overflow event source + 2 + 1 + + + OVFEN + Overflow event enable + 1 + 1 + + + TMREN + TMR enable + 0 + 1 + + + + + IDEN + IDEN + Interrupt/DMA enable register + 0xC + 0x20 + read-write + 0x0000 + + + C1IEN + Channel 1 interrupt + enable + 1 + 1 + + + OVFIEN + Overflow interrupt enable + 0 + 1 + + + + + ISTS + ISTS + Interrupt status register + 0x10 + 0x20 + read-write + 0x0000 + + + C1RF + Channel 1 recapture flag + 9 + 1 + + + C1IF + Channel 1 interrupt flag + 1 + 1 + + + OVFIF + Overflow interrupt flag + 0 + 1 + + + + + SWEVT + SWEVT + Software event register + 0x14 + 0x20 + read-write + 0x0000 + + + C1SWTR + Channel 1 event triggered by software + 1 + 1 + + + OVFSWTR + Overflow event triggered by software + 0 + 1 + + + + + CM1_OUTPUT + CM1_OUTPUT + Channel output mode register + 0x18 + 0x20 + read-write + 0x00000000 + + + C1OCTRL + Channel 1 output control + 4 + 3 + + + C1OBEN + Channel 1 output buffer enable + 3 + 1 + + + C1OIEN + Channel 1 output immediately enable + 2 + 1 + + + C1C + Channel 1 configure + 0 + 2 + + + + + CM1_INPUT + CM1_INPUT + Channel input mode register 1 + CM1_OUTPUT + 0x18 + 0x20 + read-write + 0x00000000 + + + C1DF + Channel 1 digital filter + 4 + 4 + + + C1IDIV + Channel 1 input divider + 2 + 2 + + + C1C + Channel 1 configure + 0 + 2 + + + + + CCTRL + CCTRL + Channel control + register + 0x20 + 0x20 + read-write + 0x0000 + + + C1CP + Channel 1 complementary polarity + 3 + 1 + + + C1P + Channel 1 Polarity + 1 + 1 + + + C1EN + Channel 1 enable + 0 + 1 + + + + + CVAL + CVAL + Counter value + 0x24 + 0x20 + read-write + 0x00000000 + + + CVAL + Counter value + 0 + 16 + + + + + DIV + DIV + Divider value + 0x28 + 0x20 + read-write + 0x0000 + + + DIV + Divider value + 0 + 16 + + + + + PR + PR + Period value + 0x2C + 0x20 + read-write + 0x00000000 + + + PR + Period value + 0 + 16 + + + + + C1DT + C1DT + Channel 1 data register + 0x34 + 0x20 + read-write + 0x00000000 + + + C1DT + Channel 1 data register + 0 + 16 + + + + + + + TMR11 + 0x40014800 + + TMR1_TRG_HALL_TMR11 + TMR1 trigger and HALL interrupts and + TMR11 global interrupt + 26 + + + + TMR13 + 0x40001C00 + + TMR8_OVF_TMR13 + TMR8 overflow interrupt and TMR13 global + interrupt + 44 + + + + TMR14 + 0x40002000 + + TMR8_TRG_HALL_TMR14 + TMR8 trigger and HALL interrupts and + TMR14 global interrupt + 45 + + + + TMR6 + Basic timer + TIMER + 0x40001000 + + 0x0 + 0x400 + registers + + + TMR6 + TMR6 global interrupt + 54 + + + + CTRL1 + CTRL1 + Control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + PRBEN + Period buffer enable + 7 + 1 + + + OCMEN + One cycle mode enable + 3 + 1 + + + OVFS + Overflow event source + 2 + 1 + + + OVFEN + Overflow event enable + 1 + 1 + + + TMREN + TMR enable + 0 + 1 + + + + + CTRL2 + CTRL2 + Control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + PTOS + Primary TMR output selection + 4 + 3 + + + + + IDEN + IDEN + Interrupt/DMA enable register + 0xC + 0x20 + read-write + 0x0000 + + + OVFDEN + Overflow DMA request enable + 8 + 1 + + + OVFIEN + Overflow interrupt enable + 0 + 1 + + + + + ISTS + ISTS + Interrupt status register + 0x10 + 0x20 + read-write + 0x0000 + + + OVFIF + Overflow interrupt flag + 0 + 1 + + + + + SWEVT + SWEVT + Software event register + 0x14 + 0x20 + read-write + 0x0000 + + + OVFSWTR + Overflow event triggered by software + 0 + 1 + + + + + CVAL + CVAL + Counter value + 0x24 + 0x20 + read-write + 0x00000000 + + + CVAL + Counter value + 0 + 16 + + + + + DIV + DIV + Divider value + 0x28 + 0x20 + read-write + 0x0000 + + + DIV + Divider value + 0 + 16 + + + + + PR + PR + Period value + 0x2C + 0x20 + read-write + 0x00000000 + + + PR + Period value + 0 + 16 + + + + + + + TMR7 + 0x40001400 + + TMR7 + TMR7 global interrupt + 55 + + + + ACC + HSI Auto Clock Calibration + ACC + 0x40017400 + + 0x0 + 0x400 + registers + + + + STS + STS + status register + 0x0 + 0x20 + 0x0000 + + + RSLOST + Reference Signal Lost + read-write + 1 + 1 + + + CALRDY + Internal high-speed clock calibration ready + read-write + 0 + 1 + + + + + CTRL1 + CTRL1 + control register 1 + 0x04 + 0x20 + 0x0100 + + + STEP + STEP + read-write + 8 + 4 + + + CALRDYIEN + CALRDY interrupt enable + read-write + 5 + 1 + + + EIEN + RSLOST error interrupt enable + read-write + 4 + 1 + + + SOFSEL + SOF Select + read-write + 2 + 1 + + + ENTRIM + Enable trim + read-write + 1 + 1 + + + CALON + Calibration on + read-write + 0 + 1 + + + + + CTRL2 + CTRL2 + control register 2 + 0x08 + 0x20 + 0x2080 + + + HICKTWK + Internal high-speed auto clock trimming + read-only + 8 + 6 + + + HICKCAL + Internal high-speed auto clock calibration + read-only + 0 + 8 + + + + + C1 + C1 + compare value 1 + 0x0C + 0x20 + 0x1F2C + + + C1 + Compare 1 + read-write + 0 + 16 + + + + + C2 + C2 + compare value 2 + 0x10 + 0x20 + 0x1F40 + + + C2 + Compare 2 + read-write + 0 + 16 + + + + + C3 + C3 + compare value 3 + 0x14 + 0x20 + 0x1F54 + + + C3 + Compare 3 + read-write + 0 + 16 + + + + + + + I2C1 + Inter-integrated circuit + I2C + 0x40005400 + + 0x0 + 0x400 + registers + + + I2C1_EVT + I2C1 event interrupt + 31 + + + I2C1_ERR + I2C1 error interrupt + 32 + + + + CTRL1 + CTRL1 + Control register 1 + 0x0 + 0x20 + 0x00000000 + + + I2CEN + I2C peripheral enable + 0 + 1 + read-write + + + TDIEN + Transmit data interrupt enable + 1 + 1 + read-write + + + RDIEN + Receive data interrupt enable + 2 + 1 + read-write + + + ADDRIEN + Address match interrupt enable + 3 + 1 + read-write + + + ACKFAILIEN + Acknowledge fail interrupt enable + 4 + 1 + read-write + + + STOPIEN + Stop generation complete interrupt enable + 5 + 1 + read-write + + + TDCIEN + Transfer data complete interrupt enable + 6 + 1 + read-write + + + ERRIEN + Error interrupts enable + 7 + 1 + read-write + + + DFLT + Digital filter value + 8 + 4 + read-write + + + DMATEN + DMA Transmit data request enable + 14 + 1 + read-write + + + DMAREN + DMA receive data request enable + 15 + 1 + read-write + + + SCTRL + Slave receiving data control + 16 + 1 + read-write + + + STRETCH + Clock stretching mode + 17 + 1 + read-write + + + GCAEN + General call address enable + 19 + 1 + read-write + + + HADDREN + SMBus host address enable + 20 + 1 + read-write + + + DEVADDREN + SMBus device default address enable + 21 + 1 + read-write + + + SMBALERT + SMBus alert enable / pin set + 22 + 1 + read-write + + + PECEN + PEC calculation enable + 23 + 1 + read-write + + + + + CTRL2 + CTRL2 + Control register 2 + 0x4 + 0x20 + read-write + 0x00000000 + + + PECTEN + Request PEC transmission enable + 26 + 1 + + + ASTOPEN + Automatically send stop condition enable + 25 + 1 + + + RLDEN + Send data reload mode enable + 24 + 1 + + + CNT + Transmit data counter + 16 + 8 + + + NACKEN + Not acknowledge enable + 15 + 1 + + + GENSTOP + Generate stop condition + 14 + 1 + + + GENSTART + Generate start condition + 13 + 1 + + + READH10 + 10-bit address header read enable + 12 + 1 + + + ADDR10 + Host send 10-bit address mode enable + 11 + 1 + + + DIR + Master data transmission direction + 10 + 1 + + + SADDR + Slave address + 0 + 10 + + + + + OADDR1 + OADDR1 + Own address register 1 + 0x8 + 0x20 + read-write + 0x00000000 + + + ADDR1 + Interface address + 0 + 10 + + + ADDR1MODE + Own Address mode + 10 + 1 + + + ADDR1EN + Own address 1 enable + 15 + 1 + + + + + OADDR2 + OADDR2 + Own address register 2 + 0xC + 0x20 + read-write + 0x00000000 + + + ADDR2 + Own address 2 + 1 + 7 + + + ADDR2MASK + Own address 2-bit mask + 8 + 3 + + + ADDR2EN + Own address 2 enable + 15 + 1 + + + + + CLKCTRL + CLKCTRL + Clock contorl register + 0x10 + 0x20 + read-write + 0x00000000 + + + SCLL + SCL low level + 0 + 8 + + + SCLH + SCL high level + 8 + 8 + + + SDAD + SDA output delay + 16 + 4 + + + SCLD + SCL output delay + 20 + 4 + + + DIVH + High 4 bits of clock divider value + 24 + 4 + + + DIVL + Low 4 bits of clock divider value + 28 + 4 + + + + + TIMEOUT + TIMEOUT + Timeout register + 0x14 + 0x20 + read-write + 0x00000000 + + + TOTIME + Clock timeout detection time + 0 + 12 + + + TOMOED + Clock timeout detection mode + 12 + 1 + + + TOEN + Detect clock low/high timeout enable + 15 + 1 + + + EXTTIME + Cumulative clock low extend timeout value + 16 + 12 + + + EXTEN + Cumulative clock low extend timeout enable + 31 + 1 + + + + + STS + STS + Interrupt and Status register + 0x18 + 0x20 + 0x00000001 + + + ADDR + Slave address matching value + 17 + 7 + read-only + + + SDIR + Slave data transmit direction + 16 + 1 + read-only + + + BUSYF + Bus busy + 15 + 1 + read-only + + + ALERTF + SMBus alert flag + 13 + 1 + read-only + + + TMOUT + SMBus timeout flag + 12 + 1 + read-only + + + PECERR + PEC receive error flag + 11 + 1 + read-only + + + OUF + Overflow or underflow flag + 10 + 1 + read-only + + + ARLOST + Arbitration lost flag + 9 + 1 + read-only + + + BUSERR + Bus error flag + 8 + 1 + read-only + + + TCRLD + Transmission is complete, waiting to load data + 7 + 1 + read-only + + + TDC + Transmit data complete flag + 6 + 1 + read-only + + + STOPF + Stop condition generation complete flag + 5 + 1 + read-only + + + ACKFAIL + Acknowledge failure flag + 4 + 1 + read-only + + + ADDRF + 0~7 bit address match flag + 3 + 1 + read-only + + + RDBF + Receive data buffer full flag + 2 + 1 + read-only + + + TDIS + Send interrupt status + 1 + 1 + read-write + + + TDBE + Transmit data buffer empty flag + 0 + 1 + read-write + + + + + CLR + CLR + Interrupt clear register + 0x1C + 0x20 + write-only + 0x00000000 + + + ALERTC + Clear SMBus alert flag + 13 + 1 + + + TMOUTC + Clear SMBus timeout flag + 12 + 1 + + + PECERRC + Clear PEC receive error flag + 11 + 1 + + + OUFC + Clear overload / underload flag + 10 + 1 + + + ARLOSTC + Clear arbitration lost flag + 9 + 1 + + + BUSERRC + Clear bus error flag + 8 + 1 + + + STOPC + Clear stop condition generation complete flag + 5 + 1 + + + ACKFAILC + Clear acknowledge failure flag + 4 + 1 + + + ADDRC + Clear 0~7 bit address match flag + 3 + 1 + + + + + PEC + PEC + PEC register + 0x20 + 0x20 + read-only + 0x00000000 + + + PECVAL + PEC value + 0 + 8 + + + + + RXDT + RXDT + Receive data register + 0x24 + 0x20 + read-only + 0x00000000 + + + DT + Receive data register + 0 + 8 + + + + + TXDT + TXDT + Transmit data register + 0x28 + 0x20 + read-write + 0x00000000 + + + DT + Transmit data register + 0 + 8 + + + + + + + I2C2 + 0x40005800 + + I2C2_EVT + I2C2 event interrupt + 33 + + + I2C2_ERR + I2C2 error interrupt + 34 + + + + I2C3 + 0x40005C00 + + I2C3_EVT + I2C3 event interrupt + 72 + + + I2C3_ERR + I2C3 error interrupt + 73 + + + + SPI1 + Serial peripheral interface + SPI + 0x40013000 + + 0x0 + 0x400 + registers + + + SPI1 + SPI1 global interrupt + 35 + + + + CTRL1 + CTRL1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + SLBEN + Single line bidirectional half-duplex enable + 15 + 1 + + + SLBTD + Single line bidirectional half-duplex transmission direction + 14 + 1 + + + CCEN + CRC calculation enable + 13 + 1 + + + NTC + Next transmission CRC + 12 + 1 + + + FBN + frame bit num + 11 + 1 + + + ORA + Only receive active + 10 + 1 + + + SWCSEN + Software CS enable + 9 + 1 + + + SWCSIL + Software CS internal level + 8 + 1 + + + LTF + LSB transmit first + 7 + 1 + + + SPIEN + SPI enable + 6 + 1 + + + MDIV2_0 + Master clock frequency division bit2-0 + 3 + 3 + + + MSTEN + Master enable + 2 + 1 + + + CLKPOL + Clock polarity + 1 + 1 + + + CLKPHA + Clock phase + 0 + 1 + + + + + CTRL2 + CTRL2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + MDIV3EN + Master clock frequency3 division enable + 9 + 1 + + + MDIV3 + Master clock frequency division bit3 + 8 + 1 + + + TDBEIE + Transmit data buffer empty interrupt enable + 7 + 1 + + + RDBFIE + Receive data buffer full interrupt enable + 6 + 1 + + + ERRIE + Error interrupt enable + 5 + 1 + + + TIEN + TI mode enable + 4 + 1 + + + HWCSOE + Hardware CS output enable + 2 + 1 + + + DMATEN + DMA transmit enable + 1 + 1 + + + DMAREN + DMA receive enable + 0 + 1 + + + + + STS + STS + status register + 0x8 + 0x20 + 0x0002 + + + CSPAS + CS pulse abnormal setting fiag + 8 + 1 + read-write + + + BF + Busy flag + 7 + 1 + read-only + + + ROERR + Receiver overflow error + 6 + 1 + read-only + + + MMERR + Master mode error + 5 + 1 + read-only + + + CCERR + CRC calculation error + 4 + 1 + read-write + + + TUERR + Transmitter underload error + 3 + 1 + read-only + + + ACS + Audio channel state + 2 + 1 + read-only + + + TDBE + Transmit data buffer empty + 1 + 1 + read-only + + + RDBF + Receive data buffer full + 0 + 1 + read-only + + + + + DT + DT + data register + 0xC + 0x20 + read-write + 0x0000 + + + DT + Data value + 0 + 16 + + + + + CPOLY + CPOLY + CRC polynomial register + 0x10 + 0x20 + read-write + 0x0007 + + + CPOLY + CRC polynomial + 0 + 16 + + + + + RCRC + RCRC + Receive CRC register + 0x14 + 0x20 + read-only + 0x0000 + + + RCRC + Receive CRC + 0 + 16 + + + + + TCRC + TCRC + Transmit CRC register + 0x18 + 0x20 + read-only + 0x0000 + + + TCRC + Transmit CRC + 0 + 16 + + + + + I2SCTRL + I2SCTRL + I2S control register + 0x1C + 0x20 + read-write + 0x0000 + + + I2SMSEL + I2S mode select + 11 + 1 + + + I2SEN + I2S Enable + 10 + 1 + + + OPERSEL + I2S operation select + 8 + 2 + + + PCMFSSEL + PCM frame synchronization select + 7 + 1 + + + STDSEL + I2S standard select + 4 + 2 + + + I2SCLKPOL + I2S clock polarity + 3 + 1 + + + I2SDBN + I2S data bit num + 1 + 2 + + + I2SCBN + I2S channel bit num + 0 + 1 + + + + + I2SCLK + I2SCLK + I2S clock register + 0x20 + 0x20 + read-write + 00000010 + + + I2SDIV9_8 + I2S division bit9 and bit8 + 10 + 2 + + + I2SMCLKOE + I2S master clock output enable + 9 + 1 + + + I2SODD + Odd result for I2S division + 8 + 1 + + + I2SDIV7_0 + I2S division bit7 to bit0 + 0 + 8 + + + + + + + SPI2 + 0x40003800 + + SPI2 + SPI2 global interrupt + 36 + + + + SPI3 + 0x40003C00 + + SPI3 + SPI3 global interrupt + 51 + + + + SPI4 + 0x40013400 + + SPI4 + SPI4 global interrupt + 84 + + + + I2S2_EXT + 0x40017800 + + + I2S3_EXT + 0x40017C00 + + + USART1 + Universal synchronous asynchronous receiver + transmitter + USART + 0x40011000 + + 0x0 + 0x400 + registers + + + USART1 + USART1 global interrupt + 37 + + + + STS + STS + Status register + 0x0 + 0x20 + 0x00C0 + + + CTSCF + CTS change flag + 9 + 1 + read-write + + + BFF + Break frame flag + 8 + 1 + read-write + + + TDBE + Transmit data buffer empty + 7 + 1 + read-only + + + TDC + Transmit data complete + 6 + 1 + read-write + + + RDBF + Receive data buffer full + 5 + 1 + read-write + + + IDLEF + IDLE flag + 4 + 1 + read-only + + + ROERR + Receiver overflow error + 3 + 1 + read-only + + + NERR + Noise error + 2 + 1 + read-only + + + FERR + Framing error + 1 + 1 + read-only + + + PERR + Parity error + 0 + 1 + read-only + + + + + DT + DT + Data register + 0x4 + 0x20 + read-write + 0x00000000 + + + DT + Data value + 0 + 9 + + + + + BAUDR + BAUDR + Baud rate register + 0x8 + 0x20 + read-write + 0x0000 + + + DIV + Division + 0 + 16 + + + + + CTRL1 + CTRL1 + Control register 1 + 0xC + 0x20 + read-write + 0x0000 + + + DBN1 + high bit for Data bit num + 28 + 1 + + + TSDT + transmit start delay time + 21 + 5 + + + TCDT + transmit complete delay time + 16 + 5 + + + UEN + USART enable + 13 + 1 + + + DBN0 + low bit for Data bit num + 12 + 1 + + + WUM + Wake up mode + 11 + 1 + + + PEN + Parity enable + 10 + 1 + + + PSEL + Parity selection + 9 + 1 + + + PERRIEN + PERR interrupt enable + 8 + 1 + + + TDBEIEN + TDBE interrupt enable + 7 + 1 + + + TDCIEN + TDC interrupt enable + 6 + 1 + + + RDBFIEN + RDBF interrupt enable + 5 + 1 + + + IDLEIEN + IDLE interrupt enable + 4 + 1 + + + TEN + Transmitter enable + 3 + 1 + + + REN + Receiver enable + 2 + 1 + + + RM + Receiver mute + 1 + 1 + + + SBF + Send break frame + 0 + 1 + + + + + CTRL2 + CTRL2 + Control register 2 + 0x10 + 0x20 + read-write + 0x0000 + + + ID7_4 + bit 7-4 for usart identification + 28 + 4 + + + TRPSWAP + Transmit receive pin swap + 15 + 1 + + + LINEN + LIN mode enable + 14 + 1 + + + STOPBN + STOP bit num + 12 + 2 + + + CLKEN + Clock enable + 11 + 1 + + + CLKPOL + Clock polarity + 10 + 1 + + + CLKPHA + Clock phase + 9 + 1 + + + LBCP + Last bit clock pulse + 8 + 1 + + + BFIEN + Break frame interrupt enable + 6 + 1 + + + BFBN + Break frame bit num + 5 + 1 + + + IDBN + Identification bit num + 4 + 1 + + + ID3_0 + bit 3-0 for usart identification + 0 + 4 + + + + + CTRL3 + CTRL3 + Control register 3 + 0x14 + 0x20 + read-write + 0x0000 + + + DEP + DE polarity selection + 15 + 1 + + + RS485EN + RS485 enable + 14 + 1 + + + CTSCFIEN + CTSCF interrupt enable + 10 + 1 + + + CTSEN + CTS enable + 9 + 1 + + + RTSEN + RTS enable + 8 + 1 + + + DMATEN + DMA transmitter enable + 7 + 1 + + + DMAREN + DMA receiver enable + 6 + 1 + + + SCMEN + Smartcard mode enable + 5 + 1 + + + SCNACKEN + Smartcard NACK enable + 4 + 1 + + + SLBEN + Single line bidirectional half-duplex enable + 3 + 1 + + + IRDALP + IrDA low-power mode + 2 + 1 + + + IRDAEN + IrDA enable + 1 + 1 + + + ERRIEN + Error interrupt enable + 0 + 1 + + + + + GDIV + GDIV + Guard time and division register + 0x18 + 0x20 + read-write + 0x0000 + + + SCGT + Smart card guard time value + 8 + 8 + + + ISDIV + IrDA/smartcard division value + 0 + 8 + + + + + + + USART2 + 0x40004400 + + USART2 + USART2 global interrupt + 38 + + + + USART3 + 0x40004800 + + USART3 + USART3 global interrupt + 39 + + + + USART6 + 0x40011400 + + USART6 + USART6 global interrupt + 71 + + + + ADC1 + Analog to digital converter + ADC + 0x40012000 + + 0x0 + 0x100 + registers + + + ADC + ADC1 global interrupt + 18 + + + + STS + STS + status register + 0x0 + 0x20 + read-write + 0x00000000 + + + RDY + ADC ready to conversion flag + 6 + 1 + read-only + + + OCCO + Ordinary channel conversion overflow flag + 5 + 1 + + + OCCS + Ordinary channel conversion start flag + 4 + 1 + + + PCCS + Preempted channel conversion start flag + 3 + 1 + + + PCCE + Preempted channels conversion end flag + 2 + 1 + + + OCCE + Ordinary channels conversion end flag + 1 + 1 + + + VMOR + Voltage monitoring out of range flag + 0 + 1 + + + + + CTRL1 + CTRL1 + control register 1 + 0x4 + 0x20 + read-write + 0x00000000 + + + OCCOIEN + Ordinary channel conversion overflow interrupt enable + 26 + 1 + + + CRSEL + Conversion resolution select + 24 + 2 + + + OCVMEN + Voltage monitoring enable on ordinary channels + 23 + 1 + + + PCVMEN + Voltage monitoring enable on preempted channels + 22 + 1 + + + OCPCNT + Partitioned mode conversion count of ordinary channels + 13 + 3 + + + PCPEN + Partitioned mode enable on preempted channels + 12 + 1 + + + OCPEN + Partitioned mode enable on ordinary channels + 11 + 1 + + + PCAUTOEN + Preempted group automatic conversion enable after ordinary group + 10 + 1 + + + VMSGEN + Voltage monitoring enable on a single channel + 9 + 1 + + + SQEN + Sequence mode enable + 8 + 1 + + + PCCEIEN + Conversion end interrupt enable for preempted channels + 7 + 1 + + + VMORIEN + Voltage monitoring out of range interrupt enable + 6 + 1 + + + OCCEIEN + Ordinary channel conversion end interrupt enable + 5 + 1 + + + VMCSEL + Voltage monitoring channel select + 0 + 5 + + + + + CTRL2 + CTRL2 + control register 2 + 0x8 + 0x20 + read-write + 0x00000000 + + + OCTESEL_H + High bit of trigger event select for ordinary channels conversion + 31 + 1 + + + OCSWTRG + Ordinary channel software conversion trigger + 30 + 1 + + + OCETE + Ordinary channel external trigger edge select + 28 + 2 + + + OCTESEL_L + Low bit of trigger event select for ordinary channels conversion + 24 + 4 + + + PCTESEL_H + High bit of trigger event select for preempted channels conversion + 23 + 1 + + + PCSWTRG + Preempted channel software conversion trigger + 22 + 1 + + + PCETE + Preempted channel external trigger edge select + 20 + 2 + + + PCTESEL_L + Low bit of trigger event select for preempted channels conversion + 16 + 4 + + + DTALIGN + Data alignment + 11 + 1 + + + EOCSFEN + Each ordinary channel conversion set OCCE flag enable + 10 + 1 + + + OCDRCEN + Ordinary channel DMA request continuation enable for independent mode + 9 + 1 + + + OCDMAEN + Ordinary channel DMA transfer enable for independent mode + 8 + 1 + + + ADABRT + ADC conversion abort + 4 + 1 + + + ADCALINIT + Initialize A/D calibration + 3 + 1 + + + ADCAL + A/D Calibration + 2 + 1 + + + RPEN + Repeat mode enable + 1 + 1 + + + ADCEN + A/D converter enable + 0 + 1 + + + + + SPT1 + SPT1 + sample time register 1 + 0xC + 0x20 + read-write + 0x00000000 + + + CSPT18 + Selection sample time of channel ADC_IN18 + 24 + 3 + + + CSPT17 + Selection sample time of channel ADC_IN17 + 21 + 3 + + + CSPT16 + Selection sample time of channel ADC_IN16 + 18 + 3 + + + CSPT15 + Selection sample time of channel ADC_IN15 + 15 + 3 + + + CSPT14 + Selection sample time of channel ADC_IN14 + 12 + 3 + + + CSPT13 + Selection sample time of channel ADC_IN13 + 9 + 3 + + + CSPT12 + Selection sample time of channel ADC_IN12 + 6 + 3 + + + CSPT11 + Selection sample time of channel ADC_IN11 + 3 + 3 + + + CSPT10 + Selection sample time of channel ADC_IN10 + 0 + 3 + + + + + SPT2 + SPT2 + sample time register 2 + 0x10 + 0x20 + read-write + 0x00000000 + + + CSPT9 + Selection sample time of channel ADC_IN9 + 27 + 3 + + + CSPT8 + Selection sample time of channel ADC_IN8 + 24 + 3 + + + CSPT7 + Selection sample time of channel ADC_IN7 + 21 + 3 + + + CSPT6 + Selection sample time of channel ADC_IN6 + 18 + 3 + + + CSPT5 + Selection sample time of channel ADC_IN5 + 15 + 3 + + + CSPT4 + Selection sample time of channel ADC_IN4 + 12 + 3 + + + CSPT3 + Selection sample time of channel ADC_IN3 + 9 + 3 + + + CSPT2 + Selection sample time of channel ADC_IN2 + 6 + 3 + + + CSPT1 + Selection sample time of channel ADC_IN1 + 3 + 3 + + + CSPT0 + Selection sample time of channel ADC_IN0 + 0 + 3 + + + + + PCDTO1 + PCDTO1 + Preempted channel 1 data offset register + 0x14 + 0x20 + read-write + 0x00000000 + + + PCDTO1 + Data offset for Preempted channel 1 + 0 + 12 + + + + + PCDTO2 + PCDTO2 + Preempted channel 2 data offset register + 0x18 + 0x20 + read-write + 0x00000000 + + + PCDTO2 + Data offset for Preempted channel 2 + 0 + 12 + + + + + PCDTO3 + PCDTO3 + Preempted channel 3 data offset register + 0x1C + 0x20 + read-write + 0x00000000 + + + PCDTO3 + Data offset for Preempted channel 3 + 0 + 12 + + + + + PCDTO4 + PCDTO4 + Preempted channel 4 data offset register + 0x20 + 0x20 + read-write + 0x00000000 + + + PCDTO4 + Data offset for Preempted channel 4 + 0 + 12 + + + + + VMHB + VMHB + Voltage monitoring high boundary register + 0x24 + 0x20 + read-write + 0x00000FFF + + + VMHB + Voltage monitoring high boundary + 0 + 12 + + + + + VMLB + VMLB + Voltage monitoring low boundary register + 0x28 + 0x20 + read-write + 0x00000000 + + + VMLB + Voltage monitoring low boundary + 0 + 12 + + + + + OSQ1 + OSQ1 + Ordinary sequence register 1 + 0x2C + 0x20 + read-write + 0x00000000 + + + OCLEN + Ordinary conversion sequence length + 20 + 4 + + + OSN16 + Number of 16th conversion in ordinary sequence + 15 + 5 + + + OSN15 + Number of 15th conversion in ordinary sequence + 10 + 5 + + + OSN14 + Number of 14th conversion in ordinary sequence + 5 + 5 + + + OSN13 + Number of 13th conversion in ordinary sequence + 0 + 5 + + + + + OSQ2 + OSQ2 + Ordinary sequence register 2 + 0x30 + 0x20 + read-write + 0x00000000 + + + OSN12 + Number of 12th conversion in ordinary sequence + 25 + 5 + + + OSN11 + Number of 11th conversion in ordinary sequence + 20 + 5 + + + OSN10 + Number of 10th conversion in ordinary sequence + 15 + 5 + + + OSN9 + Number of 8th conversion in ordinary sequence + 10 + 5 + + + OSN8 + Number of 7th conversion in ordinary sequence + 5 + 5 + + + OSN7 + Number of 13th conversion in ordinary sequence + 0 + 5 + + + + + OSQ3 + OSQ3 + Ordinary sequence register 3 + 0x34 + 0x20 + read-write + 0x00000000 + + + OSN6 + Number of 6th conversion in ordinary sequence + 25 + 5 + + + OSN5 + Number of 5th conversion in ordinary sequence + 20 + 5 + + + OSN4 + Number of 4th conversion in ordinary sequence + 15 + 5 + + + OSN3 + number of 3rd conversion in ordinary sequence + 10 + 5 + + + OSN2 + Number of 2nd conversion in ordinary sequence + 5 + 5 + + + OSN1 + Number of 1st conversion in ordinary sequence + 0 + 5 + + + + + PSQ + PSQ + Preempted sequence register + 0x38 + 0x20 + read-write + 0x00000000 + + + PCLEN + Preempted conversion sequence length + 20 + 2 + + + PSN4 + Number of 4th conversion in Preempted sequence + 15 + 5 + + + PSN3 + Number of 3rd conversion in Preempted sequence + 10 + 5 + + + PSN2 + Number of 2nd conversion in Preempted sequence + 5 + 5 + + + PSN1 + Number of 1st conversion in Preempted sequence + 0 + 5 + + + + + PDT1 + PDT1 + Preempted data register 1 + 0x3C + 0x20 + read-only + 0x00000000 + + + PDT1 + Preempted data + 0 + 16 + + + + + PDT2 + PDT2 + Preempted data register 2 + 0x40 + 0x20 + read-only + 0x00000000 + + + PDT2 + Preempted data + 0 + 16 + + + + + PDT3 + PDT3 + Preempted data register 3 + 0x44 + 0x20 + read-only + 0x00000000 + + + PDT3 + Preempted data + 0 + 16 + + + + + PDT4 + PDT4 + Preempted data register 4 + 0x48 + 0x20 + read-only + 0x00000000 + + + PDT4 + Preempted data + 0 + 16 + + + + + ODT + ODT + Ordinary data register + 0x4C + 0x20 + read-only + 0x00000000 + + + ODT + Conversion data of ordinary channel + 0 + 16 + + + + + OVSP + OVSP + oversampling register + 0x80 + 0x20 + read-write + 0x00000000 + + + OOSRSEL + Ordinary oversampling recovery mode select + 10 + 1 + + + OOSTREN + Ordinary oversampling trigger mode enable + 9 + 1 + + + OSSSEL + Oversampling shift select + 5 + 4 + + + OSRSEL + Oversampling ratio select + 2 + 3 + + + POSEN + Preempted oversampling enable + 1 + 1 + + + OOSEN + Ordinary oversampling enable + 0 + 1 + + + + + CALVAL + CALVAL + Calibration value register + 0xB4 + 0x20 + read-write + 0x00000000 + + + CALVAL + A/D Calibration value + 0 + 7 + + + + + + + ADC2 + 0x40012100 + + ADC + ADC2 global interrupts + 18 + + + + ADC3 + 0x40012200 + + ADC + ADC3 global interrupts + 18 + + + + ADCCOM + ADC common area + ADC + 0x40012300 + + 0x0 + 0x100 + registers + + + + CSTS + CSTS + Common status register + 0x0 + 0x20 + read-only + 0x00000000 + + + RDY3 + ADC ready to conversion flag of ADC3 + 22 + 1 + + + OCCO3 + Ordinary channel conversion overflow flag of ADC3 + 21 + 1 + + + OCCS3 + Ordinary channel conversion start flag of ADC3 + 20 + 1 + + + PCCS3 + Preempted channel conversion start flag of ADC3 + 19 + 1 + + + PCCE3 + Preempted channels conversion end flag of ADC3 + 18 + 1 + + + OCCE3 + Ordinary channels conversion end flag of ADC3 + 17 + 1 + + + VMOR3 + Voltage monitoring out of range flag of ADC3 + 16 + 1 + + + RDY2 + ADC ready to conversion flag of ADC2 + 14 + 1 + + + OCCO2 + Ordinary channel conversion overflow flag of ADC2 + 13 + 1 + + + OCCS2 + Ordinary channel conversion start flag of ADC2 + 12 + 1 + + + PCCS2 + Preempted channel conversion start flag of ADC2 + 11 + 1 + + + PCCE2 + Preempted channels conversion end flag of ADC2 + 10 + 1 + + + OCCE2 + Ordinary channels conversion end flag of ADC2 + 9 + 1 + + + VMOR2 + Voltage monitoring out of range flag of ADC2 + 8 + 1 + + + RDY1 + ADC ready to conversion flag of ADC1 + 6 + 1 + + + OCCO1 + Ordinary channel conversion overflow flag of ADC1 + 5 + 1 + + + OCCS1 + Ordinary channel conversion start flag of ADC1 + 4 + 1 + + + PCCS1 + Preempted channel conversion start flag of ADC1 + 3 + 1 + + + PCCE1 + Preempted channels conversion end flag of ADC1 + 2 + 1 + + + OCCE1 + Ordinary channels conversion end flag of ADC1 + 1 + 1 + + + VMOR1 + Voltage monitoring out of range flag of ADC1 + 0 + 1 + + + + + CCTRL + CCTRL + Common control register + 0x4 + 0x20 + read-write + 0x00000000 + + + MSDMASEL_H + High bit of ordinary channel DMA transfer mode select for master slave mode + 28 + 1 + + + ITSRVEN + Internal temperature sensor and VINTRV enable + 23 + 1 + + + VBATEN + VBAT enable + 22 + 1 + + + ADCDIV + ADC division + 16 + 4 + + + MSDMASEL_L + Low bit of ordinary channel DMA transfer mode select for master slave mode + 14 + 2 + + + MSDRCEN + Ordinary channel DMA request continuation enable for master slave mode + 13 + 1 + + + ASISEL + Adjacent ADC sampling interval select for ordinary shifting mode + 8 + 4 + + + MSSEL + Master slave mode select + 0 + 5 + + + + + CODT + CODT + Common Ordinary data register + 0x8 + 0x20 + read-only + 0x00000000 + + + CODTH + Ordinary conversion high halfword data for master slave mode + 16 + 16 + + + CODTL + Ordinary conversion low halfword data for master slave mode + 0 + 16 + + + + + + + CAN1 + Can controller area network + CAN + 0x40006400 + + 0x0 + 0x400 + registers + + + CAN1_TX + CAN1 TX interrupt + 19 + + + CAN1_RX0 + CAN1 RX0 interrupt + 20 + + + CAN_RX1 + CAN1 RX1 interrupt + 21 + + + CAN_SE + CAN1 SE interrupt + 22 + + + + MCTRL + MCTRL + Main control register + 0x0 + 0x20 + read-write + 0x00010002 + + + PTD + Prohibit transmission when debug + 16 + 1 + + + SPRST + Software partial reset + 15 + 1 + + + TTCEN + Time triggered communication mode enable + 7 + 1 + + + AEBOEN + Automatic exit bus-off enable + 6 + 1 + + + AEDEN + Automatic exit doze mode enable + 5 + 1 + + + PRSFEN + Prohibit retransmission when sending fails enable + 4 + 1 + + + MDRSEL + Message discarding rule select when overflow + 3 + 1 + + + MMSSR + Multiple message sending sequence rule + 2 + 1 + + + DZEN + Doze mode enable + 1 + 1 + + + FZEN + Freeze mode enable + 0 + 1 + + + + + MSTS + MSTS + Main status register + 0x4 + 0x20 + 0x00000C02 + + + REALRX + Real time level of RX pin + 11 + 1 + read-only + + + LSAMPRX + Last sample level of RX pin + 10 + 1 + read-only + + + CURS + Currently receiving status + 9 + 1 + read-only + + + CUSS + Currently sending status + 8 + 1 + read-only + + + EDZIF + Enter doze mode interrupt flag + 4 + 1 + read-write + + + QDZIF + Quit doze mode interrupt flag + 3 + 1 + read-write + + + EOIF + Error occur Interrupt flag + 2 + 1 + read-write + + + DZC + Doze mode confirm + 1 + 1 + read-only + + + FZC + Freeze mode confirm + 0 + 1 + read-only + + + + + TSTS + TSTS + Transmit status register + 0x8 + 0x20 + 0x1C000000 + + + TM2LPF + Transmit mailbox 2 lowest priority flag + 31 + 1 + read-only + + + TM1LPF + Transmit mailbox 1 lowest priority flag + 30 + 1 + read-only + + + TM0LPF + Transmit mailbox 0 lowest priority flag + 29 + 1 + read-only + + + TM2EF + Transmit mailbox 2 empty flag + 28 + 1 + read-only + + + TM1EF + Transmit mailbox 1 empty flag + 27 + 1 + read-only + + + TM0EF + Transmit mailbox 0 empty flag + 26 + 1 + read-only + + + TMNR + Transmit Mailbox number record + 24 + 2 + read-only + + + TM2CT + Transmit mailbox 2 cancel transmission + 23 + 1 + read-write + + + TM2TEF + Transmit mailbox 2 transmission error flag + 19 + 1 + read-write + + + TM2ALF + Transmit mailbox 2 arbitration lost flag + 18 + 1 + read-write + + + TM2TSF + Transmit mailbox 2 transmission success flag + 17 + 1 + read-write + + + TM2TCF + transmit mailbox 2 transmission complete flag + 16 + 1 + read-write + + + TM1CT + Transmit mailbox 1 cancel transmission + 15 + 1 + read-write + + + TM1TEF + Transmit mailbox 1 transmission error flag + 11 + 1 + read-write + + + TM1ALF + Transmit mailbox 1 arbitration lost flag + 10 + 1 + read-write + + + TM1TSF + Transmit mailbox 1 transmission success flag + 9 + 1 + read-write + + + TM1TCF + Transmit mailbox 1 transmission complete flag + 8 + 1 + read-write + + + TM0CT + Transmit mailbox 0 cancel transmission + 7 + 1 + read-write + + + TM0TEF + Transmit mailbox 0 transmission error flag + 3 + 1 + read-write + + + TM0ALF + Transmit mailbox 0 arbitration lost flag + 2 + 1 + read-write + + + TM0TSF + Transmit mailbox 0 transmission success flag + 1 + 1 + read-write + + + TM0TCF + Transmit mailbox 0 transmission complete flag + 0 + 1 + read-write + + + + + RF0 + RF0 + Receive FIFO 0 register + 0xC + 0x20 + 0x00000000 + + + RF0R + Receive FIFO 0 release + 5 + 1 + read-write + + + RF0OF + Receive FIFO 0 overflow flag + 4 + 1 + read-write + + + RF0FF + Receive FIFO 0 full flag + 3 + 1 + read-write + + + RF0MN + Receive FIFO 0 message num + 0 + 2 + read-only + + + + + RF1 + RF1 + Receive FIFO 1 register + 0x10 + 0x20 + 0x00000000 + + + RF1R + Receive FIFO 1 release + 5 + 1 + read-write + + + RF1OF + Receive FIFO 1 overflow flag + 4 + 1 + read-write + + + RF1FF + Receive FIFO 1 full flag + 3 + 1 + read-write + + + RF1MN + Receive FIFO 1 message num + 0 + 2 + read-only + + + + + INTEN + INTEN + Interrupt enable register + 0x14 + 0x20 + read-write + 0x00000000 + + + EDZIEN + Enter doze mode interrupt enable + 17 + 1 + + + QDZIEN + Quit doze mode interrupt enable + 16 + 1 + + + EOIEN + Error occur interrupt enable + 15 + 1 + + + ETRIEN + Error type record interrupt enable + 11 + 1 + + + BOIEN + Bus-off interrupt enable + 10 + 1 + + + EPIEN + Error passive interrupt enable + 9 + 1 + + + EAIEN + Error active interrupt enable + 8 + 1 + + + RF1OIEN + Receive FIFO 1 overflow interrupt enable + 6 + 1 + + + RF1FIEN + Receive FIFO 1 full interrupt enable + 5 + 1 + + + RF1MIEN + FIFO 1 receive message interrupt enable + 4 + 1 + + + RF0OIEN + Receive FIFO 0 overflow interrupt enable + 3 + 1 + + + RF0FIEN + Receive FIFO 0 full interrupt enable + 2 + 1 + + + RF0MIEN + FIFO 0 receive message interrupt enable + 1 + 1 + + + TCIEN + Transmission complete interrupt enable + 0 + 1 + + + + + ESTS + ESTS + Error status register + 0x18 + 0x20 + 0x00000000 + + + REC + Receive error counter + 24 + 8 + read-only + + + TEC + Transmit error counter + 16 + 8 + read-only + + + ETR + Error type record + 4 + 3 + read-write + + + BOF + Bus-off flag + 2 + 1 + read-only + + + EPF + Error passive flag + 1 + 1 + read-only + + + EAF + Error active flag + 0 + 1 + read-only + + + + + BTMG + BTMG + Bit timing register + 0x1C + 0x20 + read-write + 0x00000000 + + + LOEN + Listen-Only mode + 31 + 1 + + + LBEN + Loop back mode + 30 + 1 + + + RSAW + Resynchronization adjust width + 24 + 2 + + + BTS2 + Bit time segment 2 + 20 + 3 + + + BTS1 + Bit time segment 1 + 16 + 4 + + + BRDIV + Baud rate division + 0 + 12 + + + + + TMI0 + TMI0 + Transmit mailbox 0 identifier register + 0x180 + 0x20 + read-write + 0x00000000 + + + TMSID + Transmit mailbox standard identifier or extended identifier high bytes + 21 + 11 + + + TMEID + Ttransmit mailbox extended identifier + 3 + 18 + + + TMIDSEL + Transmit mailbox identifier type select + 2 + 1 + + + TMFRSEL + Transmit mailbox frame type select + 1 + 1 + + + TMSR + Transmit mailbox send request + 0 + 1 + + + + + TMC0 + TMC0 + Transmit mailbox 0 data length and time stamp register + 0x184 + 0x20 + read-write + 0x00000000 + + + TMTS + Transmit mailbox time stamp + 16 + 16 + + + TMTSTEN + Transmit mailbox time stamp transmit enable + 8 + 1 + + + TMDTBL + Transmit mailbox data byte length + 0 + 4 + + + + + TMDTL0 + TMDTL0 + Transmit mailbox 0 low byte data register + 0x188 + 0x20 + read-write + 0x00000000 + + + TMDT3 + Transmit mailbox data byte 3 + 24 + 8 + + + TMDT2 + Transmit mailbox data byte 2 + 16 + 8 + + + TMDT1 + Transmit mailbox data byte 1 + 8 + 8 + + + TMDT0 + Transmit mailbox data byte 0 + 0 + 8 + + + + + TMDTH0 + TMDTH0 + Transmit mailbox 0 high byte data register + 0x18C + 0x20 + read-write + 0x00000000 + + + TMDT7 + Transmit mailbox data byte 7 + 24 + 8 + + + TMDT6 + Transmit mailbox data byte 6 + 16 + 8 + + + TMDT5 + Transmit mailbox data byte 5 + 8 + 8 + + + TMDT4 + Transmit mailbox data byte 4 + 0 + 8 + + + + + TMI1 + TMI1 + Transmit mailbox 1 identifier register + 0x190 + 0x20 + read-write + 0x00000000 + + + TMSID + Transmit mailbox standard identifier or extended identifier high bytes + 21 + 11 + + + TMEID + Ttransmit mailbox extended identifier + 3 + 18 + + + TMIDSEL + Transmit mailbox identifier type select + 2 + 1 + + + TMFRSEL + Transmit mailbox frame type select + 1 + 1 + + + TMSR + Transmit mailbox send request + 0 + 1 + + + + + TMC1 + TMC1 + Transmit mailbox 1 data length and time stamp register + 0x194 + 0x20 + read-write + 0x00000000 + + + TMTS + Transmit mailbox time stamp + 16 + 16 + + + TMTSTEN + Transmit mailbox time stamp transmit enable + 8 + 1 + + + TMDTBL + Transmit mailbox data byte length + 0 + 4 + + + + + TMDTL1 + TMDTL1 + Transmit mailbox 1 low byte data register + 0x198 + 0x20 + read-write + 0x00000000 + + + TMDT3 + Transmit mailbox data byte 3 + 24 + 8 + + + TMDT2 + Transmit mailbox data byte 2 + 16 + 8 + + + TMDT1 + Transmit mailbox data byte 1 + 8 + 8 + + + TMDT0 + Transmit mailbox data byte 0 + 0 + 8 + + + + + TMDTH1 + TMDTH1 + Transmit mailbox 1 high byte data register + 0x19C + 0x20 + read-write + 0x00000000 + + + TMDT7 + Transmit mailbox data byte 7 + 24 + 8 + + + TMDT6 + Transmit mailbox data byte 6 + 16 + 8 + + + TMDT5 + Transmit mailbox data byte 5 + 8 + 8 + + + TMDT4 + Transmit mailbox data byte 4 + 0 + 8 + + + + + TMI2 + TMI2 + Transmit mailbox 2 identifier register + 0x1A0 + 0x20 + read-write + 0x00000000 + + + TMSID + Transmit mailbox standard identifier or extended identifier high bytes + 21 + 11 + + + TMEID + Ttransmit mailbox extended identifier + 3 + 18 + + + TMIDSEL + Transmit mailbox identifier type select + 2 + 1 + + + TMFRSEL + Transmit mailbox frame type select + 1 + 1 + + + TMSR + Transmit mailbox send request + 0 + 1 + + + + + TMC2 + TMC2 + Transmit mailbox 2 data length and time stamp register + 0x1A4 + 0x20 + read-write + 0x00000000 + + + TMTS + Transmit mailbox time stamp + 16 + 16 + + + TMTSTEN + Transmit mailbox time stamp transmit enable + 8 + 1 + + + TMDTBL + Transmit mailbox data byte length + 0 + 4 + + + + + TMDTL2 + TMDTL2 + Transmit mailbox 2 low byte data register + 0x1A8 + 0x20 + read-write + 0x00000000 + + + TMDT3 + Transmit mailbox data byte 3 + 24 + 8 + + + TMDT2 + Transmit mailbox data byte 2 + 16 + 8 + + + TMDT1 + Transmit mailbox data byte 1 + 8 + 8 + + + TMDT0 + Transmit mailbox data byte 0 + 0 + 8 + + + + + TMDTH2 + TMDTH2 + Transmit mailbox 2 high byte data register + 0x1AC + 0x20 + read-write + 0x00000000 + + + TMDT7 + Transmit mailbox data byte 7 + 24 + 8 + + + TMDT6 + Transmit mailbox data byte 6 + 16 + 8 + + + TMDT5 + Transmit mailbox data byte 5 + 8 + 8 + + + TMDT4 + Transmit mailbox data byte 4 + 0 + 8 + + + + + RFI0 + RFI0 + Receive FIFO 0 register + 0x1B0 + 0x20 + read-only + 0x00000000 + + + RFSID + Receive FIFO standard identifier or receive FIFO extended identifier + 21 + 11 + + + RFEID + Receive FIFO extended identifier + 3 + 18 + + + RFIDI + Receive FIFO identifier type indication + 2 + 1 + + + RFFRI + Receive FIFO frame type indication + 1 + 1 + + + + + RFC0 + RFC0 + Receive FIFO 0 data length and time stamp register + 0x1B4 + 0x20 + read-only + 0x00000000 + + + RFTS + Receive FIFO time stamp + 16 + 16 + + + RFFMN + Receive FIFO filter match number + 8 + 8 + + + RFDTL + Receive FIFO data length + 0 + 4 + + + + + RFDTL0 + RFDTL0 + Receive FIFO 0 low byte data register + 0x1B8 + 0x20 + read-only + 0x00000000 + + + RFDT3 + Receive FIFO data byte 3 + 24 + 8 + + + RFDT2 + Receive FIFO data byte 2 + 16 + 8 + + + RFDT1 + Receive FIFO data byte 1 + 8 + 8 + + + RFDT0 + Receive FIFO data byte 0 + 0 + 8 + + + + + RFDTH0 + RFDTH0 + Receive FIFO 0 high byte data register + 0x1BC + 0x20 + read-only + 0x00000000 + + + RFDT7 + Receive FIFO data byte 7 + 24 + 8 + + + RFDT6 + Receive FIFO data byte 6 + 16 + 8 + + + RFDT5 + Receive FIFO data byte 5 + 8 + 8 + + + RFDT4 + Receive FIFO data byte 4 + 0 + 8 + + + + + RFI1 + RFI1 + Receive FIFO 1 register + 0x1C0 + 0x20 + read-only + 0x00000000 + + + RFSID + Receive FIFO standard identifier or receive FIFO extended identifier + 21 + 11 + + + RFEID + Receive FIFO extended identifier + 3 + 18 + + + RFIDI + Receive FIFO identifier type indication + 2 + 1 + + + RFFRI + Receive FIFO frame type indication + 1 + 1 + + + + + RFC1 + RFC1 + Receive FIFO 1 data length and time stamp register + 0x1C4 + 0x20 + read-only + 0x00000000 + + + RFTS + Receive FIFO time stamp + 16 + 16 + + + RFFMN + Receive FIFO filter match number + 8 + 8 + + + RFDTL + Receive FIFO data length + 0 + 4 + + + + + RFDTL1 + RFDTL1 + Receive FIFO 1 low byte data register + 0x1C8 + 0x20 + read-only + 0x00000000 + + + RFDT3 + Receive FIFO data byte 3 + 24 + 8 + + + RFDT2 + Receive FIFO data byte 2 + 16 + 8 + + + RFDT1 + Receive FIFO data byte 1 + 8 + 8 + + + RFDT0 + Receive FIFO data byte 0 + 0 + 8 + + + + + RFDTH1 + RFDTH1 + Receive FIFO 1 high byte data register + 0x1CC + 0x20 + read-only + 0x00000000 + + + RFDT7 + Receive FIFO data byte 7 + 24 + 8 + + + RFDT6 + Receive FIFO data byte 6 + 16 + 8 + + + RFDT5 + Receive FIFO data byte 5 + 8 + 8 + + + RFDT4 + Receive FIFO data byte 4 + 0 + 8 + + + + + FCTRL + FCTRL + Filter control register + 0x200 + 0x20 + read-write + 0x00000000 + + + FCS + Filters configure switch + 0 + 1 + + + + + FMCFG + FMCFG + Filter mode config register + 0x204 + 0x20 + read-write + 0x00000000 + + + FMSEL0 + Filter mode select + 0 + 1 + + + FMSEL1 + Filter mode select + 1 + 1 + + + FMSEL2 + Filter mode select + 2 + 1 + + + FMSEL3 + Filter mode select + 3 + 1 + + + FMSEL4 + Filter mode select + 4 + 1 + + + FMSEL5 + Filter mode select + 5 + 1 + + + FMSEL6 + Filter mode select + 6 + 1 + + + FMSEL7 + Filter mode select + 7 + 1 + + + FMSEL8 + Filter mode select + 8 + 1 + + + FMSEL9 + Filter mode select + 9 + 1 + + + FMSEL10 + Filter mode select + 10 + 1 + + + FMSEL11 + Filter mode select + 11 + 1 + + + FMSEL12 + Filter mode select + 12 + 1 + + + FMSEL13 + Filter mode select + 13 + 1 + + + FMSEL14 + Filter mode select + 14 + 1 + + + FMSEL15 + Filter mode select + 15 + 1 + + + FMSEL16 + Filter mode select + 16 + 1 + + + FMSEL17 + Filter mode select + 17 + 1 + + + FMSEL18 + Filter mode select + 18 + 1 + + + FMSEL19 + Filter mode select + 19 + 1 + + + FMSEL20 + Filter mode select + 20 + 1 + + + FMSEL21 + Filter mode select + 21 + 1 + + + FMSEL22 + Filter mode select + 22 + 1 + + + FMSEL23 + Filter mode select + 23 + 1 + + + FMSEL24 + Filter mode select + 24 + 1 + + + FMSEL25 + Filter mode select + 25 + 1 + + + FMSEL26 + Filter mode select + 26 + 1 + + + FMSEL27 + Filter mode select + 27 + 1 + + + + + FBWCFG + FBWCFG + Filter bit width config register + 0x20C + 0x20 + read-write + 0x00000000 + + + FBWSEL0 + Filter bit width select + 0 + 1 + + + FBWSEL1 + Filter bit width select + 1 + 1 + + + FBWSEL2 + Filter bit width select + 2 + 1 + + + FBWSEL3 + Filter bit width select + 3 + 1 + + + FBWSEL4 + Filter bit width select + 4 + 1 + + + FBWSEL5 + Filter bit width select + 5 + 1 + + + FBWSEL6 + Filter bit width select + 6 + 1 + + + FBWSEL7 + Filter bit width select + 7 + 1 + + + FBWSEL8 + Filter bit width select + 8 + 1 + + + FBWSEL9 + Filter bit width select + 9 + 1 + + + FBWSEL10 + Filter bit width select + 10 + 1 + + + FBWSEL11 + Filter bit width select + 11 + 1 + + + FBWSEL12 + Filter bit width select + 12 + 1 + + + FBWSEL13 + Filter bit width select + 13 + 1 + + + FBWSEL14 + Filter bit width select + 14 + 1 + + + FBWSEL15 + Filter bit width select + 15 + 1 + + + FBWSEL16 + Filter bit width select + 16 + 1 + + + FBWSEL17 + Filter bit width select + 17 + 1 + + + FBWSEL18 + Filter bit width select + 18 + 1 + + + FBWSEL19 + Filter bit width select + 19 + 1 + + + FBWSEL20 + Filter bit width select + 20 + 1 + + + FBWSEL21 + Filter bit width select + 21 + 1 + + + FBWSEL22 + Filter bit width select + 22 + 1 + + + FBWSEL23 + Filter bit width select + 23 + 1 + + + FBWSEL24 + Filter bit width select + 24 + 1 + + + FBWSEL25 + Filter bit width select + 25 + 1 + + + FBWSEL26 + Filter bit width select + 26 + 1 + + + FBWSEL27 + Filter bit width select + 27 + 1 + + + + + FRF + FRF + Filter related FIFO register + 0x214 + 0x20 + read-write + 0x00000000 + + + FRFSEL0 + Filter relation FIFO select + 0 + 1 + + + FRFSEL1 + Filter relation FIFO select + 1 + 1 + + + FRFSEL2 + Filter relation FIFO select + 2 + 1 + + + FRFSEL3 + Filter relation FIFO select + 3 + 1 + + + FRFSEL4 + Filter relation FIFO select + 4 + 1 + + + FRFSEL5 + Filter relation FIFO select + 5 + 1 + + + FRFSEL6 + Filter relation FIFO select + 6 + 1 + + + FRFSEL7 + Filter relation FIFO select + 7 + 1 + + + FRFSEL8 + Filter relation FIFO select + 8 + 1 + + + FRFSEL9 + Filter relation FIFO select + 9 + 1 + + + FRFSEL10 + Filter relation FIFO select + 10 + 1 + + + FRFSEL11 + Filter relation FIFO select + 11 + 1 + + + FRFSEL12 + Filter relation FIFO select + 12 + 1 + + + FRFSEL13 + Filter relation FIFO select + 13 + 1 + + + FRFSEL14 + Filter relation FIFO select + 14 + 1 + + + FRFSEL15 + Filter relation FIFO select + 15 + 1 + + + FRFSEL16 + Filter relation FIFO select + 16 + 1 + + FRFSEL17 + Filter relation FIFO select + 17 + 1 + + + FRFSEL18 + Filter relation FIFO select + 18 + 1 + + + FRFSEL19 + Filter relation FIFO select + 19 + 1 + + + FRFSEL20 + Filter relation FIFO select + 20 + 1 + + + FRFSEL21 + Filter relation FIFO select + 21 + 1 + + + FRFSEL22 + Filter relation FIFO select + 22 + 1 + + + FRFSEL23 + Filter relation FIFO select + 23 + 1 + + + FRFSEL24 + Filter relation FIFO select + 24 + 1 + + + FRFSEL25 + Filter relation FIFO select + 25 + 1 + + + FRFSEL26 + Filter relation FIFO select + 26 + 1 + + + FRFSEL27 + Filter relation FIFO select + 27 + 1 + + + + + FACFG + FACFG + Filter activate configuration register + 0x21C + 0x20 + read-write + 0x00000000 + + + FAEN0 + Filter activate enable + 0 + 1 + + + FAEN1 + Filter activate enable + 1 + 1 + + + FAEN2 + Filter activate enable + 2 + 1 + + + FAEN3 + Filter activate enable + 3 + 1 + + + FAEN4 + Filter activate enable + 4 + 1 + + + FAEN5 + Filter activate enable + 5 + 1 + + + FAEN6 + Filter activate enable + 6 + 1 + + + FAEN7 + Filter activate enable + 7 + 1 + + + FAEN8 + Filter activate enable + 8 + 1 + + + FAEN9 + Filter activate enable + 9 + 1 + + + FAEN10 + Filter activate enable + 10 + 1 + + + FAEN11 + Filter activate enable + 11 + 1 + + + FAEN12 + Filter activate enable + 12 + 1 + + + FAEN13 + Filter activate enable + 13 + 1 + + + FAEN14 + Filter activate enable + 14 + 1 + + FAEN15 + Filter activate enable + 15 + 1 + + + FAEN16 + Filter activate enable + 16 + 1 + + + FAEN17 + Filter activate enable + 17 + 1 + + + FAEN18 + Filter activate enable + 18 + 1 + + + FAEN19 + Filter activate enable + 19 + 1 + + + FAEN20 + Filter activate enable + 20 + 1 + + + FAEN21 + Filter activate enable + 21 + 1 + + + FAEN22 + Filter activate enable + 22 + 1 + + + FAEN23 + Filter activate enable + 23 + 1 + + + FAEN24 + Filter activate enable + 24 + 1 + + + FAEN25 + Filter activate enable + 25 + 1 + + + FAEN26 + Filter activate enable + 26 + 1 + + + FAEN27 + Filter activate enable + 27 + 1 + + + + + F0FB1 + F0FB1 + Filter bank 0 filtrate bit register 1 + 0x240 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F0FB2 + F0FB2 + Filter bank 0 filtrate bit register 2 + 0x244 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F1FB1 + F1FB1 + Filter bank 1 filtrate bit register 1 + 0x248 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F1FB2 + F1FB2 + Filter bank 1 filtrate bit register 2 + 0x24C + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F2FB1 + F2FB1 + Filter bank 2 filtrate bit register 1 + 0x250 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F2FB2 + F2FB2 + Filter bank 2 filtrate bit register 2 + 0x254 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F3FB1 + F3FB1 + Filter bank 3 filtrate bit register 1 + 0x258 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F3FB2 + F3FB2 + Filter bank 3 filtrate bit register 2 + 0x25C + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F4FB1 + F4FB1 + Filter bank 4 filtrate bit register 1 + 0x260 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F4FB2 + F4FB2 + Filter bank 4 filtrate bit register 2 + 0x264 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F5FB1 + F5FB1 + Filter bank 5 filtrate bit register 1 + 0x268 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F5FB2 + F5FB2 + Filter bank 5 filtrate bit register 2 + 0x26C + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F6FB1 + F6FB1 + Filter bank 6 filtrate bit register 1 + 0x270 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F6FB2 + F6FB2 + Filter bank 6 filtrate bit register 2 + 0x274 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + + F7FB1 + F7FB1 + Filter bank 7 filtrate bit register 1 + 0x278 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F7FB2 + F7FB2 + Filter bank 7 filtrate bit register 2 + 0x27C + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F8FB1 + F8FB1 + Filter bank 8 filtrate bit register 1 + 0x280 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F8FB2 + F8FB2 + Filter bank 8 filtrate bit register 2 + 0x284 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F9FB1 + F9FB1 + Filter bank 9 filtrate bit register 1 + 0x288 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F9FB2 + F9FB2 + Filter bank 9 filtrate bit register 2 + 0x28C + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F10FB1 + F10FB1 + Filter bank 10 filtrate bit register 1 + 0x290 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F10FB2 + F10FB2 + Filter bank 10 filtrate bit register 2 + 0x294 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F11FB1 + F11FB1 + Filter bank 11 filtrate bit register 1 + 0x298 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F11FB2 + F11FB2 + Filter bank 11 filtrate bit register 2 + 0x29C + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F12FB1 + F12FB1 + Filter bank 12 filtrate bit register 1 + 0x2A0 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F12FB2 + F12FB2 + Filter bank 12 filtrate bit register 2 + 0x2A4 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F13FB1 + F13FB1 + Filter bank 13 filtrate bit register 1 + 0x2A8 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F13FB2 + F13FB2 + Filter bank 13 filtrate bit register 2 + 0x2AC + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F14FB1 + F14FB1 + Filter bank 14 filtrate bit register 1 + 0x2B0 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F14FB2 + F14FB2 + Filter bank 14 filtrate bit register 2 + 0x2B4 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F15FB1 + F15FB1 + Filter bank 15 filtrate bit register 1 + 0x2B8 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F15FB2 + F15FB2 + Filter bank 15 filtrate bit register 2 + 0x2BC + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F16FB1 + F16FB1 + Filter bank 16 filtrate bit register 1 + 0x2C0 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F16FB2 + F16FB2 + Filter bank 16 filtrate bit register 2 + 0x2C4 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F17FB1 + F17FB1 + Filter bank 17 filtrate bit register 1 + 0x2C8 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F17FB2 + F17FB2 + Filter bank 17 filtrate bit register 2 + 0x2CC + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F18FB1 + F18FB1 + Filter bank 18 filtrate bit register 1 + 0x2D0 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F18FB2 + F18FB2 + Filter bank 18 filtrate bit register 2 + 0x2D4 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F19FB1 + F19FB1 + Filter bank 19 filtrate bit register 1 + 0x2D8 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F19FB2 + F19FB2 + Filter bank 19 filtrate bit register 2 + 0x2DC + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F20FB1 + F20FB1 + Filter bank 20 filtrate bit register 1 + 0x2E0 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F20FB2 + F20FB2 + Filter bank 20 filtrate bit register 2 + 0x2E4 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F21FB1 + F21FB1 + Filter bank 21 filtrate bit register 1 + 0x2E8 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F21FB2 + F21FB2 + Filter bank 21 filtrate bit register 2 + 0x2EC + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F22FB1 + F22FB1 + Filter bank 22 filtrate bit register 1 + 0x2F0 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F22FB2 + F22FB2 + Filter bank 22 filtrate bit register 2 + 0x2F4 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F23FB1 + F23FB1 + Filter bank 23 filtrate bit register 1 + 0x2F8 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F23FB2 + F23FB2 + Filter bank 23 filtrate bit register 2 + 0x2FC + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F24FB1 + F24FB1 + Filter bank 24 filtrate bit register 1 + 0x300 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F24FB2 + F24FB2 + Filter bank 24 filtrate bit register 2 + 0x304 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F25FB1 + F25FB1 + Filter bank 25 filtrate bit register 1 + 0x308 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F25FB2 + F25FB2 + Filter bank 25 filtrate bit register 2 + 0x30C + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F26FB1 + F26FB1 + Filter bank 26 filtrate bit register 1 + 0x310 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F26FB2 + F26FB2 + Filter bank 26 filtrate bit register 2 + 0x314 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F27FB1 + F27FB1 + Filter bank 27 filtrate bit register 1 + 0x318 + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + F27FB2 + F27FB2 + Filter bank 27 filtrate bit register 2 + 0x31C + 0x20 + read-write + 0x00000000 + + + FFDB0 + Filter data bit + 0 + 1 + + + FFDB1 + Filter data bit + 1 + 1 + + + FFDB2 + Filter data bit + 2 + 1 + + + FFDB3 + Filter data bit + 3 + 1 + + + FFDB4 + Filter data bit + 4 + 1 + + + FFDB5 + Filter data bit + 5 + 1 + + + FFDB6 + Filter data bit + 6 + 1 + + + FFDB7 + Filter data bit + 7 + 1 + + + FFDB8 + Filter data bit + 8 + 1 + + + FFDB9 + Filter data bit + 9 + 1 + + + FFDB10 + Filter data bit + 10 + 1 + + + FFDB11 + Filter data bit + 11 + 1 + + + FFDB12 + Filter data bit + 12 + 1 + + + FFDB13 + Filter data bit + 13 + 1 + + + FFDB14 + Filter data bit + 14 + 1 + + + FFDB15 + Filter data bit + 15 + 1 + + + FFDB16 + Filter data bit + 16 + 1 + + + FFDB17 + Filter data bit + 17 + 1 + + + FFDB18 + Filter data bit + 18 + 1 + + + FFDB19 + Filter data bit + 19 + 1 + + + FFDB20 + Filter data bit + 20 + 1 + + + FFDB21 + Filter data bit + 21 + 1 + + + FFDB22 + Filter data bit + 22 + 1 + + + FFDB23 + Filter data bit + 23 + 1 + + + FFDB24 + Filter data bit + 24 + 1 + + + FFDB25 + Filter data bit + 25 + 1 + + + FFDB26 + Filter data bit + 26 + 1 + + + FFDB27 + Filter data bit + 27 + 1 + + + FFDB28 + Filter data bit + 28 + 1 + + + FFDB29 + Filter data bit + 29 + 1 + + + FFDB30 + Filter data bit + 30 + 1 + + + FFDB31 + Filter data bit + 31 + 1 + + + + + + + CAN2 + 0x40006800 + + CAN2_TX + CAN2 TX interrupt + 63 + + + CAN2_RX0 + CAN2 RX0 interrupt + 64 + + + CAN2_RX1 + CAN2 RX1 interrupt + 65 + + + CAN2_SE + CAN2 SE interrupt + 66 + + + + DAC + Digital to analog converter + DAC + 0x40007400 + + 0x0 + 0x400 + registers + + + + CTRL + CTRL + Control register (DAC_CTRL) + 0x0 + 0x20 + read-write + 0x00000000 + + + D1EN + DAC1 enable + 0 + 1 + + + D1OBDIS + DAC1 output buffer disable + 1 + 1 + + + D1TRGEN + DAC1 trigger enable + 2 + 1 + + + D1TRGSEL + DAC1 trigger selection + 3 + 3 + + + D1NM + DAC1 noise/triangle wave generation enable + 6 + 2 + + + D1NBSEL + DAC1 mask/amplitude selector + 8 + 4 + + + D1DMAEN + DAC1 DMA enable + 12 + 1 + + + D1DMAUDRIEN + DAC1 DMA underrun interrupt enable + 13 + 1 + + + D2EN + DAC2 enable + 16 + 1 + + + D2OBDIS + DAC2 output buffer disable + 17 + 1 + + + D2TRGEN + DAC2 trigger enable + 18 + 1 + + + D2TRGSEL + DAC2 trigger selection + 19 + 3 + + + D2NM + DAC2 noise/triangle wave generation enable + 22 + 2 + + + D2NBSEL + DAC2 mask/amplitude selector + 24 + 4 + + + D2DMAEN + DAC2 DMA enable + 28 + 1 + + + D2DMAUDRIEN + DAC2 DMA underrun interrupt enable + 29 + 1 + + + + + SWTRG + SWTRG + DAC software trigger register(DAC_SWTRIGR) + 0x4 + 0x20 + write-only + 0x00000000 + + + D1SWTRG + DAC1 software trigger + 0 + 1 + + + D2SWTRG + DAC2 software trigger + 1 + 1 + + + + + D1DTH12R + D1DTH12R + DAC1 12-bit right-aligned data holding register(DAC_D1DTH12R) + 0x8 + 0x20 + read-write + 0x00000000 + + + D1DT12R + DAC1 12-bit right-aligned data + 0 + 12 + + + + + D1DTH12L + D1DTH12L + DAC1 12-bit left aligned data holding register (DAC_D1DTH12L) + 0xC + 0x20 + read-write + 0x00000000 + + + D1DT12L + DAC1 12-bit left-aligned data + 4 + 12 + + + + + D1DTH8R + D1DTH8R + DAC1 8-bit right aligned data holding register (DAC_D1DTH8R) + 0x10 + 0x20 + read-write + 0x00000000 + + + D1DT8R + DAC1 8-bit right-aligned data + 0 + 8 + + + + + D2DTH12R + D2DTH12R + DAC2 12-bit right aligned data holding register (DAC_D2DTH12R) + 0x14 + 0x20 + read-write + 0x00000000 + + + D2DT12R + DAC2 12-bit right-aligned + data + 0 + 12 + + + + + D2DTH12L + D2DTH12L + DAC2 12-bit left aligned data holding register (DAC_D2DTH12L) + 0x18 + 0x20 + read-write + 0x00000000 + + + D2DT12L + DAC2 12-bit left-aligned data + 4 + 12 + + + + + D2DTH8R + D2DTH8R + DAC2 8-bit right-aligned data holding register (DAC_D2DTH8R) + 0x1C + 0x20 + read-write + 0x00000000 + + + D2DT8R + DAC2 8-bit right-aligned + data + 0 + 8 + + + + + DDTH12R + DDTH12R + Dual DAC 12-bit right-aligned data holding register (DAC_DDTH12R), Bits 31:28 Reserved, Bits 15:12 Reserved + 0x20 + 0x20 + read-write + 0x00000000 + + + DD1DT12R + DAC1 12-bit right-aligned data + 0 + 12 + + + DD2DT12R + DAC2 12-bit right-aligned data + 16 + 12 + + + + + DDTH12L + DDTH12L + DUAL DAC 12-bit left aligned data holding register (DAC_DDTH12L), Bits 19:16 Reserved, Bits 3:0 Reserved + 0x24 + 0x20 + read-write + 0x00000000 + + + DD1DT12L + DAC1 12-bit left-aligned data + 4 + 12 + + + DD2DT12L + DAC2 12-bit right-aligned data + 20 + 12 + + + + + DDTH8R + DDTH8R + DUAL DAC 8-bit right aligned data holding register (DAC_DDTH8R), Bits 31:16 Reserved + 0x28 + 0x20 + read-write + 0x00000000 + + + DD1DT8R + DAC1 8-bit right-aligned data + 0 + 8 + + + DD2DT8R + DAC2 8-bit right-aligned data + 8 + 8 + + + + + D1ODT + D1ODT + DAC1 data output register (DAC_D1ODT) + 0x2C + 0x20 + read-only + 0x00000000 + + + D1ODT + DAC1 data output + 0 + 12 + + + + + D2ODT + D2ODT + DAC2 data output register (DAC_D2ODT) + 0x30 + 0x20 + read-only + 0x00000000 + + + D2ODT + DAC2 data output + 0 + 12 + + + + + STS + STS + DAC2 status register + (DAC_STS) + 0x34 + 0x20 + read-write + 0x00000000 + + + DMAUDR1 + DAC1 DMA underrun flag + 13 + 1 + + + DMAUDR2 + DAC2 DMA underrun flag + 29 + 1 + + + + + + + DEBUG + Debug support + DEBUG + 0xE0042000 + + 0x0 + 0x400 + registers + + + + IDCODE + IDCODE + DEBUG IDCODE + 0x0 + 0x20 + read-only + 0x0 + + + PID + Product ID + 0 + 32 + + + + + CTRL + CTRL + DEBUG CTRL + 0x4 + 0x20 + read-write + 0x0 + + + SLEEP_DEBUG + SLEEP_DEBUG + 0 + 1 + + + DEEPSLEEP_DEBUG + DEEPSLEEP_DEBUG + 1 + 1 + + + STANDBY_DEBUG + STANDBY_DEBUG + 2 + 1 + + + + + APB1_PAUSE + APB1_PAUSE + DEBUG APB1 PAUSE + 0x8 + 0x20 + read-write + 0x0 + + + TMR2_PAUSE + TMR2_PAUSE + 0 + 1 + + + TMR3_PAUSE + TMR3_PAUSE + 1 + 1 + + + TMR4_PAUSE + TMR4_PAUSE + 2 + 1 + + + TMR5_PAUSE + TMR5_PAUSE + 3 + 1 + + + TMR6_PAUSE + TMR6_PAUSE + 4 + 1 + + + TMR7_PAUSE + TMR7_PAUSE + 5 + 1 + + + TMR12_PAUSE + TMR12_PAUSE + 6 + 1 + + + TMR13_PAUSE + TMR13_PAUSE + 7 + 1 + + + TMR14_PAUSE + TMR14_PAUSE + 8 + 1 + + + ERTC_PAUSE + ERTC_PAUSE + 10 + 1 + + + WWDT_PAUSE + WWDT_PAUSE + 11 + 1 + + + WDT_PAUSE + WDT_PAUSE + 12 + 1 + + + ERTC512_PAUSE + ERTC512_PAUSE + 15 + 1 + + + I2C1_SMBUS_TIMEOUT + I2C1_SMBUS_TIMEOUT + 24 + 1 + + + CAN1_PAUSE + CAN1_PAUSE + 25 + 1 + + + CAN2_PAUSE + CAN2_PAUSE + 26 + 1 + + + I2C2_SMBUS_TIMEOUT + I2C2_SMBUS_TIMEOUT + 27 + 1 + + + I2C3_SMBUS_TIMEOUT + I2C3_SMBUS_TIMEOUT + 28 + 1 + + + + + APB2_PAUSE + APB2_PAUSE + DEBUG APB2 PAUSE + 0xC + 0x20 + read-write + 0x0 + + + TMR1_PAUSE + TMR1_PAUSE + 0 + 1 + + + TMR8_PAUSE + TMR8_PAUSE + 1 + 1 + + + TMR20_PAUSE + TIM20_PAUSE + 6 + 1 + + + TMR9_PAUSE + TMR9_PAUSE + 16 + 1 + + + TMR10_PAUSE + TMR10_PAUSE + 17 + 1 + + + TMR11_PAUSE + TMR11_PAUSE + 18 + 1 + + + + + SER_ID + SER_ID + SERIES ID + 0x20 + 0x20 + read-only + 0x0 + + + REV_ID + version ID + 0 + 3 + + + SER_ID + series ID + 8 + 8 + + + + + + + UART4 + Universal asynchronous receiver transmitter + 0x40004C00 + + UART4 + UART4 global interrupt + 52 + + + + UART5 + Universal asynchronous receiver transmitter + 0x40005000 + + UART5 + UART5 global interrupt + 53 + + + + UART7 + Universal asynchronous receiver transmitter + 0x40007800 + + UART7 + UART7 global interrupt + 82 + + + + UART8 + Universal asynchronous receiver transmitter + 0x40007C00 + + UART8 + UART8 global interrupt + 83 + + + + CRC + CRC calculation unit + CRC + 0x40023000 + + 0x0 + 0x400 + registers + + + + DT + DT + Data register + 0x0 + 0x20 + read-write + 0xFFFFFFFF + + + DT + Data Register + 0 + 32 + + + + + CDT + CDT + Common data register + 0x4 + 0x20 + read-write + 0x00000000 + + + CDT + Common Data + 0 + 1 + + + + + CTRL + CTRL + Control register + 0x8 + 0x20 + read-write + 0x00000000 + + + RST + Reset bit + 0 + 1 + + + REVID + Reverse input data + 5 + 2 + + + REVOD + Reverse output data + 7 + 1 + + + + + IDT + IDT + Initial data register + 0x10 + 0x20 + read-write + 0xFFFFFFFF + + + IDT + Initial Data + 0 + 32 + + + + + + + FLASH + Flash memory controler + FLASH + 0x40023C00 + + 0x0 + 0x400 + registers + + + FLASH + Flash global interrupt + 4 + + + + PSR + PSR + Performance selection register + 0x0 + 0x20 + 0x00000330 + + + NZW_BST_STS + Flash non-zero wait area boost status + 13 + 1 + read-only + + + NZW_BST + Flash non-zero wait area boost + 12 + 1 + read-write + + + + + UNLOCK + UNLOCK + Unlock register + 0x4 + 0x20 + write-only + 0x00000000 + + + UKVAL + Unlock key value + 0 + 32 + + + + + USD_UNLOCK + USD_UNLOCK + USD unlock register + 0x8 + 0x20 + write-only + 0x00000000 + + + USD_UKVAL + User system data Unlock key value + 0 + 32 + + + + + STS + STS + Status register + 0xC + 0x20 + 0x00000000 + + + ODF + Operate done flag + 5 + 1 + read-write + + + EPPERR + Erase/program protection error + 4 + 1 + read-write + + + PRGMERR + program error + 2 + 1 + read-write + + + OBF + Operate busy flag + 0 + 1 + read-only + + + + + CTRL + CTRL + Control register + 0x10 + 0x20 + read-write + 0x00000080 + + + FPRGM + Flash program + 0 + 1 + + + SECERS + Sector erase + 1 + 1 + + + BANKERS + Bank erase + 2 + 1 + + + BLKERS + Block erase + 3 + 1 + + + USDPRGM + User system data program + 4 + 1 + + + USDERS + User system data erase + 5 + 1 + + + ERSTR + Erasing start + 6 + 1 + + + OPLK + Operation lock + 7 + 1 + + + USDULKS + User system data unlock success + 9 + 1 + + + ERRIE + Error interrupt enable + 10 + 1 + + + ODFIE + Operation done flag interrupt enable + 12 + 1 + + + + + ADDR + ADDR + Address register + 0x14 + 0x20 + write-only + 0x00000000 + + + FA + Flash Address + 0 + 32 + + + + + USD + USD + User system data register + 0x1C + 0x20 + read-only + 0x03FFFFFC + + + USDERR + User system data error + 0 + 1 + + + FAP + FLASH access protection + 1 + 1 + + + nWDT_ATO_EN + WDT auto enable + 2 + 1 + + + nDEPSLP_RST + Deepsleep reset + 3 + 1 + + + nSTDBY_RST + Standby reset + 4 + 1 + + + BTOPT + boot option + 5 + 1 + + + nWDT_DEPSLP + WDT deep sleep + 7 + 1 + + + nWDT_STDBY + WDT standby + 8 + 1 + + + USER_D0 + User data 0 + 10 + 8 + + + USER_D1 + User data 1 + 18 + 8 + + + + + EPPS0 + EPPS0 + Erase/program protection status register 0 + 0x20 + 0x20 + read-only + 0xFFFFFFFF + + + EPPS + Erase/program protection status + 0 + 32 + + + + + EPPS1 + EPPS1 + Erase/program protection status register 1 + 0x2C + 0x20 + read-only + 0xFFFFFFFF + + + EPPS + Erase/program protection status + 0 + 32 + + + + + UNLOCK2 + UNLOCK2 + Unlock 2 register + 0x44 + 0x20 + write-only + 0x00000000 + + + UKVAL + Unlock key value + 0 + 32 + + + + + STS2 + STS2 + Status 2 register + 0x4C + 0x20 + 0x00000000 + + + OBF + Operate busy flag + 0 + 1 + read-only + + + PRGMERR + program error + 2 + 1 + read-write + + + EPPERR + Erase/program protection error + 4 + 1 + read-write + + + ODF + Operate done flag + 5 + 1 + read-write + + + + + CTRL2 + CTRL2 + Control 2 register + 0x50 + 0x20 + read-write + 0x00000080 + + + FPRGM + Flash program + 0 + 1 + + + SECERS + Sector erase + 1 + 1 + + + BANKERS + Bank erase + 2 + 1 + + + BLKERS + Block erase + 3 + 1 + + + ERSTR + Erasing start + 6 + 1 + + + OPLK + Operation lock + 7 + 1 + + + ERRIE + Error interrupt enable + 10 + 1 + + + ODFIE + Operation done flag interrupt enable + 12 + 1 + + + + + ADDR2 + ADDR2 + Address 2 register + 0x54 + 0x20 + write-only + 0x00000000 + + + FA + Flash Address + 0 + 32 + + + + + CONTR + CONTR + Flash continue read register + 0x58 + 0x20 + read-write + 0x00000080 + + + FCONTR_EN + Flash continue read enable + 31 + 1 + + + + + DIVR + DIVR + Flash divider register + 0x60 + 0x20 + 0x00000022 + + + FDIV + Flash divider + 0 + 2 + read-write + + + FDIV_STS + Flash divider status + 4 + 2 + read-only + + + + + SLIB_STS2 + SLIB_STS2 + sLib status 2 register + 0xC8 + 0x20 + 0x0000FFFF + + + SLIB_INST_SS + sLib instruction start sector + 0 + 16 + read-only + + + + + SLIB_STS0 + SLIB_STS0 + sLib status 0 register + 0xCC + 0x20 + 0x00000000 + + + SLIB_ENF + sLib enabled flag + 3 + 1 + read-only + + + + + SLIB_STS1 + SLIB_STS1 + sLib status 1 register + 0xD0 + 0x20 + 0xFFFFFFFF + + + SLIB_SS + sLib start sector + 0 + 16 + read-only + + + SLIB_ES + sLib end sector + 16 + 16 + read-only + + + + + SLIB_PWD_CLR + SLIB_PWD_CLR + SLIB password clear register + 0xD4 + 0x20 + 0x00000000 + write-only + + + SLIB_PCLR_VAL + sLib password clear value + 0 + 32 + + + + + SLIB_MISC_STS + SLIB_MISC_STS + sLib misc status register + 0xD8 + 0x20 + 0x01000000 + + + SLIB_PWD_ERR + sLib password error + 0 + 1 + read-only + + + SLIB_PWD_OK + sLib password ok + 1 + 1 + read-only + + + SLIB_ULKF + sLib unlock flag + 2 + 1 + read-only + + + SLIB_RCNT + sLib remaining count + 16 + 9 + read-only + + + + + SLIB_SET_PWD + SLIB_SET_PWD + sLib password setting register + 0xDC + 0x20 + 0x00000000 + write-only + + + SLIB_PSET_VAL + sLib password setting val + 0 + 32 + + + + + SLIB_SET_RANGE0 + SLIB_SET_RANGE0 + Configure sLib range register 0 + 0xE0 + 0x20 + 0x00000000 + write-only + + + SLIB_SS_SET + sLib start sector setting + 0 + 16 + + + SLIB_ES_SET + sLib end sector setting + 16 + 16 + + + + + SLIB_SET_RANGE1 + SLIB_SET_RANGE1 + Configure sLib range register 1 + 0xE4 + 0x20 + 0x00000000 + write-only + + + SLIB_ISS_SET + sLib instruction start sector setting + 0 + 16 + + + SET_SLIB_STRT + sLib start setting + 31 + 1 + + + + + SLIB_UNLOCK + SLIB_UNLOCK + sLib unlock register + 0xF0 + 0x20 + 0x00000000 + write-only + + + SLIB_UKVAL + sLib unlock key value + 0 + 32 + + + + + CRC_CTRL + CRC_CTRL + CRC controler register + 0xF4 + 0x20 + 0x00000000 + write-only + + + CRC_SS + CRC start sector + 0 + 12 + + + CRC_SN + CRC sector numbler + 12 + 12 + + + CRC_STRT + CRC start + 31 + 1 + + + + + CRC_CHKR + CRC_CHKR + CRC check result register + 0xF8 + 0x20 + 0x00000000 + read-only + + + CRC_CHKR + CRC check result + 0 + 32 + + + + + + + NVIC + Nested Vectored Interrupt + Controller + NVIC + 0xE000E000 + + 0x0 + 0x1001 + registers + + + + ICTR + ICTR + Interrupt Controller Type + Register + 0x4 + 0x20 + read-only + 0x00000000 + + + INTLINESNUM + Total number of interrupt lines in + groups + 0 + 4 + + + + + STIR + STIR + Software Triggered Interrupt + Register + 0xF00 + 0x20 + write-only + 0x00000000 + + + INTID + interrupt to be triggered + 0 + 9 + + + + + ISER0 + ISER0 + Interrupt Set-Enable Register + 0x100 + 0x20 + read-write + 0x00000000 + + + SETENA + SETENA + 0 + 32 + + + + + ISER1 + ISER1 + Interrupt Set-Enable Register + 0x104 + 0x20 + read-write + 0x00000000 + + + SETENA + SETENA + 0 + 32 + + + + + ICER0 + ICER0 + Interrupt Clear-Enable + Register + 0x180 + 0x20 + read-write + 0x00000000 + + + CLRENA + CLRENA + 0 + 32 + + + + + ICER1 + ICER1 + Interrupt Clear-Enable + Register + 0x184 + 0x20 + read-write + 0x00000000 + + + CLRENA + CLRENA + 0 + 32 + + + + + ISPR0 + ISPR0 + Interrupt Set-Pending Register + 0x200 + 0x20 + read-write + 0x00000000 + + + SETPEND + SETPEND + 0 + 32 + + + + + ISPR1 + ISPR1 + Interrupt Set-Pending Register + 0x204 + 0x20 + read-write + 0x00000000 + + + SETPEND + SETPEND + 0 + 32 + + + + + ICPR0 + ICPR0 + Interrupt Clear-Pending + Register + 0x280 + 0x20 + read-write + 0x00000000 + + + CLRPEND + CLRPEND + 0 + 32 + + + + + ICPR1 + ICPR1 + Interrupt Clear-Pending + Register + 0x284 + 0x20 + read-write + 0x00000000 + + + CLRPEND + CLRPEND + 0 + 32 + + + + + IABR0 + IABR0 + Interrupt Active Bit Register + 0x300 + 0x20 + read-only + 0x00000000 + + + ACTIVE + ACTIVE + 0 + 32 + + + + + IABR1 + IABR1 + Interrupt Active Bit Register + 0x304 + 0x20 + read-only + 0x00000000 + + + ACTIVE + ACTIVE + 0 + 32 + + + + + IPR0 + IPR0 + Interrupt Priority Register + 0x400 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR1 + IPR1 + Interrupt Priority Register + 0x404 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR2 + IPR2 + Interrupt Priority Register + 0x408 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR3 + IPR3 + Interrupt Priority Register + 0x40C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR4 + IPR4 + Interrupt Priority Register + 0x410 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR5 + IPR5 + Interrupt Priority Register + 0x414 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR6 + IPR6 + Interrupt Priority Register + 0x418 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR7 + IPR7 + Interrupt Priority Register + 0x41C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR8 + IPR8 + Interrupt Priority Register + 0x420 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR9 + IPR9 + Interrupt Priority Register + 0x424 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR10 + IPR10 + Interrupt Priority Register + 0x428 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR11 + IPR11 + Interrupt Priority Register + 0x42C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR12 + IPR12 + Interrupt Priority Register + 0x430 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR13 + IPR13 + Interrupt Priority Register + 0x434 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR14 + IPR14 + Interrupt Priority Register + 0x438 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + + + DVP + Digital video parallel interface + DVP + 0x50050000 + + 0x0 + 0x400 + registers + + + DVP + DVP global interrupt + 78 + + + + CTRL + CTRL + Control register + 0x0 + 0x20 + 0x0000 + + + LCDS + Line capture/drop selection + 20 + 1 + read-write + + + LCDC + Line capture/drop control + + 19 + 1 + read-write + + + PCDS + Pixel capture/drop selection + + 18 + 1 + read-write + + + PCDC + Basic pixel capture/drop control + + 16 + 2 + read-write + + + ENA + DVP enable + 14 + 1 + read-write + + + PDL + Pixel data length + 10 + 2 + read-write + + + BFRC + Basic frame rate control + 8 + 2 + read-write + + + VSP + Vertical synchronization + polarity + 7 + 1 + read-write + + + HSP + Horizontal synchronization polarity + + 6 + 1 + read-write + + + CKP + Pixel clock polarity + 5 + 1 + read-write + + + SM + synchronization mode + 4 + 1 + read-write + + + JPEG + JPEG format + 3 + 1 + read-write + + + CRP + Cropping function enable + 2 + 1 + read-write + + + CFM + Capture fire mode + 1 + 1 + read-write + + + CAP + Capture function enable + 0 + 1 + read-write + + + + + STS + STS + status register + 0x4 + 0x20 + read-only + 0x0000 + + + OFNE + Output FIFO Non-empty + 2 + 1 + + + VSYN + Vertical synchronization status + 1 + 1 + + + HSYN + Horizontal synchronization status + 0 + 1 + + + + + ESTS + ESTS + Event status register + 0x8 + 0x20 + read-only + 0x0000 + + + HSES + Horizontal synchronization event status + 4 + 1 + + + VSES + Vertical synchronization event status + 3 + 1 + + + ESEES + Embedded synchronization error event status + + 2 + 1 + + + OVRES + Data FIFO overrun event status + + 1 + 1 + + + CFDES + Capture frame done event status + + 0 + 1 + + + + + IENA + IENA + interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + HSIE + Horizontal synchronization interrupt enable + + 4 + 1 + + + VSIE + Vertical synchronization interrupt enablee + + 3 + 1 + + + ESEIE + Embedded synchronization error interrupt + enable + 2 + 1 + + + OVRIE + Data FIFO overrun interrupt enable + + 1 + 1 + + + CFDIE + Capture frame done interrupt enable + + 0 + 1 + + + + + ISTS + ISTS + Interrupt status register + 0x10 + 0x20 + read-only + 0x0000 + + + HSIS + Horizontal synchronization interrupt + status + 4 + 1 + + + VSIS + Vertical synchronization interrupt + status + 3 + 1 + + + ESEIS + Embedded synchronization error + interrupt status + 2 + 1 + + + OVRIS + Data FIFO overrun interrupt + status + 1 + 1 + + + CFDIS + Capture frame done interrupt + status + 0 + 1 + + + + + ICLR + ICLR + Interrupt clear register + 0x14 + 0x20 + write-only + 0x0000 + + + HSIC + Horizontal synchronization + interrupt clear + 4 + 1 + + + VSIC + Vertical synchronization + interrupt clear + 3 + 1 + + + ESEIC + Embedded synchronization + error interrupt clear + 2 + 1 + + + OVRIC + Data FIFO overrun + interrupt clear + 1 + 1 + + + CFDIC + Capture frame done + interrupt clear + 0 + 1 + + + + + SCR + SCR + Synchronization code + register + 0x18 + 0x20 + read-write + 0x0000 + + + FMEC + Frame end code + 24 + 8 + + + LNEC + Line end code + 16 + 8 + + + LNSC + Line start code + 8 + 8 + + + FMSC + Frame start code + 0 + 8 + + + + + SUR + SUR + Synchronization unmask + register + 0x1C + 0x20 + read-write + 0x0000 + + + FMEU + Frame end unmask + 24 + 8 + + + LNEU + Line end unmask + 16 + 8 + + + LNSU + Line start unmask + + 8 + 8 + + + FMSU + Frame start unmask + + 0 + 8 + + + + + CWST + CWST + Crop window start + 0x20 + 0x20 + read-write + 0x0000 + + + CVSTR + Cropping window vertical start line + + 16 + 13 + + + CHSTR + Cropping window horizontal start pixel + + 0 + 14 + + + + + CWSZ + CWSZ + Crop window size + 0x24 + 0x20 + read-write + 0x0000 + + + CVNUM + Cropping window vertical line number + + 16 + 14 + + + CHNUM + Cropping window horizontal pixel number + + 0 + 14 + + + + + DT + DT + Data register + 0x28 + 0x20 + read-only + 0x0000 + + + DT + Data Port + 0 + 32 + + + + + ACTRL + ACTRL + Advanced Control register + + 0x40 + 0x20 + read-write + 0x0000 + + + VSEID + Vertical synchonization event and interrupt + definition + 17 + 1 + + + HSEID + Horizontal synchonization event and interrupt + definition + 16 + 1 + + + DMABT + DMA burst transfer configuration + + 12 + 1 + + + IDUS + Input data un-used setting + + 10 + 1 + + + IDUN + Input data un-used number + + 8 + 2 + + + EFDM + Enhanced function data format management + + 6 + 1 + + + EFDF + Enhanced function data format + + 4 + 2 + + + PCDES + Basic pixel capture/drop extended + selection + 3 + 1 + + + MIBE + Monochrome image binarization + enable + 2 + 1 + + + EFRCE + Enhanced frame rate control + enable + 1 + 1 + + + EISRE + Enhanced image scaling resize + enable + 0 + 1 + + + + + HSCF + HSCF + Horizontal scaling control flow + + 0x48 + 0x20 + read-write + 0x0000 + + + HSRTF + Horizontal scaling resize target factor + + 16 + 13 + + + HSRSF + Horizontal scaling resize source factor + + 0 + 13 + + + + + VSCF + VSCF + Vertical scaling control flow + + 0x4C + 0x20 + read-write + 0x0000 + + + VSRTF + Vertical scaling resize target factor + + 16 + 13 + + + VSRSF + Vertical scaling resize source factor + + 0 + 13 + + + + + FRF + FRF + Frame rate flow + + 0x50 + 0x20 + read-write + 0x0000 + + + EFRCTF + Enhanced frame rate control target factor + + 8 + 5 + + + EFRCSF + Enhanced frame rate contorl source factor + + 0 + 5 + + + + + BTH + BTH + Binarization threshold + + 0x54 + 0x20 + read-write + 0x0000 + + + MIBTHD + Monochrome image binarization threshold + + 0 + 8 + + + + + + + USB_OTG1_GLOBAL + USB on-the-go full speed + USB_OTG1 + 0x50000000 + + 0x0 + 0x400 + registers + + + OTGFS1 + USB On The Go FS global + interrupt + 67 + + + + GOTGCTL + GOTGCTL + OTGFS control and status register + (OTGFS_GOTGCTL) + 0x0 + 0x20 + 0x00000800 + + + CONIDSTS + Connector ID status + 16 + 1 + read-only + + + CURMOD + Current Mode of Operation + 21 + 1 + read-only + + + + + GOTGINT + GOTGINT + OTGFS interrupt register + (OTGFS_GOTGINT) + 0x4 + 0x20 + 0x00000000 + + + SESENDDET + VBUS is deasserted + 2 + 1 + read-write + + + + + GAHBCFG + GAHBCFG + OTGFS AHB configuration register + (OTGFS_GAHBCFG) + 0x8 + 0x20 + read-write + 0x00000000 + + + GLBINTMSK + Global interrupt mask + 0 + 1 + + + NPTXFEMPLVL + Non-Periodic TxFIFO empty level + 7 + 1 + + + PTXFEMPLVL + Periodic TxFIFO empty + level + 8 + 1 + + + + + GUSBCFG + GUSBCFG + USB configuration register + (OTGFS_GUSBCFG) + 0xC + 0x20 + 0x00000A00 + + + TOUTCAL + FS timeout calibration + 0 + 3 + read-write + + + USBTRDTIM + USB turnaround time + 10 + 4 + read-write + + + FHSTMODE + Force host mode + 29 + 1 + read-write + + + FDEVMODE + Force device mode + 30 + 1 + read-write + + + COTXPKT + Corrupt Tx packet + 31 + 1 + read-write + + + + + GRSTCTL + GRSTCTL + OTGFS reset register + (OTGFS_GRSTCTL) + 0x10 + 0x20 + 0x20000000 + + + CSFTRST + Core soft reset + 0 + 1 + read-write + + + PIUSFTRST + PIU FS Dedicated Controller Soft Reset + 1 + 1 + read-write + + + FRMCNTRST + Host frame counter reset + 2 + 1 + read-write + + + RXFFLSH + RxFIFO flush + 4 + 1 + read-write + + + TXFFLSH + TxFIFO flush + 5 + 1 + read-write + + + TXFNUM + TxFIFO number + 6 + 5 + read-write + + + AHBIDLE + AHB master idle + 31 + 1 + read-only + + + + + GINTSTS + GINTSTS + OTGFS core interrupt register + (OTGFS_GINTSTS) + 0x14 + 0x20 + 0x04000020 + + + CURMOD + Current mode of operation + 0 + 1 + read-only + + + MODEMIS + Mode mismatch interrupt + 1 + 1 + read-write + + + OTGINT + OTG interrupt + 2 + 1 + read-only + + + SOF + Start of frame + 3 + 1 + read-write + + + RXFLVL + RxFIFO non-empty + 4 + 1 + read-only + + + NPTXFEMP + Non-periodic TxFIFO empty + 5 + 1 + read-only + + + GINNAKEFF + Global IN non-periodic NAK + effective + 6 + 1 + read-only + + + GOUTNAKEFF + Global OUT NAK effective + 7 + 1 + read-only + + + ERLYSUSP + Early suspend + 10 + 1 + read-write + + + USBSUSP + USB suspend + 11 + 1 + read-write + + + USBRST + USB reset + 12 + 1 + read-write + + + ENUMDONE + Enumeration done + 13 + 1 + read-write + + + ISOOUTDROP + Isochronous OUT packet dropped + interrupt + 14 + 1 + read-write + + + EOPF + End of periodic frame + interrupt + 15 + 1 + read-write + + + IEPTINT + IN endpoint interrupt + 18 + 1 + read-only + + + OEPTINT + OUT endpoint interrupt + 19 + 1 + read-only + + + INCOMPISOIN + Incomplete isochronous IN + transfer + 20 + 1 + read-write + + + INCOMPIP_INCOMPISOOUT + Incomplete periodic transfer(Host + mode)/Incomplete isochronous OUT transfer(Device + mode) + 21 + 1 + read-write + + + PRTINT + Host port interrupt + 24 + 1 + read-only + + + HCHINT + Host channels interrupt + 25 + 1 + read-only + + + PTXFEMP + Periodic TxFIFO empty + 26 + 1 + read-only + + + CONIDSCHG + Connector ID status change + 28 + 1 + read-write + + + DISCONINT + Disconnect detected + interrupt + 29 + 1 + read-write + + + WKUPINT + Resume/remote wakeup detected + interrupt + 31 + 1 + read-write + + + + + GINTMSK + GINTMSK + OTG_FS interrupt mask register + (OTG_FS_GINTMSK) + 0x18 + 0x20 + 0x00000000 + + + MODEMISMSK + Mode mismatch interrupt + mask + 1 + 1 + read-write + + + OTGINTMSK + OTG interrupt mask + 2 + 1 + read-write + + + SOFMSK + Start of frame mask + 3 + 1 + read-write + + + RXFLVLMSK + Receive FIFO non-empty + mask + 4 + 1 + read-write + + + NPTXFEMPMSK + Non-periodic TxFIFO empty + mask + 5 + 1 + read-write + + + GINNAKEFFMSK + Global non-periodic IN NAK effective + mask + 6 + 1 + read-write + + + GOUTNAKEFFMSK + Global OUT NAK effective + mask + 7 + 1 + read-write + + + ERLYSUSPMSK + Early suspend mask + 10 + 1 + read-write + + + USBSUSPMSK + USB suspend mask + 11 + 1 + read-write + + + USBRSTMSK + USB reset mask + 12 + 1 + read-write + + + ENUMDONEMSK + Enumeration done mask + 13 + 1 + read-write + + + ISOOUTDROPMSK + Isochronous OUT packet dropped interrupt + mask + 14 + 1 + read-write + + + EOPFMSK + End of periodic frame interrupt + mask + 15 + 1 + read-write + + + IEPTINTMSK + IN endpoints interrupt + mask + 18 + 1 + read-write + + + OEPTINTMSK + OUT endpoints interrupt + mask + 19 + 1 + read-write + + + INCOMISOINMSK + Incomplete isochronous IN transfer + mask + 20 + 1 + read-write + + + INCOMPIP_INCOMPISOOUTMSK + Incomplete periodic transfer mask(Host + mode)/Incomplete isochronous OUT transfer mask(Device + mode) + 21 + 1 + read-write + + + PRTINTMSK + Host port interrupt mask + 24 + 1 + read-write + + + HCHINTMSK + Host channels interrupt + mask + 25 + 1 + read-write + + + PTXFEMPMSK + Periodic TxFIFO empty mask + 26 + 1 + read-write + + + CONIDSCHGMSK + Connector ID status change + mask + 28 + 1 + read-write + + + DISCONINTMSK + Disconnect detected interrupt + mask + 29 + 1 + read-write + + + WKUPINTMSK + Resume/remote wakeup detected interrupt + mask + 31 + 1 + read-write + + + + + GRXSTSR_Device + GRXSTSR_Device + OTGFS Receive status debug read(Device + mode) + 0x1C + 0x20 + read-only + 0x00000000 + + + EPTNUM + Endpoint number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + FN + Frame number + 21 + 4 + + + + + GRXSTSR_Host + GRXSTSR_Host + OTGFS Receive status debug read(Host + mode) + GRXSTSR_Device + 0x1C + 0x20 + read-only + 0x00000000 + + + CHNUM + Channel number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + + + GRXFSIZ + GRXFSIZ + OTGFS Receive FIFO size register + (OTGFS_GRXFSIZ) + 0x24 + 0x20 + read-write + 0x00000200 + + + RXFDEP + RxFIFO depth + 0 + 16 + + + + + DIEPTXF0 + DIEPTXF0 + IN Endpoint TxFIFO 0 transmit FIFO size + register (Device mode) + 0x28 + 0x20 + read-write + 0x00000200 + + + INEPT0TXSTADDR + Endpoint 0 transmit RAM start + address + 0 + 16 + + + INEPT0TXDEP + Endpoint 0 TxFIFO depth + 16 + 16 + + + + + GNPTXFSIZ + GNPTXFSIZ + OTGFS non-periodic transmit FIFO size + register (Host mode) + DIEPTXF0 + 0x28 + 0x20 + read-write + 0x00000200 + + + NPTXFSTADDR + Non-periodic Transmit RAM Start + address + 0 + 16 + + + NPTXFDEP + Non-periodic TxFIFO depth + 16 + 16 + + + + + GNPTXSTS + GNPTXSTS + OTGFS non-periodic transmit FIFO/queue + status register (OTGFS_GNPTXSTS) + 0x2C + 0x20 + read-only + 0x00080200 + + + NPTXFSPCAVAIL + Non-periodic TxFIFO space + available + 0 + 16 + + + NPTXQSPCAVAIL + Non-periodic transmit request queue + space available + 16 + 8 + + + NPTXQTOP + Top of the non-periodic transmit request + queue + 24 + 7 + + + + + GCCFG + GCCFG + OTGFS general core configuration register + (OTGFS_GCCFG) + 0x38 + 0x20 + read-write + 0x00000000 + + + PWRDOWN + Power down + 16 + 1 + + + LP_MODE + Low power mode + 17 + 1 + + + SOFOUTEN + SOF output enable + 20 + 1 + + + VBUSIG + VBUS Ignored + 21 + 1 + + + + + GUID + GUID + Product ID register + 0x3C + 0x20 + read-write + 0x00001000 + + + USERID + Product ID field + 0 + 32 + + + + + HPTXFSIZ + HPTXFSIZ + OTGFS Host periodic transmit FIFO size + register (OTGFS_HPTXFSIZ) + 0x100 + 0x20 + read-write + 0x02000600 + + + PTXFSTADDR + Host periodic TxFIFO start + address + 0 + 16 + + + PTXFSIZE + Host periodic TxFIFO depth + 16 + 16 + + + + + DIEPTXF1 + DIEPTXF1 + OTGFS device IN endpoint transmit FIFO size + register (OTGFS_DIEPTXF1) + 0x104 + 0x20 + read-write + 0x02000400 + + + INEPTXFSTADDR + IN endpoint FIFO1 transmit RAM start + address + 0 + 16 + + + INEPTXFDEP + IN endpoint TxFIFO depth + 16 + 16 + + + + + DIEPTXF2 + DIEPTXF2 + OTGFS device IN endpoint transmit FIFO size + register (OTGFS_DIEPTXF2) + 0x108 + 0x20 + read-write + 0x02000400 + + + INEPTXFSTADDR + IN endpoint FIFO2 transmit RAM start + address + 0 + 16 + + + INEPTXFDEP + IN endpoint TxFIFO depth + 16 + 16 + + + + + DIEPTXF3 + DIEPTXF3 + OTGFS device IN endpoint transmit FIFO size + register (OTGFS_DIEPTXF3) + 0x10C + 0x20 + read-write + 0x02000400 + + + INEPTXFSTADDR + IN endpoint FIFO3 transmit RAM start + address + 0 + 16 + + + INEPTXFDEP + IN endpoint TxFIFO depth + 16 + 16 + + + + + DIEPTXF4 + DIEPTXF4 + OTGFS device IN endpoint transmit FIFO size + register (OTGFS_DIEPTXF4) + 0x110 + 0x20 + read-write + 0x02000400 + + + INEPTXFSTADDR + IN endpoint FIFO4 transmit RAM start + address + 0 + 16 + + + INEPTXFDEP + IN endpoint TxFIFO depth + 16 + 16 + + + + + DIEPTXF5 + DIEPTXF5 + OTGFS device IN endpoint transmit FIFO size + register (OTGFS_DIEPTXF5) + 0x114 + 0x20 + read-write + 0x02000400 + + + INEPTXFSTADDR + IN endpoint FIFO5 transmit RAM start + address + 0 + 16 + + + INEPTXFDEP + IN endpoint TxFIFO depth + 16 + 16 + + + + + DIEPTXF6 + DIEPTXF6 + OTGFS device IN endpoint transmit FIFO size + register (OTGFS_DIEPTXF6) + 0x118 + 0x20 + read-write + 0x02000400 + + + INEPTXFSTADDR + IN endpoint FIFO6 transmit RAM start + address + 0 + 16 + + + INEPTXFDEP + IN endpoint TxFIFO depth + 16 + 16 + + + + + DIEPTXF7 + DIEPTXF7 + OTGFS device IN endpoint transmit FIFO size + register (OTGFS_DIEPTXF7) + 0x11C + 0x20 + read-write + 0x02000400 + + + INEPTXFSTADDR + IN endpoint FIFO7 transmit RAM start + address + 0 + 16 + + + INEPTXFDEP + IN endpoint TxFIFO depth + 16 + 16 + + + + + + + USB_OTG1_HOST + USB on the go full speed + USB_OTG1 + 0x50000400 + + 0x0 + 0x400 + registers + + + + HCFG + HCFG + OTGFS host configuration register + (OTGFS_HCFG) + 0x0 + 0x20 + 0x00000000 + + + FSLSPCLKSEL + FS/LS PHY clock select + 0 + 2 + read-write + + + FSLSSUPP + FS- and LS-only support + 2 + 1 + read-only + + + + + HFIR + HFIR + OTGFS Host frame interval + register + 0x4 + 0x20 + read-write + 0x0000EA60 + + + FRINT + Frame interval + 0 + 16 + + + + + HFNUM + HFNUM + OTGFS host frame number/frame time + remaining register (OTGFS_HFNUM) + 0x8 + 0x20 + read-only + 0x00003FFF + + + FRNUM + Frame number + 0 + 16 + + + FTREM + Frame time remaining + 16 + 16 + + + + + HPTXSTS + HPTXSTS + OTGFS_Host periodic transmit FIFO/queue + status register (OTGFS_HPTXSTS) + 0x10 + 0x20 + 0x00080100 + + + PTXFSPCAVAIL + Periodic transmit data FIFO space + available + 0 + 16 + read-write + + + PTXQSPCAVAIL + Periodic transmit request queue space + available + 16 + 8 + read-only + + + PTXQTOP + Top of the periodic transmit request + queue + 24 + 8 + read-only + + + + + HAINT + HAINT + OTGFS Host all channels interrupt + register + 0x14 + 0x20 + read-only + 0x00000000 + + + HAINT + Channel interrupts + 0 + 16 + + + + + HAINTMSK + HAINTMSK + OTGFS host all channels interrupt mask + register + 0x18 + 0x20 + read-write + 0x00000000 + + + HAINTMSK + Channel interrupt mask + 0 + 16 + + + + + HPRT + HPRT + OTGFS host port control and status register + (OTGFS_HPRT) + 0x40 + 0x20 + 0x00000000 + + + PRTCONSTS + Port connect status + 0 + 1 + read-only + + + PRTCONDET + Port connect detected + 1 + 1 + read-write + + + PRTENA + Port enable + 2 + 1 + read-write + + + PRTENCHNG + Port enable/disable change + 3 + 1 + read-write + + + PRTOVRCACT + Port overcurrent active + 4 + 1 + read-only + + + PRTOVRCCHNG + Port overcurrent change + 5 + 1 + read-write + + + PRTRES + Port resume + 6 + 1 + read-write + + + PRTSUSP + Port suspend + 7 + 1 + read-write + + + PRTRST + Port reset + 8 + 1 + read-write + + + PRTLNSTS + Port line status + 10 + 2 + read-only + + + PRTPWR + Port power + 12 + 1 + read-write + + + PRTTSTCTL + Port test control + 13 + 4 + read-write + + + PRTSPD + Port speed + 17 + 2 + read-only + + + + + HCCHAR0 + HCCHAR0 + OTGFS host channel-0 characteristics + register (OTGFS_HCCHAR0) + 0x100 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR1 + HCCHAR1 + OTGFS host channel-1 characteristics + register (OTGFS_HCCHAR1) + 0x120 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR2 + HCCHAR2 + OTGFS host channel-2 characteristics + register (OTGFS_HCCHAR2) + 0x140 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR3 + HCCHAR3 + OTGFS host channel-3 characteristics + register (OTGFS_HCCHAR3) + 0x160 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR4 + HCCHAR4 + OTGFS host channel-4 characteristics + register (OTGFS_HCCHAR4) + 0x180 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR5 + HCCHAR5 + OTGFS host channel-5 characteristics + register (OTGFS_HCCHAR5) + 0x1A0 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR6 + HCCHAR6 + OTGFS host channel-6 characteristics + register (OTGFS_HCCHAR6) + 0x1C0 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR7 + HCCHAR7 + OTGFS host channel-7 characteristics + register (OTGFS_HCCHAR7) + 0x1E0 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR8 + HCCHAR8 + OTGFS host channel-8 characteristics + register (OTGFS_HCCHAR8) + 0x200 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR9 + HCCHAR9 + OTGFS host channel-9 characteristics + register (OTGFS_HCCHAR9) + 0x220 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR10 + HCCHAR10 + OTGFS host channel-10 characteristics + register (OTGFS_HCCHAR10) + 0x240 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR11 + HCCHAR11 + OTGFS host channel-7 characteristics + register (OTGFS_HCCHAR11) + 0x260 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR12 + HCCHAR12 + OTGFS host channel-12 characteristics + register (OTGFS_HCCHAR12) + 0x280 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR13 + HCCHAR13 + OTGFS host channel-13 characteristics + register (OTGFS_HCCHAR13) + 0x2A0 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR14 + HCCHAR14 + OTGFS host channel-14 characteristics + register (OTGFS_HCCHAR14) + 0x2C0 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR15 + HCCHAR15 + OTGFS host channel-15 characteristics + register (OTGFS_HCCHAR15) + 0x2E0 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCINT0 + HCINT0 + OTGFS host channel-0 interrupt register + (OTGFS_HCINT0) + 0x108 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT1 + HCINT1 + OTG_FS host channel-1 interrupt register + (OTG_FS_HCINT1) + 0x128 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT2 + HCINT2 + OTGFS host channel-2 interrupt register + (OTGFS_HCINT2) + 0x148 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT3 + HCINT3 + OTGFS host channel-3 interrupt register + (OTGFS_HCINT3) + 0x168 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT4 + HCINT4 + OTGFS host channel-4 interrupt register + (OTGFS_HCINT4) + 0x188 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT5 + HCINT5 + OTGFS host channel-5 interrupt register + (OTGFS_HCINT5) + 0x1A8 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT6 + HCINT6 + OTGFS host channel-6 interrupt register + (OTGFS_HCINT6) + 0x1C8 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT7 + HCINT7 + OTGFS host channel-7 interrupt register + (OTGFS_HCINT7) + 0x1E8 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT8 + HCINT8 + OTGFS host channel-8 interrupt register + (OTGFS_HCINT8) + 0x208 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT9 + HCINT9 + OTGFS host channel-9 interrupt register + (OTGFS_HCINT9) + 0x228 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT10 + HCINT10 + OTGFS host channel-10 interrupt register + (OTGFS_HCINT10) + 0x248 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT11 + HCINT11 + OTGFS host channel-11 interrupt register + (OTGFS_HCINT11) + 0x268 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT12 + HCINT12 + OTGFS host channel-12 interrupt register + (OTGFS_HCINT12) + 0x288 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT13 + HCINT13 + OTGFS host channel-13 interrupt register + (OTGFS_HCINT13) + 0x2A8 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT14 + HCINT14 + OTGFS host channel-14 interrupt register + (OTGFS_HCINT14) + 0x2C8 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT15 + HCINT15 + OTGFS host channel-15 interrupt register + (OTGFS_HCINT15) + 0x2E8 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINTMSK0 + HCINTMSK0 + OTGFS host channel-0 mask register + (OTGFS_HCINTMSK0) + 0x10C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK1 + HCINTMSK1 + OTGFS host channel-1 mask register + (OTGFS_HCINTMSK1) + 0x12C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK2 + HCINTMSK2 + OTGFS host channel-2 mask register + (OTGFS_HCINTMSK2) + 0x14C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK3 + HCINTMSK3 + OTGFS host channel-3 mask register + (OTGFS_HCINTMSK3) + 0x16C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK4 + HCINTMSK4 + OTGFS host channel-4 mask register + (OTGFS_HCINTMSK4) + 0x18C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK5 + HCINTMSK5 + OTGFS host channel-5 mask register + (OTGFS_HCINTMSK5) + 0x1AC + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK6 + HCINTMSK6 + OTGFS host channel-6 mask register + (OTGFS_HCINTMSK6) + 0x1CC + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK7 + HCINTMSK7 + OTGFS host channel-7 mask register + (OTGFS_HCINTMSK7) + 0x1EC + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK8 + HCINTMSK8 + OTGFS host channel-8 mask register + (OTGFS_HCINTMSK8) + 0x20C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK9 + HCINTMSK9 + OTGFS host channel-9 mask register + (OTGFS_HCINTMSK9) + 0x22C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK10 + HCINTMSK10 + OTGFS host channel-10 mask register + (OTGFS_HCINTMSK10) + 0x24C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK11 + HCINTMSK11 + OTGFS host channel-11 mask register + (OTGFS_HCINTMSK11) + 0x26C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK12 + HCINTMSK12 + OTGFS host channel-12 mask register + (OTGFS_HCINTMSK12) + 0x28C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK13 + HCINTMSK13 + OTGFS host channel-13 mask register + (OTGFS_HCINTMSK13) + 0x2AC + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK14 + HCINTMSK14 + OTGFS host channel-14 mask register + (OTGFS_HCINTMSK14) + 0x2CC + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK15 + HCINTMSK15 + OTGFS host channel-15 mask register + (OTGFS_HCINTMSK15) + 0x2EC + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCTSIZ0 + HCTSIZ0 + OTGFS host channel-0 transfer size + register + 0x110 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ1 + HCTSIZ1 + OTGFS host channel-1 transfer size + register + 0x130 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ2 + HCTSIZ2 + OTGFS host channel-2 transfer size + register + 0x150 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ3 + HCTSIZ3 + OTGFS host channel-3 transfer size + register + 0x170 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ4 + HCTSIZ4 + OTGFS host channel-4 transfer size + register + 0x190 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ5 + HCTSIZ5 + OTGFS host channel-5 transfer size + register + 0x1B0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ6 + HCTSIZ6 + OTGFS host channel-6 transfer size + register + 0x1D0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ7 + HCTSIZ7 + OTGFS host channel-7 transfer size + register + 0x1F0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ8 + HCTSIZ8 + OTGFS host channel-8 transfer size + register + 0x210 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ9 + HCTSIZ9 + OTGFS host channel-9 transfer size + register + 0x230 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ10 + HCTSIZ10 + OTGFS host channel-10 transfer size + register + 0x250 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ11 + HCTSIZ11 + OTGFS host channel-11 transfer size + register + 0x270 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ12 + HCTSIZ12 + OTGFS host channel-12 transfer size + register + 0x290 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ13 + HCTSIZ13 + OTGFS host channel-13 transfer size + register + 0x2B0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ14 + HCTSIZ14 + OTGFS host channel-14 transfer size + register + 0x2D0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ15 + HCTSIZ15 + OTGFS host channel-15 transfer size + register + 0x2F0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + + + USB_OTG1_DEVICE + USB on the go full speed + USB_OTG1 + 0x50000800 + + 0x0 + 0x400 + registers + + + + DCFG + DCFG + OTGFS device configuration register + (OTGFS_DCFG) + 0x0 + 0x20 + read-write + 0x02200000 + + + DEVSPD + Device speed + 0 + 2 + + + NZSTSOUTHSHK + Non-zero-length status OUT + handshake + 2 + 1 + + + DEVADDR + Device address + 4 + 7 + + + PERFRINT + Periodic frame interval + 11 + 2 + + + + + DCTL + DCTL + OTGFS device control register + (OTGFS_DCTL) + 0x4 + 0x20 + 0x00000000 + + + RWKUPSIG + Remote wakeup signaling + 0 + 1 + read-write + + + SFTDISCON + Soft disconnect + 1 + 1 + read-write + + + GNPINNAKSTS + Global IN NAK status + 2 + 1 + read-only + + + GOUTNAKSTS + Global OUT NAK status + 3 + 1 + read-only + + + TSTCTL + Test control + 4 + 3 + read-write + + + SGNPINNAK + Set global IN NAK + 7 + 1 + read-write + + + CGNPINNAK + Clear global IN NAK + 8 + 1 + read-write + + + SGOUTNAK + Set global OUT NAK + 9 + 1 + read-write + + + CGOUTNAK + Clear global OUT NAK + 10 + 1 + read-write + + + PWROPRGDNE + Power-on programming done + 11 + 1 + read-write + + + + + DSTS + DSTS + OTGFS device status register + (OTGFS_DSTS) + 0x8 + 0x20 + read-only + 0x00000010 + + + SUSPSTS + Suspend status + 0 + 1 + + + ENUMSPD + Enumerated speed + 1 + 2 + + + ETICERR + Erratic error + 3 + 1 + + + SOFFN + Frame number of the received + SOF + 8 + 14 + + + + + DIEPMSK + DIEPMSK + OTGFS device IN endpoint common interrupt + mask register (OTGFS_DIEPMSK) + 0x10 + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed interrupt + mask + 0 + 1 + + + EPTDISMSK + Endpoint disabled interrupt + mask + 1 + 1 + + + TIMEOUTMSK + Timeout condition mask (Non-isochronous + endpoints) + 3 + 1 + + + INTKNTXFEMPMSK + IN token received when TxFIFO empty + mask + 4 + 1 + + + INTKNEPTMISMSK + IN token received with EP mismatch + mask + 5 + 1 + + + INEPTNAKMSK + IN endpoint NAK effective + mask + 6 + 1 + + + TXFIFOUDRMSK + FIFO underrun + mask + 8 + 1 + + + BNAINMSK + BNA interrupt + mask + 9 + 1 + + + + + DOEPMSK + DOEPMSK + OTGFS device OUT endpoint common interrupt + mask register (OTGFS_DOEPMSK) + 0x14 + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed interrupt + mask + 0 + 1 + + + EPTDISMSK + Endpoint disabled interrupt + mask + 1 + 1 + + + SETUPMSK + SETUP phase done mask + 3 + 1 + + + OUTTEPDMSK + OUT token received when endpoint + disabled mask + 4 + 1 + + + B2BSETUPMSK + Back-to-back SETUP packets + received mask + 6 + 1 + + + OUTPERRMSK + OUT packet error + mask + 8 + 1 + + + BNAOUTMSK + BNA interrupt + mask + 9 + 1 + + + + + DAINT + DAINT + OTGFS device all endpoints interrupt + register (OTGFS_DAINT) + 0x18 + 0x20 + read-only + 0x00000000 + + + INEPTINT + IN endpoint interrupt bits + 0 + 16 + + + OUTEPTINT + OUT endpoint interrupt + bits + 16 + 16 + + + + + DAINTMSK + DAINTMSK + OTGFS all endpoints interrupt mask register + (OTGFS_DAINTMSK) + 0x1C + 0x20 + read-write + 0x00000000 + + + INEPTMSK + IN EP interrupt mask bits + 0 + 16 + + + OUTEPTMSK + OUT endpoint interrupt + bits + 16 + 16 + + + + + DIEPEMPMSK + DIEPEMPMSK + OTGFS device IN endpoint FIFO empty + interrupt mask register + 0x34 + 0x20 + read-write + 0x00000000 + + + INEPTXFEMSK + IN EP Tx FIFO empty interrupt mask + bits + 0 + 16 + + + + + DIEPCTL0 + DIEPCTL0 + OTGFS device control IN endpoint 0 control + register (OTGFS_DIEPCTL0) + 0x100 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 2 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-only + + + STALL + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-only + + + EPTENA + Endpoint enable + 31 + 1 + read-only + + + + + DIEPCTL1 + DIEPCTL1 + OTGFS device IN endpoint-1 control + register + 0x120 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint Data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-write + + + STALL + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SETD0PID + Set DATA0 PID + 28 + 1 + write-only + + + SETD1PID + Set DATA1 PID + 29 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DIEPCTL2 + DIEPCTL2 + OTGFS device IN endpoint-2 control + register + 0x140 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint Data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-write + + + STALL + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SETD0PID + Set DATA0 PID + 28 + 1 + write-only + + + SETD1PID + Set DATA1 PID + 29 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DIEPCTL3 + DIEPCTL3 + OTGFS device IN endpoint-3 control + register + 0x160 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint Data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-write + + + STALL + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SETD0PID + Set DATA0 PID + 28 + 1 + write-only + + + SETD1PID + Set DATA1 PID + 29 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DIEPCTL4 + DIEPCTL4 + OTGFS device IN endpoint-4 control + register + 0x180 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint Data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-write + + + STALL + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SETD0PID + Set DATA0 PID + 28 + 1 + write-only + + + SETD1PID + Set DATA1 PID + 29 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DIEPCTL5 + DIEPCTL5 + OTGFS device IN endpoint-5 control + register + 0x1A0 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint Data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-write + + + STALL + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SETD0PID + Set DATA0 PID + 28 + 1 + write-only + + + SETD1PID + Set DATA1 PID + 29 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DIEPCTL6 + DIEPCTL6 + OTGFS device IN endpoint-6 control + register + 0x1C0 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint Data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-write + + + STALL + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SETD0PID + Set DATA0 PID + 28 + 1 + write-only + + + SETD1PID + Set DATA1 PID + 29 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DIEPCTL7 + DIEPCTL7 + OTGFS device IN endpoint-7 control + register + 0x1E0 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint Data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-write + + + STALL + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SETD0PID + Set DATA0 PID + 28 + 1 + write-only + + + SETD1PID + Set DATA1 PID + 29 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DOEPCTL0 + DOEPCTL0 + OTGFS device OUT endpoint-0 control + register + 0x300 + 0x20 + 0x00008000 + + + MPS + Maximum packet size + 0 + 2 + read-only + + + USBACEPT + USB active endpoint + 15 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-only + + + SNP + Snoop mode + 20 + 1 + read-write + + + STALL + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DOEPCTL1 + DOEPCTL1 + OTGFS device OUT endpoint-1 control + register + 0x320 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-write + + + SNP + Snoop mode + 20 + 1 + read-write + + + STALL + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DOEPCTL2 + DOEPCTL2 + OTGFS device OUT endpoint-2 control + register + 0x340 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-write + + + SNP + Snoop mode + 20 + 1 + read-write + + + STALL + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DOEPCTL3 + DOEPCTL3 + OTGFS device OUT endpoint-3 control + register + 0x360 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-write + + + SNP + Snoop mode + 20 + 1 + read-write + + + STALL + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DOEPCTL4 + DOEPCTL4 + OTGFS device OUT endpoint-4 control + register + 0x380 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-write + + + SNP + Snoop mode + 20 + 1 + read-write + + + STALL + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DOEPCTL5 + DOEPCTL5 + OTGFS device OUT endpoint-5 control + register + 0x3A0 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-write + + + SNP + Snoop mode + 20 + 1 + read-write + + + STALL + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DOEPCTL6 + DOEPCTL6 + OTGFS device OUT endpoint-6 control + register + 0x3C0 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-write + + + SNP + Snoop mode + 20 + 1 + read-write + + + STALL + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DOEPCTL7 + DOEPCTL7 + OTGFS device OUT endpoint-7 control + register + 0x3E0 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-write + + + SNP + Snoop mode + 20 + 1 + read-write + + + STALL + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DIEPINT0 + DIEPINT0 + OTGFS device IN endpoint-0 interrupt + register + 0x108 + 0x20 + 0x00000080 + + + XFERC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPTDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TIMEOUT + Timeout condition + 3 + 1 + read-write + + + INTKNTXFEMP + IN token received when + TxFIFO is empty + 4 + 1 + read-write + + + INEPTNAK + IN endpoint NAK + effective + 6 + 1 + read-write + + + TXFEMP + Transmit FIFO + empty + 7 + 1 + read-only + + + + + DIEPINT1 + DIEPINT1 + OTGFS device IN endpoint-1 interrupt + register + 0x128 + 0x20 + 0x00000080 + + + XFERC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPTDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TIMEOUT + Timeout condition + 3 + 1 + read-write + + + INTKNTXFEMP + IN token received when + TxFIFO is empty + 4 + 1 + read-write + + + INEPTNAK + IN endpoint NAK + effective + 6 + 1 + read-write + + + TXFEMP + Transmit FIFO + empty + 7 + 1 + read-only + + + + + DIEPINT2 + DIEPINT2 + OTGFS device IN endpoint-2 interrupt + register + 0x148 + 0x20 + 0x00000080 + + + XFERC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPTDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TIMEOUT + Timeout condition + 3 + 1 + read-write + + + INTKNTXFEMP + IN token received when + TxFIFO is empty + 4 + 1 + read-write + + + INEPTNAK + IN endpoint NAK + effective + 6 + 1 + read-write + + + TXFEMP + Transmit FIFO + empty + 7 + 1 + read-only + + + + + DIEPINT3 + DIEPINT3 + OTGFS device IN endpoint-3 interrupt + register + 0x168 + 0x20 + 0x00000080 + + + XFERC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPTDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TIMEOUT + Timeout condition + 3 + 1 + read-write + + + INTKNTXFEMP + IN token received when + TxFIFO is empty + 4 + 1 + read-write + + + INEPTNAK + IN endpoint NAK + effective + 6 + 1 + read-write + + + TXFEMP + Transmit FIFO + empty + 7 + 1 + read-only + + + + + DIEPINT4 + DIEPINT4 + OTGFS device IN endpoint-4 interrupt + register + 0x188 + 0x20 + 0x00000080 + + + XFERC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPTDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TIMEOUT + Timeout condition + 3 + 1 + read-write + + + INTKNTXFEMP + IN token received when + TxFIFO is empty + 4 + 1 + read-write + + + INEPTNAK + IN endpoint NAK + effective + 6 + 1 + read-write + + + TXFEMP + Transmit FIFO + empty + 7 + 1 + read-only + + + + + DIEPINT5 + DIEPINT5 + OTGFS device IN endpoint-5 interrupt + register + 0x1A8 + 0x20 + 0x00000080 + + + XFERC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPTDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TIMEOUT + Timeout condition + 3 + 1 + read-write + + + INTKNTXFEMP + IN token received when + TxFIFO is empty + 4 + 1 + read-write + + + INEPTNAK + IN endpoint NAK + effective + 6 + 1 + read-write + + + TXFEMP + Transmit FIFO + empty + 7 + 1 + read-only + + + + + DIEPINT6 + DIEPINT6 + OTGFS device IN endpoint-6 interrupt + register + 0x1C8 + 0x20 + 0x00000080 + + + XFERC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPTDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TIMEOUT + Timeout condition + 3 + 1 + read-write + + + INTKNTXFEMP + IN token received when + TxFIFO is empty + 4 + 1 + read-write + + + INEPTNAK + IN endpoint NAK + effective + 6 + 1 + read-write + + + TXFEMP + Transmit FIFO + empty + 7 + 1 + read-only + + + + + DIEPINT7 + DIEPINT7 + OTGFS device IN endpoint-7 interrupt + register + 0x1E8 + 0x20 + 0x00000080 + + + XFERC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPTDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TIMEOUT + Timeout condition + 3 + 1 + read-write + + + INTKNTXFEMP + IN token received when + TxFIFO is empty + 4 + 1 + read-write + + + INEPTNAK + IN endpoint NAK + effective + 6 + 1 + read-write + + + TXFEMP + Transmit FIFO + empty + 7 + 1 + read-only + + + + + DOEPINT0 + DOEPINT0 + OTGFS device OUT endpoint-0 interrupt + register + 0x308 + 0x20 + read-write + 0x00000080 + + + XFERC + Transfer completed interrupt + 0 + 1 + + + EPTDISD + Endpoint disabled interrupt + 1 + 1 + + + SETUP + SETUP phase done + 3 + 1 + + + OUTTEPD + OUT token received when + endpoint disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP + packets received + 6 + 1 + + + + + DOEPINT1 + DOEPINT1 + OTGFS device OUT endpoint-1 interrupt + register + 0x328 + 0x20 + read-write + 0x00000080 + + + XFERC + Transfer completed interrupt + 0 + 1 + + + EPTDISD + Endpoint disabled interrupt + 1 + 1 + + + SETUP + SETUP phase done + 3 + 1 + + + OUTTEPD + OUT token received when + endpoint disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP + packets received + 6 + 1 + + + + + DOEPINT2 + DOEPINT2 + OTGFS device OUT endpoint-2 interrupt + register + 0x348 + 0x20 + read-write + 0x00000080 + + + XFERC + Transfer completed interrupt + 0 + 1 + + + EPTDISD + Endpoint disabled interrupt + 1 + 1 + + + SETUP + SETUP phase done + 3 + 1 + + + OUTTEPD + OUT token received when + endpoint disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP + packets received + 6 + 1 + + + + + DOEPINT3 + DOEPINT3 + OTGFS device OUT endpoint-3 interrupt + register + 0x368 + 0x20 + read-write + 0x00000080 + + + XFERC + Transfer completed interrupt + 0 + 1 + + + EPTDISD + Endpoint disabled interrupt + 1 + 1 + + + SETUP + SETUP phase done + 3 + 1 + + + OUTTEPD + OUT token received when + endpoint disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP + packets received + 6 + 1 + + + + + DOEPINT4 + DOEPINT4 + OTGFS device OUT endpoint-4 interrupt + register + 0x388 + 0x20 + read-write + 0x00000080 + + + XFERC + Transfer completed interrupt + 0 + 1 + + + EPTDISD + Endpoint disabled interrupt + 1 + 1 + + + SETUP + SETUP phase done + 3 + 1 + + + OUTTEPD + OUT token received when + endpoint disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP + packets received + 6 + 1 + + + + + DOEPINT5 + DOEPINT5 + OTGFS device OUT endpoint-5 interrupt + register + 0x3A8 + 0x20 + read-write + 0x00000080 + + + XFERC + Transfer completed interrupt + 0 + 1 + + + EPTDISD + Endpoint disabled interrupt + 1 + 1 + + + SETUP + SETUP phase done + 3 + 1 + + + OUTTEPD + OUT token received when + endpoint disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP + packets received + 6 + 1 + + + + + DOEPINT6 + DOEPINT6 + OTGFS device OUT endpoint-6 interrupt + register + 0x3C8 + 0x20 + read-write + 0x00000080 + + + XFERC + Transfer completed interrupt + 0 + 1 + + + EPTDISD + Endpoint disabled interrupt + 1 + 1 + + + SETUP + SETUP phase done + 3 + 1 + + + OUTTEPD + OUT token received when + endpoint disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP + packets received + 6 + 1 + + + + + DOEPINT7 + DOEPINT7 + OTGFS device OUT endpoint-7 interrupt + register + 0x3E8 + 0x20 + read-write + 0x00000080 + + + XFERC + Transfer completed interrupt + 0 + 1 + + + EPTDISD + Endpoint disabled interrupt + 1 + 1 + + + SETUP + SETUP phase done + 3 + 1 + + + OUTTEPD + OUT token received when + endpoint disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP + packets received + 6 + 1 + + + + + DIEPTSIZ0 + DIEPTSIZ0 + OTGFS device IN endpoint-0 transfer size + register + 0x110 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 7 + + + PKTCNT + Packet count + 19 + 2 + + + + + DOEPTSIZ0 + DOEPTSIZ0 + OTGFS device OUT endpoint-0 transfer size + register + 0x310 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 7 + + + PKTCNT + Packet count + 19 + 1 + + + SETUPCNT + SETUP packet count + 29 + 2 + + + + + DIEPTSIZ1 + DIEPTSIZ1 + OTGFS device IN endpoint-1 transfer size + register + 0x130 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MC + Multi count + 29 + 2 + + + + + DIEPTSIZ2 + DIEPTSIZ2 + OTGFS device IN endpoint-2 transfer size + register + 0x150 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MC + Multi count + 29 + 2 + + + + + DIEPTSIZ3 + DIEPTSIZ3 + OTG device IN endpoint-3 transfer size + register + 0x170 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MC + Multi count + 29 + 2 + + + + + DIEPTSIZ4 + DIEPTSIZ4 + OTG device IN endpoint-4 transfer size + register + 0x190 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MC + Multi count + 29 + 2 + + + + + DIEPTSIZ5 + DIEPTSIZ5 + OTG device IN endpoint-5 transfer size + register + 0x1B0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MC + Multi count + 29 + 2 + + + + + DIEPTSIZ6 + DIEPTSIZ6 + OTG device IN endpoint-6 transfer size + register + 0x1D0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MC + Multi count + 29 + 2 + + + + + DIEPTSIZ7 + DIEPTSIZ7 + OTG device IN endpoint-7 transfer size + register + 0x1F0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MC + Multi count + 29 + 2 + + + + + DTXFSTS0 + DTXFSTS0 + OTGFS device IN endpoint-0 transmit FIFO + status register + 0x118 + 0x20 + read-only + 0x00000000 + + + INEPTXFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS1 + DTXFSTS1 + OTGFS device IN endpoint-1 transmit FIFO + status register + 0x138 + 0x20 + read-only + 0x00000000 + + + INEPTXFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS2 + DTXFSTS2 + OTGFS device IN endpoint-2 transmit FIFO + status register + 0x158 + 0x20 + read-only + 0x00000000 + + + INEPTXFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS3 + DTXFSTS3 + OTGFS device IN endpoint-3 transmit FIFO + status register + 0x178 + 0x20 + read-only + 0x00000000 + + + INEPTXFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS4 + DTXFSTS4 + OTGFS device IN endpoint-4 transmit FIFO + status register + 0x198 + 0x20 + read-only + 0x00000000 + + + INEPTXFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS5 + DTXFSTS5 + OTGFS device IN endpoint-5 transmit FIFO + status register + 0x1B8 + 0x20 + read-only + 0x00000000 + + + INEPTXFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS6 + DTXFSTS6 + OTGFS device IN endpoint-6 transmit FIFO + status register + 0x1D8 + 0x20 + read-only + 0x00000000 + + + INEPTXFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS7 + DTXFSTS7 + OTGFS device IN endpoint-7 transmit FIFO + status register + 0x1F8 + 0x20 + read-only + 0x00000000 + + + INEPTXFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DOEPTSIZ1 + DOEPTSIZ1 + OTGFS device OUT endpoint-1 transfer size + register + 0x330 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID + Received data PID + 29 + 2 + + + + + DOEPTSIZ2 + DOEPTSIZ2 + OTGFS device OUT endpoint-2 transfer size + register + 0x350 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID + Received data PID + 29 + 2 + + + + + DOEPTSIZ3 + DOEPTSIZ3 + OTGFS device OUT endpoint-3 transfer size + register + 0x370 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID + Received data PID + 29 + 2 + + + + + DOEPTSIZ4 + DOEPTSIZ4 + OTGFS device OUT endpoint-4 transfer size + register + 0x390 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID + Received data PID + 29 + 2 + + + + + DOEPTSIZ5 + DOEPTSIZ5 + OTGFS device OUT endpoint-5 transfer size + register + 0x3B0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID + Received data PID + 29 + 2 + + + + + DOEPTSIZ6 + DOEPTSIZ6 + OTGFS device OUT endpoint-6 transfer size + register + 0x3D0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID + Received data PID + 29 + 2 + + + + + DOEPTSIZ7 + DOEPTSIZ7 + OTGFS device OUT endpoint-7 transfer size + register + 0x3F0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID + Received data PID + 29 + 2 + + + + + + + USB_OTG1_PWRCLK + USB on the go full speed + USB_OTG1 + 0x50000E00 + + 0x0 + 0x400 + registers + + + + PCGCCTL + PCGCCTL + OTGFS power and clock gating control + register (OTGFS_PCGCCTL) + 0x0 + 0x20 + 0x00000000 + + + STOPPCLK + Stop PHY clock + 0 + 1 + read-write + + + SUSPENDM + PHY Suspended + 4 + 1 + read-only + + + + + + + USB_OTG2_GLOBAL + USB on the go full speed + USB_OTG2 + 0x40040000 + + 0x0 + 0x400 + registers + + + OTGFS2 + USB On The Go FS2 global + interrupt + 77 + + + + GOTGCTL + GOTGCTL + OTGFS control and status register + (OTGFS_GOTGCTL) + 0x0 + 0x20 + 0x00000800 + + + CONIDSTS + Connector ID status + 16 + 1 + read-only + + + CURMOD + Current Mode of Operation + 21 + 1 + read-only + + + + + GOTGINT + GOTGINT + OTGFS interrupt register + (OTGFS_GOTGINT) + 0x4 + 0x20 + 0x00000000 + + + SESENDDET + VBUS is deasserted + 2 + 1 + read-write + + + + + GAHBCFG + GAHBCFG + OTGFS AHB configuration register + (OTGFS_GAHBCFG) + 0x8 + 0x20 + read-write + 0x00000000 + + + GLBINTMSK + Global interrupt mask + 0 + 1 + + + NPTXFEMPLVL + Non-Periodic TxFIFO empty level + 7 + 1 + + + PTXFEMPLVL + Periodic TxFIFO empty + level + 8 + 1 + + + + + GUSBCFG + GUSBCFG + USB configuration register + (OTGFS_GUSBCFG) + 0xC + 0x20 + 0x00000A00 + + + TOUTCAL + FS timeout calibration + 0 + 3 + read-write + + + USBTRDTIM + USB turnaround time + 10 + 4 + read-write + + + FHSTMODE + Force host mode + 29 + 1 + read-write + + + FDEVMODE + Force device mode + 30 + 1 + read-write + + + COTXPKT + Corrupt Tx packet + 31 + 1 + read-write + + + + + GRSTCTL + GRSTCTL + OTGFS reset register + (OTGFS_GRSTCTL) + 0x10 + 0x20 + 0x20000000 + + + CSFTRST + Core soft reset + 0 + 1 + read-write + + + PIUSFTRST + PIU FS Dedicated Controller Soft Reset + 1 + 1 + read-write + + + FRMCNTRST + Host frame counter reset + 2 + 1 + read-write + + + RXFFLSH + RxFIFO flush + 4 + 1 + read-write + + + TXFFLSH + TxFIFO flush + 5 + 1 + read-write + + + TXFNUM + TxFIFO number + 6 + 5 + read-write + + + AHBIDLE + AHB master idle + 31 + 1 + read-only + + + + + GINTSTS + GINTSTS + OTGFS core interrupt register + (OTGFS_GINTSTS) + 0x14 + 0x20 + 0x04000020 + + + CURMOD + Current mode of operation + 0 + 1 + read-only + + + MODEMIS + Mode mismatch interrupt + 1 + 1 + read-write + + + OTGINT + OTG interrupt + 2 + 1 + read-only + + + SOF + Start of frame + 3 + 1 + read-write + + + RXFLVL + RxFIFO non-empty + 4 + 1 + read-only + + + NPTXFEMP + Non-periodic TxFIFO empty + 5 + 1 + read-only + + + GINNAKEFF + Global IN non-periodic NAK + effective + 6 + 1 + read-only + + + GOUTNAKEFF + Global OUT NAK effective + 7 + 1 + read-only + + + ERLYSUSP + Early suspend + 10 + 1 + read-write + + + USBSUSP + USB suspend + 11 + 1 + read-write + + + USBRST + USB reset + 12 + 1 + read-write + + + ENUMDONE + Enumeration done + 13 + 1 + read-write + + + ISOOUTDROP + Isochronous OUT packet dropped + interrupt + 14 + 1 + read-write + + + EOPF + End of periodic frame + interrupt + 15 + 1 + read-write + + + IEPTINT + IN endpoint interrupt + 18 + 1 + read-only + + + OEPTINT + OUT endpoint interrupt + 19 + 1 + read-only + + + INCOMPISOIN + Incomplete isochronous IN + transfer + 20 + 1 + read-write + + + INCOMPIP_INCOMPISOOUT + Incomplete periodic transfer(Host + mode)/Incomplete isochronous OUT transfer(Device + mode) + 21 + 1 + read-write + + + PRTINT + Host port interrupt + 24 + 1 + read-only + + + HCHINT + Host channels interrupt + 25 + 1 + read-only + + + PTXFEMP + Periodic TxFIFO empty + 26 + 1 + read-only + + + CONIDSCHG + Connector ID status change + 28 + 1 + read-write + + + DISCONINT + Disconnect detected + interrupt + 29 + 1 + read-write + + + WKUPINT + Resume/remote wakeup detected + interrupt + 31 + 1 + read-write + + + + + GINTMSK + GINTMSK + OTG_FS interrupt mask register + (OTG_FS_GINTMSK) + 0x18 + 0x20 + 0x00000000 + + + MODEMISMSK + Mode mismatch interrupt + mask + 1 + 1 + read-write + + + OTGINTMSK + OTG interrupt mask + 2 + 1 + read-write + + + SOFMSK + Start of frame mask + 3 + 1 + read-write + + + RXFLVLMSK + Receive FIFO non-empty + mask + 4 + 1 + read-write + + + NPTXFEMPMSK + Non-periodic TxFIFO empty + mask + 5 + 1 + read-write + + + GINNAKEFFMSK + Global non-periodic IN NAK effective + mask + 6 + 1 + read-write + + + GOUTNAKEFFMSK + Global OUT NAK effective + mask + 7 + 1 + read-write + + + ERLYSUSPMSK + Early suspend mask + 10 + 1 + read-write + + + USBSUSPMSK + USB suspend mask + 11 + 1 + read-write + + + USBRSTMSK + USB reset mask + 12 + 1 + read-write + + + ENUMDONEMSK + Enumeration done mask + 13 + 1 + read-write + + + ISOOUTDROPMSK + Isochronous OUT packet dropped interrupt + mask + 14 + 1 + read-write + + + EOPFMSK + End of periodic frame interrupt + mask + 15 + 1 + read-write + + + IEPTINTMSK + IN endpoints interrupt + mask + 18 + 1 + read-write + + + OEPTINTMSK + OUT endpoints interrupt + mask + 19 + 1 + read-write + + + INCOMISOINMSK + Incomplete isochronous IN transfer + mask + 20 + 1 + read-write + + + INCOMPIP_INCOMPISOOUTMSK + Incomplete periodic transfer mask(Host + mode)/Incomplete isochronous OUT transfer mask(Device + mode) + 21 + 1 + read-write + + + PRTINTMSK + Host port interrupt mask + 24 + 1 + read-only + + + HCHINTMSK + Host channels interrupt + mask + 25 + 1 + read-write + + + PTXFEMPMSK + Periodic TxFIFO empty mask + 26 + 1 + read-write + + + CONIDSCHGMSK + Connector ID status change + mask + 28 + 1 + read-write + + + DISCONINTMSK + Disconnect detected interrupt + mask + 29 + 1 + read-write + + + WKUPINTMSK + Resume/remote wakeup detected interrupt + mask + 31 + 1 + read-write + + + + + GRXSTSR_Device + GRXSTSR_Device + OTGFS Receive status debug read(Device + mode) + 0x1C + 0x20 + read-only + 0x00000000 + + + EPTNUM + Endpoint number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + FN + Frame number + 21 + 4 + + + + + GRXSTSR_Host + GRXSTSR_Host + OTGFS Receive status debug read(Host + mode) + GRXSTSR_Device + 0x1C + 0x20 + read-only + 0x00000000 + + + CHNUM + Channel number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + + + GRXFSIZ + GRXFSIZ + OTGFS Receive FIFO size register + (OTGFS_GRXFSIZ) + 0x24 + 0x20 + read-write + 0x00000200 + + + RXFDEP + RxFIFO depth + 0 + 16 + + + + + DIEPTXF0 + DIEPTXF0 + IN Endpoint TxFIFO 0 transmit FIFO size + register (Device mode) + 0x28 + 0x20 + read-write + 0x00000200 + + + INEPT0TXSTADDR + Endpoint 0 transmit RAM start + address + 0 + 16 + + + INEPT0TXDEP + Endpoint 0 TxFIFO depth + 16 + 16 + + + + + GNPTXFSIZ + GNPTXFSIZ + OTGFS non-periodic transmit FIFO size + register (Host mode) + DIEPTXF0 + 0x28 + 0x20 + read-write + 0x00000200 + + + NPTXFSTADDR + Non-periodic Transmit RAM Start + address + 0 + 16 + + + NPTXFDEP + Non-periodic TxFIFO depth + 16 + 16 + + + + + GNPTXSTS + GNPTXSTS + OTGFS non-periodic transmit FIFO/queue + status register (OTGFS_GNPTXSTS) + 0x2C + 0x20 + read-only + 0x00080200 + + + NPTXFSPCAVAIL + Non-periodic TxFIFO space + available + 0 + 16 + + + NPTXQSPCAVAIL + Non-periodic transmit request queue + space available + 16 + 8 + + + NPTXQTOP + Top of the non-periodic transmit request + queue + 24 + 7 + + + + + GCCFG + GCCFG + OTGFS general core configuration register + (OTGFS_GCCFG) + 0x38 + 0x20 + read-write + 0x00000000 + + + PWRDOWN + Power down + 16 + 1 + + + LP_MODE + Low power mode + 17 + 1 + + + SOFOUTEN + SOF output enable + 20 + 1 + + + VBUSIG + VBUS Ignored + 21 + 1 + + + + + GUID + GUID + Product ID register + 0x3C + 0x20 + read-write + 0x00001000 + + + USERID + Product ID field + 0 + 32 + + + + + HPTXFSIZ + HPTXFSIZ + OTGFS Host periodic transmit FIFO size + register (OTGFS_HPTXFSIZ) + 0x100 + 0x20 + read-write + 0x02000600 + + + PTXFSTADDR + Host periodic TxFIFO start + address + 0 + 16 + + + PTXFSIZE + Host periodic TxFIFO depth + 16 + 16 + + + + + DIEPTXF1 + DIEPTXF1 + OTGFS device IN endpoint transmit FIFO size + register (OTGFS_DIEPTXF1) + 0x104 + 0x20 + read-write + 0x02000400 + + + INEPTXFSTADDR + IN endpoint FIFO1 transmit RAM start + address + 0 + 16 + + + INEPTXFDEP + IN endpoint TxFIFO depth + 16 + 16 + + + + + DIEPTXF2 + DIEPTXF2 + OTGFS device IN endpoint transmit FIFO size + register (OTGFS_DIEPTXF2) + 0x108 + 0x20 + read-write + 0x02000400 + + + INEPTXFSTADDR + IN endpoint FIFO2 transmit RAM start + address + 0 + 16 + + + INEPTXFDEP + IN endpoint TxFIFO depth + 16 + 16 + + + + + DIEPTXF3 + DIEPTXF3 + OTGFS device IN endpoint transmit FIFO size + register (OTGFS_DIEPTXF3) + 0x10C + 0x20 + read-write + 0x02000400 + + + INEPTXFSTADDR + IN endpoint FIFO3 transmit RAM start + address + 0 + 16 + + + INEPTXFDEP + IN endpoint TxFIFO depth + 16 + 16 + + + + + DIEPTXF4 + DIEPTXF4 + OTGFS device IN endpoint transmit FIFO size + register (OTGFS_DIEPTXF4) + 0x110 + 0x20 + read-write + 0x02000400 + + + INEPTXFSTADDR + IN endpoint FIFO4 transmit RAM start + address + 0 + 16 + + + INEPTXFDEP + IN endpoint TxFIFO depth + 16 + 16 + + + + + DIEPTXF5 + DIEPTXF5 + OTGFS device IN endpoint transmit FIFO size + register (OTGFS_DIEPTXF5) + 0x114 + 0x20 + read-write + 0x02000400 + + + INEPTXFSTADDR + IN endpoint FIFO5 transmit RAM start + address + 0 + 16 + + + INEPTXFDEP + IN endpoint TxFIFO depth + 16 + 16 + + + + + DIEPTXF6 + DIEPTXF6 + OTGFS device IN endpoint transmit FIFO size + register (OTGFS_DIEPTXF6) + 0x118 + 0x20 + read-write + 0x02000400 + + + INEPTXFSTADDR + IN endpoint FIFO6 transmit RAM start + address + 0 + 16 + + + INEPTXFDEP + IN endpoint TxFIFO depth + 16 + 16 + + + + + DIEPTXF7 + DIEPTXF7 + OTGFS device IN endpoint transmit FIFO size + register (OTGFS_DIEPTXF7) + 0x11C + 0x20 + read-write + 0x02000400 + + + INEPTXFSTADDR + IN endpoint FIFO7 transmit RAM start + address + 0 + 16 + + + INEPTXFDEP + IN endpoint TxFIFO depth + 16 + 16 + + + + + + + USB_OTG2_HOST + USB on the go full speed + USB_OTG2 + 0x40040400 + + 0x0 + 0x400 + registers + + + + HCFG + HCFG + OTGFS host configuration register + (OTGFS_HCFG) + 0x0 + 0x20 + 0x00000000 + + + FSLSPCLKSEL + FS/LS PHY clock select + 0 + 2 + read-write + + + FSLSSUPP + FS- and LS-only support + 2 + 1 + read-only + + + + + HFIR + HFIR + OTGFS Host frame interval + register + 0x4 + 0x20 + read-write + 0x0000EA60 + + + FRINT + Frame interval + 0 + 16 + + + + + HFNUM + HFNUM + OTGFS host frame number/frame time + remaining register (OTGFS_HFNUM) + 0x8 + 0x20 + read-only + 0x00003FFF + + + FRNUM + Frame number + 0 + 16 + + + FTREM + Frame time remaining + 16 + 16 + + + + + HPTXSTS + HPTXSTS + OTGFS_Host periodic transmit FIFO/queue + status register (OTGFS_HPTXSTS) + 0x10 + 0x20 + 0x00080100 + + + PTXFSPCAVAIL + Periodic transmit data FIFO space + available + 0 + 16 + read-write + + + PTXQSPCAVAIL + Periodic transmit request queue space + available + 16 + 8 + read-only + + + PTXQTOP + Top of the periodic transmit request + queue + 24 + 8 + read-only + + + + + HAINT + HAINT + OTGFS Host all channels interrupt + register + 0x14 + 0x20 + read-only + 0x00000000 + + + HAINT + Channel interrupts + 0 + 16 + + + + + HAINTMSK + HAINTMSK + OTGFS host all channels interrupt mask + register + 0x18 + 0x20 + read-write + 0x00000000 + + + HAINTMSK + Channel interrupt mask + 0 + 16 + + + + + HPRT + HPRT + OTGFS host port control and status register + (OTGFS_HPRT) + 0x40 + 0x20 + 0x00000000 + + + PRTCONSTS + Port connect status + 0 + 1 + read-only + + + PRTCONDET + Port connect detected + 1 + 1 + read-write + + + PRTENA + Port enable + 2 + 1 + read-write + + + PRTENCHNG + Port enable/disable change + 3 + 1 + read-write + + + PRTOVRCACT + Port overcurrent active + 4 + 1 + read-only + + + PRTOVRCCHNG + Port overcurrent change + 5 + 1 + read-write + + + PRTRES + Port resume + 6 + 1 + read-write + + + PRTSUSP + Port suspend + 7 + 1 + read-write + + + PRTRST + Port reset + 8 + 1 + read-write + + + PRTLNSTS + Port line status + 10 + 2 + read-only + + + PRTPWR + Port power + 12 + 1 + read-write + + + PRTTSTCTL + Port test control + 13 + 4 + read-write + + + PRTSPD + Port speed + 17 + 2 + read-only + + + + + HCCHAR0 + HCCHAR0 + OTGFS host channel-0 characteristics + register (OTGFS_HCCHAR0) + 0x100 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR1 + HCCHAR1 + OTGFS host channel-1 characteristics + register (OTGFS_HCCHAR1) + 0x120 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR2 + HCCHAR2 + OTGFS host channel-2 characteristics + register (OTGFS_HCCHAR2) + 0x140 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR3 + HCCHAR3 + OTGFS host channel-3 characteristics + register (OTGFS_HCCHAR3) + 0x160 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR4 + HCCHAR4 + OTGFS host channel-4 characteristics + register (OTGFS_HCCHAR4) + 0x180 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR5 + HCCHAR5 + OTGFS host channel-5 characteristics + register (OTGFS_HCCHAR5) + 0x1A0 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR6 + HCCHAR6 + OTGFS host channel-6 characteristics + register (OTGFS_HCCHAR6) + 0x1C0 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR7 + HCCHAR7 + OTGFS host channel-7 characteristics + register (OTGFS_HCCHAR7) + 0x1E0 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR8 + HCCHAR8 + OTGFS host channel-8 characteristics + register (OTGFS_HCCHAR8) + 0x200 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR9 + HCCHAR9 + OTGFS host channel-9 characteristics + register (OTGFS_HCCHAR9) + 0x220 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR10 + HCCHAR10 + OTGFS host channel-10 characteristics + register (OTGFS_HCCHAR10) + 0x240 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR11 + HCCHAR11 + OTGFS host channel-7 characteristics + register (OTGFS_HCCHAR11) + 0x260 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR12 + HCCHAR12 + OTGFS host channel-12 characteristics + register (OTGFS_HCCHAR12) + 0x280 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR13 + HCCHAR13 + OTGFS host channel-13 characteristics + register (OTGFS_HCCHAR13) + 0x2A0 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR14 + HCCHAR14 + OTGFS host channel-14 characteristics + register (OTGFS_HCCHAR14) + 0x2C0 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCCHAR15 + HCCHAR15 + OTGFS host channel-15 characteristics + register (OTGFS_HCCHAR15) + 0x2E0 + 0x20 + read-write + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + + + EPTNUM + Endpoint number + 11 + 4 + + + EPTDIR + Endpoint direction + 15 + 1 + + + LSPDDEV + Low-speed device + 17 + 1 + + + EPTYPE + Endpoint type + 18 + 2 + + + MC + Multicount + 20 + 2 + + + DEVADDR + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + HCINT0 + HCINT0 + OTGFS host channel-0 interrupt register + (OTGFS_HCINT0) + 0x108 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT1 + HCINT1 + OTG_FS host channel-1 interrupt register + (OTG_FS_HCINT1) + 0x128 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT2 + HCINT2 + OTGFS host channel-2 interrupt register + (OTGFS_HCINT2) + 0x148 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT3 + HCINT3 + OTGFS host channel-3 interrupt register + (OTGFS_HCINT3) + 0x168 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT4 + HCINT4 + OTGFS host channel-4 interrupt register + (OTGFS_HCINT4) + 0x188 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT5 + HCINT5 + OTGFS host channel-5 interrupt register + (OTGFS_HCINT5) + 0x1A8 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT6 + HCINT6 + OTGFS host channel-6 interrupt register + (OTGFS_HCINT6) + 0x1C8 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT7 + HCINT7 + OTGFS host channel-7 interrupt register + (OTGFS_HCINT7) + 0x1E8 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT8 + HCINT8 + OTGFS host channel-8 interrupt register + (OTGFS_HCINT8) + 0x208 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT9 + HCINT9 + OTGFS host channel-9 interrupt register + (OTGFS_HCINT9) + 0x228 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT10 + HCINT10 + OTGFS host channel-10 interrupt register + (OTGFS_HCINT10) + 0x248 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT11 + HCINT11 + OTGFS host channel-11 interrupt register + (OTGFS_HCINT11) + 0x268 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT12 + HCINT12 + OTGFS host channel-12 interrupt register + (OTGFS_HCINT12) + 0x288 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT13 + HCINT13 + OTGFS host channel-13 interrupt register + (OTGFS_HCINT13) + 0x2A8 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT14 + HCINT14 + OTGFS host channel-14 interrupt register + (OTGFS_HCINT14) + 0x2C8 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINT15 + HCINT15 + OTGFS host channel-15 interrupt register + (OTGFS_HCINT15) + 0x2E8 + 0x20 + read-write + 0x00000000 + + + XFERC + Transfer completed + 0 + 1 + + + CHHLTD + Channel halted + 1 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + XACTERR + Transaction error + 7 + 1 + + + BBLERR + Babble error + 8 + 1 + + + FRMOVRUN + Frame overrun + 9 + 1 + + + DTGLERR + Data toggle error + 10 + 1 + + + + + HCINTMSK0 + HCINTMSK0 + OTGFS host channel-0 mask register + (OTGFS_HCINTMSK0) + 0x10C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK1 + HCINTMSK1 + OTGFS host channel-1 mask register + (OTGFS_HCINTMSK1) + 0x12C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK2 + HCINTMSK2 + OTGFS host channel-2 mask register + (OTGFS_HCINTMSK2) + 0x14C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK3 + HCINTMSK3 + OTGFS host channel-3 mask register + (OTGFS_HCINTMSK3) + 0x16C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK4 + HCINTMSK4 + OTGFS host channel-4 mask register + (OTGFS_HCINTMSK4) + 0x18C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK5 + HCINTMSK5 + OTGFS host channel-5 mask register + (OTGFS_HCINTMSK5) + 0x1AC + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK6 + HCINTMSK6 + OTGFS host channel-6 mask register + (OTGFS_HCINTMSK6) + 0x1CC + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK7 + HCINTMSK7 + OTGFS host channel-7 mask register + (OTGFS_HCINTMSK7) + 0x1EC + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK8 + HCINTMSK8 + OTGFS host channel-8 mask register + (OTGFS_HCINTMSK8) + 0x20C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK9 + HCINTMSK9 + OTGFS host channel-9 mask register + (OTGFS_HCINTMSK9) + 0x22C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK10 + HCINTMSK10 + OTGFS host channel-10 mask register + (OTGFS_HCINTMSK10) + 0x24C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK11 + HCINTMSK11 + OTGFS host channel-11 mask register + (OTGFS_HCINTMSK11) + 0x26C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK12 + HCINTMSK12 + OTGFS host channel-12 mask register + (OTGFS_HCINTMSK12) + 0x28C + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK13 + HCINTMSK13 + OTGFS host channel-13 mask register + (OTGFS_HCINTMSK13) + 0x2AC + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK14 + HCINTMSK14 + OTGFS host channel-14 mask register + (OTGFS_HCINTMSK14) + 0x2CC + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCINTMSK15 + HCINTMSK15 + OTGFS host channel-15 mask register + (OTGFS_HCINTMSK15) + 0x2EC + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed mask + 0 + 1 + + + CHHLTDMSK + Channel halted mask + 1 + 1 + + + STALLMSK + STALL response received interrupt + mask + 3 + 1 + + + NAKMSK + NAK response received interrupt + mask + 4 + 1 + + + ACKMSK + ACK response received/transmitted + interrupt mask + 5 + 1 + + + XACTERRMSK + Transaction error mask + 7 + 1 + + + BBLERRMSK + Babble error mask + 8 + 1 + + + FRMOVRUNMSK + Frame overrun mask + 9 + 1 + + + DTGLERRMSK + Data toggle error mask + 10 + 1 + + + + + HCTSIZ0 + HCTSIZ0 + OTGFS host channel-0 transfer size + register + 0x110 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ1 + HCTSIZ1 + OTGFS host channel-1 transfer size + register + 0x130 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ2 + HCTSIZ2 + OTGFS host channel-2 transfer size + register + 0x150 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ3 + HCTSIZ3 + OTGFS host channel-3 transfer size + register + 0x170 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ4 + HCTSIZ4 + OTGFS host channel-4 transfer size + register + 0x190 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ5 + HCTSIZ5 + OTGFS host channel-5 transfer size + register + 0x1B0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ6 + HCTSIZ6 + OTGFS host channel-6 transfer size + register + 0x1D0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ7 + HCTSIZ7 + OTGFS host channel-7 transfer size + register + 0x1F0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ8 + HCTSIZ8 + OTGFS host channel-8 transfer size + register + 0x210 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ9 + HCTSIZ9 + OTGFS host channel-9 transfer size + register + 0x230 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ10 + HCTSIZ10 + OTGFS host channel-10 transfer size + register + 0x250 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ11 + HCTSIZ11 + OTGFS host channel-11 transfer size + register + 0x270 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ12 + HCTSIZ12 + OTGFS host channel-12 transfer size + register + 0x290 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ13 + HCTSIZ13 + OTGFS host channel-13 transfer size + register + 0x2B0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ14 + HCTSIZ14 + OTGFS host channel-14 transfer size + register + 0x2D0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + HCTSIZ15 + HCTSIZ15 + OTGFS host channel-15 transfer size + register + 0x2F0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + PID + PID + 29 + 2 + + + + + + + USB_OTG2_DEVICE + USB on the go full speed + USB_OTG2 + 0x40040800 + + 0x0 + 0x400 + registers + + + + DCFG + DCFG + OTGFS device configuration register + (OTGFS_DCFG) + 0x0 + 0x20 + read-write + 0x02200000 + + + DEVSPD + Device speed + 0 + 2 + + + NZSTSOUTHSHK + Non-zero-length status OUT + handshake + 2 + 1 + + + DEVADDR + Device address + 4 + 7 + + + PERFRINT + Periodic frame interval + 11 + 2 + + + + + DCTL + DCTL + OTGFS device control register + (OTGFS_DCTL) + 0x4 + 0x20 + 0x00000000 + + + RWKUPSIG + Remote wakeup signaling + 0 + 1 + read-write + + + SFTDISCON + Soft disconnect + 1 + 1 + read-write + + + GNPINNAKSTS + Global IN NAK status + 2 + 1 + read-only + + + GOUTNAKSTS + Global OUT NAK status + 3 + 1 + read-only + + + TSTCTL + Test control + 4 + 3 + read-write + + + SGNPINNAK + Set global IN NAK + 7 + 1 + read-write + + + CGNPINNAK + Clear global IN NAK + 8 + 1 + read-write + + + SGOUTNAK + Set global OUT NAK + 9 + 1 + read-write + + + CGOUTNAK + Clear global OUT NAK + 10 + 1 + read-write + + + PWROPRGDNE + Power-on programming done + 11 + 1 + read-write + + + + + DSTS + DSTS + OTGFS device status register + (OTGFS_DSTS) + 0x8 + 0x20 + read-only + 0x00000010 + + + SUSPSTS + Suspend status + 0 + 1 + + + ENUMSPD + Enumerated speed + 1 + 2 + + + ETICERR + Erratic error + 3 + 1 + + + SOFFN + Frame number of the received + SOF + 8 + 14 + + + + + DIEPMSK + DIEPMSK + OTGFS device IN endpoint common interrupt + mask register (OTGFS_DIEPMSK) + 0x10 + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed interrupt + mask + 0 + 1 + + + EPTDISMSK + Endpoint disabled interrupt + mask + 1 + 1 + + + TIMEOUTMSK + Timeout condition mask (Non-isochronous + endpoints) + 3 + 1 + + + INTKNTXFEMPMSK + IN token received when TxFIFO empty + mask + 4 + 1 + + + INTKNEPTMISMSK + IN token received with EP mismatch + mask + 5 + 1 + + + INEPTNAKMSK + IN endpoint NAK effective + mask + 6 + 1 + + + TXFIFOUDRMSK + FIFO underrun + mask + 8 + 1 + + + BNAINMSK + BNA interrupt + mask + 9 + 1 + + + + + DOEPMSK + DOEPMSK + OTGFS device OUT endpoint common interrupt + mask register (OTGFS_DOEPMSK) + 0x14 + 0x20 + read-write + 0x00000000 + + + XFERCMSK + Transfer completed interrupt + mask + 0 + 1 + + + EPTDISMSK + Endpoint disabled interrupt + mask + 1 + 1 + + + SETUPMSK + SETUP phase done mask + 3 + 1 + + + OUTTEPDMSK + OUT token received when endpoint + disabled mask + 4 + 1 + + + B2BSETUPMSK + Back-to-back SETUP packets + received mask + 6 + 1 + + + OUTPERRMSK + OUT packet error + mask + 8 + 1 + + + BNAOUTMSK + BNA interrupt + mask + 9 + 1 + + + + + DAINT + DAINT + OTGFS device all endpoints interrupt + register (OTGFS_DAINT) + 0x18 + 0x20 + read-only + 0x00000000 + + + INEPTINT + IN endpoint interrupt bits + 0 + 16 + + + OUTEPTINT + OUT endpoint interrupt + bits + 16 + 16 + + + + + DAINTMSK + DAINTMSK + OTGFS all endpoints interrupt mask register + (OTGFS_DAINTMSK) + 0x1C + 0x20 + read-write + 0x00000000 + + + INEPTMSK + IN EP interrupt mask bits + 0 + 16 + + + OUTEPTMSK + OUT endpoint interrupt + bits + 16 + 16 + + + + + DIEPEMPMSK + DIEPEMPMSK + OTGFS device IN endpoint FIFO empty + interrupt mask register + 0x34 + 0x20 + read-write + 0x00000000 + + + INEPTXFEMSK + IN EP Tx FIFO empty interrupt mask + bits + 0 + 16 + + + + + DIEPCTL0 + DIEPCTL0 + OTGFS device control IN endpoint 0 control + register (OTGFS_DIEPCTL0) + 0x100 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 2 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-only + + + STALL + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-only + + + EPTENA + Endpoint enable + 31 + 1 + read-only + + + + + DIEPCTL1 + DIEPCTL1 + OTGFS device IN endpoint-1 control + register + 0x120 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint Data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-write + + + STALL + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SETD0PID + Set DATA0 PID + 28 + 1 + write-only + + + SETD1PID + Set DATA1 PID + 29 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DIEPCTL2 + DIEPCTL2 + OTGFS device IN endpoint-2 control + register + 0x140 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint Data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-write + + + STALL + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SETD0PID + Set DATA0 PID + 28 + 1 + write-only + + + SETD1PID + Set DATA1 PID + 29 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DIEPCTL3 + DIEPCTL3 + OTGFS device IN endpoint-3 control + register + 0x160 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint Data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-write + + + STALL + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SETD0PID + Set DATA0 PID + 28 + 1 + write-only + + + SETD1PID + Set DATA1 PID + 29 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DIEPCTL4 + DIEPCTL4 + OTGFS device IN endpoint-4 control + register + 0x180 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint Data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-write + + + STALL + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SETD0PID + Set DATA0 PID + 28 + 1 + write-only + + + SETD1PID + Set DATA1 PID + 29 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DIEPCTL5 + DIEPCTL5 + OTGFS device IN endpoint-5 control + register + 0x1A0 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint Data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-write + + + STALL + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SETD0PID + Set DATA0 PID + 28 + 1 + write-only + + + SETD1PID + Set DATA1 PID + 29 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DIEPCTL6 + DIEPCTL6 + OTGFS device IN endpoint-6 control + register + 0x1C0 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint Data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-write + + + STALL + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SETD0PID + Set DATA0 PID + 28 + 1 + write-only + + + SETD1PID + Set DATA1 PID + 29 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DIEPCTL7 + DIEPCTL7 + OTGFS device IN endpoint-7 control + register + 0x1E0 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-write + + + DPID + Endpoint Data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-write + + + STALL + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SETD0PID + Set DATA0 PID + 28 + 1 + write-only + + + SETD1PID + Set DATA1 PID + 29 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DOEPCTL0 + DOEPCTL0 + OTGFS device OUT endpoint-0 control + register + 0x300 + 0x20 + 0x00008000 + + + MPS + Maximum packet size + 0 + 2 + read-only + + + USBACEPT + USB active endpoint + 15 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-only + + + SNP + Snoop mode + 20 + 1 + read-write + + + STALL + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DOEPCTL1 + DOEPCTL1 + OTGFS device OUT endpoint-1 control + register + 0x320 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-only + + + DPID + Endpoint data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-only + + + SNP + Snoop mode + 20 + 1 + read-write + + + STALL + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DOEPCTL2 + DOEPCTL2 + OTGFS device OUT endpoint-2 control + register + 0x340 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-only + + + DPID + Endpoint data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-only + + + SNP + Snoop mode + 20 + 1 + read-write + + + STALL + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DOEPCTL3 + DOEPCTL3 + OTGFS device OUT endpoint-3 control + register + 0x360 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-only + + + DPID + Endpoint data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-only + + + SNP + Snoop mode + 20 + 1 + read-write + + + STALL + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DOEPCTL4 + DOEPCTL4 + OTGFS device OUT endpoint-4 control + register + 0x380 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-only + + + DPID + Endpoint data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-only + + + SNP + Snoop mode + 20 + 1 + read-write + + + STALL + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DOEPCTL5 + DOEPCTL5 + OTGFS device OUT endpoint-5 control + register + 0x3A0 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-only + + + DPID + Endpoint data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-only + + + SNP + Snoop mode + 20 + 1 + read-write + + + STALL + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DOEPCTL6 + DOEPCTL6 + OTGFS device OUT endpoint-6 control + register + 0x3C0 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-only + + + DPID + Endpoint data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-only + + + SNP + Snoop mode + 20 + 1 + read-write + + + STALL + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DOEPCTL7 + DOEPCTL7 + OTGFS device OUT endpoint-7 control + register + 0x3E0 + 0x20 + 0x00000000 + + + MPS + Maximum packet size + 0 + 11 + read-write + + + USBACEPT + USB active endpoint + 15 + 1 + read-only + + + DPID + Endpoint data PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYPE + Endpoint type + 18 + 2 + read-only + + + SNP + Snoop mode + 20 + 1 + read-write + + + STALL + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + EPTDIS + Endpoint disable + 30 + 1 + read-write + + + EPTENA + Endpoint enable + 31 + 1 + read-write + + + + + DIEPINT0 + DIEPINT0 + OTGFS device IN endpoint-0 interrupt + register + 0x108 + 0x20 + 0x00000080 + + + XFERC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPTDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TIMEOUT + Timeout condition + 3 + 1 + read-write + + + INTKNTXFEMP + IN token received when + TxFIFO is empty + 4 + 1 + read-write + + + INEPTNAK + IN endpoint NAK + effective + 6 + 1 + read-write + + + TXFEMP + Transmit FIFO + empty + 7 + 1 + read-only + + + + + DIEPINT1 + DIEPINT1 + OTGFS device IN endpoint-1 interrupt + register + 0x128 + 0x20 + 0x00000080 + + + XFERC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPTDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TIMEOUT + Timeout condition + 3 + 1 + read-write + + + INTKNTXFEMP + IN token received when + TxFIFO is empty + 4 + 1 + read-write + + + INEPTNAK + IN endpoint NAK + effective + 6 + 1 + read-write + + + TXFEMP + Transmit FIFO + empty + 7 + 1 + read-only + + + + + DIEPINT2 + DIEPINT2 + OTGFS device IN endpoint-2 interrupt + register + 0x148 + 0x20 + 0x00000080 + + + XFERC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPTDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TIMEOUT + Timeout condition + 3 + 1 + read-write + + + INTKNTXFEMP + IN token received when + TxFIFO is empty + 4 + 1 + read-write + + + INEPTNAK + IN endpoint NAK + effective + 6 + 1 + read-write + + + TXFEMP + Transmit FIFO + empty + 7 + 1 + read-only + + + + + DIEPINT3 + DIEPINT3 + OTGFS device IN endpoint-3 interrupt + register + 0x168 + 0x20 + 0x00000080 + + + XFERC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPTDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TIMEOUT + Timeout condition + 3 + 1 + read-write + + + INTKNTXFEMP + IN token received when + TxFIFO is empty + 4 + 1 + read-write + + + INEPTNAK + IN endpoint NAK + effective + 6 + 1 + read-write + + + TXFEMP + Transmit FIFO + empty + 7 + 1 + read-only + + + + + DIEPINT4 + DIEPINT4 + OTGFS device IN endpoint-4 interrupt + register + 0x188 + 0x20 + 0x00000080 + + + XFERC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPTDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TIMEOUT + Timeout condition + 3 + 1 + read-write + + + INTKNTXFEMP + IN token received when + TxFIFO is empty + 4 + 1 + read-write + + + INEPTNAK + IN endpoint NAK + effective + 6 + 1 + read-write + + + TXFEMP + Transmit FIFO + empty + 7 + 1 + read-only + + + + + DIEPINT5 + DIEPINT5 + OTGFS device IN endpoint-5 interrupt + register + 0x1A8 + 0x20 + 0x00000080 + + + XFERC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPTDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TIMEOUT + Timeout condition + 3 + 1 + read-write + + + INTKNTXFEMP + IN token received when + TxFIFO is empty + 4 + 1 + read-write + + + INEPTNAK + IN endpoint NAK + effective + 6 + 1 + read-write + + + TXFEMP + Transmit FIFO + empty + 7 + 1 + read-only + + + + + DIEPINT6 + DIEPINT6 + OTGFS device IN endpoint-6 interrupt + register + 0x1C8 + 0x20 + 0x00000080 + + + XFERC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPTDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TIMEOUT + Timeout condition + 3 + 1 + read-write + + + INTKNTXFEMP + IN token received when + TxFIFO is empty + 4 + 1 + read-write + + + INEPTNAK + IN endpoint NAK + effective + 6 + 1 + read-write + + + TXFEMP + Transmit FIFO + empty + 7 + 1 + read-only + + + + + DIEPINT7 + DIEPINT7 + OTGFS device IN endpoint-7 interrupt + register + 0x1E8 + 0x20 + 0x00000080 + + + XFERC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPTDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TIMEOUT + Timeout condition + 3 + 1 + read-write + + + INTKNTXFEMP + IN token received when + TxFIFO is empty + 4 + 1 + read-write + + + INEPTNAK + IN endpoint NAK + effective + 6 + 1 + read-write + + + TXFEMP + Transmit FIFO + empty + 7 + 1 + read-only + + + + + DOEPINT0 + DOEPINT0 + OTGFS device OUT endpoint-0 interrupt + register + 0x308 + 0x20 + read-write + 0x00000080 + + + XFERC + Transfer completed interrupt + 0 + 1 + + + EPTDISD + Endpoint disabled interrupt + 1 + 1 + + + SETUP + SETUP phase done + 3 + 1 + + + OUTTEPD + OUT token received when + endpoint disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP + packets received + 6 + 1 + + + + + DOEPINT1 + DOEPINT1 + OTGFS device OUT endpoint-1 interrupt + register + 0x328 + 0x20 + read-write + 0x00000080 + + + XFERC + Transfer completed interrupt + 0 + 1 + + + EPTDISD + Endpoint disabled interrupt + 1 + 1 + + + SETUP + SETUP phase done + 3 + 1 + + + OUTTEPD + OUT token received when + endpoint disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP + packets received + 6 + 1 + + + + + DOEPINT2 + DOEPINT2 + OTGFS device OUT endpoint-2 interrupt + register + 0x348 + 0x20 + read-write + 0x00000080 + + + XFERC + Transfer completed interrupt + 0 + 1 + + + EPTDISD + Endpoint disabled interrupt + 1 + 1 + + + SETUP + SETUP phase done + 3 + 1 + + + OUTTEPD + OUT token received when + endpoint disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP + packets received + 6 + 1 + + + + + DOEPINT3 + DOEPINT3 + OTGFS device OUT endpoint-3 interrupt + register + 0x368 + 0x20 + read-write + 0x00000080 + + + XFERC + Transfer completed interrupt + 0 + 1 + + + EPTDISD + Endpoint disabled interrupt + 1 + 1 + + + SETUP + SETUP phase done + 3 + 1 + + + OUTTEPD + OUT token received when + endpoint disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP + packets received + 6 + 1 + + + + + DOEPINT4 + DOEPINT4 + OTGFS device OUT endpoint-4 interrupt + register + 0x388 + 0x20 + read-write + 0x00000080 + + + XFERC + Transfer completed interrupt + 0 + 1 + + + EPTDISD + Endpoint disabled interrupt + 1 + 1 + + + SETUP + SETUP phase done + 3 + 1 + + + OUTTEPD + OUT token received when + endpoint disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP + packets received + 6 + 1 + + + + + DOEPINT5 + DOEPINT5 + OTGFS device OUT endpoint-5 interrupt + register + 0x3A8 + 0x20 + read-write + 0x00000080 + + + XFERC + Transfer completed interrupt + 0 + 1 + + + EPTDISD + Endpoint disabled interrupt + 1 + 1 + + + SETUP + SETUP phase done + 3 + 1 + + + OUTTEPD + OUT token received when + endpoint disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP + packets received + 6 + 1 + + + + + DOEPINT6 + DOEPINT6 + OTGFS device OUT endpoint-6 interrupt + register + 0x3C8 + 0x20 + read-write + 0x00000080 + + + XFERC + Transfer completed interrupt + 0 + 1 + + + EPTDISD + Endpoint disabled interrupt + 1 + 1 + + + SETUP + SETUP phase done + 3 + 1 + + + OUTTEPD + OUT token received when + endpoint disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP + packets received + 6 + 1 + + + + + DOEPINT7 + DOEPINT7 + OTGFS device OUT endpoint-7 interrupt + register + 0x3E8 + 0x20 + read-write + 0x00000080 + + + XFERC + Transfer completed interrupt + 0 + 1 + + + EPTDISD + Endpoint disabled interrupt + 1 + 1 + + + SETUP + SETUP phase done + 3 + 1 + + + OUTTEPD + OUT token received when + endpoint disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP + packets received + 6 + 1 + + + + + DIEPTSIZ0 + DIEPTSIZ0 + OTGFS device IN endpoint-0 transfer size + register + 0x110 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 7 + + + PKTCNT + Packet count + 19 + 2 + + + + + DOEPTSIZ0 + DOEPTSIZ0 + OTGFS device OUT endpoint-0 transfer size + register + 0x310 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 7 + + + PKTCNT + Packet count + 19 + 1 + + + SETUPCNT + SETUP packet count + 29 + 2 + + + + + DIEPTSIZ1 + DIEPTSIZ1 + OTGFS device IN endpoint-1 transfer size + register + 0x130 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MC + Multi count + 29 + 2 + + + + + DIEPTSIZ2 + DIEPTSIZ2 + OTGFS device IN endpoint-2 transfer size + register + 0x150 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MC + Multi count + 29 + 2 + + + + + DIEPTSIZ3 + DIEPTSIZ3 + OTG device IN endpoint-3 transfer size + register + 0x170 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MC + Multi count + 29 + 2 + + + + + DIEPTSIZ4 + DIEPTSIZ4 + OTG device IN endpoint-4 transfer size + register + 0x190 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MC + Multi count + 29 + 2 + + + + + DIEPTSIZ5 + DIEPTSIZ5 + OTG device IN endpoint-5 transfer size + register + 0x1B0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MC + Multi count + 29 + 2 + + + + + DIEPTSIZ6 + DIEPTSIZ6 + OTG device IN endpoint-6 transfer size + register + 0x1D0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MC + Multi count + 29 + 2 + + + + + DIEPTSIZ7 + DIEPTSIZ7 + OTG device IN endpoint-7 transfer size + register + 0x1F0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MC + Multi count + 29 + 2 + + + + + DTXFSTS0 + DTXFSTS0 + OTGFS device IN endpoint-0 transmit FIFO + status register + 0x118 + 0x20 + read-only + 0x00000000 + + + INEPTXFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS1 + DTXFSTS1 + OTGFS device IN endpoint-1 transmit FIFO + status register + 0x138 + 0x20 + read-only + 0x00000000 + + + INEPTXFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS2 + DTXFSTS2 + OTGFS device IN endpoint-2 transmit FIFO + status register + 0x158 + 0x20 + read-only + 0x00000000 + + + INEPTXFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS3 + DTXFSTS3 + OTGFS device IN endpoint-3 transmit FIFO + status register + 0x178 + 0x20 + read-only + 0x00000000 + + + INEPTXFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS4 + DTXFSTS4 + OTGFS device IN endpoint-4 transmit FIFO + status register + 0x198 + 0x20 + read-only + 0x00000000 + + + INEPTXFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS5 + DTXFSTS5 + OTGFS device IN endpoint-5 transmit FIFO + status register + 0x1B8 + 0x20 + read-only + 0x00000000 + + + INEPTXFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS6 + DTXFSTS6 + OTGFS device IN endpoint-6 transmit FIFO + status register + 0x1D8 + 0x20 + read-only + 0x00000000 + + + INEPTXFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DTXFSTS7 + DTXFSTS7 + OTGFS device IN endpoint-7 transmit FIFO + status register + 0x1F8 + 0x20 + read-only + 0x00000000 + + + INEPTXFSAV + IN endpoint TxFIFO space + available + 0 + 16 + + + + + DOEPTSIZ1 + DOEPTSIZ1 + OTGFS device OUT endpoint-1 transfer size + register + 0x330 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID + Received data PID + 29 + 2 + + + + + DOEPTSIZ2 + DOEPTSIZ2 + OTGFS device OUT endpoint-2 transfer size + register + 0x350 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID + Received data PID + 29 + 2 + + + + + DOEPTSIZ3 + DOEPTSIZ3 + OTGFS device OUT endpoint-3 transfer size + register + 0x370 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID + Received data PID + 29 + 2 + + + + + DOEPTSIZ4 + DOEPTSIZ4 + OTGFS device OUT endpoint-4 transfer size + register + 0x390 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID + Received data PID + 29 + 2 + + + + + DOEPTSIZ5 + DOEPTSIZ5 + OTGFS device OUT endpoint-5 transfer size + register + 0x3B0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID + Received data PID + 29 + 2 + + + + + DOEPTSIZ6 + DOEPTSIZ6 + OTGFS device OUT endpoint-6 transfer size + register + 0x3D0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID + Received data PID + 29 + 2 + + + + + DOEPTSIZ7 + DOEPTSIZ7 + OTGFS device OUT endpoint-7 transfer size + register + 0x3F0 + 0x20 + read-write + 0x00000000 + + + XFERSIZE + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID + Received data PID + 29 + 2 + + + + + + + USB_OTG2_PWRCLK + USB on the go full speed + USB_OTG2 + 0x40040E00 + + 0x0 + 0x400 + registers + + + + PCGCCTL + PCGCCTL + OTGFS power and clock gating control + register (OTGFS_PCGCCTL) + 0x0 + 0x20 + 0x00000000 + + + STOPPCLK + Stop PHY clock + 0 + 1 + read-write + + + SUSPENDM + PHY Suspended + 4 + 1 + read-only + + + + + + + SCFG + System configuration controller + SCFG + 0x40013800 + + 0x0 + 0x400 + registers + + + + CFG1 + CFG1 + configuration register 1 + 0x0 + 0x20 + read-write + 0x00000000 + + + MEM_MAP_SEL + Memory address mapping selection bits + 0 + 3 + + + IR_POL + IR output polarity selection + 5 + 1 + + + IR_SRC_SEL + IR signal source selection + 6 + 2 + + + SWAP_XMC + XMC address mapping swap + 10 + 2 + + + + + CFG2 + CFG2 + configuration register 2 + 0x4 + 0x20 + read-write + 0x00000000 + + + MII_RMII_SEL + MII or RMII selection + bits + 23 + 1 + + + + + EXINTC1 + EXINTC1 + external interrupt configuration register 1 + 0x8 + 0x20 + read-write + 0x0000 + + + EXINT3 + EXINT 3 configuration bits + 12 + 4 + + + EXINT2 + EXINT 2 configuration bits + 8 + 4 + + + EXINT1 + EXINT 1 configuration bits + 4 + 4 + + + EXINT0 + EXINT 0 configuration bits + 0 + 4 + + + + + EXINTC2 + EXINTC2 + external interrupt configuration register 2 + 0xC + 0x20 + read-write + 0x0000 + + + EXINT7 + EXINT 7 configuration bits + 12 + 4 + + + EXINT6 + EXINT 6 configuration bits + 8 + 4 + + + EXINT5 + EXINT 5 configuration bits + 4 + 4 + + + EXINT4 + EXINT 4 configuration bits + 0 + 4 + + + + + EXINTC3 + EXINTC3 + external interrupt configuration register 3 + 0x10 + 0x20 + read-write + 0x0000 + + + EXINT11 + EXINT 11 configuration bits + 12 + 4 + + + EXINT10 + EXINT 10 configuration bits + 8 + 4 + + + EXINT9 + EXINT 9 configuration bits + 4 + 4 + + + EXINT8 + EXINT 8 configuration bits + 0 + 4 + + + + + EXINTC4 + EXINTC4 + external interrupt configuration register + 4 + 0x14 + 0x20 + read-write + 0x0000 + + + EXINT15 + EXINT 15 configuration bits + 12 + 4 + + + EXINT14 + EXINT 14 configuration bits + 8 + 4 + + + EXINT13 + EXINT 13 configuration bits + 4 + 4 + + + EXINT12 + EXINT 12 configuration bits + 0 + 4 + + + + + UHDRV + UHDRV + Ultra high drive register + 0x2C + 0x20 + read-write + 0x0000 + + + PF15_UH + PF15 ultra high sourcing/sinking strength + 10 + 1 + + + PF14_UH + PF14 ultra high sourcing/sinking strength + 9 + 1 + + + PD15_UH + PD15 ultra high sourcing/sinking strength + 8 + 1 + + + PD14_UH + PD14 ultra high sourcing/sinking strength + 7 + 1 + + + PD13_UH + PD13 ultra high sourcing/sinking strength + 6 + 1 + + + PD12_UH + PD12 ultra high sourcing/sinking strength + 5 + 1 + + + PB10_UH + PB10 ultra high sourcing/sinking strength + 2 + 1 + + + PB9_UH + PB9 ultra high sourcing/sinking strength + 1 + 1 + + + PB3_UH + PB3 ultra high sourcing/sinking strength + 0 + 1 + + + + + + + QSPI1 + Quad SPI Controller + QSPI + 0xA0001000 + + 0x0 + 0x400 + registers + + + QSPI1 + QSPI1 global interrupt + 92 + + + + CMD_W0 + CMD_W0 + Command word 0 + 0x0 + 0x20 + read-write + 0x00000000 + + + SPIADR + SPI flash address + 0 + 32 + + + + + CMD_W1 + CMD_W1 + Command word 1 + 0x4 + 0x20 + read-write + 0x01000003 + + + ADRLEN + SPI address length + 0 + 3 + + + DUM2 + Second dummy state cycle + 16 + 8 + + + INSLEN + Instruction code length + 24 + 2 + + + PEMEN + Perfrmance enhance mode enable + 28 + 1 + + + + + CMD_W2 + CMD_W2 + Command word 2 + 0x8 + 0x20 + read-write + 0x01000003 + + + DCNT + Read write data counter + 0 + 32 + + + + + CMD_W3 + CMD_W3 + Command word 3 + 0xC + 0x20 + read-write + 0x00000000 + + + WEN + Write data enable + 1 + 1 + + + RSTSEN + Read spi status enable + 2 + 1 + + + RSTSC + Read spi status configure + 3 + 1 + + + OPMODE + SPI operate mode + 5 + 3 + + + PEMOPC + Performance enhance mode operate code + 16 + 8 + + + INSC + Instruction code + 24 + 8 + + + + + CTRL + CTRL + Control register + 0x10 + 0x20 + read-write + 0x00000000 + + + CLKDIV + SPI clock divider + 0 + 3 + + + SCKMODE + Sckout mode + 4 + 1 + + + XIPIDLE + XIP port idle status + 7 + 1 + + + ABORT + Abort instruction + 8 + 1 + + + BUSY + Busy bit of spi status + 16 + 3 + + + XIPRCMDF + XIP read command flush + 19 + 1 + + + XIPSEL + XIP port selection + 20 + 1 + + + KEYEN + encryption key enable + 21 + 1 + + + + + ACTR + ACTR + AC timing control register + 0x14 + 0x20 + read-write + 0x0000000F + + + CSDLY + CS delay + 0 + 4 + + + + + FIFOSTS + FIFOSTS + FIFO Status register + 0x18 + 0x20 + read-only + 0x00000001 + + + TXFIFORDY + TxFIFO ready status + 0 + 1 + + + RXFIFORDY + RxFIFO ready status + 1 + 1 + + + + + CTRL2 + CTRL2 + control register 2 + 0x20 + 0x20 + read-write + 0x00000001 + + + DMAEN + DMA handshake enable + 0 + 1 + + + CMDIE + Command complete interrupt enable + 1 + 1 + + + TXFIFOTHOD + TxFIFO thod + 8 + 2 + + + RXFIFOTHOD + RxFIFO thod + 12 + 2 + + + + + CMDSTS + CMDSTS + CMD status register + 0x24 + 0x20 + read-only + 0x00000000 + + + CMDSTS + Command complete status + 0 + 1 + + + + + RSTS + RSTS + SPI read status register + 0x28 + 0x20 + read-only + 0x00000000 + + + SPISTS + SPI read status + 0 + 8 + + + + + FSIZE + FSIZE + SPI flash size + 0x2C + 0x20 + read-write + 0x00000000 + + + SPIFSIZE + SPI flash size + 0 + 32 + + + + + XIP_CMD_W0 + XIP_CMD_W0 + XIP command word 0 + 0x30 + 0x20 + read-write + 0x00000000 + + + XIPR_DUM2 + XIP read second dummy cycle + 0 + 8 + + + XIPR_OPMODE + XIP read operate mode + 8 + 3 + + + XIPR_ADRLEN + XIP read address length + 11 + 1 + + + XIPR_INSC + XIP read instruction code + 12 + 8 + + + + + XIP_CMD_W1 + XIP_CMD_W1 + XIP command word 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + XIPW_DUM2 + XIP write second dummy cycle + 0 + 8 + + + XIPW_OPMODE + XIP write operate mode + 8 + 3 + + + XIPW_ADRLEN + XIP write address length + 11 + 1 + + + XIPW_INSC + XIP write instruction code + 12 + 8 + + + + + XIP_CMD_W2 + XIP_CMD_W2 + XIP command word 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + XIPR_DCNT + XIP read data counter + 0 + 6 + + + XIPR_TCNT + XIP continue read cycle counter + 8 + 7 + + + XIPR_SEL + XIP read continue mode select + 15 + 1 + + + XIPW_DCNT + XIP write data counter + 16 + 6 + + + XIPW_TCNT + XIP continue write cycle counter + 24 + 7 + + + XIPW_SEL + XIP write continue mode select + 31 + 1 + + + + + XIP_CMD_W3 + XIP_CMD_W3 + XIP command word 3 + 0x3C + 0x20 + read-write + 0x00000000 + + + BYPASSC + Bypass cache function + 0 + 1 + + + CSTS + Cache status + 3 + 1 + + + + + REV + REV + Revision + 0x50 + 0x20 + read-write + 0x00010500 + + + REVISION + Revision number + 0 + 31 + + + + + DT + DT + 32/16/8 bit data port register + 0x100 + 0x20 + read-write + 0x00000000 + + + + + QSPI2 + 0xA0002000 + + QSPI2 + QSPI2 global interrupt + 91 + + + + ETHERNET_MAC + Ethernet: media access control + ETHERNET + 0x40028000 + + 0x0 + 0x100 + registers + + + EMAC + Ethernet mac global interrupt + 61 + + + + MACCTRL + MACCTRL + Ethernet MAC configuration register + 0x0 + 0x20 + read-write + 0x00008000 + + + RE + Receiver enable + 2 + 1 + + + TE + Transmitter enable + 3 + 1 + + + DC + Deferral check + 4 + 1 + + + BL + Back-off limit + 5 + 2 + + + ACS + Automatic pad/CRC + stripping + 7 + 1 + + + DR + Disable retry + 9 + 1 + + + IPC + IPv4 checksum offload + 10 + 1 + + + DM + Duplex mode + 11 + 1 + + + LM + Loopback mode + 12 + 1 + + + DRO + Disable receive own + 13 + 1 + + + FES + Fast EMAC speed + 14 + 1 + + + DCS + Disable carrier sense + 16 + 1 + + + IFG + Interframe gap + 17 + 3 + + + JD + Jabber disable + 22 + 1 + + + WD + Watchdog disable + 23 + 1 + + + + + MACFRMF + MACFRMF + Ethernet MAC frame filter register + 0x4 + 0x20 + read-write + 0x00000000 + + + PR + Promiscuous mode + 0 + 1 + + + HUC + Hash unicast + 1 + 1 + + + HMC + Hash multicast + 2 + 1 + + + DAIF + Destination address inverse + filtering + 3 + 1 + + + PMC + Pass multicast + 4 + 1 + + + DBF + Disable broadcast frames + 5 + 1 + + + PCF + Pass control frames + 6 + 2 + + + SAIF + Source address inverse + filtering + 8 + 1 + + + SAF + Source address filter + 9 + 1 + + + HPF + Hash or perfect filter + 10 + 1 + + + RA + Receive all + 31 + 1 + + + + + MACHTH + MACHTH + Ethernet MAC hash table high register + 0x8 + 0x20 + read-write + 0x00000000 + + + HTH + Hash table high + 0 + 32 + + + + + MACHTL + MACHTL + Ethernet MAC hash table low register + 0xC + 0x20 + read-write + 0x00000000 + + + HTL + Hash table low + 0 + 32 + + + + + MACMIIADDR + MACMIIADDR + Ethernet MAC MII address register + 0x10 + 0x20 + read-write + 0x00000000 + + + MB + MII busy + 0 + 1 + + + MW + MII write + 1 + 1 + + + CR + Clock range + 2 + 3 + + + MII + MII register + 6 + 5 + + + PA + PHY address + 11 + 5 + + + + + MACMIIDT + MACMIIDT + Ethernet MAC MII data register + 0x14 + 0x20 + read-write + 0x00000000 + + + MD + MII data + 0 + 16 + + + + + MACFCTRL + MACFCTRL + Ethernet MAC flow control register + 0x18 + 0x20 + read-write + 0x00000000 + + + FCB_BPA + Flow control busy/back pressure + activate + 0 + 1 + + + ETF + Enable transmit flow control + + 1 + 1 + + + ERF + Enable receive flow control + + 2 + 1 + + + DUP + Detect unicast pause frame + 3 + 1 + + + PLT + Pause low threshold + 4 + 2 + + + DZQP + Disable zero-quanta pause + 7 + 1 + + + PT + Pass time + 16 + 16 + + + + + MACVLT + MACVLT + Ethernet MAC VLAN tag register + 0x1C + 0x20 + read-write + 0x00000000 + + + VTI + VLAN tag identifier (for receive + frames) + 0 + 16 + + + ETV + Enable 12-bit VLAN tag comparison + 16 + 1 + + + + + MACRWFF + MACRWFF + Ethernet MAC remote wakeup frame filter register + 0x28 + 0x20 + read-write + 0x00000000 + + + MACPMTCTRLSTS + MACPMTCTRLSTS + Ethernet MAC PMT control and status register + 0x2C + 0x20 + read-write + 0x00000000 + + + PD + Power down + 0 + 1 + + + EMP + Enable magic packet + 1 + 1 + + + ERWF + Enable remote wakeup frame + 2 + 1 + + + RMP + Received magic packet + 5 + 1 + + + RRWF + Recevied remote wakeup frame + 6 + 1 + + + GUC + Global unicast + 9 + 1 + + + RWFFPR + Remote wakeup frame filter register pointer + reset + 31 + 1 + + + + + MACISTS + MACISTS + Ethernet MAC interrupt status register + 0x38 + 0x20 + read-write + 0x00000000 + + + PIS + PMT interrupt status + 3 + 1 + + + MIS + MMC interrupt status + 4 + 1 + + + MRIS + MMC receive interrupt status + 5 + 1 + + + MTIS + MMC transmit interrupt status + 6 + 1 + + + TIS + Timestamp interrupt status + 9 + 1 + + + + + MACIMR + MACIMR + Ethernet MAC interrupt mask register + 0x3C + 0x20 + read-write + 0x00000000 + + + PIM + PMT interrupt mask + 3 + 1 + + + TIM + Timestamp interrupt mask + 9 + 1 + + + + + MACA0H + MACA0H + Ethernet MAC address 0 high register + 0x40 + 0x20 + 0x0010FFFF + + + MA0H + MAC address0 high + 0 + 16 + read-write + + + AE + Address enable + 31 + 1 + read-only + + + + + MACA0L + MACA0L + Ethernet MAC address 0 low register + 0x44 + 0x20 + read-write + 0xFFFFFFFF + + + MA0L + MAC address0 low + 0 + 32 + + + + + MACA1H + MACA1H + Ethernet MAC address 1 high register + 0x48 + 0x20 + read-write + 0x0000FFFF + + + MA1H + MAC address1 high + 0 + 16 + + + MBC + Mask byte control + 24 + 6 + + + SA + Source address + 30 + 1 + + + AE + Address enable + 31 + 1 + + + + + MACA1L + MACA1L + Ethernet MAC address1 low register + 0x4C + 0x20 + read-write + 0xFFFFFFFF + + + MA1L + MAC address1 low + 0 + 32 + + + + + MACA2H + MACA2H + Ethernet MAC address 2 high register + 0x50 + 0x20 + read-write + 0x0050 + + + MA2H + MAC address 2 high + 0 + 16 + + + MBC + Mask byte control + 24 + 6 + + + SA + Source address + 30 + 1 + + + AE + Address enable + 31 + 1 + + + + + MACA2L + MACA2L + Ethernet MAC address 2 low register + 0x54 + 0x20 + read-write + 0xFFFFFFFF + + + MA2L + MAC address2 low + 0 + 31 + + + + + MACA3H + MACA3H + Ethernet MAC address 3 high register + 0x58 + 0x20 + read-write + 0x0000FFFF + + + MA3H + MAC address3 high + 0 + 16 + + + MBC + Mask byte control + 24 + 6 + + + SA + Source address + 30 + 1 + + + AE + Address enable + 31 + 1 + + + + + MACA3L + MACA3L + Ethernet MAC address 3 low register + 0x5C + 0x20 + read-write + 0xFFFFFFFF + + + MA3L + MAC address3 low + 0 + 32 + + + + + + + ETHERNET_MMC + Ethernet: MAC management counters + ETHERNET + 0x40028100 + + 0x0 + 0x100 + registers + + + + MMCCTRL + MMCCTRL + Ethernet MMC control register + 0x0 + 0x20 + read-write + 0x00000000 + + + RC + Reset counter + 0 + 1 + + + SCR + Stop counter rollover + 1 + 1 + + + RR + Reset on read + 2 + 1 + + + FMC + Freeze MMC counter + 31 + 1 + + + + + MMCRI + MMCRI + Ethernet MMC receive interrupt register + 0x4 + 0x20 + read-write + 0x00000000 + + + RFCE + Received frames CRC error + 5 + 1 + + + RFAE + Received frames alignment error + 6 + 1 + + + RGUF + Received good unicast frames + 17 + 1 + + + + + MMCTI + MMCTI + Ethernet MMC transmit interrupt register + 0x8 + 0x20 + read-write + 0x00000000 + + + TSCGFCI + Transmit single collision good frame + counter interrupt + 14 + 1 + + + TGFMSC + Transmit good frames more single + collision + 15 + 1 + + + TGF + Transmitted good frames + 21 + 1 + + + + + MMCRIM + MMCRIM + Ethernet MMC receive interrupt mask register + 0xC + 0x20 + read-write + 0x00000000 + + + RCEFCIM + Received CRC error frame counter interrupt + mask + 5 + 1 + + + RAEFACIM + Received alignment error frame alignment + counter interrupt mask + 6 + 1 + + + RUGFCIM + Received unicast good frame counter + interrupt mask + 17 + 1 + + + + + MMCTIM + MMCTIM + Ethernet MMC transmit interrupt mask register + 0x10 + 0x20 + read-write + 0x00000000 + + + TSCGFCIM + Transmit single collision good frame + counter interrupt mask + 14 + 1 + + + TMCGFCIM + Transmit multiple collision good frame + counter interrupt mask + 15 + 1 + + + TGFCIM + Transmitted good frame counter interrupt + mask + 21 + 1 + + + + + MMCTFSCC + MMCTFSCC + Ethernet MMC transmitted good frames after a single collision counter + 0x4C + 0x20 + read-only + 0x00000000 + + + TGFSCC + Transmitted good frames single + collision counter + 0 + 32 + + + + + MMCTFMSCC + MMCTFMSCC + Ethernet MMC transmitted good frames after more than a single collision + 0x50 + 0x20 + read-only + 0x00000000 + + + TGFMSCC + Transmitted good frame more single + collision counter + 0 + 32 + + + + + MMCTFCNT + MMCTFCNT + Ethernet MMC transmitted good frames counter register + 0x68 + 0x20 + read-only + 0x00000000 + + + TGFC + Transmitted good frames + counter + 0 + 32 + + + + + MMCRFCECNT + MMCRFCECNT + Ethernet MMC received frames with CRC error counter register + 0x94 + 0x20 + read-only + 0x00000000 + + + RFCEC + Received frames CRC error counter + 0 + 32 + + + + + MMCRFAECNT + MMCRFAECNT + Ethernet MMC received frames with alignment error counter register + 0x98 + 0x20 + read-only + 0x00000000 + + + RFAEC + Received frames alignment error counter + 0 + 32 + + + + + MMCRGUFCNT + MMCRGUFCNT + MMC received good unicast frames counter register + 0xC4 + 0x20 + read-only + 0x00000000 + + + RGUFC + Received good unicast frames + counter + 0 + 32 + + + + + + + ETHERNET_PTP + Ethernet: Precision time protocol + ETHERNET + 0x40028700 + + 0x0 + 0x100 + registers + + + + PTPTSCTRL + PTPTSCTRL + Ethernet PTP time stamp control register + 0x0 + 0x20 + read-write + 0x2000 + + + TE + Timestamp enable + 0 + 1 + + + TFCU + Timestamp fine or coarse + update + 1 + 1 + + + TI + Timestamp initialize + 2 + 1 + + + TU + Timestamp update + 3 + 1 + + + TITE + Timestamp interrupt trigger + enable + 4 + 1 + + + ARU + Addend register update + 5 + 1 + + + ETAF + Enable timestamp for all frames + 8 + 1 + + + TDBRC + Timestamp digital or binary + rollover control + 9 + 1 + + + EPPV2F + Enable PTP packet processing for + version2 format + 10 + 1 + + + EPPEF + Enable processing of PTP + over EMAC frames + 11 + 1 + + + EPPFSIP6U + Enable processing of PTP frames + sent over IPv6-UDP + 12 + 1 + + + EPPFSIP4U + Enable processing of PTP frames + sent over IPv4-UDP + 13 + 1 + + + ETSFEM + Enable timestamp snapshot for + event message + 14 + 1 + + + ESFMRTM + Enable snapshot for message + relevant to master + 15 + 1 + + + SPPFTS + Select PTP packet for taking snapshot + 16 + 2 + + + EMAFPFF + Enable MAC address for PTP frame filtering + 18 + 1 + + + + + PTPSSINC + PTPSSINC + Ethernet PTP subsecond increment register + 0x4 + 0x20 + read-write + 0x00000000 + + + SSIV + Sub-second increment value + 0 + 8 + + + + + PTPTSH + PTPTSH + Ethernet PTP time stamp high register + 0x8 + 0x20 + read-only + 0x00000000 + + + TS + Timestamp second + 0 + 32 + + + + + PTPTSL + PTPTSL + Ethernet PTP time stamp low register + 0xC + 0x20 + read-only + 0x00000000 + + + TSS + Timestamp subseconds + 0 + 31 + + + AST + Add or subtract time + 31 + 1 + + + + + PTPTSHUD + PTPTSHUD + Ethernet PTP time stamp high update register + 0x10 + 0x20 + read-write + 0x00000000 + + + TS + Timestamp second + 0 + 32 + + + + + PTPTSLUD + PTPTSLUD + Ethernet PTP time stamp low update register + 0x14 + 0x20 + read-write + 0x00000000 + + + TSS + Timestamp subseconds + 0 + 31 + + + AST + Add or subtract time + 31 + 1 + + + + + PTPTSAD + PTPTSAD + Ethernet PTP time stamp addend register + 0x18 + 0x20 + read-write + 0x00000000 + + + TAR + Timestamp addend register + 0 + 32 + + + + + PTPTTH + PTPTTH + Ethernet PTP target time high register + 0x1C + 0x20 + read-write + 0x00000000 + + + TTSR + Target time seconds register + 0 + 32 + + + + + PTPTTL + PTPTTL + Ethernet PTP target time low register + 0x20 + 0x20 + read-write + 0x00000000 + + + TTLR + Target timestamp low register + 0 + 32 + + + + + PTPTSSR + PTPTSSR + Ethernet PTP time stamp status register + 0x28 + 0x20 + read-only + 0x00000000 + + + TSO + Timestamp second overflow + 0 + 1 + + + TTTR + Timestamp target time reached + 1 + 1 + + + + + PTPPPSCR + PTPPPSCR + Ethernet PTP PPS control register + 0x2C + 0x20 + read-only + 0x00000000 + + + POFC + PPS Output frequency control + 0 + 4 + + + + + + + ETHERNET_DMA + Ethernet: DMA controller operation + ETHERNET + 0x40029000 + + 0x0 + 0x100 + registers + + + + DMABM + DMABM + Ethernet DMA bus mode register + 0x0 + 0x20 + read-write + 0x20101 + + + SWR + Software reset + 0 + 1 + + + DA + DMA Arbitration + 1 + 1 + + + DSL + Descriptor skip length + 2 + 5 + + + PBL + Programmable burst length + 8 + 6 + + + PR + Priority ratio + 14 + 2 + + + FB + Fixed burst + 16 + 1 + + + RDP + Rx DMA PBL + 17 + 6 + + + USP + Use separate PBL + 23 + 1 + + + PBLx8 + PNLx8 mode + 24 + 1 + + + AAB + Address-aligned beats + 25 + 1 + + + + + DMATPD + DMATPD + Ethernet DMA transmit poll demand register + 0x4 + 0x20 + read-write + 0x00000000 + + + TPD + Transmit poll demand + 0 + 32 + + + + + DMARPD + DMARPD + EHERNET DMA receive poll demand register + 0x8 + 0x20 + read-write + 0x00000000 + + + RPD + Receive poll demand + 0 + 32 + + + + + DMARDLADDR + DMARDLADDR + Ethernet DMA receive descriptor list address register + 0xC + 0x20 + read-write + 0x00000000 + + + SRL + Start of receive list + 0 + 32 + + + + + DMATDLADDR + DMATDLADDR + Ethernet DMA transmit descriptor list address register + 0x10 + 0x20 + read-write + 0x00000000 + + + STL + Start of transmit list + 0 + 32 + + + + + DMASTS + DMASTS + Ethernet DMA status register + 0x14 + 0x20 + 0x00000000 + + + TI + Transmit interrupt + 0 + 1 + read-write + + + TPS + Transmit process stopped + 1 + 1 + read-write + + + TBU + Transmit buffer unavailable + 2 + 1 + read-write + + + TJT + Transmit jabber timeout + 3 + 1 + read-write + + + OVF + Receive overflow + 4 + 1 + read-write + + + UNF + Transmit underflow + 5 + 1 + read-write + + + RI + Receive interrupt + 6 + 1 + read-write + + + RBU + Receive buffer unavailable + 7 + 1 + read-write + + + RPS + Receive process stopped + 8 + 1 + read-write + + + RWT + Receive watchdog timeout + 9 + 1 + read-write + + + ETI + Early transmit interrupt + 10 + 1 + read-write + + + FBEI + Fatal bus error interrupt + 13 + 1 + read-write + + + ERI + Early receive interrupt + 14 + 1 + read-write + + + AIS + Abnormal interrupt summary + 15 + 1 + read-write + + + NIS + Normal interrupt summary + 16 + 1 + read-write + + + RS + Receive process state + 17 + 3 + read-only + + + TS + Transmit process state + 20 + 3 + read-only + + + EB + Error bits + 23 + 3 + read-only + + + MMI + MAC MMC interrupt + 27 + 1 + read-only + + + MPI + MAC PMT interrupt + 28 + 1 + read-only + + + TTI + Timestamp trigger interrupt + 29 + 1 + read-only + + + + + DMAOPM + DMAOPM + Ethernet DMA operation mode register + 0x18 + 0x20 + read-write + 0x00000000 + + + SSR + Start or stop receive + 1 + 1 + + + OSF + Operate on second frame + 2 + 1 + + + RTC + Receive threshold control + 3 + 2 + + + FUGF + Forward undersized good frames + 6 + 1 + + + FEF + Forward error frames + 7 + 1 + + + SSTC + Start of stop transmission command + 13 + 1 + + + TTC + Transmit threshold control + 14 + 3 + + + FTF + Flush transmit FIFO + 20 + 1 + + + TSF + Transmit store and forward + 21 + 1 + + + DFRF + Disable flushing of received + frames + 24 + 1 + + + RSF + Receive store and forward + 25 + 1 + + + DT + Disable dropping of TCP/IP + checksum error frames + 26 + 1 + + + + + DMAIE + DMAIE + Ethernet DMA interrupt enable register + 0x1C + 0x20 + read-write + 0x00000000 + + + TIE + Transmit interrupt enable + 0 + 1 + + + TSE + Transmit stopped enable + 1 + 1 + + + TUE + Transmit buffer unavailable enable + 2 + 1 + + + TJE + Transmit jabber timeout enable + 3 + 1 + + + OVE + Overflow interrupt enable + 4 + 1 + + + UNE + Underflow interrupt enable + 5 + 1 + + + RIE + Receive interrupt enable + 6 + 1 + + + RBUE + Receive buffer unavailable enable + 7 + 1 + + + RSE + Receive stopped enable + 8 + 1 + + + RWTE + receive watchdog timeout enable + 9 + 1 + + + EIE + Early transmit interrupt enable + 10 + 1 + + + FBEE + Fatal bus error enable + 13 + 1 + + + ERE + Early receive interrupt + enable + 14 + 1 + + + AIE + Abnormal interrupt enable + 15 + 1 + + + NIE + Normal interrupt enable + 16 + 1 + + + + + DMAMFBOCNT + DMAMFBOCNT + Ethernet DMA missed frame and buffer overflow counter register + 0x20 + 0x20 + read-only + 0x00000000 + + + MFC + Missed frames control + 0 + 16 + + + OBMFC + Overflow bit for missed frame + counter + 16 + 1 + + + OFC + Overflow frame counter + 17 + 11 + + + OBFOC + Overflow bit for FIFO overflow + counter + 28 + 1 + + + + + DMACTD + DMACTD + Ethernet DMA current host transmit descriptor register + 0x48 + 0x20 + read-only + 0x00000000 + + + HTDAP + Host transmit descriptor address pointer + 0 + 32 + + + + + DMACRD + DMACRD + Ethernet DMA current host receive descriptor register + 0x4C + 0x20 + read-only + 0x00000000 + + + HRDAP + Host receive descriptor address pointer + 0 + 32 + + + + + DMACTBADDR + DMACTBADDR + Ethernet DMA current host transmit buffer address register + 0x50 + 0x20 + read-only + 0x00000000 + + + HTBAP + Host transmit buffer address pointer + 0 + 32 + + + + + DMACRBADDR + DMACRBADDR + Ethernet DMA current host receive buffer address register + 0x54 + 0x20 + read-only + 0x00000000 + + + HRBAP + Host receive buffer address pointer + 0 + 32 + + + + + + + diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_acc.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_acc.h new file mode 100644 index 0000000000..aa3c70d768 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_acc.h @@ -0,0 +1,205 @@ +/** + ************************************************************************** + * @file at32f435_437_acc.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 acc header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_ACC_H +#define __AT32F435_437_ACC_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup ACC + * @{ + */ + +/** @defgroup ACC_exported_constants + * @{ + */ + +#define ACC_CAL_HICKCAL ((uint16_t)0x0000) /*!< acc hick calibration */ +#define ACC_CAL_HICKTRIM ((uint16_t)0x0002) /*!< acc hick trim */ + +#define ACC_RSLOST_FLAG ((uint16_t)0x0002) /*!< acc reference signal lost error flag */ +#define ACC_CALRDY_FLAG ((uint16_t)0x0001) /*!< acc internal high-speed clock calibration ready error flag */ + +#define ACC_CALRDYIEN_INT ((uint16_t)0x0020) /*!< acc internal high-speed clock calibration ready interrupt enable */ +#define ACC_EIEN_INT ((uint16_t)0x0010) /*!< acc reference signal lost interrupt enable */ + +#define ACC_SOF_OTG1 ((uint16_t)0x0000) /*!< acc sof signal select: otg1 */ +#define ACC_SOF_OTG2 ((uint16_t)0x0004) /*!< acc sof signal select: otg2 */ + +/** + * @} + */ + +/** @defgroup ACC_exported_types + * @{ + */ + +/** + * @brief type define acc register all + */ +typedef struct +{ + + /** + * @brief acc sts register, offset:0x00 + */ + union + { + __IO uint32_t sts; + struct + { + __IO uint32_t calrdy : 1; /* [0] */ + __IO uint32_t rslost : 1; /* [1] */ + __IO uint32_t reserved1 : 30;/* [31:2] */ + } sts_bit; + }; + + /** + * @brief acc ctrl1 register, offset:0x04 + */ + union + { + __IO uint32_t ctrl1; + struct + { + __IO uint32_t calon : 1; /* [0] */ + __IO uint32_t entrim : 1; /* [1] */ + __IO uint32_t reserved1 : 2; /* [3:2] */ + __IO uint32_t eien : 1; /* [4] */ + __IO uint32_t calrdyien : 1; /* [5] */ + __IO uint32_t reserved2 : 2; /* [7:6] */ + __IO uint32_t step : 4; /* [11:8] */ + __IO uint32_t reserved3 : 20;/* [31:12] */ + } ctrl1_bit; + }; + + /** + * @brief acc ctrl2 register, offset:0x08 + */ + union + { + __IO uint32_t ctrl2; + struct + { + __IO uint32_t hickcal : 8; /* [7:0] */ + __IO uint32_t hicktrim : 6; /* [13:8] */ + __IO uint32_t reserved1 : 18;/* [31:14] */ + } ctrl2_bit; + }; + + /** + * @brief acc acc_c1 register, offset:0x0C + */ + union + { + __IO uint32_t c1; + struct + { + __IO uint32_t c1 : 16;/* [15:0] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } c1_bit; + }; + + /** + * @brief acc acc_c2 register, offset:0x10 + */ + union + { + __IO uint32_t c2; + struct + { + __IO uint32_t c2 : 16;/* [15:0] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } c2_bit; + }; + + /** + * @brief acc acc_c3 register, offset:0x14 + */ + union + { + __IO uint32_t c3; + struct + { + __IO uint32_t c3 : 16;/* [15:0] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } c3_bit; + }; +} acc_type; + +/** + * @} + */ + +#define ACC ((acc_type *) ACC_BASE) + +/** @defgroup ACC_exported_functions + * @{ + */ + +void acc_calibration_mode_enable(uint16_t acc_trim, confirm_state new_state); +void acc_step_set(uint8_t step_value); +void acc_sof_select(uint16_t sof_sel); +void acc_interrupt_enable(uint16_t acc_int, confirm_state new_state); +uint8_t acc_hicktrim_get(void); +uint8_t acc_hickcal_get(void); +void acc_write_c1(uint16_t acc_c1_value); +void acc_write_c2(uint16_t acc_c2_value); +void acc_write_c3(uint16_t acc_c3_value); +uint16_t acc_read_c1(void); +uint16_t acc_read_c2(void); +uint16_t acc_read_c3(void); +flag_status acc_flag_get(uint16_t acc_flag); +void acc_flag_clear(uint16_t acc_flag); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_adc.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_adc.h new file mode 100644 index 0000000000..1232495c8e --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_adc.h @@ -0,0 +1,938 @@ +/** + ************************************************************************** + * @file at32f435_437_adc.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 adc header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_ADC_H +#define __AT32F435_437_ADC_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup ADC + * @{ + */ + +/** @defgroup ADC_interrupts_definition + * @brief adc interrupt + * @{ + */ + +#define ADC_OCCE_INT ((uint32_t)0x00000020) /*!< ordinary channels conversion end interrupt */ +#define ADC_VMOR_INT ((uint32_t)0x00000040) /*!< voltage monitoring out of range interrupt */ +#define ADC_PCCE_INT ((uint32_t)0x00000080) /*!< preempt channels conversion end interrupt */ +#define ADC_OCCO_INT ((uint32_t)0x04000000) /*!< ordinary channel conversion overflow interrupt */ + +/** + * @} + */ + +/** @defgroup ADC_flags_definition + * @brief adc flag + * @{ + */ + +#define ADC_VMOR_FLAG ((uint8_t)0x01) /*!< voltage monitoring out of range flag */ +#define ADC_OCCE_FLAG ((uint8_t)0x02) /*!< ordinary channels conversion end flag */ +#define ADC_PCCE_FLAG ((uint8_t)0x04) /*!< preempt channels conversion end flag */ +#define ADC_PCCS_FLAG ((uint8_t)0x08) /*!< preempt channel conversion start flag */ +#define ADC_OCCS_FLAG ((uint8_t)0x10) /*!< ordinary channel conversion start flag */ +#define ADC_OCCO_FLAG ((uint8_t)0x20) /*!< ordinary channel conversion overflow flag */ +#define ADC_RDY_FLAG ((uint8_t)0x40) /*!< adc ready to conversion flag */ + +/** + * @} + */ + +/** @defgroup ADC_exported_types + * @{ + */ + +/** + * @brief adc division type + */ +typedef enum +{ + ADC_HCLK_DIV_2 = 0x00, /*!< adcclk is hclk/2 */ + ADC_HCLK_DIV_3 = 0x01, /*!< adcclk is hclk/3 */ + ADC_HCLK_DIV_4 = 0x02, /*!< adcclk is hclk/4 */ + ADC_HCLK_DIV_5 = 0x03, /*!< adcclk is hclk/5 */ + ADC_HCLK_DIV_6 = 0x04, /*!< adcclk is hclk/6 */ + ADC_HCLK_DIV_7 = 0x05, /*!< adcclk is hclk/7 */ + ADC_HCLK_DIV_8 = 0x06, /*!< adcclk is hclk/8 */ + ADC_HCLK_DIV_9 = 0x07, /*!< adcclk is hclk/9 */ + ADC_HCLK_DIV_10 = 0x08, /*!< adcclk is hclk/10 */ + ADC_HCLK_DIV_11 = 0x09, /*!< adcclk is hclk/11 */ + ADC_HCLK_DIV_12 = 0x0A, /*!< adcclk is hclk/12 */ + ADC_HCLK_DIV_13 = 0x0B, /*!< adcclk is hclk/13 */ + ADC_HCLK_DIV_14 = 0x0C, /*!< adcclk is hclk/14 */ + ADC_HCLK_DIV_15 = 0x0D, /*!< adcclk is hclk/15 */ + ADC_HCLK_DIV_16 = 0x0E, /*!< adcclk is hclk/16 */ + ADC_HCLK_DIV_17 = 0x0F /*!< adcclk is hclk/17 */ +} adc_div_type; + +/** + * @brief adc combine mode type + */ +typedef enum +{ + ADC_INDEPENDENT_MODE = 0x00, /*!< independent mode */ + ADC_ORDINARY_SMLT_PREEMPT_SMLT_ONESLAVE_MODE = 0x01, /*!< single slaver combined ordinary simultaneous + preempt simultaneous mode */ + ADC_ORDINARY_SMLT_PREEMPT_INTERLTRIG_ONESLAVE_MODE = 0x02, /*!< single slaver combined ordinary simultaneous + preempt interleaved trigger mode */ + ADC_PREEMPT_SMLT_ONLY_ONESLAVE_MODE = 0x05, /*!< single slaver preempt simultaneous mode only */ + ADC_ORDINARY_SMLT_ONLY_ONESLAVE_MODE = 0x06, /*!< single slaver ordinary simultaneous mode only */ + ADC_ORDINARY_SHIFT_ONLY_ONESLAVE_MODE = 0x07, /*!< single slaver ordinary shifting mode only */ + ADC_PREEMPT_INTERLTRIG_ONLY_ONESLAVE_MODE = 0x09, /*!< single slaver preempt interleaved trigger mode only */ + ADC_ORDINARY_SMLT_PREEMPT_SMLT_TWOSLAVE_MODE = 0x11, /*!< double slaver combined ordinary simultaneous + preempt simultaneous mode */ + ADC_ORDINARY_SMLT_PREEMPT_INTERLTRIG_TWOSLAVE_MODE = 0x12, /*!< double slaver combined ordinary simultaneous + preempt interleaved trigger mode */ + ADC_PREEMPT_SMLT_ONLY_TWOSLAVE_MODE = 0x15, /*!< double slaver preempt simultaneous mode only */ + ADC_ORDINARY_SMLT_ONLY_TWOSLAVE_MODE = 0x16, /*!< double slaver ordinary simultaneous mode only */ + ADC_ORDINARY_SHIFT_ONLY_TWOSLAVE_MODE = 0x17, /*!< double slaver ordinary shifting mode only */ + ADC_PREEMPT_INTERLTRIG_ONLY_TWOSLAVE_MODE = 0x19 /*!< double slaver preempt interleaved trigger mode only */ +} adc_combine_mode_type; + +/** + * @brief adc common dma mode type + */ +typedef enum +{ + ADC_COMMON_DMAMODE_DISABLE = 0x00, /*!< dma mode disabled */ + ADC_COMMON_DMAMODE_1 = 0x01, /*!< dma mode1: each dma request trans a half-word data(reference manual account the rule of data package) */ + ADC_COMMON_DMAMODE_2 = 0x02, /*!< dma mode2: each dma request trans two half-word data(reference manual account the rule of data package) */ + ADC_COMMON_DMAMODE_3 = 0x03, /*!< dma mode3: each dma request trans two bytes data(reference manual account the rule of data package) */ + ADC_COMMON_DMAMODE_4 = 0x04, /*!< dma mode4: each dma request trans three bytes data(reference manual account the rule of data package) */ + ADC_COMMON_DMAMODE_5 = 0x05 /*!< dma mode5: odd dma request trans two half-word data,even dma request trans a half-word data(reference manual account the rule of data package) */ +} adc_common_dma_mode_type; + +/** + * @brief adc common sampling interval type + */ +typedef enum +{ + ADC_SAMPLING_INTERVAL_5CYCLES = 0x00, /*!< ordinary shifting mode adjacent adc sampling interval 5 adcclk */ + ADC_SAMPLING_INTERVAL_6CYCLES = 0x01, /*!< ordinary shifting mode adjacent adc sampling interval 6 adcclk */ + ADC_SAMPLING_INTERVAL_7CYCLES = 0x02, /*!< ordinary shifting mode adjacent adc sampling interval 7 adcclk */ + ADC_SAMPLING_INTERVAL_8CYCLES = 0x03, /*!< ordinary shifting mode adjacent adc sampling interval 8 adcclk */ + ADC_SAMPLING_INTERVAL_9CYCLES = 0x04, /*!< ordinary shifting mode adjacent adc sampling interval 9 adcclk */ + ADC_SAMPLING_INTERVAL_10CYCLES = 0x05, /*!< ordinary shifting mode adjacent adc sampling interval 10 adcclk */ + ADC_SAMPLING_INTERVAL_11CYCLES = 0x06, /*!< ordinary shifting mode adjacent adc sampling interval 11 adcclk */ + ADC_SAMPLING_INTERVAL_12CYCLES = 0x07, /*!< ordinary shifting mode adjacent adc sampling interval 12 adcclk */ + ADC_SAMPLING_INTERVAL_13CYCLES = 0x08, /*!< ordinary shifting mode adjacent adc sampling interval 13 adcclk */ + ADC_SAMPLING_INTERVAL_14CYCLES = 0x09, /*!< ordinary shifting mode adjacent adc sampling interval 14 adcclk */ + ADC_SAMPLING_INTERVAL_15CYCLES = 0x0A, /*!< ordinary shifting mode adjacent adc sampling interval 15 adcclk */ + ADC_SAMPLING_INTERVAL_16CYCLES = 0x0B, /*!< ordinary shifting mode adjacent adc sampling interval 16 adcclk */ + ADC_SAMPLING_INTERVAL_17CYCLES = 0x0C, /*!< ordinary shifting mode adjacent adc sampling interval 17 adcclk */ + ADC_SAMPLING_INTERVAL_18CYCLES = 0x0D, /*!< ordinary shifting mode adjacent adc sampling interval 18 adcclk */ + ADC_SAMPLING_INTERVAL_19CYCLES = 0x0E, /*!< ordinary shifting mode adjacent adc sampling interval 19 adcclk */ + ADC_SAMPLING_INTERVAL_20CYCLES = 0x0F /*!< ordinary shifting mode adjacent adc sampling interval 20 adcclk */ +} adc_sampling_interval_type; + +/** + * @brief adc conversion resolution type + */ +typedef enum +{ + ADC_RESOLUTION_12B = 0x00, /*!< conversion resolution 12 bit */ + ADC_RESOLUTION_10B = 0x01, /*!< conversion resolution 10 bit */ + ADC_RESOLUTION_8B = 0x02, /*!< conversion resolution 8 bit */ + ADC_RESOLUTION_6B = 0x03 /*!< conversion resolution 6 bit */ +} adc_resolution_type; + +/** + * @brief adc data align type + */ +typedef enum +{ + ADC_RIGHT_ALIGNMENT = 0x00, /*!< data right alignment */ + ADC_LEFT_ALIGNMENT = 0x01 /*!< data left alignment */ +} adc_data_align_type; + +/** + * @brief adc channel select type + */ +typedef enum +{ + ADC_CHANNEL_0 = 0x00, /*!< adc channel 0 */ + ADC_CHANNEL_1 = 0x01, /*!< adc channel 1 */ + ADC_CHANNEL_2 = 0x02, /*!< adc channel 2 */ + ADC_CHANNEL_3 = 0x03, /*!< adc channel 3 */ + ADC_CHANNEL_4 = 0x04, /*!< adc channel 4 */ + ADC_CHANNEL_5 = 0x05, /*!< adc channel 5 */ + ADC_CHANNEL_6 = 0x06, /*!< adc channel 6 */ + ADC_CHANNEL_7 = 0x07, /*!< adc channel 7 */ + ADC_CHANNEL_8 = 0x08, /*!< adc channel 8 */ + ADC_CHANNEL_9 = 0x09, /*!< adc channel 9 */ + ADC_CHANNEL_10 = 0x0A, /*!< adc channel 10 */ + ADC_CHANNEL_11 = 0x0B, /*!< adc channel 11 */ + ADC_CHANNEL_12 = 0x0C, /*!< adc channel 12 */ + ADC_CHANNEL_13 = 0x0D, /*!< adc channel 13 */ + ADC_CHANNEL_14 = 0x0E, /*!< adc channel 14 */ + ADC_CHANNEL_15 = 0x0F, /*!< adc channel 15 */ + ADC_CHANNEL_16 = 0x10, /*!< adc channel 16 */ + ADC_CHANNEL_17 = 0x11, /*!< adc channel 17 */ + ADC_CHANNEL_18 = 0x12 /*!< adc channel 18 */ +} adc_channel_select_type; + +/** + * @brief adc sampletime select type + */ +typedef enum +{ + ADC_SAMPLETIME_2_5 = 0x00, /*!< adc sample time 2.5 cycle */ + ADC_SAMPLETIME_6_5 = 0x01, /*!< adc sample time 6.5 cycle */ + ADC_SAMPLETIME_12_5 = 0x02, /*!< adc sample time 12.5 cycle */ + ADC_SAMPLETIME_24_5 = 0x03, /*!< adc sample time 24.5 cycle */ + ADC_SAMPLETIME_47_5 = 0x04, /*!< adc sample time 47.5 cycle */ + ADC_SAMPLETIME_92_5 = 0x05, /*!< adc sample time 92.5 cycle */ + ADC_SAMPLETIME_247_5 = 0x06, /*!< adc sample time 247.5 cycle */ + ADC_SAMPLETIME_640_5 = 0x07 /*!< adc sample time 640.5 cycle */ +} adc_sampletime_select_type; + +/** + * @brief adc ordinary group trigger event select type + */ +typedef enum +{ + ADC_ORDINARY_TRIG_TMR1CH1 = 0x00, /*!< timer1 ch1 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR1CH2 = 0x01, /*!< timer1 ch2 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR1CH3 = 0x02, /*!< timer1 ch3 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR2CH2 = 0x03, /*!< timer2 ch2 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR2CH3 = 0x04, /*!< timer2 ch3 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR2CH4 = 0x05, /*!< timer2 ch4 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR2TRGOUT = 0x06, /*!< timer2 trgout event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR3CH1 = 0x07, /*!< timer3 ch1 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR3TRGOUT = 0x08, /*!< timer3 trgout event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR4CH4 = 0x09, /*!< timer4 ch4 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR5CH1 = 0x0A, /*!< timer5 ch1 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR5CH2 = 0x0B, /*!< timer5 ch2 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR5CH3 = 0x0C, /*!< timer5 ch3 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR8CH1 = 0x0D, /*!< timer8 ch1 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR8TRGOUT = 0x0E, /*!< timer8 trgout event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_EXINT11 = 0x0F, /*!< exint line11 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR20TRGOUT = 0x10, /*!< timer20 trgout event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR20TRGOUT2 = 0x11, /*!< timer20 trgout2 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR20CH1 = 0x12, /*!< timer20 ch1 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR20CH2 = 0x13, /*!< timer20 ch2 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR20CH3 = 0x14, /*!< timer20 ch3 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR8TRGOUT2 = 0x15, /*!< timer8 trgout2 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR1TRGOUT2 = 0x16, /*!< timer1 trgout2 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR4TRGOUT = 0x17, /*!< timer4 trgout event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR6TRGOUT = 0x18, /*!< timer6 trgout event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR3CH4 = 0x19, /*!< timer3 ch4 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR4CH1 = 0x1A, /*!< timer4 ch1 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR1TRGOUT = 0x1B, /*!< timer1 trgout event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR2CH1 = 0x1C, /*!< timer2 ch1 event as trigger source of ordinary sequence */ + ADC_ORDINARY_TRIG_TMR7TRGOUT = 0x1E /*!< timer7 trgout event as trigger source of ordinary sequence */ +} adc_ordinary_trig_select_type; + +/** + * @brief adc ordinary channel conversion's external_trigger_edge type + */ +typedef enum +{ + ADC_ORDINARY_TRIG_EDGE_NONE = 0x00, /*!< ordinary channels trigger detection disabled */ + ADC_ORDINARY_TRIG_EDGE_RISING = 0x01, /*!< ordinary channels trigger detection on the rising edge */ + ADC_ORDINARY_TRIG_EDGE_FALLING = 0x02, /*!< ordinary channels trigger detection on the falling edge */ + ADC_ORDINARY_TRIG_EDGE_RISING_FALLING = 0x03 /*!< ordinary channels trigger detection on both the rising and falling edges */ +} adc_ordinary_trig_edge_type; + +/** + * @brief adc preempt group external trigger event select type + */ +typedef enum +{ + ADC_PREEMPT_TRIG_TMR1CH4 = 0x00, /*!< timer1 ch4 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR1TRGOUT = 0x01, /*!< timer1 trgout event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR2CH1 = 0x02, /*!< timer2 ch1 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR2TRGOUT = 0x03, /*!< timer2 trgout event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR3CH2 = 0x04, /*!< timer3 ch2 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR3CH4 = 0x05, /*!< timer3 ch4 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR4CH1 = 0x06, /*!< timer4 ch1 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR4CH2 = 0x07, /*!< timer4 ch2 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR4CH3 = 0x08, /*!< timer4 ch3 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR4TRGOUT = 0x09, /*!< timer4 trgout event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR5CH4 = 0x0A, /*!< timer5 ch4 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR5TRGOUT = 0x0B, /*!< timer5 trgout event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR8CH2 = 0x0C, /*!< timer8 ch2 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR8CH3 = 0x0D, /*!< timer8 ch3 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR8CH4 = 0x0E, /*!< timer8 ch4 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_EXINT15 = 0x0F, /*!< exint line15 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR20TRGOUT = 0x10, /*!< timer20 trgout event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR20TRGOUT2 = 0x11, /*!< timer20 trgout2 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR20CH4 = 0x12, /*!< timer20 ch4 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR1TRGOUT2 = 0x13, /*!< timer1 trgout2 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR8TRGOUT = 0x14, /*!< timer8 trgout event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR8TRGOUT2 = 0x15, /*!< timer8 trgout2 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR3CH3 = 0x16, /*!< timer3 ch3 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR3TRGOUT = 0x17, /*!< timer3 trgout event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR3CH1 = 0x18, /*!< timer3 ch1 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR6TRGOUT = 0x19, /*!< timer6 trgout event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR4CH4 = 0x1A, /*!< timer4 ch4 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR1CH3 = 0x1B, /*!< timer1 ch3 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR20CH2 = 0x1C, /*!< timer20 ch2 event as trigger source of preempt sequence */ + ADC_PREEMPT_TRIG_TMR7TRGOUT = 0x1E /*!< timer7 trgout event as trigger source of preempt sequence */ +} adc_preempt_trig_select_type; + +/** + * @brief adc preempt channel conversion's external_trigger_edge type + */ +typedef enum +{ + ADC_PREEMPT_TRIG_EDGE_NONE = 0x00, /*!< preempt channels trigger detection disabled */ + ADC_PREEMPT_TRIG_EDGE_RISING = 0x01, /*!< preempt channels trigger detection on the rising edge */ + ADC_PREEMPT_TRIG_EDGE_FALLING = 0x02, /*!< preempt channels trigger detection on the falling edge */ + ADC_PREEMPT_TRIG_EDGE_RISING_FALLING = 0x03 /*!< preempt channels trigger detection on both the rising and falling edges */ +} adc_preempt_trig_edge_type; + +/** + * @brief adc preempt channel type + */ +typedef enum +{ + ADC_PREEMPT_CHANNEL_1 = 0x00, /*!< adc preempt channel 1 */ + ADC_PREEMPT_CHANNEL_2 = 0x01, /*!< adc preempt channel 2 */ + ADC_PREEMPT_CHANNEL_3 = 0x02, /*!< adc preempt channel 3 */ + ADC_PREEMPT_CHANNEL_4 = 0x03 /*!< adc preempt channel 4 */ +} adc_preempt_channel_type; + +/** + * @brief adc voltage_monitoring type + */ +typedef enum +{ + ADC_VMONITOR_SINGLE_ORDINARY = 0x00800200, /*!< voltage_monitoring on a single ordinary channel */ + ADC_VMONITOR_SINGLE_PREEMPT = 0x00400200, /*!< voltage_monitoring on a single preempt channel */ + ADC_VMONITOR_SINGLE_ORDINARY_PREEMPT = 0x00C00200, /*!< voltage_monitoring on a single ordinary or preempt channel */ + ADC_VMONITOR_ALL_ORDINARY = 0x00800000, /*!< voltage_monitoring on all ordinary channel */ + ADC_VMONITOR_ALL_PREEMPT = 0x00400000, /*!< voltage_monitoring on all preempt channel */ + ADC_VMONITOR_ALL_ORDINARY_PREEMPT = 0x00C00000, /*!< voltage_monitoring on all ordinary and preempt channel */ + ADC_VMONITOR_NONE = 0x00000000 /*!< no channel guarded by the voltage_monitoring */ +} adc_voltage_monitoring_type; + +/** + * @brief adc oversample ratio type + */ +typedef enum +{ + ADC_OVERSAMPLE_RATIO_2 = 0x00, /*!< adc oversample ratio 2 */ + ADC_OVERSAMPLE_RATIO_4 = 0x01, /*!< adc oversample ratio 4 */ + ADC_OVERSAMPLE_RATIO_8 = 0x02, /*!< adc oversample ratio 8 */ + ADC_OVERSAMPLE_RATIO_16 = 0x03, /*!< adc oversample ratio 16 */ + ADC_OVERSAMPLE_RATIO_32 = 0x04, /*!< adc oversample ratio 32 */ + ADC_OVERSAMPLE_RATIO_64 = 0x05, /*!< adc oversample ratio 64 */ + ADC_OVERSAMPLE_RATIO_128 = 0x06, /*!< adc oversample ratio 128 */ + ADC_OVERSAMPLE_RATIO_256 = 0x07 /*!< adc oversample ratio 256 */ +} adc_oversample_ratio_type; + +/** + * @brief adc oversample shift type + */ +typedef enum +{ + ADC_OVERSAMPLE_SHIFT_0 = 0x00, /*!< adc oversample shift 0 */ + ADC_OVERSAMPLE_SHIFT_1 = 0x01, /*!< adc oversample shift 1 */ + ADC_OVERSAMPLE_SHIFT_2 = 0x02, /*!< adc oversample shift 2 */ + ADC_OVERSAMPLE_SHIFT_3 = 0x03, /*!< adc oversample shift 3 */ + ADC_OVERSAMPLE_SHIFT_4 = 0x04, /*!< adc oversample shift 4 */ + ADC_OVERSAMPLE_SHIFT_5 = 0x05, /*!< adc oversample shift 5 */ + ADC_OVERSAMPLE_SHIFT_6 = 0x06, /*!< adc oversample shift 6 */ + ADC_OVERSAMPLE_SHIFT_7 = 0x07, /*!< adc oversample shift 7 */ + ADC_OVERSAMPLE_SHIFT_8 = 0x08 /*!< adc oversample shift 8 */ +} adc_oversample_shift_type; + +/** + * @brief adc ordinary oversample recover type + */ +typedef enum +{ + ADC_OVERSAMPLE_CONTINUE = 0x00, /*!< continue mode:when preempt triggered,oversampling is temporary stopped and continued after preempt sequence */ + ADC_OVERSAMPLE_RESTART = 0x01 /*!< restart mode:when preempt triggered,oversampling is aborted and resumed from start after preempt sequence */ +} adc_ordinary_oversample_restart_type; + +/** + * @brief adc common config type + */ +typedef struct +{ + adc_combine_mode_type combine_mode; /*!< adc combine mode select */ + adc_div_type div; /*!< adc division select */ + adc_common_dma_mode_type common_dma_mode; /*!< adc common dma mode select */ + confirm_state common_dma_request_repeat_state; /*!< adc common dma repeat state */ + adc_sampling_interval_type sampling_interval; /*!< ordinary shifting mode adjacent adc sampling interval select */ + confirm_state tempervintrv_state; /*!< adc temperature sensor and vintrv state */ + confirm_state vbat_state; /*!< adc voltage battery state */ +} adc_common_config_type; + +/** + * @brief adc base config type + */ +typedef struct +{ + confirm_state sequence_mode; /*!< adc sequence mode */ + confirm_state repeat_mode; /*!< adc repeat mode */ + adc_data_align_type data_align; /*!< adc data alignment */ + uint8_t ordinary_channel_length; /*!< adc ordinary channel sequence length*/ +} adc_base_config_type; + +/** + * @brief type define adc register all + */ +typedef struct +{ + + /** + * @brief adc sts register, offset:0x00 + */ + union + { + __IO uint32_t sts; + struct + { + __IO uint32_t vmor : 1; /* [0] */ + __IO uint32_t occe : 1; /* [1] */ + __IO uint32_t pcce : 1; /* [2] */ + __IO uint32_t pccs : 1; /* [3] */ + __IO uint32_t occs : 1; /* [4] */ + __IO uint32_t occo : 1; /* [5] */ + __IO uint32_t rdy : 1; /* [6] */ + __IO uint32_t reserved1 : 25;/* [31:7] */ + } sts_bit; + }; + + /** + * @brief adc ctrl1 register, offset:0x04 + */ + union + { + __IO uint32_t ctrl1; + struct + { + __IO uint32_t vmcsel : 5; /* [4:0] */ + __IO uint32_t occeien : 1; /* [5] */ + __IO uint32_t vmorien : 1; /* [6] */ + __IO uint32_t pcceien : 1; /* [7] */ + __IO uint32_t sqen : 1; /* [8] */ + __IO uint32_t vmsgen : 1; /* [9] */ + __IO uint32_t pcautoen : 1; /* [10] */ + __IO uint32_t ocpen : 1; /* [11] */ + __IO uint32_t pcpen : 1; /* [12] */ + __IO uint32_t ocpcnt : 3; /* [15:13] */ + __IO uint32_t reserved1 : 6; /* [21:16] */ + __IO uint32_t pcvmen : 1; /* [22] */ + __IO uint32_t ocvmen : 1; /* [23] */ + __IO uint32_t crsel : 2; /* [25:24] */ + __IO uint32_t occoien : 1; /* [26] */ + __IO uint32_t reserved2 : 5; /* [31:27] */ + } ctrl1_bit; + }; + + /** + * @brief adc ctrl2 register, offset:0x08 + */ + union + { + __IO uint32_t ctrl2; + struct + { + __IO uint32_t adcen : 1; /* [0] */ + __IO uint32_t rpen : 1; /* [1] */ + __IO uint32_t adcal : 1; /* [2] */ + __IO uint32_t adcalinit : 1; /* [3] */ + __IO uint32_t adabrt : 1; /* [4] */ + __IO uint32_t reserved1 : 3; /* [7:5] */ + __IO uint32_t ocdmaen : 1; /* [8] */ + __IO uint32_t ocdrcen : 1; /* [9] */ + __IO uint32_t eocsfen : 1; /* [10] */ + __IO uint32_t dtalign : 1; /* [11] */ + __IO uint32_t reserved2 : 4; /* [15:12] */ + __IO uint32_t pctesel_l : 4; /* [19:16] */ + __IO uint32_t pcete : 2; /* [21:20] */ + __IO uint32_t pcswtrg : 1; /* [22] */ + __IO uint32_t pctesel_h : 1; /* [23] */ + __IO uint32_t octesel_l : 4; /* [27:24] */ + __IO uint32_t ocete : 2; /* [29:28] */ + __IO uint32_t ocswtrg : 1; /* [30] */ + __IO uint32_t octesel_h : 1; /* [31] */ + } ctrl2_bit; + }; + + /** + * @brief adc spt1 register, offset:0x0C + */ + union + { + __IO uint32_t spt1; + struct + { + __IO uint32_t cspt10 : 3; /* [2:0] */ + __IO uint32_t cspt11 : 3; /* [5:3] */ + __IO uint32_t cspt12 : 3; /* [8:6] */ + __IO uint32_t cspt13 : 3; /* [11:9] */ + __IO uint32_t cspt14 : 3; /* [14:12] */ + __IO uint32_t cspt15 : 3; /* [17:15] */ + __IO uint32_t cspt16 : 3; /* [20:18] */ + __IO uint32_t cspt17 : 3; /* [23:21] */ + __IO uint32_t cspt18 : 3; /* [26:24] */ + __IO uint32_t reserved1 : 5;/* [31:27] */ + } spt1_bit; + }; + + /** + * @brief adc spt2 register, offset:0x10 + */ + union + { + __IO uint32_t spt2; + struct + { + __IO uint32_t cspt0 : 3;/* [2:0] */ + __IO uint32_t cspt1 : 3;/* [5:3] */ + __IO uint32_t cspt2 : 3;/* [8:6] */ + __IO uint32_t cspt3 : 3;/* [11:9] */ + __IO uint32_t cspt4 : 3;/* [14:12] */ + __IO uint32_t cspt5 : 3;/* [17:15] */ + __IO uint32_t cspt6 : 3;/* [20:18] */ + __IO uint32_t cspt7 : 3;/* [23:21] */ + __IO uint32_t cspt8 : 3;/* [26:24] */ + __IO uint32_t cspt9 : 3;/* [29:27] */ + __IO uint32_t reserved1 : 2;/* [31:30] */ + } spt2_bit; + }; + + /** + * @brief adc pcdto1 register, offset:0x14 + */ + union + { + __IO uint32_t pcdto1; + struct + { + __IO uint32_t pcdto1 : 12; /* [11:0] */ + __IO uint32_t reserved1 : 20; /* [31:12] */ + } pcdto1_bit; + }; + + /** + * @brief adc pcdto2 register, offset:0x18 + */ + union + { + __IO uint32_t pcdto2; + struct + { + __IO uint32_t pcdto2 : 12; /* [11:0] */ + __IO uint32_t reserved1 : 20; /* [31:12] */ + } pcdto2_bit; + }; + + /** + * @brief adc pcdto3 register, offset:0x1C + */ + union + { + __IO uint32_t pcdto3; + struct + { + __IO uint32_t pcdto3 : 12; /* [11:0] */ + __IO uint32_t reserved1 : 20; /* [31:12] */ + } pcdto3_bit; + }; + + /** + * @brief adc pcdto4 register, offset:0x20 + */ + union + { + __IO uint32_t pcdto4; + struct + { + __IO uint32_t pcdto4 : 12; /* [11:0] */ + __IO uint32_t reserved1 : 20; /* [31:12] */ + } pcdto4_bit; + }; + + /** + * @brief adc vmhb register, offset:0x24 + */ + union + { + __IO uint32_t vmhb; + struct + { + __IO uint32_t vmhb : 12; /* [11:0] */ + __IO uint32_t reserved1 : 20; /* [31:12] */ + } vmhb_bit; + }; + + /** + * @brief adc vmlb register, offset:0x28 + */ + union + { + __IO uint32_t vmlb; + struct + { + __IO uint32_t vmlb : 12; /* [11:0] */ + __IO uint32_t reserved1 : 20; /* [31:12] */ + } vmlb_bit; + }; + + /** + * @brief adc osq1 register, offset:0x2C + */ + union + { + __IO uint32_t osq1; + struct + { + __IO uint32_t osn13 : 5; /* [4:0] */ + __IO uint32_t osn14 : 5; /* [9:5] */ + __IO uint32_t osn15 : 5; /* [14:10] */ + __IO uint32_t osn16 : 5; /* [19:15] */ + __IO uint32_t oclen : 4; /* [23:20] */ + __IO uint32_t reserved1 : 8; /* [31:24] */ + } osq1_bit; + }; + + /** + * @brief adc osq2 register, offset:0x30 + */ + union + { + __IO uint32_t osq2; + struct + { + __IO uint32_t osn7 : 5; /* [4:0] */ + __IO uint32_t osn8 : 5; /* [9:5] */ + __IO uint32_t osn9 : 5; /* [14:10] */ + __IO uint32_t osn10 : 5; /* [19:15] */ + __IO uint32_t osn11 : 5; /* [24:20] */ + __IO uint32_t osn12 : 5; /* [29:25] */ + __IO uint32_t reserved1 : 2; /* [31:30] */ + } osq2_bit; + }; + + /** + * @brief adc osq3 register, offset:0x34 + */ + union + { + __IO uint32_t osq3; + struct + { + __IO uint32_t osn1 : 5; /* [4:0] */ + __IO uint32_t osn2 : 5; /* [9:5] */ + __IO uint32_t osn3 : 5; /* [14:10] */ + __IO uint32_t osn4 : 5; /* [19:15] */ + __IO uint32_t osn5 : 5; /* [24:20] */ + __IO uint32_t osn6 : 5; /* [29:25] */ + __IO uint32_t reserved1 : 2; /* [31:30] */ + } osq3_bit; + }; + + /** + * @brief adc psq register, offset:0x38 + */ + union + { + __IO uint32_t psq; + struct + { + __IO uint32_t psn1 : 5; /* [4:0] */ + __IO uint32_t psn2 : 5; /* [9:5] */ + __IO uint32_t psn3 : 5; /* [14:10] */ + __IO uint32_t psn4 : 5; /* [19:15] */ + __IO uint32_t pclen : 2; /* [21:20] */ + __IO uint32_t reserved1 : 10;/* [31:22] */ + } psq_bit; + }; + + /** + * @brief adc pdt1 register, offset:0x3C + */ + union + { + __IO uint32_t pdt1; + struct + { + __IO uint32_t pdt1 : 16; /* [15:0] */ + __IO uint32_t reserved1 : 16; /* [31:16] */ + } pdt1_bit; + }; + + /** + * @brief adc pdt2 register, offset:0x40 + */ + union + { + __IO uint32_t pdt2; + struct + { + __IO uint32_t pdt2 : 16; /* [15:0] */ + __IO uint32_t reserved1 : 16; /* [31:16] */ + } pdt2_bit; + }; + + /** + * @brief adc pdt3 register, offset:0x44 + */ + union + { + __IO uint32_t pdt3; + struct + { + __IO uint32_t pdt3 : 16; /* [15:0] */ + __IO uint32_t reserved1 : 16; /* [31:16] */ + } pdt3_bit; + }; + + /** + * @brief adc pdt4 register, offset:0x48 + */ + union + { + __IO uint32_t pdt4; + struct + { + __IO uint32_t pdt4 : 16; /* [15:0] */ + __IO uint32_t reserved1 : 16; /* [31:16] */ + } pdt4_bit; + }; + + /** + * @brief adc odt register, offset:0x4C + */ + union + { + __IO uint32_t odt; + struct + { + __IO uint32_t odt : 16; /* [15:0] */ + __IO uint32_t reserved1 : 16; /* [31:16] */ + } odt_bit; + }; + + __IO uint32_t reserved1[12]; + + /** + * @brief adc ovsp register, offset:0x80 + */ + union + { + __IO uint32_t ovsp; + struct + { + __IO uint32_t oosen : 1; /* [0] */ + __IO uint32_t posen : 1; /* [1] */ + __IO uint32_t osrsel : 3; /* [4:2] */ + __IO uint32_t osssel : 4; /* [8:5] */ + __IO uint32_t oostren : 1; /* [9] */ + __IO uint32_t oosrsel : 1; /* [10] */ + __IO uint32_t reserved1 : 21; /* [31:11] */ + } ovsp_bit; + }; + + __IO uint32_t reserved2[12]; + + /** + * @brief adc calval register, offset:0xB4 + */ + union + { + __IO uint32_t calval; + struct + { + __IO uint32_t calval : 7; /* [6:0] */ + __IO uint32_t reserved1 : 25; /* [31:7] */ + } calval_bit; + }; +} adc_type; + +/** + * @brief type define adc register all + */ +typedef struct +{ + + /** + * @brief adc csts register, offset:0x00 + */ + union + { + __IO uint32_t csts; + struct + { + __IO uint32_t vmor1 : 1; /* [0] */ + __IO uint32_t occe1 : 1; /* [1] */ + __IO uint32_t pcce1 : 1; /* [2] */ + __IO uint32_t pccs1 : 1; /* [3] */ + __IO uint32_t occs1 : 1; /* [4] */ + __IO uint32_t occo1 : 1; /* [5] */ + __IO uint32_t rdy1 : 1; /* [6] */ + __IO uint32_t reserved1 : 1; /* [7] */ + __IO uint32_t vmor2 : 1; /* [8] */ + __IO uint32_t occe2 : 1; /* [9] */ + __IO uint32_t pcce2 : 1; /* [10] */ + __IO uint32_t pccs2 : 1; /* [11] */ + __IO uint32_t occs2 : 1; /* [12] */ + __IO uint32_t occo2 : 1; /* [13] */ + __IO uint32_t rdy2 : 1; /* [14] */ + __IO uint32_t reserved2 : 1; /* [15] */ + __IO uint32_t vmor3 : 1; /* [16] */ + __IO uint32_t occe3 : 1; /* [17] */ + __IO uint32_t pcce3 : 1; /* [18] */ + __IO uint32_t pccs3 : 1; /* [19] */ + __IO uint32_t occs3 : 1; /* [20] */ + __IO uint32_t occo3 : 1; /* [21] */ + __IO uint32_t rdy3 : 1; /* [22] */ + __IO uint32_t reserved3 : 9; /* [31:23] */ + } csts_bit; + }; + + /** + * @brief adc cctrl register, offset:0x04 + */ + union + { + __IO uint32_t cctrl; + struct + { + __IO uint32_t mssel : 5; /* [4_0] */ + __IO uint32_t reserved1 : 3; /* [7:5] */ + __IO uint32_t asisel : 4; /* [11:8] */ + __IO uint32_t reserved2 : 1; /* [12] */ + __IO uint32_t msdrcen : 1; /* [13] */ + __IO uint32_t msdmasel_l : 2; /* [15:14] */ + __IO uint32_t adcdiv : 4; /* [19:16] */ + __IO uint32_t reserved3 : 2; /* [21:20] */ + __IO uint32_t vbaten : 1; /* [22] */ + __IO uint32_t itsrven : 1; /* [23] */ + __IO uint32_t reserved4 : 4; /* [27:24] */ + __IO uint32_t msdmasel_h : 1; /* [28] */ + __IO uint32_t reserved5 : 3; /* [31:29] */ + } cctrl_bit; + }; + + /** + * @brief adc codt register, offset:0x08 + */ + union + { + __IO uint32_t codt; + struct + { + __IO uint32_t codtl : 16; /* [15:0] */ + __IO uint32_t codth : 16; /* [31:16] */ + } codt_bit; + }; +} adccom_type; + +/** + * @} + */ + +#define ADC1 ((adc_type *) ADC1_BASE) +#define ADC2 ((adc_type *) ADC2_BASE) +#define ADC3 ((adc_type *) ADC3_BASE) +#define ADCCOM ((adccom_type *) ADCCOM_BASE) + +/** @defgroup ADC_exported_functions + * @{ + */ + +void adc_reset(void); +void adc_enable(adc_type *adc_x, confirm_state new_state); +void adc_base_default_para_init(adc_base_config_type *adc_base_struct); +void adc_base_config(adc_type *adc_x, adc_base_config_type *adc_base_struct); +void adc_common_default_para_init(adc_common_config_type *adc_common_struct); +void adc_common_config(adc_common_config_type *adc_common_struct); +void adc_resolution_set(adc_type *adc_x, adc_resolution_type resolution); +void adc_voltage_battery_enable(confirm_state new_state); +void adc_dma_mode_enable(adc_type *adc_x, confirm_state new_state); +void adc_dma_request_repeat_enable(adc_type *adc_x, confirm_state new_state); +void adc_interrupt_enable(adc_type *adc_x, uint32_t adc_int, confirm_state new_state); +void adc_calibration_value_set(adc_type *adc_x, uint8_t adc_calibration_value); +void adc_calibration_init(adc_type *adc_x); +flag_status adc_calibration_init_status_get(adc_type *adc_x); +void adc_calibration_start(adc_type *adc_x); +flag_status adc_calibration_status_get(adc_type *adc_x); +void adc_voltage_monitor_enable(adc_type *adc_x, adc_voltage_monitoring_type adc_voltage_monitoring); +void adc_voltage_monitor_threshold_value_set(adc_type *adc_x, uint16_t adc_high_threshold, uint16_t adc_low_threshold); +void adc_voltage_monitor_single_channel_select(adc_type *adc_x, adc_channel_select_type adc_channel); +void adc_ordinary_channel_set(adc_type *adc_x, adc_channel_select_type adc_channel, uint8_t adc_sequence, adc_sampletime_select_type adc_sampletime); +void adc_preempt_channel_length_set(adc_type *adc_x, uint8_t adc_channel_lenght); +void adc_preempt_channel_set(adc_type *adc_x, adc_channel_select_type adc_channel, uint8_t adc_sequence, adc_sampletime_select_type adc_sampletime); +void adc_ordinary_conversion_trigger_set(adc_type *adc_x, adc_ordinary_trig_select_type adc_ordinary_trig, adc_ordinary_trig_edge_type adc_ordinary_trig_edge); +void adc_preempt_conversion_trigger_set(adc_type *adc_x, adc_preempt_trig_select_type adc_preempt_trig, adc_preempt_trig_edge_type adc_preempt_trig_edge); +void adc_preempt_offset_value_set(adc_type *adc_x, adc_preempt_channel_type adc_preempt_channel, uint16_t adc_offset_value); +void adc_ordinary_part_count_set(adc_type *adc_x, uint8_t adc_channel_count); +void adc_ordinary_part_mode_enable(adc_type *adc_x, confirm_state new_state); +void adc_preempt_part_mode_enable(adc_type *adc_x, confirm_state new_state); +void adc_preempt_auto_mode_enable(adc_type *adc_x, confirm_state new_state); +void adc_conversion_stop(adc_type *adc_x); +flag_status adc_conversion_stop_status_get(adc_type *adc_x); +void adc_occe_each_conversion_enable(adc_type *adc_x, confirm_state new_state); +void adc_ordinary_software_trigger_enable(adc_type *adc_x, confirm_state new_state); +flag_status adc_ordinary_software_trigger_status_get(adc_type *adc_x); +void adc_preempt_software_trigger_enable(adc_type *adc_x, confirm_state new_state); +flag_status adc_preempt_software_trigger_status_get(adc_type *adc_x); +uint16_t adc_ordinary_conversion_data_get(adc_type *adc_x); +uint32_t adc_combine_ordinary_conversion_data_get(void); +uint16_t adc_preempt_conversion_data_get(adc_type *adc_x, adc_preempt_channel_type adc_preempt_channel); +flag_status adc_flag_get(adc_type *adc_x, uint8_t adc_flag); +void adc_flag_clear(adc_type *adc_x, uint32_t adc_flag); +void adc_ordinary_oversample_enable(adc_type *adc_x, confirm_state new_state); +void adc_preempt_oversample_enable(adc_type *adc_x, confirm_state new_state); +void adc_oversample_ratio_shift_set(adc_type *adc_x, adc_oversample_ratio_type adc_oversample_ratio, adc_oversample_shift_type adc_oversample_shift); +void adc_ordinary_oversample_trig_enable(adc_type *adc_x, confirm_state new_state); +void adc_ordinary_oversample_restart_set(adc_type *adc_x, adc_ordinary_oversample_restart_type adc_ordinary_oversample_restart); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_can.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_can.h new file mode 100644 index 0000000000..ddb1a07402 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_can.h @@ -0,0 +1,1042 @@ +/** + ************************************************************************** + * @file at32f435_437_can.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 can header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_CAN_H +#define __AT32F435_437_CAN_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup CAN + * @{ + */ + + +/** @defgroup CAN_timeout_count + * @{ + */ + +#define FZC_TIMEOUT ((uint32_t)0x0000FFFF) /*!< time out for fzc bit */ +#define DZC_TIMEOUT ((uint32_t)0x0000FFFF) /*!< time out for dzc bit */ + +/** + * @} + */ + +/** @defgroup CAN_flags_definition + * @brief can flag + * @{ + */ + +#define CAN_EAF_FLAG ((uint32_t)0x01) /*!< error active flag */ +#define CAN_EPF_FLAG ((uint32_t)0x02) /*!< error passive flag */ +#define CAN_BOF_FLAG ((uint32_t)0x03) /*!< bus-off flag */ +#define CAN_ETR_FLAG ((uint32_t)0x04) /*!< error type record flag */ +#define CAN_EOIF_FLAG ((uint32_t)0x05) /*!< error occur interrupt flag */ +#define CAN_TM0TCF_FLAG ((uint32_t)0x06) /*!< transmit mailbox 0 transmission completed flag */ +#define CAN_TM1TCF_FLAG ((uint32_t)0x07) /*!< transmit mailbox 1 transmission completed flag */ +#define CAN_TM2TCF_FLAG ((uint32_t)0x08) /*!< transmit mailbox 2 transmission completed flag */ +#define CAN_RF0MN_FLAG ((uint32_t)0x09) /*!< receive fifo 0 message num flag */ +#define CAN_RF0FF_FLAG ((uint32_t)0x0A) /*!< receive fifo 0 full flag */ +#define CAN_RF0OF_FLAG ((uint32_t)0x0B) /*!< receive fifo 0 overflow flag */ +#define CAN_RF1MN_FLAG ((uint32_t)0x0C) /*!< receive fifo 1 message num flag */ +#define CAN_RF1FF_FLAG ((uint32_t)0x0D) /*!< receive fifo 1 full flag */ +#define CAN_RF1OF_FLAG ((uint32_t)0x0E) /*!< receive fifo 1 overflow flag */ +#define CAN_QDZIF_FLAG ((uint32_t)0x0F) /*!< quit doze mode interrupt flag */ +#define CAN_EDZC_FLAG ((uint32_t)0x10) /*!< enter doze mode confirm flag */ +#define CAN_TMEF_FLAG ((uint32_t)0x11) /*!< transmit mailbox empty flag */ + +/** + * @} + */ + +/** @defgroup CAN_interrupts_definition + * @brief can interrupt + * @{ + */ + +#define CAN_TCIEN_INT ((uint32_t)0x00000001) /*!< transmission complete interrupt */ +#define CAN_RF0MIEN_INT ((uint32_t)0x00000002) /*!< receive fifo 0 message interrupt */ +#define CAN_RF0FIEN_INT ((uint32_t)0x00000004) /*!< receive fifo 0 full interrupt */ +#define CAN_RF0OIEN_INT ((uint32_t)0x00000008) /*!< receive fifo 0 overflow interrupt */ +#define CAN_RF1MIEN_INT ((uint32_t)0x00000010) /*!< receive fifo 1 message interrupt */ +#define CAN_RF1FIEN_INT ((uint32_t)0x00000020) /*!< receive fifo 1 full interrupt */ +#define CAN_RF1OIEN_INT ((uint32_t)0x00000040) /*!< receive fifo 1 overflow interrupt */ +#define CAN_EAIEN_INT ((uint32_t)0x00000100) /*!< error active interrupt */ +#define CAN_EPIEN_INT ((uint32_t)0x00000200) /*!< error passive interrupt */ +#define CAN_BOIEN_INT ((uint32_t)0x00000400) /*!< bus-off interrupt */ +#define CAN_ETRIEN_INT ((uint32_t)0x00000800) /*!< error type record interrupt */ +#define CAN_EOIEN_INT ((uint32_t)0x00008000) /*!< error occur interrupt */ +#define CAN_QDZIEN_INT ((uint32_t)0x00010000) /*!< quit doze mode interrupt */ +#define CAN_EDZIEN_INT ((uint32_t)0x00020000) /*!< enter doze mode confirm interrupt */ + +/** + * @} + */ + +/** + * @brief can flag clear operation macro definition val + */ +#define CAN_MSTS_EOIF_VAL ((uint32_t)0x00000004) /*!< eoif bit value, it clear by writing 1 */ +#define CAN_MSTS_QDZIF_VAL ((uint32_t)0x00000008) /*!< qdzif bit value, it clear by writing 1 */ +#define CAN_MSTS_EDZIF_VAL ((uint32_t)0x00000010) /*!< edzif bit value, it clear by writing 1 */ +#define CAN_TSTS_TM0TCF_VAL ((uint32_t)0x00000001) /*!< tm0tcf bit value, it clear by writing 1 */ +#define CAN_TSTS_TM1TCF_VAL ((uint32_t)0x00000100) /*!< tm1tcf bit value, it clear by writing 1 */ +#define CAN_TSTS_TM2TCF_VAL ((uint32_t)0x00010000) /*!< tm2tcf bit value, it clear by writing 1 */ +#define CAN_TSTS_TM0CT_VAL ((uint32_t)0x00000080) /*!< tm0ct bit value, it clear by writing 1 */ +#define CAN_TSTS_TM1CT_VAL ((uint32_t)0x00008000) /*!< tm1ct bit value, it clear by writing 1 */ +#define CAN_TSTS_TM2CT_VAL ((uint32_t)0x00800000) /*!< tm2ct bit value, it clear by writing 1 */ +#define CAN_RF0_RF0FF_VAL ((uint32_t)0x00000008) /*!< rf0ff bit value, it clear by writing 1 */ +#define CAN_RF0_RF0OF_VAL ((uint32_t)0x00000010) /*!< rf0of bit value, it clear by writing 1 */ +#define CAN_RF0_RF0R_VAL ((uint32_t)0x00000020) /*!< rf0r bit value, it clear by writing 1 */ +#define CAN_RF1_RF1FF_VAL ((uint32_t)0x00000008) /*!< rf1ff bit value, it clear by writing 1 */ +#define CAN_RF1_RF1OF_VAL ((uint32_t)0x00000010) /*!< rf1of bit value, it clear by writing 1 */ +#define CAN_RF1_RF1R_VAL ((uint32_t)0x00000020) /*!< rf1r bit value, it clear by writing 1 */ + +/** @defgroup CAN_exported_types + * @{ + */ + +/** + * @brief can filter fifo + */ +typedef enum +{ + CAN_FILTER_FIFO0 = 0x00, /*!< filter fifo 0 assignment for filter x */ + CAN_FILTER_FIFO1 = 0x01 /*!< filter fifo 1 assignment for filter x */ +} can_filter_fifo_type; + +/** + * @brief can filter mode + */ +typedef enum +{ + CAN_FILTER_MODE_ID_MASK = 0x00, /*!< identifier mask mode */ + CAN_FILTER_MODE_ID_LIST = 0x01 /*!< identifier list mode */ +} can_filter_mode_type; + +/** + * @brief can filter bit width select + */ +typedef enum +{ + CAN_FILTER_16BIT = 0x00, /*!< two 16-bit filters */ + CAN_FILTER_32BIT = 0x01 /*!< one 32-bit filter */ +} can_filter_bit_width_type; + +/** + * @brief can mode + */ +typedef enum +{ + CAN_MODE_COMMUNICATE = 0x00, /*!< communication mode */ + CAN_MODE_LOOPBACK = 0x01, /*!< loopback mode */ + CAN_MODE_LISTENONLY = 0x02, /*!< listen-only mode */ + CAN_MODE_LISTENONLY_LOOPBACK = 0x03 /*!< loopback combined with listen-only mode */ +} can_mode_type; + +/** + * @brief can operating mode + */ +typedef enum +{ + CAN_OPERATINGMODE_FREEZE = 0x00, /*!< freeze mode */ + CAN_OPERATINGMODE_DOZE = 0x01, /*!< doze mode */ + CAN_OPERATINGMODE_COMMUNICATE = 0x02 /*!< communication mode */ +} can_operating_mode_type; + +/** + * @brief can resynchronization adjust width + */ +typedef enum +{ + CAN_RSAW_1TQ = 0x00, /*!< 1 time quantum */ + CAN_RSAW_2TQ = 0x01, /*!< 2 time quantum */ + CAN_RSAW_3TQ = 0x02, /*!< 3 time quantum */ + CAN_RSAW_4TQ = 0x03 /*!< 4 time quantum */ +} can_rsaw_type; + +/** + * @brief can bit time segment 1 + */ +typedef enum +{ + CAN_BTS1_1TQ = 0x00, /*!< 1 time quantum */ + CAN_BTS1_2TQ = 0x01, /*!< 2 time quantum */ + CAN_BTS1_3TQ = 0x02, /*!< 3 time quantum */ + CAN_BTS1_4TQ = 0x03, /*!< 4 time quantum */ + CAN_BTS1_5TQ = 0x04, /*!< 5 time quantum */ + CAN_BTS1_6TQ = 0x05, /*!< 6 time quantum */ + CAN_BTS1_7TQ = 0x06, /*!< 7 time quantum */ + CAN_BTS1_8TQ = 0x07, /*!< 8 time quantum */ + CAN_BTS1_9TQ = 0x08, /*!< 9 time quantum */ + CAN_BTS1_10TQ = 0x09, /*!< 10 time quantum */ + CAN_BTS1_11TQ = 0x0A, /*!< 11 time quantum */ + CAN_BTS1_12TQ = 0x0B, /*!< 12 time quantum */ + CAN_BTS1_13TQ = 0x0C, /*!< 13 time quantum */ + CAN_BTS1_14TQ = 0x0D, /*!< 14 time quantum */ + CAN_BTS1_15TQ = 0x0E, /*!< 15 time quantum */ + CAN_BTS1_16TQ = 0x0F /*!< 16 time quantum */ +} can_bts1_type; + +/** + * @brief can bit time segment 2 + */ +typedef enum +{ + CAN_BTS2_1TQ = 0x00, /*!< 1 time quantum */ + CAN_BTS2_2TQ = 0x01, /*!< 2 time quantum */ + CAN_BTS2_3TQ = 0x02, /*!< 3 time quantum */ + CAN_BTS2_4TQ = 0x03, /*!< 4 time quantum */ + CAN_BTS2_5TQ = 0x04, /*!< 5 time quantum */ + CAN_BTS2_6TQ = 0x05, /*!< 6 time quantum */ + CAN_BTS2_7TQ = 0x06, /*!< 7 time quantum */ + CAN_BTS2_8TQ = 0x07 /*!< 8 time quantum */ +} can_bts2_type; + +/** + * @brief can identifier type + */ +typedef enum +{ + CAN_ID_STANDARD = 0x00, /*!< standard Id */ + CAN_ID_EXTENDED = 0x01 /*!< extended Id */ +} can_identifier_type; + +/** + * @brief can transmission frame type + */ +typedef enum +{ + CAN_TFT_DATA = 0x00, /*!< data frame */ + CAN_TFT_REMOTE = 0x01 /*!< remote frame */ +} can_trans_frame_type; + +/** + * @brief can tx mailboxes + */ +typedef enum +{ + CAN_TX_MAILBOX0 = 0x00, /*!< can tx mailbox 0 */ + CAN_TX_MAILBOX1 = 0x01, /*!< can tx mailbox 1 */ + CAN_TX_MAILBOX2 = 0x02 /*!< can tx mailbox 2 */ +} can_tx_mailbox_num_type; + +/** + * @brief can receive fifo + */ +typedef enum +{ + CAN_RX_FIFO0 = 0x00, /*!< can fifo 0 used to receive */ + CAN_RX_FIFO1 = 0x01 /*!< can fifo 1 used to receive */ +} can_rx_fifo_num_type; + +/** + * @brief can transmit status + */ +typedef enum +{ + CAN_TX_STATUS_FAILED = 0x00, /*!< can transmission failed */ + CAN_TX_STATUS_SUCCESSFUL = 0x01, /*!< can transmission successful */ + CAN_TX_STATUS_PENDING = 0x02, /*!< can transmission pending */ + CAN_TX_STATUS_NO_EMPTY = 0x04 /*!< can transmission no empty mailbox */ +} can_transmit_status_type; + +/** + * @brief can enter doze mode status + */ +typedef enum +{ + CAN_ENTER_DOZE_FAILED = 0x00, /*!< can enter the doze mode failed */ + CAN_ENTER_DOZE_SUCCESSFUL = 0x01 /*!< can enter the doze mode successful */ +} can_enter_doze_status_type; + +/** + * @brief can quit doze mode status + */ +typedef enum +{ + CAN_QUIT_DOZE_FAILED = 0x00, /*!< can quit doze mode failed */ + CAN_QUIT_DOZE_SUCCESSFUL = 0x01 /*!< can quit doze mode successful */ +} can_quit_doze_status_type; + +/** + * @brief can message discarding rule select when overflow + */ +typedef enum +{ + CAN_DISCARDING_FIRST_RECEIVED = 0x00, /*!< can discarding the first received message */ + CAN_DISCARDING_LAST_RECEIVED = 0x01 /*!< can discarding the last received message */ +} can_msg_discarding_rule_type; + +/** + * @brief can multiple message sending sequence rule + */ +typedef enum +{ + CAN_SENDING_BY_ID = 0x00, /*!< can sending the minimum id message first*/ + CAN_SENDING_BY_REQUEST = 0x01 /*!< can sending the first request message first */ +} can_msg_sending_rule_type; + +/** + * @brief can error type record + */ +typedef enum +{ + CAN_ERRORRECORD_NOERR = 0x00, /*!< no error */ + CAN_ERRORRECORD_STUFFERR = 0x01, /*!< stuff error */ + CAN_ERRORRECORD_FORMERR = 0x02, /*!< form error */ + CAN_ERRORRECORD_ACKERR = 0x03, /*!< acknowledgment error */ + CAN_ERRORRECORD_BITRECESSIVEERR = 0x04, /*!< bit recessive error */ + CAN_ERRORRECORD_BITDOMINANTERR = 0x05, /*!< bit dominant error */ + CAN_ERRORRECORD_CRCERR = 0x06, /*!< crc error */ + CAN_ERRORRECORD_SOFTWARESETERR = 0x07 /*!< software set error */ +} can_error_record_type; + +/** + * @brief can init structure definition + */ +typedef struct +{ + can_mode_type mode_selection; /*!< specifies the can mode.*/ + + confirm_state ttc_enable; /*!< time triggered communication mode enable */ + + confirm_state aebo_enable; /*!< automatic exit bus-off enable */ + + confirm_state aed_enable; /*!< automatic exit doze mode enable */ + + confirm_state prsf_enable; /*!< prohibit retransmission when sending fails enable */ + + can_msg_discarding_rule_type mdrsel_selection; /*!< message discarding rule select when overflow */ + + can_msg_sending_rule_type mmssr_selection; /*!< multiple message sending sequence rule */ + +} can_base_type; + +/** + * @brief can baudrate structure definition + */ +typedef struct +{ + uint16_t baudrate_div; /*!< baudrate division,this parameter can be 0x001~0x1000.*/ + + can_rsaw_type rsaw_size; /*!< resynchronization adjust width */ + + can_bts1_type bts1_size; /*!< bit time segment 1 */ + + can_bts2_type bts2_size; /*!< bit time segment 2 */ + +} can_baudrate_type; + +/** + * @brief can filter init structure definition + */ +typedef struct +{ + confirm_state filter_activate_enable; /*!< enable or disable the filter activate.*/ + + can_filter_mode_type filter_mode; /*!< config the filter mode mask or list.*/ + + can_filter_fifo_type filter_fifo; /*!< config the fifo which will be assigned to the filter. */ + + uint8_t filter_number; /*!< config the filter number, parameter ranges from 0 to 13. */ + + can_filter_bit_width_type filter_bit; /*!< config the filter bit width 16bit or 32bit.*/ + + uint16_t filter_id_high; /*!< config the filter identification, for 32-bit configuration + it's high 16 bits, for 16-bit configuration it's first. */ + + uint16_t filter_id_low; /*!< config the filter identification, for 32-bit configuration + it's low 16 bits, for 16-bit configuration it's second. */ + + uint16_t filter_mask_high; /*!< config the filter mask or identification, according to the filtering mode, + for 32-bit configuration it's high 16 bits, for 16-bit configuration it's first. */ + + uint16_t filter_mask_low; /*!< config the filter mask or identification, according to the filtering mode, + for 32-bit configuration it's low 16 bits, for 16-bit configuration it's second. */ +} can_filter_init_type; + +/** + * @brief can tx message structure definition + */ +typedef struct +{ + uint32_t standard_id; /*!< specifies the 11 bits standard identifier. + this parameter can be a value between 0 to 0x7FF. */ + + uint32_t extended_id; /*!< specifies the 29 bits extended identifier. + this parameter can be a value between 0 to 0x1FFFFFFF. */ + + can_identifier_type id_type; /*!< specifies identifier type for the transmit message.*/ + + can_trans_frame_type frame_type; /*!< specifies frame type for the transmit message.*/ + + uint8_t dlc; /*!< specifies frame data length that will be transmitted. + this parameter can be a value between 0 to 8 */ + + uint8_t data[8]; /*!< contains the transmit data. it ranges from 0 to 0xFF. */ + +} can_tx_message_type; + +/** + * @brief can rx message structure definition + */ +typedef struct +{ + uint32_t standard_id; /*!< specifies the 11 bits standard identifier + this parameter can be a value between 0 to 0x7FF. */ + + uint32_t extended_id; /*!< specifies the 29 bits extended identifier. + this parameter can be a value between 0 to 0x1FFFFFFF. */ + + can_identifier_type id_type; /*!< specifies identifier type for the receive message.*/ + + can_trans_frame_type frame_type; /*!< specifies frame type for the receive message.*/ + + uint8_t dlc; /*!< specifies the frame data length that will be received. + this parameter can be a value between 0 to 8 */ + + uint8_t data[8]; /*!< contains the receive data. it ranges from 0 to 0xFF.*/ + + uint8_t filter_index; /*!< specifies the message stored in which filter + this parameter can be a value between 0 to 0xFF */ +} can_rx_message_type; + +/** + * @brief can controller area network tx mailbox + */ +typedef struct +{ + /** + * @brief can tmi register + */ + union + { + __IO uint32_t tmi; + struct + { + __IO uint32_t tmsr : 1; /* [0] */ + __IO uint32_t tmfrsel : 1; /* [1] */ + __IO uint32_t tmidsel : 1; /* [2] */ + __IO uint32_t tmeid : 18;/* [20:3] */ + __IO uint32_t tmsid : 11;/* [31:21] */ + } tmi_bit; + }; + + /** + * @brief can tmc register + */ + union + { + __IO uint32_t tmc; + struct + { + __IO uint32_t tmdtbl : 4; /* [3:0] */ + __IO uint32_t reserved1 : 4; /* [7:4] */ + __IO uint32_t tmtsten : 1; /* [8] */ + __IO uint32_t reserved2 : 7; /* [15:9] */ + __IO uint32_t tmts : 16;/* [31:16] */ + } tmc_bit; + }; + + /** + * @brief can tmdtl register + */ + union + { + __IO uint32_t tmdtl; + struct + { + __IO uint32_t tmdt0 : 8; /* [7:0] */ + __IO uint32_t tmdt1 : 8; /* [15:8] */ + __IO uint32_t tmdt2 : 8; /* [23:16] */ + __IO uint32_t tmdt3 : 8; /* [31:24] */ + } tmdtl_bit; + }; + + /** + * @brief can tmdth register + */ + union + { + __IO uint32_t tmdth; + struct + { + __IO uint32_t tmdt4 : 8; /* [7:0] */ + __IO uint32_t tmdt5 : 8; /* [15:8] */ + __IO uint32_t tmdt6 : 8; /* [23:16] */ + __IO uint32_t tmdt7 : 8; /* [31:24] */ + } tmdth_bit; + }; +} can_tx_mailbox_type; + +/** + * @brief can controller area network fifo mailbox + */ +typedef struct +{ + /** + * @brief can rfi register + */ + union + { + __IO uint32_t rfi; + struct + { + __IO uint32_t reserved1 : 1; /* [0] */ + __IO uint32_t rffri : 1; /* [1] */ + __IO uint32_t rfidi : 1; /* [2] */ + __IO uint32_t rfeid : 18;/* [20:3] */ + __IO uint32_t rfsid : 11;/* [31:21] */ + } rfi_bit; + }; + + /** + * @brief can rfc register + */ + union + { + __IO uint32_t rfc; + struct + { + __IO uint32_t rfdtl : 4; /* [3:0] */ + __IO uint32_t reserved1 : 4; /* [7:4] */ + __IO uint32_t rffmn : 8; /* [15:8] */ + __IO uint32_t rfts : 16;/* [31:16] */ + } rfc_bit; + }; + + /** + * @brief can rfdtl register + */ + union + { + __IO uint32_t rfdtl; + struct + { + __IO uint32_t rfdt0 : 8; /* [7:0] */ + __IO uint32_t rfdt1 : 8; /* [15:8] */ + __IO uint32_t rfdt2 : 8; /* [23:16] */ + __IO uint32_t rfdt3 : 8; /* [31:24] */ + } rfdtl_bit; + }; + + /** + * @brief can rfdth register + */ + union + { + __IO uint32_t rfdth; + struct + { + __IO uint32_t rfdt4 : 8; /* [7:0] */ + __IO uint32_t rfdt5 : 8; /* [15:8] */ + __IO uint32_t rfdt6 : 8; /* [23:16] */ + __IO uint32_t rfdt7 : 8; /* [31:24] */ + } rfdth_bit; + }; +} can_fifo_mailbox_type; + +/** + * @brief can controller area network filter bit register + */ +typedef struct +{ + __IO uint32_t ffdb1; + __IO uint32_t ffdb2; +} can_filter_register_type; + +/** + * @brief type define can register all + */ +typedef struct +{ + + /** + * @brief can mctrl register, offset:0x00 + */ + union + { + __IO uint32_t mctrl; + struct + { + __IO uint32_t fzen : 1; /* [0] */ + __IO uint32_t dzen : 1; /* [1] */ + __IO uint32_t mmssr : 1; /* [2] */ + __IO uint32_t mdrsel : 1; /* [3] */ + __IO uint32_t prsfen : 1; /* [4] */ + __IO uint32_t aeden : 1; /* [5] */ + __IO uint32_t aeboen : 1; /* [6] */ + __IO uint32_t ttcen : 1; /* [7] */ + __IO uint32_t reserved1 : 7; /* [14:8] */ + __IO uint32_t sprst : 1; /* [15] */ + __IO uint32_t ptd : 1; /* [16] */ + __IO uint32_t reserved2 : 15;/*[31:17] */ + } mctrl_bit; + }; + + /** + * @brief can msts register, offset:0x04 + */ + union + { + __IO uint32_t msts; + struct + { + __IO uint32_t fzc : 1; /* [0] */ + __IO uint32_t dzc : 1; /* [1] */ + __IO uint32_t eoif : 1; /* [2] */ + __IO uint32_t qdzif : 1; /* [3] */ + __IO uint32_t edzif : 1; /* [4] */ + __IO uint32_t reserved1 : 3; /* [7:5] */ + __IO uint32_t cuss : 1; /* [8] */ + __IO uint32_t curs : 1; /* [9] */ + __IO uint32_t lsamprx : 1; /* [10] */ + __IO uint32_t realrx : 1; /* [11] */ + __IO uint32_t reserved2 : 20;/*[31:12] */ + } msts_bit; + }; + + /** + * @brief can tsts register, offset:0x08 + */ + union + { + __IO uint32_t tsts; + struct + { + __IO uint32_t tm0tcf : 1; /* [0] */ + __IO uint32_t tm0tsf : 1; /* [1] */ + __IO uint32_t tm0alf : 1; /* [2] */ + __IO uint32_t tm0tef : 1; /* [3] */ + __IO uint32_t reserved1 : 3; /* [6:4] */ + __IO uint32_t tm0ct : 1; /* [7] */ + __IO uint32_t tm1tcf : 1; /* [8] */ + __IO uint32_t tm1tsf : 1; /* [9] */ + __IO uint32_t tm1alf : 1; /* [10] */ + __IO uint32_t tm1tef : 1; /* [11] */ + __IO uint32_t reserved2 : 3; /* [14:12] */ + __IO uint32_t tm1ct : 1; /* [15] */ + __IO uint32_t tm2tcf : 1; /* [16] */ + __IO uint32_t tm2tsf : 1; /* [17] */ + __IO uint32_t tm2alf : 1; /* [18] */ + __IO uint32_t tm2tef : 1; /* [19] */ + __IO uint32_t reserved3 : 3; /* [22:20] */ + __IO uint32_t tm2ct : 1; /* [23] */ + __IO uint32_t tmnr : 2; /* [25:24] */ + __IO uint32_t tm0ef : 1; /* [26] */ + __IO uint32_t tm1ef : 1; /* [27] */ + __IO uint32_t tm2ef : 1; /* [28] */ + __IO uint32_t tm0lpf : 1; /* [29] */ + __IO uint32_t tm1lpf : 1; /* [30] */ + __IO uint32_t tm2lpf : 1; /* [31] */ + } tsts_bit; + }; + + /** + * @brief can rf0 register, offset:0x0C + */ + union + { + __IO uint32_t rf0; + struct + { + __IO uint32_t rf0mn : 2; /* [1:0] */ + __IO uint32_t reserved1 : 1; /* [2] */ + __IO uint32_t rf0ff : 1; /* [3] */ + __IO uint32_t rf0of : 1; /* [4] */ + __IO uint32_t rf0r : 1; /* [5] */ + __IO uint32_t reserved2 : 26;/* [31:6] */ + } rf0_bit; + }; + + /** + * @brief can rf1 register, offset:0x10 + */ + union + { + __IO uint32_t rf1; + struct + { + __IO uint32_t rf1mn : 2; /* [1:0] */ + __IO uint32_t reserved1 : 1; /* [2] */ + __IO uint32_t rf1ff : 1; /* [3] */ + __IO uint32_t rf1of : 1; /* [4] */ + __IO uint32_t rf1r : 1; /* [5] */ + __IO uint32_t reserved2 : 26;/* [31:6] */ + } rf1_bit; + }; + + /** + * @brief can inten register, offset:0x14 + */ + union + { + __IO uint32_t inten; + struct + { + __IO uint32_t tcien : 1; /* [0] */ + __IO uint32_t rf0mien : 1; /* [1] */ + __IO uint32_t rf0fien : 1; /* [2] */ + __IO uint32_t rf0oien : 1; /* [3] */ + __IO uint32_t rf1mien : 1; /* [4] */ + __IO uint32_t rf1fien : 1; /* [5] */ + __IO uint32_t rf1oien : 1; /* [6] */ + __IO uint32_t reserved1 : 1; /* [7] */ + __IO uint32_t eaien : 1; /* [8] */ + __IO uint32_t epien : 1; /* [9] */ + __IO uint32_t boien : 1; /* [10] */ + __IO uint32_t etrien : 1; /* [11] */ + __IO uint32_t reserved2 : 3; /* [14:12] */ + __IO uint32_t eoien : 1; /* [15] */ + __IO uint32_t qdzien : 1; /* [16] */ + __IO uint32_t edzien : 1; /* [17] */ + __IO uint32_t reserved3 : 14;/* [31:18] */ + } inten_bit; + }; + + /** + * @brief can ests register, offset:0x18 + */ + union + { + __IO uint32_t ests; + struct + { + __IO uint32_t eaf : 1; /* [0] */ + __IO uint32_t epf : 1; /* [1] */ + __IO uint32_t bof : 1; /* [2] */ + __IO uint32_t reserved1 : 1; /* [3] */ + __IO uint32_t etr : 3; /* [6:4] */ + __IO uint32_t reserved2 : 9; /* [15:7] */ + __IO uint32_t tec : 8; /* [23:16] */ + __IO uint32_t rec : 8; /* [31:24] */ + } ests_bit; + }; + + /** + * @brief can btmg register, offset:0x1C + */ + union + { + __IO uint32_t btmg; + struct + { + __IO uint32_t brdiv : 12;/* [11:0] */ + __IO uint32_t reserved1 : 4; /* [15:12] */ + __IO uint32_t bts1 : 4; /* [19:16] */ + __IO uint32_t bts2 : 3; /* [22:20] */ + __IO uint32_t reserved2 : 1; /* [23] */ + __IO uint32_t rsaw : 2; /* [25:24] */ + __IO uint32_t reserved3 : 4; /* [29:26] */ + __IO uint32_t lben : 1; /* [30] */ + __IO uint32_t loen : 1; /* [31] */ + } btmg_bit; + }; + + /** + * @brief can reserved register, offset:0x20~0x17C + */ + __IO uint32_t reserved1[88]; + + /** + * @brief can controller area network tx mailbox register, offset:0x180~0x1AC + */ + can_tx_mailbox_type tx_mailbox[3]; + + /** + * @brief can controller area network fifo mailbox register, offset:0x1B0~0x1CC + */ + can_fifo_mailbox_type fifo_mailbox[2]; + + /** + * @brief can reserved register, offset:0x1D0~0x1FC + */ + __IO uint32_t reserved2[12]; + + /** + * @brief can fctrl register, offset:0x200 + */ + union + { + __IO uint32_t fctrl; + struct + { + __IO uint32_t fcs : 1; /* [0] */ + __IO uint32_t reserved1 : 31;/* [31:1] */ + } fctrl_bit; + }; + + /** + * @brief can fmcfg register, offset:0x204 + */ + union + { + __IO uint32_t fmcfg; + struct + { + __IO uint32_t fmsel0 : 1; /* [0] */ + __IO uint32_t fmsel1 : 1; /* [1] */ + __IO uint32_t fmsel2 : 1; /* [2] */ + __IO uint32_t fmsel3 : 1; /* [3] */ + __IO uint32_t fmsel4 : 1; /* [4] */ + __IO uint32_t fmsel5 : 1; /* [5] */ + __IO uint32_t fmsel6 : 1; /* [6] */ + __IO uint32_t fmsel7 : 1; /* [7] */ + __IO uint32_t fmsel8 : 1; /* [8] */ + __IO uint32_t fmsel9 : 1; /* [9] */ + __IO uint32_t fmsel10 : 1; /* [10] */ + __IO uint32_t fmsel11 : 1; /* [11] */ + __IO uint32_t fmsel12 : 1; /* [12] */ + __IO uint32_t fmsel13 : 1; /* [13] */ + __IO uint32_t fmsel14 : 1; /* [14] */ + __IO uint32_t fmsel15 : 1; /* [15] */ + __IO uint32_t fmsel16 : 1; /* [16] */ + __IO uint32_t fmsel17 : 1; /* [17] */ + __IO uint32_t fmsel18 : 1; /* [18] */ + __IO uint32_t fmsel19 : 1; /* [19] */ + __IO uint32_t fmsel20 : 1; /* [20] */ + __IO uint32_t fmsel21 : 1; /* [21] */ + __IO uint32_t fmsel22 : 1; /* [22] */ + __IO uint32_t fmsel23 : 1; /* [23] */ + __IO uint32_t fmsel24 : 1; /* [24] */ + __IO uint32_t fmsel25 : 1; /* [25] */ + __IO uint32_t fmsel26 : 1; /* [26] */ + __IO uint32_t fmsel27 : 1; /* [27] */ + __IO uint32_t reserved1 : 4;/* [31:28] */ + } fmcfg_bit; + }; + + /** + * @brief can reserved register, offset:0x208 + */ + __IO uint32_t reserved3; + + /** + * @brief can fbwcfg register, offset:0x20C + */ + union + { + __IO uint32_t fbwcfg; + struct + { + __IO uint32_t fbwsel0 : 1; /* [0] */ + __IO uint32_t fbwsel1 : 1; /* [1] */ + __IO uint32_t fbwsel2 : 1; /* [2] */ + __IO uint32_t fbwsel3 : 1; /* [3] */ + __IO uint32_t fbwsel4 : 1; /* [4] */ + __IO uint32_t fbwsel5 : 1; /* [5] */ + __IO uint32_t fbwsel6 : 1; /* [6] */ + __IO uint32_t fbwsel7 : 1; /* [7] */ + __IO uint32_t fbwsel8 : 1; /* [8] */ + __IO uint32_t fbwsel9 : 1; /* [9] */ + __IO uint32_t fbwsel10 : 1; /* [10] */ + __IO uint32_t fbwsel11 : 1; /* [11] */ + __IO uint32_t fbwsel12 : 1; /* [12] */ + __IO uint32_t fbwsel13 : 1; /* [13] */ + __IO uint32_t fbwsel14 : 1; /* [14] */ + __IO uint32_t fbwsel15 : 1; /* [15] */ + __IO uint32_t fbwsel16 : 1; /* [16] */ + __IO uint32_t fbwsel17 : 1; /* [17] */ + __IO uint32_t fbwsel18 : 1; /* [18] */ + __IO uint32_t fbwsel19 : 1; /* [19] */ + __IO uint32_t fbwsel20 : 1; /* [20] */ + __IO uint32_t fbwsel21 : 1; /* [21] */ + __IO uint32_t fbwsel22 : 1; /* [22] */ + __IO uint32_t fbwsel23 : 1; /* [23] */ + __IO uint32_t fbwsel24 : 1; /* [24] */ + __IO uint32_t fbwsel25 : 1; /* [25] */ + __IO uint32_t fbwsel26 : 1; /* [26] */ + __IO uint32_t fbwsel27 : 1; /* [27] */ + __IO uint32_t reserved1 : 4;/* [31:28] */ + } fbwcfg_bit; + }; + + /** + * @brief can reserved register, offset:0x210 + */ + __IO uint32_t reserved4; + + /** + * @brief can frf register, offset:0x214 + */ + union + { + __IO uint32_t frf; + struct + { + __IO uint32_t frfsel0 : 1; /* [0] */ + __IO uint32_t frfsel1 : 1; /* [1] */ + __IO uint32_t frfsel2 : 1; /* [2] */ + __IO uint32_t frfsel3 : 1; /* [3] */ + __IO uint32_t frfsel4 : 1; /* [4] */ + __IO uint32_t frfsel5 : 1; /* [5] */ + __IO uint32_t frfsel6 : 1; /* [6] */ + __IO uint32_t frfsel7 : 1; /* [7] */ + __IO uint32_t frfsel8 : 1; /* [8] */ + __IO uint32_t frfsel9 : 1; /* [9] */ + __IO uint32_t frfsel10 : 1; /* [10] */ + __IO uint32_t frfsel11 : 1; /* [11] */ + __IO uint32_t frfsel12 : 1; /* [12] */ + __IO uint32_t frfsel13 : 1; /* [13] */ + __IO uint32_t frfsel14 : 1; /* [14] */ + __IO uint32_t frfsel15 : 1; /* [15] */ + __IO uint32_t frfsel16 : 1; /* [16] */ + __IO uint32_t frfsel17 : 1; /* [17] */ + __IO uint32_t frfsel18 : 1; /* [18] */ + __IO uint32_t frfsel19 : 1; /* [19] */ + __IO uint32_t frfsel20 : 1; /* [20] */ + __IO uint32_t frfsel21 : 1; /* [21] */ + __IO uint32_t frfsel22 : 1; /* [22] */ + __IO uint32_t frfsel23 : 1; /* [23] */ + __IO uint32_t frfsel24 : 1; /* [24] */ + __IO uint32_t frfsel25 : 1; /* [25] */ + __IO uint32_t frfsel26 : 1; /* [26] */ + __IO uint32_t frfsel27 : 1; /* [27] */ + __IO uint32_t reserved1 : 4;/* [31:28] */ + } frf_bit; + }; + + /** + * @brief can reserved register, offset:0x218 + */ + __IO uint32_t reserved5; + + /** + * @brief can facfg register, offset:0x21C + */ + union + { + __IO uint32_t facfg; + struct + { + __IO uint32_t faen0 : 1; /* [0] */ + __IO uint32_t faen1 : 1; /* [1] */ + __IO uint32_t faen2 : 1; /* [2] */ + __IO uint32_t faen3 : 1; /* [3] */ + __IO uint32_t faen4 : 1; /* [4] */ + __IO uint32_t faen5 : 1; /* [5] */ + __IO uint32_t faen6 : 1; /* [6] */ + __IO uint32_t faen7 : 1; /* [7] */ + __IO uint32_t faen8 : 1; /* [8] */ + __IO uint32_t faen9 : 1; /* [9] */ + __IO uint32_t faen10 : 1; /* [10] */ + __IO uint32_t faen11 : 1; /* [11] */ + __IO uint32_t faen12 : 1; /* [12] */ + __IO uint32_t faen13 : 1; /* [13] */ + __IO uint32_t faen14 : 1; /* [14] */ + __IO uint32_t faen15 : 1; /* [15] */ + __IO uint32_t faen16 : 1; /* [16] */ + __IO uint32_t faen17 : 1; /* [17] */ + __IO uint32_t faen18 : 1; /* [18] */ + __IO uint32_t faen19 : 1; /* [19] */ + __IO uint32_t faen20 : 1; /* [20] */ + __IO uint32_t faen21 : 1; /* [21] */ + __IO uint32_t faen22 : 1; /* [22] */ + __IO uint32_t faen23 : 1; /* [23] */ + __IO uint32_t faen24 : 1; /* [24] */ + __IO uint32_t faen25 : 1; /* [25] */ + __IO uint32_t faen26 : 1; /* [26] */ + __IO uint32_t faen27 : 1; /* [27] */ + __IO uint32_t reserved1 : 4;/* [31:28] */ + } facfg_bit; + }; + + /** + * @brief can reserved register, offset:0x220~0x23C + */ + __IO uint32_t reserved6[8]; + + /** + * @brief can ffb register, offset:0x240~0x2AC + */ + can_filter_register_type ffb[28]; +} can_type; + +/** + * @} + */ + +#define CAN1 ((can_type *) CAN1_BASE) +#define CAN2 ((can_type *) CAN2_BASE) + +/** @defgroup CAN_exported_functions + * @{ + */ + +void can_reset(can_type* can_x); +void can_baudrate_default_para_init(can_baudrate_type* can_baudrate_struct); +error_status can_baudrate_set(can_type* can_x, can_baudrate_type* can_baudrate_struct); +void can_default_para_init(can_base_type* can_base_struct); +error_status can_base_init(can_type* can_x, can_base_type* can_base_struct); +void can_filter_default_para_init(can_filter_init_type* can_filter_init_struct); +void can_filter_init(can_type* can_x, can_filter_init_type* can_filter_init_struct); +void can_debug_transmission_prohibit(can_type* can_x, confirm_state new_state); +void can_ttc_mode_enable(can_type* can_x, confirm_state new_state); +uint8_t can_message_transmit(can_type* can_x, can_tx_message_type* tx_message_struct); +can_transmit_status_type can_transmit_status_get(can_type* can_x, can_tx_mailbox_num_type transmit_mailbox); +void can_transmit_cancel(can_type* can_x, can_tx_mailbox_num_type transmit_mailbox); +void can_message_receive(can_type* can_x, can_rx_fifo_num_type fifo_number, can_rx_message_type* rx_message_struct); +void can_receive_fifo_release(can_type* can_x, can_rx_fifo_num_type fifo_number); +uint8_t can_receive_message_pending_get(can_type* can_x, can_rx_fifo_num_type fifo_number); +error_status can_operating_mode_set(can_type* can_x, can_operating_mode_type can_operating_mode); +can_enter_doze_status_type can_doze_mode_enter(can_type* can_x); +can_quit_doze_status_type can_doze_mode_exit(can_type* can_x); +can_error_record_type can_error_type_record_get(can_type* can_x); +uint8_t can_receive_error_counter_get(can_type* can_x); +uint8_t can_transmit_error_counter_get(can_type* can_x); +void can_interrupt_enable(can_type* can_x, uint32_t can_int, confirm_state new_state); +flag_status can_flag_get(can_type* can_x, uint32_t can_flag); +void can_flag_clear(can_type* can_x, uint32_t can_flag); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_crc.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_crc.h new file mode 100644 index 0000000000..df3f882816 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_crc.h @@ -0,0 +1,172 @@ +/** + ************************************************************************** + * @file at32f435_437_crc.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 crc header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_CRC_H +#define __AT32F435_437_CRC_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup CRC + * @{ + */ + +/** @defgroup CRC_exported_types + * @{ + */ + +/** + * @brief crc reverse input data + */ +typedef enum +{ + CRC_REVERSE_INPUT_NO_AFFECTE = 0x00, /*!< input data no reverse */ + CRC_REVERSE_INPUT_BY_BYTE = 0x01, /*!< input data reverse by byte */ + CRC_REVERSE_INPUT_BY_HALFWORD = 0x02, /*!< input data reverse by half word */ + CRC_REVERSE_INPUT_BY_WORD = 0x03 /*!< input data reverse by word */ +} crc_reverse_input_type; + +/** + * @brief crc reverse output data + */ +typedef enum +{ + CRC_REVERSE_OUTPUT_NO_AFFECTE = 0x00, /*!< output data no reverse */ + CRC_REVERSE_OUTPUT_DATA = 0x01 /*!< output data reverse by word */ +} crc_reverse_output_type; + +/** + * @brief type define crc register all + */ +typedef struct +{ + /** + * @brief crc dt register, offset:0x00 + */ + union + { + __IO uint32_t dt; + struct + { + __IO uint32_t dt : 32; /* [31:0] */ + } dt_bit; + }; + + /** + * @brief crc cdt register, offset:0x04 + */ + union + { + __IO uint32_t cdt; + struct + { + __IO uint32_t cdt : 8 ; /* [7:0] */ + __IO uint32_t reserved1 : 24 ;/* [31:8] */ + } cdt_bit; + }; + + /** + * @brief crc ctrl register, offset:0x08 + */ + union + { + __IO uint32_t ctrl; + struct + { + __IO uint32_t rst : 1 ; /* [0] */ + __IO uint32_t reserved1 : 4 ; /* [4:1] */ + __IO uint32_t revid : 2 ; /* [6:5] */ + __IO uint32_t revod : 1 ; /* [7] */ + __IO uint32_t reserved2 : 24 ;/* [31:8] */ + } ctrl_bit; + }; + + /** + * @brief crm reserved1 register, offset:0x0C + */ + __IO uint32_t reserved1; + + /** + * @brief crc idt register, offset:0x10 + */ + union + { + __IO uint32_t idt; + struct + { + __IO uint32_t idt : 32; /* [31:0] */ + } idt_bit; + }; + +} crc_type; + +/** + * @} + */ + +#define CRC ((crc_type *) CRC_BASE) + +/** @defgroup CRC_exported_functions + * @{ + */ + +void crc_data_reset(void); +uint32_t crc_one_word_calculate(uint32_t data); +uint32_t crc_block_calculate(uint32_t *pbuffer, uint32_t length); +uint32_t crc_data_get(void); +void crc_common_data_set(uint8_t cdt_value); +uint8_t crc_common_data_get(void); +void crc_init_data_set(uint32_t value); +void crc_reverse_input_data_set(crc_reverse_input_type value); +void crc_reverse_output_data_set(crc_reverse_output_type value); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_crm.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_crm.h new file mode 100644 index 0000000000..09ed2fa29a --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_crm.h @@ -0,0 +1,1572 @@ +/** + ************************************************************************** + * @file at32f435_437_crm.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 crm header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_CRM_H +#define __AT32F435_437_CRM_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup CRM + * @{ + */ + +#define CRM_REG(value) PERIPH_REG(CRM_BASE, value) +#define CRM_REG_BIT(value) PERIPH_REG_BIT(value) + +/** @defgroup CRM_flags_definition + * @brief crm flag + * @{ + */ + +#define CRM_HICK_STABLE_FLAG MAKE_VALUE(0x00, 1) /*!< high speed internal clock stable flag */ +#define CRM_HEXT_STABLE_FLAG MAKE_VALUE(0x00, 17) /*!< high speed external crystal stable flag */ +#define CRM_PLL_STABLE_FLAG MAKE_VALUE(0x00, 25) /*!< phase locking loop stable flag */ +#define CRM_LEXT_STABLE_FLAG MAKE_VALUE(0x70, 1) /*!< low speed external crystal stable flag */ +#define CRM_LICK_STABLE_FLAG MAKE_VALUE(0x74, 1) /*!< low speed internal clock stable flag */ +#define CRM_ALL_RESET_FLAG MAKE_VALUE(0x74, 24) /*!< all reset flag */ +#define CRM_NRST_RESET_FLAG MAKE_VALUE(0x74, 26) /*!< nrst pin reset flag */ +#define CRM_POR_RESET_FLAG MAKE_VALUE(0x74, 27) /*!< power on reset flag */ +#define CRM_SW_RESET_FLAG MAKE_VALUE(0x74, 28) /*!< software reset flag */ +#define CRM_WDT_RESET_FLAG MAKE_VALUE(0x74, 29) /*!< watchdog timer reset flag */ +#define CRM_WWDT_RESET_FLAG MAKE_VALUE(0x74, 30) /*!< window watchdog timer reset flag */ +#define CRM_LOWPOWER_RESET_FLAG MAKE_VALUE(0x74, 31) /*!< low-power reset flag */ +#define CRM_LICK_READY_INT_FLAG MAKE_VALUE(0x0C, 0) /*!< low speed internal clock stable interrupt ready flag */ +#define CRM_LEXT_READY_INT_FLAG MAKE_VALUE(0x0C, 1) /*!< low speed external crystal stable interrupt ready flag */ +#define CRM_HICK_READY_INT_FLAG MAKE_VALUE(0x0C, 2) /*!< high speed internal clock stable interrupt ready flag */ +#define CRM_HEXT_READY_INT_FLAG MAKE_VALUE(0x0C, 3) /*!< high speed external crystal stable interrupt ready flag */ +#define CRM_PLL_READY_INT_FLAG MAKE_VALUE(0x0C, 4) /*!< phase locking loop stable interrupt ready flag */ +#define CRM_CLOCK_FAILURE_INT_FLAG MAKE_VALUE(0x0C, 7) /*!< clock failure interrupt ready flag */ + +/** + * @} + */ + +/** @defgroup CRM_interrupts_definition + * @brief crm interrupt + * @{ + */ + +#define CRM_LICK_STABLE_INT ((uint32_t)0x00000100) /*!< low speed internal clock stable interrupt */ +#define CRM_LEXT_STABLE_INT ((uint32_t)0x00000200) /*!< low speed external crystal stable interrupt */ +#define CRM_HICK_STABLE_INT ((uint32_t)0x00000400) /*!< high speed internal clock stable interrupt */ +#define CRM_HEXT_STABLE_INT ((uint32_t)0x00000800) /*!< high speed external crystal stable interrupt */ +#define CRM_PLL_STABLE_INT ((uint32_t)0x00001000) /*!< phase locking loop stable interrupt */ +#define CRM_CLOCK_FAILURE_INT ((uint32_t)0x00800000) /*!< clock failure interrupt */ + +/** + * @} + */ + +/** @defgroup CRM_exported_types + * @{ + */ + +/** + * @brief crm periph clock + */ +typedef enum +{ +#if defined (AT32F435xx) + /* ahb periph1 */ + CRM_GPIOA_PERIPH_CLOCK = MAKE_VALUE(0x30, 0), /*!< gpioa periph clock */ + CRM_GPIOB_PERIPH_CLOCK = MAKE_VALUE(0x30, 1), /*!< gpiob periph clock */ + CRM_GPIOC_PERIPH_CLOCK = MAKE_VALUE(0x30, 2), /*!< gpioc periph clock */ + CRM_GPIOD_PERIPH_CLOCK = MAKE_VALUE(0x30, 3), /*!< gpiod periph clock */ + CRM_GPIOE_PERIPH_CLOCK = MAKE_VALUE(0x30, 4), /*!< gpioe periph clock */ + CRM_GPIOF_PERIPH_CLOCK = MAKE_VALUE(0x30, 5), /*!< gpiof periph clock */ + CRM_GPIOG_PERIPH_CLOCK = MAKE_VALUE(0x30, 6), /*!< gpiog periph clock */ + CRM_GPIOH_PERIPH_CLOCK = MAKE_VALUE(0x30, 7), /*!< gpioh periph clock */ + CRM_CRC_PERIPH_CLOCK = MAKE_VALUE(0x30, 12), /*!< crc periph clock */ + CRM_EDMA_PERIPH_CLOCK = MAKE_VALUE(0x30, 21), /*!< edma periph clock */ + CRM_DMA1_PERIPH_CLOCK = MAKE_VALUE(0x30, 22), /*!< dma1 periph clock */ + CRM_DMA2_PERIPH_CLOCK = MAKE_VALUE(0x30, 24), /*!< dma2 periph clock */ + CRM_OTGFS2_PERIPH_CLOCK = MAKE_VALUE(0x30, 29), /*!< otgfs2 periph clock */ + /* ahb periph2 */ + CRM_DVP_PERIPH_CLOCK = MAKE_VALUE(0x34, 0), /*!< dvp periph clock */ + CRM_OTGFS1_PERIPH_CLOCK = MAKE_VALUE(0x34, 7), /*!< otgfs1 periph clock */ + CRM_SDIO1_PERIPH_CLOCK = MAKE_VALUE(0x34, 15), /*!< sdio1 periph clock */ + /* ahb periph3 */ + CRM_XMC_PERIPH_CLOCK = MAKE_VALUE(0x38, 0), /*!< xmc periph clock */ + CRM_QSPI1_PERIPH_CLOCK = MAKE_VALUE(0x38, 1), /*!< qspi1 periph clock */ + CRM_QSPI2_PERIPH_CLOCK = MAKE_VALUE(0x38, 14), /*!< qspi2 periph clock */ + CRM_SDIO2_PERIPH_CLOCK = MAKE_VALUE(0x38, 15), /*!< sdio2 periph clock */ + /* apb1 periph */ + CRM_TMR2_PERIPH_CLOCK = MAKE_VALUE(0x40, 0), /*!< tmr2 periph clock */ + CRM_TMR3_PERIPH_CLOCK = MAKE_VALUE(0x40, 1), /*!< tmr3 periph clock */ + CRM_TMR4_PERIPH_CLOCK = MAKE_VALUE(0x40, 2), /*!< tmr4 periph clock */ + CRM_TMR5_PERIPH_CLOCK = MAKE_VALUE(0x40, 3), /*!< tmr5 periph clock */ + CRM_TMR6_PERIPH_CLOCK = MAKE_VALUE(0x40, 4), /*!< tmr6 periph clock */ + CRM_TMR7_PERIPH_CLOCK = MAKE_VALUE(0x40, 5), /*!< tmr7 periph clock */ + CRM_TMR12_PERIPH_CLOCK = MAKE_VALUE(0x40, 6), /*!< tmr12 periph clock */ + CRM_TMR13_PERIPH_CLOCK = MAKE_VALUE(0x40, 7), /*!< tmr13 periph clock */ + CRM_TMR14_PERIPH_CLOCK = MAKE_VALUE(0x40, 8), /*!< tmr14 periph clock */ + CRM_WWDT_PERIPH_CLOCK = MAKE_VALUE(0x40, 11), /*!< wwdt periph clock */ + CRM_SPI2_PERIPH_CLOCK = MAKE_VALUE(0x40, 14), /*!< spi2 periph clock */ + CRM_SPI3_PERIPH_CLOCK = MAKE_VALUE(0x40, 15), /*!< spi3 periph clock */ + CRM_USART2_PERIPH_CLOCK = MAKE_VALUE(0x40, 17), /*!< usart2 periph clock */ + CRM_USART3_PERIPH_CLOCK = MAKE_VALUE(0x40, 18), /*!< usart3 periph clock */ + CRM_UART4_PERIPH_CLOCK = MAKE_VALUE(0x40, 19), /*!< uart4 periph clock */ + CRM_UART5_PERIPH_CLOCK = MAKE_VALUE(0x40, 20), /*!< uart5 periph clock */ + CRM_I2C1_PERIPH_CLOCK = MAKE_VALUE(0x40, 21), /*!< i2c1 periph clock */ + CRM_I2C2_PERIPH_CLOCK = MAKE_VALUE(0x40, 22), /*!< i2c2 periph clock */ + CRM_I2C3_PERIPH_CLOCK = MAKE_VALUE(0x40, 23), /*!< i2c3 periph clock */ + CRM_CAN1_PERIPH_CLOCK = MAKE_VALUE(0x40, 25), /*!< can1 periph clock */ + CRM_CAN2_PERIPH_CLOCK = MAKE_VALUE(0x40, 26), /*!< can2 periph clock */ + CRM_PWC_PERIPH_CLOCK = MAKE_VALUE(0x40, 28), /*!< pwc periph clock */ + CRM_DAC_PERIPH_CLOCK = MAKE_VALUE(0x40, 29), /*!< dac periph clock */ + CRM_UART7_PERIPH_CLOCK = MAKE_VALUE(0x40, 30), /*!< uart7 periph clock */ + CRM_UART8_PERIPH_CLOCK = MAKE_VALUE(0x40, 31), /*!< uart8 periph clock */ + /* apb2 periph */ + CRM_TMR1_PERIPH_CLOCK = MAKE_VALUE(0x44, 0), /*!< tmr1 periph clock */ + CRM_TMR8_PERIPH_CLOCK = MAKE_VALUE(0x44, 1), /*!< tmr8 periph clock */ + CRM_USART1_PERIPH_CLOCK = MAKE_VALUE(0x44, 4), /*!< usart1 periph clock */ + CRM_USART6_PERIPH_CLOCK = MAKE_VALUE(0x44, 5), /*!< usart6 periph clock */ + CRM_ADC1_PERIPH_CLOCK = MAKE_VALUE(0x44, 8), /*!< adc1 periph clock */ + CRM_ADC2_PERIPH_CLOCK = MAKE_VALUE(0x44, 9), /*!< adc2 periph clock */ + CRM_ADC3_PERIPH_CLOCK = MAKE_VALUE(0x44, 10), /*!< adc3 periph clock */ + CRM_SPI1_PERIPH_CLOCK = MAKE_VALUE(0x44, 12), /*!< spi1 periph clock */ + CRM_SPI4_PERIPH_CLOCK = MAKE_VALUE(0x44, 13), /*!< spi4 periph clock */ + CRM_SCFG_PERIPH_CLOCK = MAKE_VALUE(0x44, 14), /*!< scfg periph clock */ + CRM_TMR9_PERIPH_CLOCK = MAKE_VALUE(0x44, 16), /*!< tmr9 periph clock */ + CRM_TMR10_PERIPH_CLOCK = MAKE_VALUE(0x44, 17), /*!< tmr10 periph clock */ + CRM_TMR11_PERIPH_CLOCK = MAKE_VALUE(0x44, 18), /*!< tmr11 periph clock */ + CRM_TMR20_PERIPH_CLOCK = MAKE_VALUE(0x44, 20), /*!< tmr20 periph clock */ + CRM_ACC_PERIPH_CLOCK = MAKE_VALUE(0x44, 29) /*!< acc periph clock */ +#endif + +#if defined (AT32F437xx) + /* ahb periph1 */ + CRM_GPIOA_PERIPH_CLOCK = MAKE_VALUE(0x30, 0), /*!< gpioa periph clock */ + CRM_GPIOB_PERIPH_CLOCK = MAKE_VALUE(0x30, 1), /*!< gpiob periph clock */ + CRM_GPIOC_PERIPH_CLOCK = MAKE_VALUE(0x30, 2), /*!< gpioc periph clock */ + CRM_GPIOD_PERIPH_CLOCK = MAKE_VALUE(0x30, 3), /*!< gpiod periph clock */ + CRM_GPIOE_PERIPH_CLOCK = MAKE_VALUE(0x30, 4), /*!< gpioe periph clock */ + CRM_GPIOF_PERIPH_CLOCK = MAKE_VALUE(0x30, 5), /*!< gpiof periph clock */ + CRM_GPIOG_PERIPH_CLOCK = MAKE_VALUE(0x30, 6), /*!< gpiog periph clock */ + CRM_GPIOH_PERIPH_CLOCK = MAKE_VALUE(0x30, 7), /*!< gpioh periph clock */ + CRM_CRC_PERIPH_CLOCK = MAKE_VALUE(0x30, 12), /*!< crc periph clock */ + CRM_EDMA_PERIPH_CLOCK = MAKE_VALUE(0x30, 21), /*!< edma periph clock */ + CRM_DMA1_PERIPH_CLOCK = MAKE_VALUE(0x30, 22), /*!< dma1 periph clock */ + CRM_DMA2_PERIPH_CLOCK = MAKE_VALUE(0x30, 24), /*!< dma2 periph clock */ + CRM_EMAC_PERIPH_CLOCK = MAKE_VALUE(0x30, 25), /*!< emac periph clock */ + CRM_EMACTX_PERIPH_CLOCK = MAKE_VALUE(0x30, 26), /*!< emac tx periph clock */ + CRM_EMACRX_PERIPH_CLOCK = MAKE_VALUE(0x30, 27), /*!< emac rx periph clock */ + CRM_EMACPTP_PERIPH_CLOCK = MAKE_VALUE(0x30, 28), /*!< emac ptp periph clock */ + CRM_OTGFS2_PERIPH_CLOCK = MAKE_VALUE(0x30, 29), /*!< otgfs2 periph clock */ + /* ahb periph2 */ + CRM_DVP_PERIPH_CLOCK = MAKE_VALUE(0x34, 0), /*!< dvp periph clock */ + CRM_OTGFS1_PERIPH_CLOCK = MAKE_VALUE(0x34, 7), /*!< otgfs1 periph clock */ + CRM_SDIO1_PERIPH_CLOCK = MAKE_VALUE(0x34, 15), /*!< sdio1 periph clock */ + /* ahb periph3 */ + CRM_XMC_PERIPH_CLOCK = MAKE_VALUE(0x38, 0), /*!< xmc periph clock */ + CRM_QSPI1_PERIPH_CLOCK = MAKE_VALUE(0x38, 1), /*!< qspi1 periph clock */ + CRM_QSPI2_PERIPH_CLOCK = MAKE_VALUE(0x38, 14), /*!< qspi2 periph clock */ + CRM_SDIO2_PERIPH_CLOCK = MAKE_VALUE(0x38, 15), /*!< sdio2 periph clock */ + /* apb1 periph */ + CRM_TMR2_PERIPH_CLOCK = MAKE_VALUE(0x40, 0), /*!< tmr2 periph clock */ + CRM_TMR3_PERIPH_CLOCK = MAKE_VALUE(0x40, 1), /*!< tmr3 periph clock */ + CRM_TMR4_PERIPH_CLOCK = MAKE_VALUE(0x40, 2), /*!< tmr4 periph clock */ + CRM_TMR5_PERIPH_CLOCK = MAKE_VALUE(0x40, 3), /*!< tmr5 periph clock */ + CRM_TMR6_PERIPH_CLOCK = MAKE_VALUE(0x40, 4), /*!< tmr6 periph clock */ + CRM_TMR7_PERIPH_CLOCK = MAKE_VALUE(0x40, 5), /*!< tmr7 periph clock */ + CRM_TMR12_PERIPH_CLOCK = MAKE_VALUE(0x40, 6), /*!< tmr12 periph clock */ + CRM_TMR13_PERIPH_CLOCK = MAKE_VALUE(0x40, 7), /*!< tmr13 periph clock */ + CRM_TMR14_PERIPH_CLOCK = MAKE_VALUE(0x40, 8), /*!< tmr14 periph clock */ + CRM_WWDT_PERIPH_CLOCK = MAKE_VALUE(0x40, 11), /*!< wwdt periph clock */ + CRM_SPI2_PERIPH_CLOCK = MAKE_VALUE(0x40, 14), /*!< spi2 periph clock */ + CRM_SPI3_PERIPH_CLOCK = MAKE_VALUE(0x40, 15), /*!< spi3 periph clock */ + CRM_USART2_PERIPH_CLOCK = MAKE_VALUE(0x40, 17), /*!< usart2 periph clock */ + CRM_USART3_PERIPH_CLOCK = MAKE_VALUE(0x40, 18), /*!< usart3 periph clock */ + CRM_UART4_PERIPH_CLOCK = MAKE_VALUE(0x40, 19), /*!< uart4 periph clock */ + CRM_UART5_PERIPH_CLOCK = MAKE_VALUE(0x40, 20), /*!< uart5 periph clock */ + CRM_I2C1_PERIPH_CLOCK = MAKE_VALUE(0x40, 21), /*!< i2c1 periph clock */ + CRM_I2C2_PERIPH_CLOCK = MAKE_VALUE(0x40, 22), /*!< i2c2 periph clock */ + CRM_I2C3_PERIPH_CLOCK = MAKE_VALUE(0x40, 23), /*!< i2c3 periph clock */ + CRM_CAN1_PERIPH_CLOCK = MAKE_VALUE(0x40, 25), /*!< can1 periph clock */ + CRM_CAN2_PERIPH_CLOCK = MAKE_VALUE(0x40, 26), /*!< can2 periph clock */ + CRM_PWC_PERIPH_CLOCK = MAKE_VALUE(0x40, 28), /*!< pwc periph clock */ + CRM_DAC_PERIPH_CLOCK = MAKE_VALUE(0x40, 29), /*!< dac periph clock */ + CRM_UART7_PERIPH_CLOCK = MAKE_VALUE(0x40, 30), /*!< uart7 periph clock */ + CRM_UART8_PERIPH_CLOCK = MAKE_VALUE(0x40, 31), /*!< uart8 periph clock */ + /* apb2 periph */ + CRM_TMR1_PERIPH_CLOCK = MAKE_VALUE(0x44, 0), /*!< tmr1 periph clock */ + CRM_TMR8_PERIPH_CLOCK = MAKE_VALUE(0x44, 1), /*!< tmr8 periph clock */ + CRM_USART1_PERIPH_CLOCK = MAKE_VALUE(0x44, 4), /*!< usart1 periph clock */ + CRM_USART6_PERIPH_CLOCK = MAKE_VALUE(0x44, 5), /*!< usart6 periph clock */ + CRM_ADC1_PERIPH_CLOCK = MAKE_VALUE(0x44, 8), /*!< adc1 periph clock */ + CRM_ADC2_PERIPH_CLOCK = MAKE_VALUE(0x44, 9), /*!< adc2 periph clock */ + CRM_ADC3_PERIPH_CLOCK = MAKE_VALUE(0x44, 10), /*!< adc3 periph clock */ + CRM_SPI1_PERIPH_CLOCK = MAKE_VALUE(0x44, 12), /*!< spi1 periph clock */ + CRM_SPI4_PERIPH_CLOCK = MAKE_VALUE(0x44, 13), /*!< spi4 periph clock */ + CRM_SCFG_PERIPH_CLOCK = MAKE_VALUE(0x44, 14), /*!< scfg periph clock */ + CRM_TMR9_PERIPH_CLOCK = MAKE_VALUE(0x44, 16), /*!< tmr9 periph clock */ + CRM_TMR10_PERIPH_CLOCK = MAKE_VALUE(0x44, 17), /*!< tmr10 periph clock */ + CRM_TMR11_PERIPH_CLOCK = MAKE_VALUE(0x44, 18), /*!< tmr11 periph clock */ + CRM_TMR20_PERIPH_CLOCK = MAKE_VALUE(0x44, 20), /*!< tmr20 periph clock */ + CRM_ACC_PERIPH_CLOCK = MAKE_VALUE(0x44, 29) /*!< acc periph clock */ +#endif + +} crm_periph_clock_type; + +/** + * @brief crm periph reset + */ +typedef enum +{ +#if defined (AT32F435xx) + /* ahb periph1 */ + CRM_GPIOA_PERIPH_RESET = MAKE_VALUE(0x10, 0), /*!< gpioa periph reset */ + CRM_GPIOB_PERIPH_RESET = MAKE_VALUE(0x10, 1), /*!< gpiob periph reset */ + CRM_GPIOC_PERIPH_RESET = MAKE_VALUE(0x10, 2), /*!< gpioc periph reset */ + CRM_GPIOD_PERIPH_RESET = MAKE_VALUE(0x10, 3), /*!< gpiod periph reset */ + CRM_GPIOE_PERIPH_RESET = MAKE_VALUE(0x10, 4), /*!< gpioe periph reset */ + CRM_GPIOF_PERIPH_RESET = MAKE_VALUE(0x10, 5), /*!< gpiof periph reset */ + CRM_GPIOG_PERIPH_RESET = MAKE_VALUE(0x10, 6), /*!< gpiog periph reset */ + CRM_GPIOH_PERIPH_RESET = MAKE_VALUE(0x10, 7), /*!< gpioh periph reset */ + CRM_CRC_PERIPH_RESET = MAKE_VALUE(0x10, 12), /*!< crc periph reset */ + CRM_EDMA_PERIPH_RESET = MAKE_VALUE(0x10, 21), /*!< edma periph reset */ + CRM_DMA1_PERIPH_RESET = MAKE_VALUE(0x10, 22), /*!< dma1 periph reset */ + CRM_DMA2_PERIPH_RESET = MAKE_VALUE(0x10, 24), /*!< dma2 periph reset */ + CRM_OTGFS2_PERIPH_RESET = MAKE_VALUE(0x10, 29), /*!< otgfs2 periph reset */ + /* ahb periph2 */ + CRM_DVP_PERIPH_RESET = MAKE_VALUE(0x14, 0), /*!< dvp periph reset */ + CRM_OTGFS1_PERIPH_RESET = MAKE_VALUE(0x14, 7), /*!< otgfs1 periph reset */ + CRM_SDIO1_PERIPH_RESET = MAKE_VALUE(0x14, 15), /*!< sdio1 periph reset */ + /* ahb periph3 */ + CRM_XMC_PERIPH_RESET = MAKE_VALUE(0x18, 0), /*!< xmc periph reset */ + CRM_QSPI1_PERIPH_RESET = MAKE_VALUE(0x18, 1), /*!< qspi1 periph reset */ + CRM_QSPI2_PERIPH_RESET = MAKE_VALUE(0x18, 14), /*!< qspi2 periph reset */ + CRM_SDIO2_PERIPH_RESET = MAKE_VALUE(0x18, 15), /*!< sdio2 periph reset */ + /* apb1 periph */ + CRM_TMR2_PERIPH_RESET = MAKE_VALUE(0x20, 0), /*!< tmr2 periph reset */ + CRM_TMR3_PERIPH_RESET = MAKE_VALUE(0x20, 1), /*!< tmr3 periph reset */ + CRM_TMR4_PERIPH_RESET = MAKE_VALUE(0x20, 2), /*!< tmr4 periph reset */ + CRM_TMR5_PERIPH_RESET = MAKE_VALUE(0x20, 3), /*!< tmr5 periph reset */ + CRM_TMR6_PERIPH_RESET = MAKE_VALUE(0x20, 4), /*!< tmr6 periph reset */ + CRM_TMR7_PERIPH_RESET = MAKE_VALUE(0x20, 5), /*!< tmr7 periph reset */ + CRM_TMR12_PERIPH_RESET = MAKE_VALUE(0x20, 6), /*!< tmr12 periph reset */ + CRM_TMR13_PERIPH_RESET = MAKE_VALUE(0x20, 7), /*!< tmr13 periph reset */ + CRM_TMR14_PERIPH_RESET = MAKE_VALUE(0x20, 8), /*!< tmr14 periph reset */ + CRM_WWDT_PERIPH_RESET = MAKE_VALUE(0x20, 11), /*!< wwdt periph reset */ + CRM_SPI2_PERIPH_RESET = MAKE_VALUE(0x20, 14), /*!< spi2 periph reset */ + CRM_SPI3_PERIPH_RESET = MAKE_VALUE(0x20, 15), /*!< spi3 periph reset */ + CRM_USART2_PERIPH_RESET = MAKE_VALUE(0x20, 17), /*!< usart2 periph reset */ + CRM_USART3_PERIPH_RESET = MAKE_VALUE(0x20, 18), /*!< usart3 periph reset */ + CRM_UART4_PERIPH_RESET = MAKE_VALUE(0x20, 19), /*!< uart4 periph reset */ + CRM_UART5_PERIPH_RESET = MAKE_VALUE(0x20, 20), /*!< uart5 periph reset */ + CRM_I2C1_PERIPH_RESET = MAKE_VALUE(0x20, 21), /*!< i2c1 periph reset */ + CRM_I2C2_PERIPH_RESET = MAKE_VALUE(0x20, 22), /*!< i2c2 periph reset */ + CRM_I2C3_PERIPH_RESET = MAKE_VALUE(0x20, 23), /*!< i2c3 periph reset */ + CRM_CAN1_PERIPH_RESET = MAKE_VALUE(0x20, 25), /*!< can1 periph reset */ + CRM_CAN2_PERIPH_RESET = MAKE_VALUE(0x20, 26), /*!< can2 periph reset */ + CRM_PWC_PERIPH_RESET = MAKE_VALUE(0x20, 28), /*!< pwc periph reset */ + CRM_DAC_PERIPH_RESET = MAKE_VALUE(0x20, 29), /*!< dac periph reset */ + CRM_UART7_PERIPH_RESET = MAKE_VALUE(0x20, 30), /*!< uart7 periph reset */ + CRM_UART8_PERIPH_RESET = MAKE_VALUE(0x20, 31), /*!< uart8 periph reset */ + /* apb2 periph */ + CRM_TMR1_PERIPH_RESET = MAKE_VALUE(0x24, 0), /*!< tmr1 periph reset */ + CRM_TMR8_PERIPH_RESET = MAKE_VALUE(0x24, 1), /*!< tmr8 periph reset */ + CRM_USART1_PERIPH_RESET = MAKE_VALUE(0x24, 4), /*!< usart1 periph reset */ + CRM_USART6_PERIPH_RESET = MAKE_VALUE(0x24, 5), /*!< usart6 periph reset */ + CRM_ADC_PERIPH_RESET = MAKE_VALUE(0x24, 8), /*!< adc periph reset */ + CRM_SPI1_PERIPH_RESET = MAKE_VALUE(0x24, 12), /*!< spi1 periph reset */ + CRM_SPI4_PERIPH_RESET = MAKE_VALUE(0x24, 13), /*!< spi4 periph reset */ + CRM_SCFG_PERIPH_RESET = MAKE_VALUE(0x24, 14), /*!< scfg periph reset */ + CRM_TMR9_PERIPH_RESET = MAKE_VALUE(0x24, 16), /*!< tmr9 periph reset */ + CRM_TMR10_PERIPH_RESET = MAKE_VALUE(0x24, 17), /*!< tmr10 periph reset */ + CRM_TMR11_PERIPH_RESET = MAKE_VALUE(0x24, 18), /*!< tmr11 periph reset */ + CRM_TMR20_PERIPH_RESET = MAKE_VALUE(0x24, 20), /*!< tmr20 periph reset */ + CRM_ACC_PERIPH_RESET = MAKE_VALUE(0x24, 29) /*!< acc periph reset */ +#endif + +#if defined (AT32F437xx) + /* ahb periph1 */ + CRM_GPIOA_PERIPH_RESET = MAKE_VALUE(0x10, 0), /*!< gpioa periph reset */ + CRM_GPIOB_PERIPH_RESET = MAKE_VALUE(0x10, 1), /*!< gpiob periph reset */ + CRM_GPIOC_PERIPH_RESET = MAKE_VALUE(0x10, 2), /*!< gpioc periph reset */ + CRM_GPIOD_PERIPH_RESET = MAKE_VALUE(0x10, 3), /*!< gpiod periph reset */ + CRM_GPIOE_PERIPH_RESET = MAKE_VALUE(0x10, 4), /*!< gpioe periph reset */ + CRM_GPIOF_PERIPH_RESET = MAKE_VALUE(0x10, 5), /*!< gpiof periph reset */ + CRM_GPIOG_PERIPH_RESET = MAKE_VALUE(0x10, 6), /*!< gpiog periph reset */ + CRM_GPIOH_PERIPH_RESET = MAKE_VALUE(0x10, 7), /*!< gpioh periph reset */ + CRM_CRC_PERIPH_RESET = MAKE_VALUE(0x10, 12), /*!< crc periph reset */ + CRM_EDMA_PERIPH_RESET = MAKE_VALUE(0x10, 21), /*!< edma periph reset */ + CRM_DMA1_PERIPH_RESET = MAKE_VALUE(0x10, 22), /*!< dma1 periph reset */ + CRM_DMA2_PERIPH_RESET = MAKE_VALUE(0x10, 24), /*!< dma2 periph reset */ + CRM_EMAC_PERIPH_RESET = MAKE_VALUE(0x10, 25), /*!< emac periph reset */ + CRM_OTGFS2_PERIPH_RESET = MAKE_VALUE(0x10, 29), /*!< otgfs2 periph reset */ + /* ahb periph2 */ + CRM_DVP_PERIPH_RESET = MAKE_VALUE(0x14, 0), /*!< dvp periph reset */ + CRM_OTGFS1_PERIPH_RESET = MAKE_VALUE(0x14, 7), /*!< otgfs1 periph reset */ + CRM_SDIO1_PERIPH_RESET = MAKE_VALUE(0x14, 15), /*!< sdio1 periph reset */ + /* ahb periph3 */ + CRM_XMC_PERIPH_RESET = MAKE_VALUE(0x18, 0), /*!< xmc periph reset */ + CRM_QSPI1_PERIPH_RESET = MAKE_VALUE(0x18, 1), /*!< qspi1 periph reset */ + CRM_QSPI2_PERIPH_RESET = MAKE_VALUE(0x18, 14), /*!< qspi2 periph reset */ + CRM_SDIO2_PERIPH_RESET = MAKE_VALUE(0x18, 15), /*!< sdio2 periph reset */ + /* apb1 periph */ + CRM_TMR2_PERIPH_RESET = MAKE_VALUE(0x20, 0), /*!< tmr2 periph reset */ + CRM_TMR3_PERIPH_RESET = MAKE_VALUE(0x20, 1), /*!< tmr3 periph reset */ + CRM_TMR4_PERIPH_RESET = MAKE_VALUE(0x20, 2), /*!< tmr4 periph reset */ + CRM_TMR5_PERIPH_RESET = MAKE_VALUE(0x20, 3), /*!< tmr5 periph reset */ + CRM_TMR6_PERIPH_RESET = MAKE_VALUE(0x20, 4), /*!< tmr6 periph reset */ + CRM_TMR7_PERIPH_RESET = MAKE_VALUE(0x20, 5), /*!< tmr7 periph reset */ + CRM_TMR12_PERIPH_RESET = MAKE_VALUE(0x20, 6), /*!< tmr12 periph reset */ + CRM_TMR13_PERIPH_RESET = MAKE_VALUE(0x20, 7), /*!< tmr13 periph reset */ + CRM_TMR14_PERIPH_RESET = MAKE_VALUE(0x20, 8), /*!< tmr14 periph reset */ + CRM_WWDT_PERIPH_RESET = MAKE_VALUE(0x20, 11), /*!< wwdt periph reset */ + CRM_SPI2_PERIPH_RESET = MAKE_VALUE(0x20, 14), /*!< spi2 periph reset */ + CRM_SPI3_PERIPH_RESET = MAKE_VALUE(0x20, 15), /*!< spi3 periph reset */ + CRM_USART2_PERIPH_RESET = MAKE_VALUE(0x20, 17), /*!< usart2 periph reset */ + CRM_USART3_PERIPH_RESET = MAKE_VALUE(0x20, 18), /*!< usart3 periph reset */ + CRM_UART4_PERIPH_RESET = MAKE_VALUE(0x20, 19), /*!< uart4 periph reset */ + CRM_UART5_PERIPH_RESET = MAKE_VALUE(0x20, 20), /*!< uart5 periph reset */ + CRM_I2C1_PERIPH_RESET = MAKE_VALUE(0x20, 21), /*!< i2c1 periph reset */ + CRM_I2C2_PERIPH_RESET = MAKE_VALUE(0x20, 22), /*!< i2c2 periph reset */ + CRM_I2C3_PERIPH_RESET = MAKE_VALUE(0x20, 23), /*!< i2c3 periph reset */ + CRM_CAN1_PERIPH_RESET = MAKE_VALUE(0x20, 25), /*!< can1 periph reset */ + CRM_CAN2_PERIPH_RESET = MAKE_VALUE(0x20, 26), /*!< can2 periph reset */ + CRM_PWC_PERIPH_RESET = MAKE_VALUE(0x20, 28), /*!< pwc periph reset */ + CRM_DAC_PERIPH_RESET = MAKE_VALUE(0x20, 29), /*!< dac periph reset */ + CRM_UART7_PERIPH_RESET = MAKE_VALUE(0x20, 30), /*!< uart7 periph reset */ + CRM_UART8_PERIPH_RESET = MAKE_VALUE(0x20, 31), /*!< uart8 periph reset */ + /* apb2 periph */ + CRM_TMR1_PERIPH_RESET = MAKE_VALUE(0x24, 0), /*!< tmr1 periph reset */ + CRM_TMR8_PERIPH_RESET = MAKE_VALUE(0x24, 1), /*!< tmr8 periph reset */ + CRM_USART1_PERIPH_RESET = MAKE_VALUE(0x24, 4), /*!< usart1 periph reset */ + CRM_USART6_PERIPH_RESET = MAKE_VALUE(0x24, 5), /*!< usart6 periph reset */ + CRM_ADC_PERIPH_RESET = MAKE_VALUE(0x24, 8), /*!< adc periph reset */ + CRM_SPI1_PERIPH_RESET = MAKE_VALUE(0x24, 12), /*!< spi1 periph reset */ + CRM_SPI4_PERIPH_RESET = MAKE_VALUE(0x24, 13), /*!< spi4 periph reset */ + CRM_SCFG_PERIPH_RESET = MAKE_VALUE(0x24, 14), /*!< scfg periph reset */ + CRM_TMR9_PERIPH_RESET = MAKE_VALUE(0x24, 16), /*!< tmr9 periph reset */ + CRM_TMR10_PERIPH_RESET = MAKE_VALUE(0x24, 17), /*!< tmr10 periph reset */ + CRM_TMR11_PERIPH_RESET = MAKE_VALUE(0x24, 18), /*!< tmr11 periph reset */ + CRM_TMR20_PERIPH_RESET = MAKE_VALUE(0x24, 20), /*!< tmr20 periph reset */ + CRM_ACC_PERIPH_RESET = MAKE_VALUE(0x24, 29) /*!< acc periph reset */ +#endif + +} crm_periph_reset_type; + +/** + * @brief crm periph clock in low power mode + */ +typedef enum +{ +#if defined (AT32F435xx) + /* ahb periph1 */ + CRM_GPIOA_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 0), /*!< gpioa sleep mode periph clock */ + CRM_GPIOB_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 1), /*!< gpiob sleep mode periph clock */ + CRM_GPIOC_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 2), /*!< gpioc sleep mode periph clock */ + CRM_GPIOD_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 3), /*!< gpiod sleep mode periph clock */ + CRM_GPIOE_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 4), /*!< gpioe sleep mode periph clock */ + CRM_GPIOF_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 5), /*!< gpiof sleep mode periph clock */ + CRM_GPIOG_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 6), /*!< gpiog sleep mode periph clock */ + CRM_GPIOH_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 7), /*!< gpioh sleep mode periph clock */ + CRM_CRC_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 12), /*!< crc sleep mode periph clock */ + CRM_FLASH_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 15), /*!< flash sleep mode periph clock */ + CRM_SRAM1_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 16), /*!< sram1 sleep mode periph clock */ + CRM_SRAM2_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 17), /*!< sram2 sleep mode periph clock */ + CRM_EDMA_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 21), /*!< edma sleep mode periph clock */ + CRM_DMA1_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 22), /*!< dma1 sleep mode periph clock */ + CRM_DMA2_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 24), /*!< dma2 sleep mode periph clock */ + CRM_EMAC_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 25), /*!< emac sleep mode periph clock */ + CRM_EMACTX_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 26), /*!< emac tx sleep mode periph clock */ + CRM_EMACRX_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 27), /*!< emac rx sleep mode periph clock */ + CRM_EMACPTP_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 28), /*!< emac ptp sleep mode periph clock */ + CRM_OTGFS2_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 29), /*!< otgfs2 sleep mode periph clock */ + /* ahb periph2 */ + CRM_DVP_PERIPH_LOWPOWER = MAKE_VALUE(0x54, 0), /*!< dvp sleep mode periph clock */ + CRM_OTGFS1_PERIPH_LOWPOWER = MAKE_VALUE(0x54, 7), /*!< otgfs1 sleep mode periph clock */ + CRM_SDIO1_PERIPH_LOWPOWER = MAKE_VALUE(0x54, 15), /*!< sdio1 sleep mode periph clock */ + /* ahb periph3 */ + CRM_XMC_PERIPH_LOWPOWER = MAKE_VALUE(0x58, 0), /*!< xmc sleep mode periph clock */ + CRM_QSPI1_PERIPH_LOWPOWER = MAKE_VALUE(0x58, 1), /*!< qspi1 sleep mode periph clock */ + CRM_QSPI2_PERIPH_LOWPOWER = MAKE_VALUE(0x58, 14), /*!< qspi2 sleep mode periph clock */ + CRM_SDIO2_PERIPH_LOWPOWER = MAKE_VALUE(0x58, 15), /*!< sdio2 sleep mode periph clock */ + /* apb1 periph */ + CRM_TMR2_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 0), /*!< tmr2 sleep mode periph clock */ + CRM_TMR3_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 1), /*!< tmr3 sleep mode periph clock */ + CRM_TMR4_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 2), /*!< tmr4 sleep mode periph clock */ + CRM_TMR5_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 3), /*!< tmr5 sleep mode periph clock */ + CRM_TMR6_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 4), /*!< tmr6 sleep mode periph clock */ + CRM_TMR7_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 5), /*!< tmr7 sleep mode periph clock */ + CRM_TMR12_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 6), /*!< tmr12 sleep mode periph clock */ + CRM_TMR13_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 7), /*!< tmr13 sleep mode periph clock */ + CRM_TMR14_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 8), /*!< tmr14 sleep mode periph clock */ + CRM_WWDT_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 11), /*!< wwdt sleep mode periph clock */ + CRM_SPI2_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 14), /*!< spi2 sleep mode periph clock */ + CRM_SPI3_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 15), /*!< spi3 sleep mode periph clock */ + CRM_USART2_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 17), /*!< usart2 sleep mode periph clock */ + CRM_USART3_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 18), /*!< usart3 sleep mode periph clock */ + CRM_UART4_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 19), /*!< uart4 sleep mode periph clock */ + CRM_UART5_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 20), /*!< uart5 sleep mode periph clock */ + CRM_I2C1_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 21), /*!< i2c1 sleep mode periph clock */ + CRM_I2C2_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 22), /*!< i2c2 sleep mode periph clock */ + CRM_I2C3_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 23), /*!< i2c3 sleep mode periph clock */ + CRM_CAN1_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 25), /*!< can1 sleep mode periph clock */ + CRM_CAN2_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 26), /*!< can2 sleep mode periph clock */ + CRM_PWC_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 28), /*!< pwc sleep mode periph clock */ + CRM_DAC_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 29), /*!< dac sleep mode periph clock */ + CRM_UART7_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 30), /*!< uart7 sleep mode periph clock */ + CRM_UART8_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 31), /*!< uart8 sleep mode periph clock */ + /* apb2 periph */ + CRM_TMR1_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 0), /*!< tmr1 sleep mode periph clock */ + CRM_TMR8_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 1), /*!< tmr8 sleep mode periph clock */ + CRM_USART1_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 4), /*!< usart1 sleep mode periph clock */ + CRM_USART6_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 5), /*!< usart6 sleep mode periph clock */ + CRM_ADC1_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 8), /*!< adc1 sleep mode periph clock */ + CRM_ADC2_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 9), /*!< adc2 sleep mode periph clock */ + CRM_ADC3_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 10), /*!< adc3 sleep mode periph clock */ + CRM_SPI1_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 12), /*!< spi1 sleep mode periph clock */ + CRM_SPI4_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 13), /*!< spi4 sleep mode periph clock */ + CRM_SCFG_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 14), /*!< scfg sleep mode periph clock */ + CRM_TMR9_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 16), /*!< tmr9 sleep mode periph clock */ + CRM_TMR10_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 17), /*!< tmr10 sleep mode periph clock */ + CRM_TMR11_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 18), /*!< tmr11 sleep mode periph clock */ + CRM_TMR20_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 20), /*!< tmr20 sleep mode periph clock */ + CRM_ACC_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 29) /*!< acc sleep mode periph clock */ +#endif + +#if defined (AT32F437xx) + /* ahb periph1 */ + CRM_GPIOA_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 0), /*!< gpioa sleep mode periph clock */ + CRM_GPIOB_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 1), /*!< gpiob sleep mode periph clock */ + CRM_GPIOC_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 2), /*!< gpioc sleep mode periph clock */ + CRM_GPIOD_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 3), /*!< gpiod sleep mode periph clock */ + CRM_GPIOE_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 4), /*!< gpioe sleep mode periph clock */ + CRM_GPIOF_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 5), /*!< gpiof sleep mode periph clock */ + CRM_GPIOG_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 6), /*!< gpiog sleep mode periph clock */ + CRM_GPIOH_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 7), /*!< gpioh sleep mode periph clock */ + CRM_CRC_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 12), /*!< crc sleep mode periph clock */ + CRM_FLASH_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 15), /*!< flash sleep mode periph clock */ + CRM_SRAM1_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 16), /*!< sram1 sleep mode periph clock */ + CRM_SRAM2_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 17), /*!< sram2 sleep mode periph clock */ + CRM_EDMA_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 21), /*!< edma sleep mode periph clock */ + CRM_DMA1_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 22), /*!< dma1 sleep mode periph clock */ + CRM_DMA2_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 24), /*!< dma2 sleep mode periph clock */ + CRM_OTGFS2_PERIPH_LOWPOWER = MAKE_VALUE(0x50, 29), /*!< otgfs2 sleep mode periph clock */ + /* ahb periph2 */ + CRM_DVP_PERIPH_LOWPOWER = MAKE_VALUE(0x54, 0), /*!< dvp sleep mode periph clock */ + CRM_OTGFS1_PERIPH_LOWPOWER = MAKE_VALUE(0x54, 7), /*!< otgfs1 sleep mode periph clock */ + CRM_SDIO1_PERIPH_LOWPOWER = MAKE_VALUE(0x54, 15), /*!< sdio1 sleep mode periph clock */ + /* ahb periph3 */ + CRM_XMC_PERIPH_LOWPOWER = MAKE_VALUE(0x58, 0), /*!< xmc sleep mode periph clock */ + CRM_QSPI1_PERIPH_LOWPOWER = MAKE_VALUE(0x58, 1), /*!< qspi1 sleep mode periph clock */ + CRM_QSPI2_PERIPH_LOWPOWER = MAKE_VALUE(0x58, 14), /*!< qspi2 sleep mode periph clock */ + CRM_SDIO2_PERIPH_LOWPOWER = MAKE_VALUE(0x58, 15), /*!< sdio2 sleep mode periph clock */ + /* apb1 periph */ + CRM_TMR2_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 0), /*!< tmr2 sleep mode periph clock */ + CRM_TMR3_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 1), /*!< tmr3 sleep mode periph clock */ + CRM_TMR4_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 2), /*!< tmr4 sleep mode periph clock */ + CRM_TMR5_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 3), /*!< tmr5 sleep mode periph clock */ + CRM_TMR6_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 4), /*!< tmr6 sleep mode periph clock */ + CRM_TMR7_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 5), /*!< tmr7 sleep mode periph clock */ + CRM_TMR12_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 6), /*!< tmr12 sleep mode periph clock */ + CRM_TMR13_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 7), /*!< tmr13 sleep mode periph clock */ + CRM_TMR14_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 8), /*!< tmr14 sleep mode periph clock */ + CRM_WWDT_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 11), /*!< wwdt sleep mode periph clock */ + CRM_SPI2_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 14), /*!< spi2 sleep mode periph clock */ + CRM_SPI3_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 15), /*!< spi3 sleep mode periph clock */ + CRM_USART2_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 17), /*!< usart2 sleep mode periph clock */ + CRM_USART3_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 18), /*!< usart3 sleep mode periph clock */ + CRM_UART4_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 19), /*!< uart4 sleep mode periph clock */ + CRM_UART5_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 20), /*!< uart5 sleep mode periph clock */ + CRM_I2C1_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 21), /*!< i2c1 sleep mode periph clock */ + CRM_I2C2_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 22), /*!< i2c2 sleep mode periph clock */ + CRM_I2C3_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 23), /*!< i2c3 sleep mode periph clock */ + CRM_CAN1_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 25), /*!< can1 sleep mode periph clock */ + CRM_CAN2_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 26), /*!< can2 sleep mode periph clock */ + CRM_PWC_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 28), /*!< pwc sleep mode periph clock */ + CRM_DAC_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 29), /*!< dac sleep mode periph clock */ + CRM_UART7_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 30), /*!< uart7 sleep mode periph clock */ + CRM_UART8_PERIPH_LOWPOWER = MAKE_VALUE(0x60, 31), /*!< uart8 sleep mode periph clock */ + /* apb2 periph */ + CRM_TMR1_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 0), /*!< tmr1 sleep mode periph clock */ + CRM_TMR8_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 1), /*!< tmr8 sleep mode periph clock */ + CRM_USART1_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 4), /*!< usart1 sleep mode periph clock */ + CRM_USART6_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 5), /*!< usart6 sleep mode periph clock */ + CRM_ADC1_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 8), /*!< adc1 sleep mode periph clock */ + CRM_ADC2_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 9), /*!< adc2 sleep mode periph clock */ + CRM_ADC3_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 10), /*!< adc3 sleep mode periph clock */ + CRM_SPI1_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 12), /*!< spi1 sleep mode periph clock */ + CRM_SPI4_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 13), /*!< spi4 sleep mode periph clock */ + CRM_SCFG_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 14), /*!< scfg sleep mode periph clock */ + CRM_TMR9_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 16), /*!< tmr9 sleep mode periph clock */ + CRM_TMR10_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 17), /*!< tmr10 sleep mode periph clock */ + CRM_TMR11_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 18), /*!< tmr11 sleep mode periph clock */ + CRM_TMR20_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 20), /*!< tmr20 sleep mode periph clock */ + CRM_ACC_PERIPH_LOWPOWER = MAKE_VALUE(0x64, 29) /*!< acc sleep mode periph clock */ +#endif + +} crm_periph_clock_lowpower_type; + +/** + * @brief crm pll clock source + */ +typedef enum +{ + CRM_PLL_SOURCE_HICK = 0x00, /*!< high speed internal clock as pll reference clock source */ + CRM_PLL_SOURCE_HEXT = 0x01 /*!< high speed external crystal as pll reference clock source */ +} crm_pll_clock_source_type; + +/** + * @brief crm pll fr + */ +typedef enum +{ + CRM_PLL_FR_1 = 0x00, /*!< pll post-division div1 */ + CRM_PLL_FR_2 = 0x01, /*!< pll post-division div2 */ + CRM_PLL_FR_4 = 0x02, /*!< pll post-division div4 */ + CRM_PLL_FR_8 = 0x03, /*!< pll post-division div8 */ + CRM_PLL_FR_16 = 0x04, /*!< pll post-division div16 */ + CRM_PLL_FR_32 = 0x05 /*!< pll post-division div32 */ +} crm_pll_fr_type; + +/** + * @brief crm clock source + */ +typedef enum +{ + CRM_CLOCK_SOURCE_HICK = 0x00, /*!< high speed internal clock */ + CRM_CLOCK_SOURCE_HEXT = 0x01, /*!< high speed external crystal */ + CRM_CLOCK_SOURCE_PLL = 0x02, /*!< phase locking loop */ + CRM_CLOCK_SOURCE_LEXT = 0x03, /*!< low speed external crystal */ + CRM_CLOCK_SOURCE_LICK = 0x04 /*!< low speed internal clock */ +} crm_clock_source_type; + +/** + * @brief crm ahb division + */ +typedef enum +{ + CRM_AHB_DIV_1 = 0x00, /*!< sclk div1 to ahbclk */ + CRM_AHB_DIV_2 = 0x08, /*!< sclk div2 to ahbclk */ + CRM_AHB_DIV_4 = 0x09, /*!< sclk div4 to ahbclk */ + CRM_AHB_DIV_8 = 0x0A, /*!< sclk div8 to ahbclk */ + CRM_AHB_DIV_16 = 0x0B, /*!< sclk div16 to ahbclk */ + CRM_AHB_DIV_64 = 0x0C, /*!< sclk div64 to ahbclk */ + CRM_AHB_DIV_128 = 0x0D, /*!< sclk div128 to ahbclk */ + CRM_AHB_DIV_256 = 0x0E, /*!< sclk div256 to ahbclk */ + CRM_AHB_DIV_512 = 0x0F /*!< sclk div512 to ahbclk */ +} crm_ahb_div_type; + +/** + * @brief crm apb1 division + */ +typedef enum +{ + CRM_APB1_DIV_1 = 0x00, /*!< ahbclk div1 to apb1clk */ + CRM_APB1_DIV_2 = 0x04, /*!< ahbclk div2 to apb1clk */ + CRM_APB1_DIV_4 = 0x05, /*!< ahbclk div4 to apb1clk */ + CRM_APB1_DIV_8 = 0x06, /*!< ahbclk div8 to apb1clk */ + CRM_APB1_DIV_16 = 0x07 /*!< ahbclk div16 to apb1clk */ +} crm_apb1_div_type; + +/** + * @brief crm apb2 division + */ +typedef enum +{ + CRM_APB2_DIV_1 = 0x00, /*!< ahbclk div1 to apb2clk */ + CRM_APB2_DIV_2 = 0x04, /*!< ahbclk div2 to apb2clk */ + CRM_APB2_DIV_4 = 0x05, /*!< ahbclk div4 to apb2clk */ + CRM_APB2_DIV_8 = 0x06, /*!< ahbclk div8 to apb2clk */ + CRM_APB2_DIV_16 = 0x07 /*!< ahbclk div16 to apb2clk */ +} crm_apb2_div_type; + +/** + * @brief crm usb division + */ +typedef enum +{ + CRM_USB_DIV_1_5 = 0x00, /*!< pllclk div1.5 to usbclk */ + CRM_USB_DIV_1 = 0x01, /*!< pllclk div1 to usbclk */ + CRM_USB_DIV_2_5 = 0x02, /*!< pllclk div2.5 to usbclk */ + CRM_USB_DIV_2 = 0x03, /*!< pllclk div2 to usbclk */ + CRM_USB_DIV_3_5 = 0x04, /*!< pllclk div3.5 to usbclk */ + CRM_USB_DIV_3 = 0x05, /*!< pllclk div3 to usbclk */ + CRM_USB_DIV_4_5 = 0x06, /*!< pllclk div4.5 to usbclk */ + CRM_USB_DIV_4 = 0x07, /*!< pllclk div4 to usbclk */ + CRM_USB_DIV_5_5 = 0x08, /*!< pllclk div5.5 to usbclk */ + CRM_USB_DIV_5 = 0x09, /*!< pllclk div5 to usbclk */ + CRM_USB_DIV_6_5 = 0x0A, /*!< pllclk div6.5 to usbclk */ + CRM_USB_DIV_6 = 0x0B, /*!< pllclk div6 to usbclk */ + CRM_USB_DIV_7 = 0x0C /*!< pllclk div7 to usbclk */ +} crm_usb_div_type; + +/** + * @brief crm ertc clock + */ +typedef enum +{ + CRM_ERTC_CLOCK_NOCLK = 0x000, /*!< no clock as ertc clock source */ + CRM_ERTC_CLOCK_LEXT = 0x001, /*!< low speed external crystal as ertc clock source */ + CRM_ERTC_CLOCK_LICK = 0x002, /*!< low speed internal clock as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_2 = 0x023, /*!< high speed external crystal div2 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_3 = 0x033, /*!< high speed external crystal div3 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_4 = 0x043, /*!< high speed external crystal div4 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_5 = 0x053, /*!< high speed external crystal div5 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_6 = 0x063, /*!< high speed external crystal div6 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_7 = 0x073, /*!< high speed external crystal div7 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_8 = 0x083, /*!< high speed external crystal div8 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_9 = 0x093, /*!< high speed external crystal div9 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_10 = 0x0A3, /*!< high speed external crystal div10 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_11 = 0x0B3, /*!< high speed external crystal div11 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_12 = 0x0C3, /*!< high speed external crystal div12 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_13 = 0x0D3, /*!< high speed external crystal div13 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_14 = 0x0E3, /*!< high speed external crystal div14 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_15 = 0x0F3, /*!< high speed external crystal div15 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_16 = 0x103, /*!< high speed external crystal div16 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_17 = 0x113, /*!< high speed external crystal div17 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_18 = 0x123, /*!< high speed external crystal div18 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_19 = 0x133, /*!< high speed external crystal div19 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_20 = 0x143, /*!< high speed external crystal div20 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_21 = 0x153, /*!< high speed external crystal div21 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_22 = 0x163, /*!< high speed external crystal div22 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_23 = 0x173, /*!< high speed external crystal div23 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_24 = 0x183, /*!< high speed external crystal div24 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_25 = 0x193, /*!< high speed external crystal div25 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_26 = 0x1A3, /*!< high speed external crystal div26 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_27 = 0x1B3, /*!< high speed external crystal div27 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_28 = 0x1C3, /*!< high speed external crystal div28 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_29 = 0x1D3, /*!< high speed external crystal div29 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_30 = 0x1E3, /*!< high speed external crystal div30 as ertc clock source */ + CRM_ERTC_CLOCK_HEXT_DIV_31 = 0x1F3 /*!< high speed external crystal div31 as ertc clock source */ +} crm_ertc_clock_type; + +/** + * @brief crm hick 48mhz division + */ +typedef enum +{ + CRM_HICK48_DIV6 = 0x00, /*!< fixed 8 mhz when hick is selected as sclk */ + CRM_HICK48_NODIV = 0x01 /*!< 8 mhz or 48 mhz depend on hickdiv when hick is selected as sclk */ +} crm_hick_div_6_type; + +/** + * @brief crm sclk select + */ +typedef enum +{ + CRM_SCLK_HICK = 0x00, /*!< select high speed internal clock as sclk */ + CRM_SCLK_HEXT = 0x01, /*!< select high speed external crystal as sclk */ + CRM_SCLK_PLL = 0x02 /*!< select phase locking loop clock as sclk */ +} crm_sclk_type; + +/** + * @brief crm clkout index + */ +typedef enum +{ + CRM_CLKOUT_INDEX_1 = 0x00, /*!< clkout1 */ + CRM_CLKOUT_INDEX_2 = 0x01 /*!< clkout2 */ +} crm_clkout_index_type; + +/** + * @brief crm clkout1 select + */ +typedef enum +{ + CRM_CLKOUT1_HICK = 0x00, /*!< output high speed internal clock to clkout1 pin */ + CRM_CLKOUT1_LEXT = 0x01, /*!< output low speed external crystal to clkout1 pin */ + CRM_CLKOUT1_HEXT = 0x02, /*!< output high speed external crystal to clkout1 pin */ + CRM_CLKOUT1_PLL = 0x03 /*!< output phase locking loop clock to clkout1 pin */ +} crm_clkout1_select_type; + +/** + * @brief crm clkout2 select + */ +typedef enum +{ + CRM_CLKOUT2_SCLK = 0x00, /*!< output system clock to clkout2 pin */ + CRM_CLKOUT2_HEXT = 0x02, /*!< output high speed external crystal to clkout2 pin */ + CRM_CLKOUT2_PLL = 0x03, /*!< output phase locking loop clock to clkout2 pin */ + CRM_CLKOUT2_USB = 0x10, /*!< output usbclk to clkout2 pin */ + CRM_CLKOUT2_ADC = 0x11, /*!< output adcclk to clkout2 pin */ + CRM_CLKOUT2_HICK = 0x12, /*!< output high speed internal clock to clkout2 pin */ + CRM_CLKOUT2_LICK = 0x13, /*!< output low speed internal clock to clkout2 pin */ + CRM_CLKOUT2_LEXT = 0x14 /*!< output low speed external crystal to clkout2 pin */ +} crm_clkout2_select_type; + +/** + * @brief crm clkout division1 + */ +typedef enum +{ + CRM_CLKOUT_DIV1_1 = 0x00, /*!< clkout division1 div1 */ + CRM_CLKOUT_DIV1_2 = 0x04, /*!< clkout division1 div2 */ + CRM_CLKOUT_DIV1_3 = 0x05, /*!< clkout division1 div3 */ + CRM_CLKOUT_DIV1_4 = 0x06, /*!< clkout division1 div4 */ + CRM_CLKOUT_DIV1_5 = 0x07 /*!< clkout division1 div5 */ +} crm_clkout_div1_type; + +/** + * @brief crm clkout division2 + */ +typedef enum +{ + CRM_CLKOUT_DIV2_1 = 0x00, /*!< clkout division2 div1 */ + CRM_CLKOUT_DIV2_2 = 0x08, /*!< clkout division2 div2 */ + CRM_CLKOUT_DIV2_4 = 0x09, /*!< clkout division2 div4 */ + CRM_CLKOUT_DIV2_8 = 0x0A, /*!< clkout division2 div8 */ + CRM_CLKOUT_DIV2_16 = 0x0B, /*!< clkout division2 div16 */ + CRM_CLKOUT_DIV2_64 = 0x0C, /*!< clkout division2 div64 */ + CRM_CLKOUT_DIV2_128 = 0x0D, /*!< clkout division2 div128 */ + CRM_CLKOUT_DIV2_256 = 0x0E, /*!< clkout division2 div256 */ + CRM_CLKOUT_DIV2_512 = 0x0F /*!< clkout division2 div512 */ +} crm_clkout_div2_type; + +/** + * @brief crm auto step mode + */ +typedef enum +{ + CRM_AUTO_STEP_MODE_DISABLE = 0x00, /*!< disable auto step mode */ + CRM_AUTO_STEP_MODE_ENABLE = 0x03 /*!< enable auto step mode */ +} crm_auto_step_mode_type; + +/** + * @brief crm usb 48 mhz clock source select + */ +typedef enum +{ + CRM_USB_CLOCK_SOURCE_PLL = 0x00, /*!< select phase locking loop clock as usb clock source */ + CRM_USB_CLOCK_SOURCE_HICK = 0x01 /*!< select high speed internal clock as usb clock source */ +} crm_usb_clock_source_type; + +/** + * @brief crm hick as system clock frequency select + */ +typedef enum +{ + CRM_HICK_SCLK_8MHZ = 0x00, /*!< fixed 8 mhz when hick is selected as sclk */ + CRM_HICK_SCLK_48MHZ = 0x01 /*!< 8 mhz or 48 mhz depend on hickdiv when hick is selected as sclk */ +} crm_hick_sclk_frequency_type; + +/** + * @brief crm emac output pulse width + */ +typedef enum +{ + CRM_EMAC_PULSE_125MS = 0x00, /*!< emac output pulse width 125ms */ + CRM_EMAC_PULSE_1SCLK = 0x01 /*!< emac output pulse width 1 system clock */ +} crm_emac_output_pulse_type; + +/** + * @brief crm clocks freqency structure + */ +typedef struct +{ + uint32_t sclk_freq; /*!< system clock frequency */ + uint32_t ahb_freq; /*!< ahb bus clock frequency */ + uint32_t apb2_freq; /*!< apb2 bus clock frequency */ + uint32_t apb1_freq; /*!< apb1 bus clock frequency */ +} crm_clocks_freq_type; + +/** + * @brief type define crm register all + */ +typedef struct +{ + /** + * @brief crm ctrl register, offset:0x00 + */ + union + { + __IO uint32_t ctrl; + struct + { + __IO uint32_t hicken : 1; /* [0] */ + __IO uint32_t hickstbl : 1; /* [1] */ + __IO uint32_t hicktrim : 6; /* [7:2] */ + __IO uint32_t hickcal : 8; /* [15:8] */ + __IO uint32_t hexten : 1; /* [16] */ + __IO uint32_t hextstbl : 1; /* [17] */ + __IO uint32_t hextbyps : 1; /* [18] */ + __IO uint32_t cfden : 1; /* [19] */ + __IO uint32_t reserved1 : 4; /* [23:20] */ + __IO uint32_t pllen : 1; /* [24] */ + __IO uint32_t pllstbl : 1; /* [25] */ + __IO uint32_t reserved2 : 6; /* [31:26] */ + } ctrl_bit; + }; + + /** + * @brief crm pllcfg register, offset:0x04 + */ + union + { + __IO uint32_t pllcfg; + struct + { + __IO uint32_t pllms : 4; /* [3:0] */ + __IO uint32_t reserved1 : 2; /* [5:4] */ + __IO uint32_t pllns : 9; /* [14:6] */ + __IO uint32_t reserved2 : 1; /* [15] */ + __IO uint32_t pllfr : 3; /* [18:16] */ + __IO uint32_t reserved3 : 3; /* [21:19] */ + __IO uint32_t pllrcs : 1; /* [22] */ + __IO uint32_t reserved4 : 9; /* [31:23] */ + } pllcfg_bit; + }; + + /** + * @brief crm cfg register, offset:0x08 + */ + union + { + __IO uint32_t cfg; + struct + { + __IO uint32_t sclksel : 2; /* [1:0] */ + __IO uint32_t sclksts : 2; /* [3:2] */ + __IO uint32_t ahbdiv : 4; /* [7:4] */ + __IO uint32_t reserved1 : 2; /* [9:8] */ + __IO uint32_t apb1div : 3; /* [12:10] */ + __IO uint32_t apb2div : 3; /* [15:13] */ + __IO uint32_t ertcdiv : 5; /* [20:16] */ + __IO uint32_t clkout1_sel : 2; /* [22:21] */ + __IO uint32_t reserved2 : 1; /* [23] */ + __IO uint32_t clkout1div1 : 3; /* [26:24] */ + __IO uint32_t clkout2div1 : 3; /* [29:27] */ + __IO uint32_t clkout2_sel1 : 2; /* [31:30] */ + } cfg_bit; + }; + + /** + * @brief crm clkint register, offset:0x0C + */ + union + { + __IO uint32_t clkint; + struct + { + __IO uint32_t lickstblf : 1; /* [0] */ + __IO uint32_t lextstblf : 1; /* [1] */ + __IO uint32_t hickstblf : 1; /* [2] */ + __IO uint32_t hextstblf : 1; /* [3] */ + __IO uint32_t pllstblf : 1; /* [4] */ + __IO uint32_t reserved1 : 2; /* [6:5] */ + __IO uint32_t cfdf : 1; /* [7] */ + __IO uint32_t lickstblien : 1; /* [8] */ + __IO uint32_t lextstblien : 1; /* [9] */ + __IO uint32_t hickstblien : 1; /* [10] */ + __IO uint32_t hextstblien : 1; /* [11] */ + __IO uint32_t pllstblien : 1; /* [12] */ + __IO uint32_t reserved2 : 3; /* [15:13] */ + __IO uint32_t lickstblfc : 1; /* [16] */ + __IO uint32_t lextstblfc : 1; /* [17] */ + __IO uint32_t hickstblfc : 1; /* [18] */ + __IO uint32_t hextstblfc : 1; /* [19] */ + __IO uint32_t pllstblfc : 1; /* [20] */ + __IO uint32_t reserved3 : 2; /* [22:21] */ + __IO uint32_t cfdfc : 1; /* [23] */ + __IO uint32_t reserved4 : 8; /* [31:24] */ + } clkint_bit; + }; + + /** + * @brief crm ahbrst1 register, offset:0x10 + */ + union + { + __IO uint32_t ahbrst1; +#if defined (AT32F435xx) + struct + { + __IO uint32_t gpioarst : 1; /* [0] */ + __IO uint32_t gpiobrst : 1; /* [1] */ + __IO uint32_t gpiocrst : 1; /* [2] */ + __IO uint32_t gpiodrst : 1; /* [3] */ + __IO uint32_t gpioerst : 1; /* [4] */ + __IO uint32_t gpiofrst : 1; /* [5] */ + __IO uint32_t gpiogrst : 1; /* [6] */ + __IO uint32_t gpiohrst : 1; /* [7] */ + __IO uint32_t reserved1 : 4; /* [11:8] */ + __IO uint32_t crcrst : 1; /* [12] */ + __IO uint32_t reserved2 : 8; /* [20:13] */ + __IO uint32_t edmarst : 1; /* [21] */ + __IO uint32_t dma1rst : 1; /* [22] */ + __IO uint32_t reserved3 : 1; /* [23] */ + __IO uint32_t dma2rst : 1; /* [24] */ + __IO uint32_t reserved4 : 4; /* [28:25] */ + __IO uint32_t otgfs2rst : 1; /* [29] */ + __IO uint32_t reserved5 : 2; /* [31:30] */ + } ahbrst1_bit; +#endif + +#if defined (AT32F437xx) + struct + { + __IO uint32_t gpioarst : 1; /* [0] */ + __IO uint32_t gpiobrst : 1; /* [1] */ + __IO uint32_t gpiocrst : 1; /* [2] */ + __IO uint32_t gpiodrst : 1; /* [3] */ + __IO uint32_t gpioerst : 1; /* [4] */ + __IO uint32_t gpiofrst : 1; /* [5] */ + __IO uint32_t gpiogrst : 1; /* [6] */ + __IO uint32_t gpiohrst : 1; /* [7] */ + __IO uint32_t reserved1 : 4; /* [11:8] */ + __IO uint32_t crcrst : 1; /* [12] */ + __IO uint32_t reserved2 : 8; /* [20:13] */ + __IO uint32_t edmarst : 1; /* [21] */ + __IO uint32_t dma1rst : 1; /* [22] */ + __IO uint32_t reserved3 : 1; /* [23] */ + __IO uint32_t dma2rst : 1; /* [24] */ + __IO uint32_t emacrst : 1; /* [25] */ + __IO uint32_t reserved4 : 3; /* [28:26] */ + __IO uint32_t otgfs2rst : 1; /* [29] */ + __IO uint32_t reserved5 : 2; /* [31:30] */ + } ahbrst1_bit; +#endif + }; + + /** + * @brief crm ahbrst2 register, offset:0x14 + */ + union + { + __IO uint32_t ahbrst2; + struct + { + __IO uint32_t dvprst : 1; /* [0] */ + __IO uint32_t reserved1 : 6; /* [6:1] */ + __IO uint32_t otgfs1rst : 1; /* [7] */ + __IO uint32_t reserved2 : 7; /* [14:8] */ + __IO uint32_t sdio1rst : 1; /* [15] */ + __IO uint32_t reserved3 : 16;/* [31:16] */ + } ahbrst2_bit; + }; + + /** + * @brief crm ahbrst3 register, offset:0x18 + */ + union + { + __IO uint32_t ahbrst3; + struct + { + __IO uint32_t xmcrst : 1; /* [0] */ + __IO uint32_t qspi1rst : 1; /* [1] */ + __IO uint32_t reserved1 : 12;/* [13:2] */ + __IO uint32_t qspi2rst : 1; /* [14] */ + __IO uint32_t sdio2rst : 1; /* [15] */ + __IO uint32_t reserved3 : 16;/* [31:16] */ + } ahbrst3_bit; + }; + + /** + * @brief crm reserved1 register, offset:0x1C + */ + __IO uint32_t reserved1; + + /** + * @brief crm apb1rst register, offset:0x20 + */ + union + { + __IO uint32_t apb1rst; + struct + { + __IO uint32_t tmr2rst : 1; /* [0] */ + __IO uint32_t tmr3rst : 1; /* [1] */ + __IO uint32_t tmr4rst : 1; /* [2] */ + __IO uint32_t tmr5rst : 1; /* [3] */ + __IO uint32_t tmr6rst : 1; /* [4] */ + __IO uint32_t tmr7rst : 1; /* [5] */ + __IO uint32_t tmr12rst : 1; /* [6] */ + __IO uint32_t tmr13rst : 1; /* [7] */ + __IO uint32_t adc14rst : 1; /* [8] */ + __IO uint32_t reserved1 : 2; /* [10:9] */ + __IO uint32_t wwdtrst : 1; /* [11] */ + __IO uint32_t reserved2 : 2; /* [13:12] */ + __IO uint32_t spi2rst : 1; /* [14] */ + __IO uint32_t spi3rst : 1; /* [15] */ + __IO uint32_t reserved3 : 1; /* [16] */ + __IO uint32_t usart2rst : 1; /* [17] */ + __IO uint32_t usart3rst : 1; /* [18] */ + __IO uint32_t uart4rst : 1; /* [19] */ + __IO uint32_t uart5rst : 1; /* [20] */ + __IO uint32_t i2c1rst : 1; /* [21] */ + __IO uint32_t i2c2rst : 1; /* [22] */ + __IO uint32_t i2c3rst : 1; /* [23] */ + __IO uint32_t reserved4 : 1; /* [24] */ + __IO uint32_t can1rst : 1; /* [25] */ + __IO uint32_t can2rst : 1; /* [26] */ + __IO uint32_t reserved5 : 1; /* [27] */ + __IO uint32_t pwcrst : 1; /* [28] */ + __IO uint32_t dacrst : 1; /* [29] */ + __IO uint32_t uart7rst : 1; /* [30] */ + __IO uint32_t uart8rst : 1; /* [31] */ + } apb1rst_bit; + }; + + /** + * @brief crm apb2rst register, offset:0x24 + */ + union + { + __IO uint32_t apb2rst; + struct + { + __IO uint32_t tmr1rst : 1; /* [0] */ + __IO uint32_t tmr8rst : 1; /* [1] */ + __IO uint32_t reserved1 : 2; /* [3:2] */ + __IO uint32_t usart1rst : 1; /* [4] */ + __IO uint32_t usart6rst : 1; /* [5] */ + __IO uint32_t reserved2 : 2; /* [7:6] */ + __IO uint32_t adcrst : 1; /* [8] */ + __IO uint32_t reserved3 : 3; /* [11:9] */ + __IO uint32_t spi1rst : 1; /* [12] */ + __IO uint32_t spi4rst : 1; /* [13] */ + __IO uint32_t scfgrst : 1; /* [14] */ + __IO uint32_t reserved4 : 1; /* [15] */ + __IO uint32_t tmr9rst : 1; /* [16] */ + __IO uint32_t tmr10rst : 1; /* [17] */ + __IO uint32_t tmr11rst : 1; /* [18] */ + __IO uint32_t reserved5 : 1; /* [19] */ + __IO uint32_t tmr20rst : 1; /* [20] */ + __IO uint32_t reserved6 : 8; /* [28:21] */ + __IO uint32_t accrst : 1; /* [29] */ + __IO uint32_t reserved7 : 2; /* [31:30] */ + } apb2rst_bit; + }; + + /** + * @brief crm reserved2 register, offset:0x28~0x2C + */ + __IO uint32_t reserved2[2]; + + /** + * @brief crm ahben1 register, offset:0x30 + */ + union + { + __IO uint32_t ahben1; +#if defined (AT32F435xx) + struct + { + __IO uint32_t gpioaen : 1; /* [0] */ + __IO uint32_t gpioben : 1; /* [1] */ + __IO uint32_t gpiocen : 1; /* [2] */ + __IO uint32_t gpioden : 1; /* [3] */ + __IO uint32_t gpioeen : 1; /* [4] */ + __IO uint32_t gpiofen : 1; /* [5] */ + __IO uint32_t gpiogen : 1; /* [6] */ + __IO uint32_t gpiohen : 1; /* [7] */ + __IO uint32_t reserved1 : 4; /* [11:8] */ + __IO uint32_t crcen : 1; /* [12] */ + __IO uint32_t reserved2 : 8; /* [20:13] */ + __IO uint32_t edmaen : 1; /* [21] */ + __IO uint32_t dma1en : 1; /* [22] */ + __IO uint32_t reserved3 : 1; /* [23] */ + __IO uint32_t dma2en : 1; /* [24] */ + __IO uint32_t reserved4 : 4; /* [28:25] */ + __IO uint32_t otgfs2en : 1; /* [29] */ + __IO uint32_t reserved5 : 2; /* [31:30] */ + } ahben1_bit; +#endif + +#if defined (AT32F437xx) + struct + { + __IO uint32_t gpioaen : 1; /* [0] */ + __IO uint32_t gpioben : 1; /* [1] */ + __IO uint32_t gpiocen : 1; /* [2] */ + __IO uint32_t gpioden : 1; /* [3] */ + __IO uint32_t gpioeen : 1; /* [4] */ + __IO uint32_t gpiofen : 1; /* [5] */ + __IO uint32_t gpiogen : 1; /* [6] */ + __IO uint32_t gpiohen : 1; /* [7] */ + __IO uint32_t reserved1 : 4; /* [11:8] */ + __IO uint32_t crcen : 1; /* [12] */ + __IO uint32_t reserved2 : 8; /* [20:13] */ + __IO uint32_t edmaen : 1; /* [21] */ + __IO uint32_t dma1en : 1; /* [22] */ + __IO uint32_t reserved3 : 1; /* [23] */ + __IO uint32_t dma2en : 1; /* [24] */ + __IO uint32_t emacen : 1; /* [25] */ + __IO uint32_t reserved4 : 3; /* [28:26] */ + __IO uint32_t otgfs2en : 1; /* [29] */ + __IO uint32_t reserved5 : 2; /* [31:30] */ + } ahben1_bit; +#endif + }; + + /** + * @brief crm ahben2 register, offset:0x34 + */ + union + { + __IO uint32_t ahben2; + struct + { + __IO uint32_t dvpen : 1; /* [0] */ + __IO uint32_t reserved1 : 6; /* [6:1] */ + __IO uint32_t otgfs1en : 1; /* [7] */ + __IO uint32_t reserved2 : 7; /* [14:8] */ + __IO uint32_t sdio1en : 1; /* [15] */ + __IO uint32_t reserved3 : 16;/* [31:16] */ + } ahben2_bit; + }; + + /** + * @brief crm ahben3 register, offset:0x38 + */ + union + { + __IO uint32_t ahben3; + struct + { + __IO uint32_t xmcen : 1; /* [0] */ + __IO uint32_t qspi1en : 1; /* [1] */ + __IO uint32_t reserved1 : 12;/* [13:2] */ + __IO uint32_t qspi2en : 1; /* [14] */ + __IO uint32_t sdio2en : 1; /* [15] */ + __IO uint32_t reserved3 : 16;/* [31:16] */ + } ahben3_bit; + }; + + /** + * @brief crm reserved3 register, offset:0x3C + */ + __IO uint32_t reserved3; + + /** + * @brief crm apb1en register, offset:0x40 + */ + union + { + __IO uint32_t apb1en; + struct + { + __IO uint32_t tmr2en : 1; /* [0] */ + __IO uint32_t tmr3en : 1; /* [1] */ + __IO uint32_t tmr4en : 1; /* [2] */ + __IO uint32_t tmr5en : 1; /* [3] */ + __IO uint32_t tmr6en : 1; /* [4] */ + __IO uint32_t tmr7en : 1; /* [5] */ + __IO uint32_t tmr12en : 1; /* [6] */ + __IO uint32_t tmr13en : 1; /* [7] */ + __IO uint32_t adc14en : 1; /* [8] */ + __IO uint32_t reserved1 : 2; /* [10:9] */ + __IO uint32_t wwdten : 1; /* [11] */ + __IO uint32_t reserved2 : 2; /* [13:12] */ + __IO uint32_t spi2en : 1; /* [14] */ + __IO uint32_t spi3en : 1; /* [15] */ + __IO uint32_t reserved3 : 1; /* [16] */ + __IO uint32_t usart2en : 1; /* [17] */ + __IO uint32_t usart3en : 1; /* [18] */ + __IO uint32_t uart4en : 1; /* [19] */ + __IO uint32_t uart5en : 1; /* [20] */ + __IO uint32_t i2c1en : 1; /* [21] */ + __IO uint32_t i2c2en : 1; /* [22] */ + __IO uint32_t i2c3en : 1; /* [23] */ + __IO uint32_t reserved4 : 1; /* [24] */ + __IO uint32_t can1en : 1; /* [25] */ + __IO uint32_t can2en : 1; /* [26] */ + __IO uint32_t reserved5 : 1; /* [27] */ + __IO uint32_t pwcen : 1; /* [28] */ + __IO uint32_t dacen : 1; /* [29] */ + __IO uint32_t uart7en : 1; /* [30] */ + __IO uint32_t uart8en : 1; /* [31] */ + } apb1en_bit; + }; + + /** + * @brief crm apb2en register, offset:0x44 + */ + union + { + __IO uint32_t apb2en; + struct + { + __IO uint32_t tmr1en : 1; /* [0] */ + __IO uint32_t tmr8en : 1; /* [1] */ + __IO uint32_t reserved1 : 2; /* [3:2] */ + __IO uint32_t usart1en : 1; /* [4] */ + __IO uint32_t usart6en : 1; /* [5] */ + __IO uint32_t reserved2 : 2; /* [7:6] */ + __IO uint32_t adcen : 1; /* [8] */ + __IO uint32_t reserved3 : 3; /* [11:9] */ + __IO uint32_t spi1en : 1; /* [12] */ + __IO uint32_t spi4en : 1; /* [13] */ + __IO uint32_t scfgen : 1; /* [14] */ + __IO uint32_t reserved4 : 1; /* [15] */ + __IO uint32_t tmr9en : 1; /* [16] */ + __IO uint32_t tmr10en : 1; /* [17] */ + __IO uint32_t tmr11en : 1; /* [18] */ + __IO uint32_t reserved5 : 1; /* [19] */ + __IO uint32_t tmr20en : 1; /* [20] */ + __IO uint32_t reserved6 : 8; /* [28:21] */ + __IO uint32_t accen : 1; /* [29] */ + __IO uint32_t reserved7 : 2; /* [31:30] */ + } apb2en_bit; + }; + + /** + * @brief crm reserved4 register, offset:0x48~0x4C + */ + __IO uint32_t reserved4[2]; + + /** + * @brief crm ahblpen1 register, offset:0x50 + */ + union + { + __IO uint32_t ahblpen1; +#if defined (AT32F435xx) + struct + { + __IO uint32_t gpioalpen : 1; /* [0] */ + __IO uint32_t gpioblpen : 1; /* [1] */ + __IO uint32_t gpioclpen : 1; /* [2] */ + __IO uint32_t gpiodlpen : 1; /* [3] */ + __IO uint32_t gpioelpen : 1; /* [4] */ + __IO uint32_t gpioflpen : 1; /* [5] */ + __IO uint32_t gpioglpen : 1; /* [6] */ + __IO uint32_t gpiohlpen : 1; /* [7] */ + __IO uint32_t reserved1 : 4; /* [11:8] */ + __IO uint32_t crclpen : 1; /* [12] */ + __IO uint32_t reserved2 : 8; /* [20:13] */ + __IO uint32_t edmalpen : 1; /* [21] */ + __IO uint32_t dma1lpen : 1; /* [22] */ + __IO uint32_t reserved3 : 1; /* [23] */ + __IO uint32_t dma2lpen : 1; /* [24] */ + __IO uint32_t reserved4 : 4; /* [28:25] */ + __IO uint32_t otgfs2lpen : 1; /* [29] */ + __IO uint32_t reserved5 : 2; /* [31:30] */ + } ahblpen1_bit; +#endif + +#if defined (AT32F437xx) + struct + { + __IO uint32_t gpioalpen : 1; /* [0] */ + __IO uint32_t gpioblpen : 1; /* [1] */ + __IO uint32_t gpioclpen : 1; /* [2] */ + __IO uint32_t gpiodlpen : 1; /* [3] */ + __IO uint32_t gpioelpen : 1; /* [4] */ + __IO uint32_t gpioflpen : 1; /* [5] */ + __IO uint32_t gpioglpen : 1; /* [6] */ + __IO uint32_t gpiohlpen : 1; /* [7] */ + __IO uint32_t reserved1 : 4; /* [11:8] */ + __IO uint32_t crclpen : 1; /* [12] */ + __IO uint32_t reserved2 : 8; /* [20:13] */ + __IO uint32_t edmalpen : 1; /* [21] */ + __IO uint32_t dma1lpen : 1; /* [22] */ + __IO uint32_t reserved3 : 1; /* [23] */ + __IO uint32_t dma2lpen : 1; /* [24] */ + __IO uint32_t emaclpen : 1; /* [25] */ + __IO uint32_t reserved4 : 3; /* [28:26] */ + __IO uint32_t otgfs2lpen : 1; /* [29] */ + __IO uint32_t reserved5 : 2; /* [31:30] */ + } ahblpen1_bit; +#endif + }; + + /** + * @brief crm ahblpen2 register, offset:0x54 + */ + union + { + __IO uint32_t ahblpen2; + struct + { + __IO uint32_t dvplpen : 1; /* [0] */ + __IO uint32_t reserved1 : 6; /* [6:1] */ + __IO uint32_t otgfs1lpen : 1; /* [7] */ + __IO uint32_t reserved2 : 7; /* [14:8] */ + __IO uint32_t sdio1lpen : 1; /* [15] */ + __IO uint32_t reserved3 : 16;/* [31:16] */ + } ahblpen2_bit; + }; + + /** + * @brief crm ahblpen3 register, offset:0x58 + */ + union + { + __IO uint32_t ahblpen3; + struct + { + __IO uint32_t xmclpen : 1; /* [0] */ + __IO uint32_t qspi1lpen : 1; /* [1] */ + __IO uint32_t reserved1 : 12;/* [13:2] */ + __IO uint32_t qspi2lpen : 1; /* [14] */ + __IO uint32_t sdio2lpen : 1; /* [15] */ + __IO uint32_t reserved3 : 16;/* [31:16] */ + } ahblpen3_bit; + }; + + /** + * @brief crm reserved5 register, offset:0x5C + */ + __IO uint32_t reserved5; + + /** + * @brief crm apb1lpen register, offset:0x60 + */ + union + { + __IO uint32_t apb1lpen; + struct + { + __IO uint32_t tmr2lpen : 1; /* [0] */ + __IO uint32_t tmr3lpen : 1; /* [1] */ + __IO uint32_t tmr4lpen : 1; /* [2] */ + __IO uint32_t tmr5lpen : 1; /* [3] */ + __IO uint32_t tmr6lpen : 1; /* [4] */ + __IO uint32_t tmr7lpen : 1; /* [5] */ + __IO uint32_t tmr12lpen : 1; /* [6] */ + __IO uint32_t tmr13lpen : 1; /* [7] */ + __IO uint32_t adc14lpen : 1; /* [8] */ + __IO uint32_t reserved1 : 2; /* [10:9] */ + __IO uint32_t wwdtlpen : 1; /* [11] */ + __IO uint32_t reserved2 : 2; /* [13:12] */ + __IO uint32_t spi2lpen : 1; /* [14] */ + __IO uint32_t spi3lpen : 1; /* [15] */ + __IO uint32_t reserved3 : 1; /* [16] */ + __IO uint32_t usart2lpen : 1; /* [17] */ + __IO uint32_t usart3lpen : 1; /* [18] */ + __IO uint32_t uart4lpen : 1; /* [19] */ + __IO uint32_t uart5lpen : 1; /* [20] */ + __IO uint32_t i2c1lpen : 1; /* [21] */ + __IO uint32_t i2c2lpen : 1; /* [22] */ + __IO uint32_t i2c3lpen : 1; /* [23] */ + __IO uint32_t reserved4 : 1; /* [24] */ + __IO uint32_t can1lpen : 1; /* [25] */ + __IO uint32_t can2lpen : 1; /* [26] */ + __IO uint32_t reserved5 : 1; /* [27] */ + __IO uint32_t pwclpen : 1; /* [28] */ + __IO uint32_t daclpen : 1; /* [29] */ + __IO uint32_t uart7lpen : 1; /* [30] */ + __IO uint32_t uart8lpen : 1; /* [31] */ + } apb1lpen_bit; + }; + + /** + * @brief crm apb2lpen register, offset:0x64 + */ + union + { + __IO uint32_t apb2lpen; + struct + { + __IO uint32_t tmr1lpen : 1; /* [0] */ + __IO uint32_t tmr8lpen : 1; /* [1] */ + __IO uint32_t reserved1 : 2; /* [3:2] */ + __IO uint32_t usart1lpen : 1; /* [4] */ + __IO uint32_t usart6lpen : 1; /* [5] */ + __IO uint32_t reserved2 : 2; /* [7:6] */ + __IO uint32_t adclpen : 1; /* [8] */ + __IO uint32_t reserved3 : 3; /* [11:9] */ + __IO uint32_t spi1lpen : 1; /* [12] */ + __IO uint32_t spi4lpen : 1; /* [13] */ + __IO uint32_t scfglpen : 1; /* [14] */ + __IO uint32_t reserved4 : 1; /* [15] */ + __IO uint32_t tmr9lpen : 1; /* [16] */ + __IO uint32_t tmr10lpen : 1; /* [17] */ + __IO uint32_t tmr11lpen : 1; /* [18] */ + __IO uint32_t reserved5 : 1; /* [19] */ + __IO uint32_t tmr20lpen : 1; /* [20] */ + __IO uint32_t reserved6 : 8; /* [28:21] */ + __IO uint32_t acclpen : 1; /* [29] */ + __IO uint32_t reserved7 : 2; /* [31:30] */ + } apb2lpen_bit; + }; + + /** + * @brief crm reserved6 register, offset:0x68~0x6C + */ + __IO uint32_t reserved6[2]; + + /** + * @brief crm bpdc register, offset:0x70 + */ + union + { + __IO uint32_t bpdc; + struct + { + __IO uint32_t lexten : 1; /* [0] */ + __IO uint32_t lextstbl : 1; /* [1] */ + __IO uint32_t lextbyps : 1; /* [2] */ + __IO uint32_t reserved1 : 5; /* [7:3] */ + __IO uint32_t ertcsel : 2; /* [9:8] */ + __IO uint32_t reserved2 : 5; /* [14:10] */ + __IO uint32_t ertcen : 1; /* [15] */ + __IO uint32_t bpdrst : 1; /* [16] */ + __IO uint32_t reserved3 : 15;/* [31:17] */ + } bpdc_bit; + }; + + /** + * @brief crm ctrlsts register, offset:0x74 + */ + union + { + __IO uint32_t ctrlsts; + struct + { + __IO uint32_t licken : 1; /* [0] */ + __IO uint32_t lickstbl : 1; /* [1] */ + __IO uint32_t reserved1 : 22;/* [23:2] */ + __IO uint32_t rstfc : 1; /* [24] */ + __IO uint32_t reserved2 : 1; /* [25] */ + __IO uint32_t nrstf : 1; /* [26] */ + __IO uint32_t porrstf : 1; /* [27] */ + __IO uint32_t swrstf : 1; /* [28] */ + __IO uint32_t wdtrstf : 1; /* [29] */ + __IO uint32_t wwdtrstf : 1; /* [30] */ + __IO uint32_t lprstf : 1; /* [31] */ + } ctrlsts_bit; + }; + + /** + * @brief crm reserved7 register, offset:0x78~0x9C + */ + __IO uint32_t reserved7[10]; + + /** + * @brief crm misc1 register, offset:0xA0 + */ + union + { + __IO uint32_t misc1; + struct + { + __IO uint32_t hickcal_key : 8; /* [7:0] */ + __IO uint32_t reserved1 : 4; /* [11:8] */ + __IO uint32_t hickdiv : 1; /* [12] */ + __IO uint32_t hick_to_usb : 1; /* [13] */ + __IO uint32_t hick_to_sclk : 1; /* [14] */ + __IO uint32_t reserved2 : 1; /* [15] */ + __IO uint32_t clkout2_sel2 : 4; /* [19:16] */ + __IO uint32_t reserved3 : 4; /* [23:20] */ + __IO uint32_t clkout1div2 : 4; /* [27:24] */ + __IO uint32_t clkout2div2 : 4; /* [31:28] */ + } misc1_bit; + }; + + /** + * @brief crm misc2 register, offset:0xA4 + */ + union + { + __IO uint32_t misc2; + struct + { + __IO uint32_t reserved1 : 4; /* [3:0] */ + __IO uint32_t auto_step_en : 2; /* [5:4] */ + __IO uint32_t reserved2 : 2; /* [7:6] */ + __IO uint32_t clk_to_tmr : 1; /* [8] */ + __IO uint32_t emac_pps_sel : 1; /* [9] */ + __IO uint32_t reserved3 : 2; /* [11:10] */ + __IO uint32_t usbdiv : 4; /* [15:12] */ + __IO uint32_t reserved4 : 16;/* [31:16] */ + } misc2_bit; + }; + +} crm_type; + +/** + * @} + */ + +#define CRM ((crm_type *) CRM_BASE) + +/** @defgroup CRM_exported_functions + * @{ + */ + +void crm_reset(void); +void crm_lext_bypass(confirm_state new_state); +void crm_hext_bypass(confirm_state new_state); +flag_status crm_flag_get(uint32_t flag); +error_status crm_hext_stable_wait(void); +void crm_hick_clock_trimming_set(uint8_t trim_value); +void crm_hick_clock_calibration_set(uint8_t cali_value); +void crm_periph_clock_enable(crm_periph_clock_type value, confirm_state new_state); +void crm_periph_reset(crm_periph_reset_type value, confirm_state new_state); +void crm_periph_lowpower_mode_enable(crm_periph_clock_lowpower_type value, confirm_state new_state); +void crm_clock_source_enable(crm_clock_source_type source, confirm_state new_state); +void crm_flag_clear(uint32_t flag); +void crm_ertc_clock_select(crm_ertc_clock_type value); +void crm_ertc_clock_enable(confirm_state new_state); +void crm_ahb_div_set(crm_ahb_div_type value); +void crm_apb1_div_set(crm_apb1_div_type value); +void crm_apb2_div_set(crm_apb2_div_type value); +void crm_usb_clock_div_set(crm_usb_div_type value); +void crm_clock_failure_detection_enable(confirm_state new_state); +void crm_battery_powered_domain_reset(confirm_state new_state); +void crm_auto_step_mode_enable(confirm_state new_state); +void crm_hick_divider_select(crm_hick_div_6_type value); +void crm_hick_sclk_frequency_select(crm_hick_sclk_frequency_type value); +void crm_usb_clock_source_select(crm_usb_clock_source_type value); +void crm_clkout_to_tmr10_enable(confirm_state new_state); +void crm_pll_config(crm_pll_clock_source_type clock_source, uint16_t pll_ns, \ + uint16_t pll_ms, crm_pll_fr_type pll_fr); +void crm_sysclk_switch(crm_sclk_type value); +crm_sclk_type crm_sysclk_switch_status_get(void); +void crm_clocks_freq_get(crm_clocks_freq_type *clocks_struct); +void crm_clock_out1_set(crm_clkout1_select_type clkout); +void crm_clock_out2_set(crm_clkout2_select_type clkout); +void crm_clkout_div_set(crm_clkout_index_type index, crm_clkout_div1_type div1, crm_clkout_div2_type div2); +void crm_emac_output_pulse_set(crm_emac_output_pulse_type width); +void crm_interrupt_enable(uint32_t crm_int, confirm_state new_state); +error_status crm_pll_parameter_calculate(crm_pll_clock_source_type pll_rcs, uint32_t target_sclk_freq, \ + uint16_t *ret_ms, uint16_t *ret_ns, uint16_t *ret_fr); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_dac.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_dac.h new file mode 100644 index 0000000000..4b0e944252 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_dac.h @@ -0,0 +1,394 @@ +/** + ************************************************************************** + * @file at32f435_437_dac.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 dac header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_DAC_H +#define __AT32F435_437_DAC_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup DAC + * @{ + */ + +#define DAC1_D1DMAUDRF ((uint32_t)(0x00002000)) +#define DAC2_D2DMAUDRF ((uint32_t)(0x20000000)) + +/** @defgroup DAC_exported_types + * @{ + */ + +/** + * @brief dac select type + */ +typedef enum +{ + DAC1_SELECT = 0x01, /*!< dac1 select */ + DAC2_SELECT = 0x02 /*!< dac2 select */ +} dac_select_type; + +/** + * @brief dac trigger type + */ +typedef enum +{ + DAC_TMR6_TRGOUT_EVENT = 0x00, /*!< dac trigger selection:timer6 trgout event */ + DAC_TMR8_TRGOUT_EVENT = 0x01, /*!< dac trigger selection:timer8 trgout event */ + DAC_TMR7_TRGOUT_EVENT = 0x02, /*!< dac trigger selection:timer7 trgout event */ + DAC_TMR5_TRGOUT_EVENT = 0x03, /*!< dac trigger selection:timer5 trgout event */ + DAC_TMR2_TRGOUT_EVENT = 0x04, /*!< dac trigger selection:timer2 trgout event */ + DAC_TMR4_TRGOUT_EVENT = 0x05, /*!< dac trigger selection:timer4 trgout event */ + DAC_EXTERNAL_INTERRUPT_LINE_9 = 0x06, /*!< dac trigger selection:external line9 */ + DAC_SOFTWARE_TRIGGER = 0x07 /*!< dac trigger selection:software trigger */ +} dac_trigger_type; + +/** + * @brief dac wave type + */ +typedef enum +{ + DAC_WAVE_GENERATE_NONE = 0x00, /*!< dac wave generation disabled */ + DAC_WAVE_GENERATE_NOISE = 0x01, /*!< dac noise wave generation enabled */ + DAC_WAVE_GENERATE_TRIANGLE = 0x02 /*!< dac triangle wave generation enabled */ +} dac_wave_type; + +/** + * @brief dac mask amplitude type + */ +typedef enum +{ + DAC_LSFR_BIT0_AMPLITUDE_1 = 0x00, /*!< unmask bit0/ triangle amplitude equal to 1 */ + DAC_LSFR_BIT10_AMPLITUDE_3 = 0x01, /*!< unmask bit[1:0]/ triangle amplitude equal to 3 */ + DAC_LSFR_BIT20_AMPLITUDE_7 = 0x02, /*!< unmask bit[2:0]/ triangle amplitude equal to 7 */ + DAC_LSFR_BIT30_AMPLITUDE_15 = 0x03, /*!< unmask bit[3:0]/ triangle amplitude equal to 15 */ + DAC_LSFR_BIT40_AMPLITUDE_31 = 0x04, /*!< unmask bit[4:0]/ triangle amplitude equal to 31 */ + DAC_LSFR_BIT50_AMPLITUDE_63 = 0x05, /*!< unmask bit[5:0]/ triangle amplitude equal to 63 */ + DAC_LSFR_BIT60_AMPLITUDE_127 = 0x06, /*!< unmask bit[6:0]/ triangle amplitude equal to 127 */ + DAC_LSFR_BIT70_AMPLITUDE_255 = 0x07, /*!< unmask bit[7:0]/ triangle amplitude equal to 255 */ + DAC_LSFR_BIT80_AMPLITUDE_511 = 0x08, /*!< unmask bit[8:0]/ triangle amplitude equal to 511 */ + DAC_LSFR_BIT90_AMPLITUDE_1023 = 0x09, /*!< unmask bit[9:0]/ triangle amplitude equal to 1023 */ + DAC_LSFR_BITA0_AMPLITUDE_2047 = 0x0A, /*!< unmask bit[10:0]/ triangle amplitude equal to 2047 */ + DAC_LSFR_BITB0_AMPLITUDE_4095 = 0x0B /*!< unmask bit[11:0]/ triangle amplitude equal to 4095 */ +} dac_mask_amplitude_type; + +/** + * @brief dac1 aligned data type + */ +typedef enum +{ + DAC1_12BIT_RIGHT = 0x40007408, /*!< dac1 12-bit data right-aligned */ + DAC1_12BIT_LEFT = 0x4000740C, /*!< dac1 12-bit data left-aligned */ + DAC1_8BIT_RIGHT = 0x40007410 /*!< dac1 8-bit data right-aligned */ +} dac1_aligned_data_type; + +/** + * @brief dac2 aligned data type + */ +typedef enum +{ + DAC2_12BIT_RIGHT = 0x40007414, /*!< dac2 12-bit data right-aligned */ + DAC2_12BIT_LEFT = 0x40007418, /*!< dac2 12-bit data left-aligned */ + DAC2_8BIT_RIGHT = 0x4000741C /*!< dac2 8-bit data right-aligned */ +} dac2_aligned_data_type; + +/** + * @brief dac dual data type + */ +typedef enum +{ + DAC_DUAL_12BIT_RIGHT = 0x40007420, /*!divr_bit.fdiv = div) + +/** + * @} + */ + +/** @defgroup FLASH_exported_types + * @{ + */ + +/** + * @brief flash usd eopb0 type + */ +typedef enum +{ + FLASH_EOPB0_SRAM_512K = 0x00, /*!< sram 512k, flash zw area 128k */ + FLASH_EOPB0_SRAM_448K = 0x01, /*!< sram 448k, flash zw area 192k */ + FLASH_EOPB0_SRAM_384K = 0x02, /*!< sram 384k, flash zw area 256k */ + FLASH_EOPB0_SRAM_320K = 0x03, /*!< sram 320k, flash zw area 320k */ + FLASH_EOPB0_SRAM_256K = 0x04, /*!< sram 256k, flash zw area 384k */ + FLASH_EOPB0_SRAM_192K = 0x05, /*!< sram 192k, flash zw area 448k */ + FLASH_EOPB0_SRAM_128K = 0x06 /*!< sram 128k, flash zw area 512k */ +} flash_usd_eopb0_type; + +/** + * @brief flash clock divider type + */ +typedef enum +{ + FLASH_CLOCK_DIV_2 = 0x00, /*!< flash clock divide by 2 */ + FLASH_CLOCK_DIV_3 = 0x01, /*!< flash clock divide by 3 */ + FLASH_CLOCK_DIV_4 = 0x02 /*!< flash clock divide by 4 */ +} flash_clock_divider_type; + +/** + * @brief flash status type + */ +typedef enum +{ + FLASH_OPERATE_BUSY = 0x00, /*!< flash status is operate busy */ + FLASH_PROGRAM_ERROR = 0x01, /*!< flash status is program error */ + FLASH_EPP_ERROR = 0x02, /*!< flash status is epp error */ + FLASH_OPERATE_DONE = 0x03, /*!< flash status is operate done */ + FLASH_OPERATE_TIMEOUT = 0x04 /*!< flash status is operate timeout */ +} flash_status_type; + +/** + * @brief type define flash register all + */ +typedef struct +{ + /** + * @brief flash psr register, offset:0x00 + */ + union + { + __IO uint32_t psr; + struct + { + __IO uint32_t reserved1 : 12;/* [11:0] */ + __IO uint32_t nzw_bst : 1; /* [12] */ + __IO uint32_t nzw_bst_sts : 1; /* [13] */ + __IO uint32_t reserved2 : 18;/* [31:14] */ + } psr_bit; + }; + + /** + * @brief flash unlock register, offset:0x04 + */ + union + { + __IO uint32_t unlock; + struct + { + __IO uint32_t ukval : 32;/* [31:0] */ + } unlock_bit; + }; + + /** + * @brief flash usd unlock register, offset:0x08 + */ + union + { + __IO uint32_t usd_unlock; + struct + { + __IO uint32_t usd_ukval : 32;/* [31:0] */ + } usd_unlock_bit; + }; + + /** + * @brief flash sts register, offset:0x0C + */ + union + { + __IO uint32_t sts; + struct + { + __IO uint32_t obf : 1; /* [0] */ + __IO uint32_t reserved1 : 1; /* [1] */ + __IO uint32_t prgmerr : 1; /* [2] */ + __IO uint32_t reserved2 : 1; /* [3] */ + __IO uint32_t epperr : 1; /* [4] */ + __IO uint32_t odf : 1; /* [5] */ + __IO uint32_t reserved3 : 26;/* [31:6] */ + } sts_bit; + }; + + /** + * @brief flash ctrl register, offset:0x10 + */ + union + { + __IO uint32_t ctrl; + struct + { + __IO uint32_t fprgm : 1; /* [0] */ + __IO uint32_t secers : 1; /* [1] */ + __IO uint32_t bankers : 1; /* [2] */ + __IO uint32_t blkers : 1; /* [3] */ + __IO uint32_t usdprgm : 1; /* [4] */ + __IO uint32_t usders : 1; /* [5] */ + __IO uint32_t erstr : 1; /* [6] */ + __IO uint32_t oplk : 1; /* [7] */ + __IO uint32_t reserved1 : 1; /* [8] */ + __IO uint32_t usdulks : 1; /* [9] */ + __IO uint32_t errie : 1; /* [10] */ + __IO uint32_t reserved2 : 1; /* [11] */ + __IO uint32_t odfie : 1; /* [12] */ + __IO uint32_t reserved3 : 19;/* [31:13] */ + } ctrl_bit; + }; + + /** + * @brief flash addr register, offset:0x14 + */ + union + { + __IO uint32_t addr; + struct + { + __IO uint32_t fa : 32;/* [31:0] */ + } addr_bit; + }; + + /** + * @brief flash reserved1 register, offset:0x18 + */ + __IO uint32_t reserved1; + + /** + * @brief flash usd register, offset:0x1C + */ + union + { + __IO uint32_t usd; + struct + { + __IO uint32_t usderr : 1; /* [0] */ + __IO uint32_t fap : 1; /* [1] */ + __IO uint32_t wdt_ato_en : 1; /* [2] */ + __IO uint32_t depslp_rst : 1; /* [3] */ + __IO uint32_t stdby_rst : 1; /* [4] */ + __IO uint32_t btopt : 1; /* [5] */ + __IO uint32_t reserved1 : 1; /* [6] */ + __IO uint32_t wdt_depslp : 1; /* [7] */ + __IO uint32_t wdt_stdby : 1; /* [8] */ + __IO uint32_t reserved2 : 1; /* [9] */ + __IO uint32_t user_d0 : 8; /* [17:10] */ + __IO uint32_t user_d1 : 8; /* [25:18] */ + __IO uint32_t reserved3 : 6; /* [31:26] */ + } usd_bit; + }; + + /** + * @brief flash epps0 register, offset:0x20 + */ + union + { + __IO uint32_t epps0; + struct + { + __IO uint32_t epps : 32;/* [31:0] */ + } epps0_bit; + }; + + /** + * @brief flash reserved2 register, offset:0x28~0x24 + */ + __IO uint32_t reserved2[2]; + + /** + * @brief flash epps1 register, offset:0x2C + */ + union + { + __IO uint32_t epps1; + struct + { + __IO uint32_t epps : 32;/* [31:0] */ + } epps1_bit; + }; + + /** + * @brief flash reserved3 register, offset:0x40~0x30 + */ + __IO uint32_t reserved3[5]; + + /** + * @brief flash unlock2 register, offset:0x44 + */ + union + { + __IO uint32_t unlock2; + struct + { + __IO uint32_t ukval : 32;/* [31:0] */ + } unlock2_bit; + }; + + /** + * @brief flash reserved4 register, offset:0x48 + */ + __IO uint32_t reserved4; + + /** + * @brief flash sts2 register, offset:0x4C + */ + union + { + __IO uint32_t sts2; + struct + { + __IO uint32_t obf : 1; /* [0] */ + __IO uint32_t reserved1 : 1; /* [1] */ + __IO uint32_t prgmerr : 1; /* [2] */ + __IO uint32_t reserved2 : 1; /* [3] */ + __IO uint32_t epperr : 1; /* [4] */ + __IO uint32_t odf : 1; /* [5] */ + __IO uint32_t reserved3 : 26;/* [31:6] */ + } sts2_bit; + }; + + /** + * @brief flash ctrl2 register, offset:0x50 + */ + union + { + __IO uint32_t ctrl2; + struct + { + __IO uint32_t fprgm : 1; /* [0] */ + __IO uint32_t secers : 1; /* [1] */ + __IO uint32_t bankers : 1; /* [2] */ + __IO uint32_t blkers : 1; /* [3] */ + __IO uint32_t reserved1 : 2; /* [5:4] */ + __IO uint32_t erstr : 1; /* [6] */ + __IO uint32_t oplk : 1; /* [7] */ + __IO uint32_t reserved2 : 2; /* [9:8] */ + __IO uint32_t errie : 1; /* [10] */ + __IO uint32_t reserved3 : 1; /* [11] */ + __IO uint32_t odfie : 1; /* [12] */ + __IO uint32_t reserved4 : 19;/* [31:13] */ + } ctrl2_bit; + }; + + /** + * @brief flash addr2 register, offset:0x54 + */ + union + { + __IO uint32_t addr2; + struct + { + __IO uint32_t fa : 32;/* [31:0] */ + } addr2_bit; + }; + + /** + * @brief flash contr register, offset:0x58 + */ + union + { + __IO uint32_t contr; + struct + { + __IO uint32_t reserved1 : 31;/* [30:0] */ + __IO uint32_t fcontr_en : 1; /* [31] */ + } contr_bit; + }; + + /** + * @brief flash reserved5 register, offset:0x5C + */ + __IO uint32_t reserved5; + + /** + * @brief flash divr register, offset:0x60 + */ + union + { + __IO uint32_t divr; + struct + { + __IO uint32_t fdiv : 2; /* [1:0] */ + __IO uint32_t reserved1 : 2; /* [3:2] */ + __IO uint32_t fdiv_sts : 2; /* [5:4] */ + __IO uint32_t reserved2 : 26;/* [31:6] */ + } divr_bit; + }; + + /** + * @brief flash reserved6 register, offset:0xC4~0x64 + */ + __IO uint32_t reserved6[25]; + + /** + * @brief flash slib_sts2 register, offset:0xC8 + */ + union + { + __IO uint32_t slib_sts2; + struct + { + __IO uint32_t slib_inst_ss : 16;/* [15:0] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } slib_sts2_bit; + }; + + /** + * @brief flash slib_sts0 register, offset:0xCC + */ + union + { + __IO uint32_t slib_sts0; + struct + { + __IO uint32_t reserved1 : 3; /* [2:0] */ + __IO uint32_t slib_enf : 1; /* [3] */ + __IO uint32_t reserved2 : 28;/* [31:4] */ + } slib_sts0_bit; + }; + + /** + * @brief flash slib_sts1 register, offset:0xD0 + */ + union + { + __IO uint32_t slib_sts1; + struct + { + __IO uint32_t slib_ss : 16;/* [15:0] */ + __IO uint32_t slib_es : 16;/* [31:16] */ + } slib_sts1_bit; + }; + + /** + * @brief flash slib_pwd_clr register, offset:0xD4 + */ + union + { + __IO uint32_t slib_pwd_clr; + struct + { + __IO uint32_t slib_pclr_val : 32;/* [31:0] */ + } slib_pwd_clr_bit; + }; + + /** + * @brief flash slib_misc_sts register, offset:0xD8 + */ + union + { + __IO uint32_t slib_misc_sts; + struct + { + __IO uint32_t slib_pwd_err : 1; /* [0] */ + __IO uint32_t slib_pwd_ok : 1; /* [1] */ + __IO uint32_t slib_ulkf : 1; /* [2] */ + __IO uint32_t reserved1 : 13;/* [15:3] */ + __IO uint32_t slib_rcnt : 9; /* [24:16] */ + __IO uint32_t reserved2 : 7; /* [31:25] */ + } slib_misc_sts_bit; + }; + + /** + * @brief flash slib_set_pwd register, offset:0xDC + */ + union + { + __IO uint32_t slib_set_pwd; + struct + { + __IO uint32_t slib_pset_val : 32;/* [31:0] */ + } slib_set_pwd_bit; + }; + + /** + * @brief flash slib_set_range0 register, offset:0xE0 + */ + union + { + __IO uint32_t slib_set_range0; + struct + { + __IO uint32_t slib_ss_set : 16;/* [15:0] */ + __IO uint32_t slib_es_set : 16;/* [31:16] */ + } slib_set_range0_bit; + }; + + /** + * @brief flash slib_set_range1 register, offset:0xE4 + */ + union + { + __IO uint32_t slib_set_range1; + struct + { + __IO uint32_t slib_iss_set : 16;/* [15:0] */ + __IO uint32_t reserved1 : 15;/* [30:16] */ + __IO uint32_t set_slib_strt : 1; /* [31] */ + } slib_set_range1_bit; + }; + + /** + * @brief flash reserved7 register, offset:0xEC~0xE8 + */ + __IO uint32_t reserved7[2]; + + /** + * @brief flash slib_unlock register, offset:0xF0 + */ + union + { + __IO uint32_t slib_unlock; + struct + { + __IO uint32_t slib_ukval : 32;/* [31:0] */ + } slib_unlock_bit; + }; + + /** + * @brief flash crc_ctrl register, offset:0xF4 + */ + union + { + __IO uint32_t crc_ctrl; + struct + { + __IO uint32_t crc_ss : 12;/* [11:0] */ + __IO uint32_t crc_sn : 12;/* [23:12] */ + __IO uint32_t reserved1 : 7; /* [30:24] */ + __IO uint32_t crc_strt : 1; /* [31] */ + } crc_ctrl_bit; + }; + + /** + * @brief flash crc_chkr register, offset:0xF8 + */ + union + { + __IO uint32_t crc_chkr; + struct + { + __IO uint32_t crc_chkr : 32;/* [31:0] */ + } crc_chkr_bit; + }; + +} flash_type; + +/** + * @brief user system data + */ +typedef struct +{ + __IO uint16_t fap; + __IO uint16_t ssb; + __IO uint16_t data0; + __IO uint16_t data1; + __IO uint16_t epp0; + __IO uint16_t epp1; + __IO uint16_t epp2; + __IO uint16_t epp3; + __IO uint16_t eopb0; + __IO uint16_t reserved1; + __IO uint16_t epp4; + __IO uint16_t epp5; + __IO uint16_t epp6; + __IO uint16_t epp7; + __IO uint16_t reserved2[12]; + __IO uint16_t qspikey[8]; +} usd_type; + +/** + * @} + */ + +#define FLASH ((flash_type *) FLASH_REG_BASE) +#define USD ((usd_type *) USD_BASE) + +/** @defgroup FLASH_exported_functions + * @{ + */ + +flag_status flash_flag_get(uint32_t flash_flag); +void flash_flag_clear(uint32_t flash_flag); +flash_status_type flash_operation_status_get(void); +flash_status_type flash_bank1_operation_status_get(void); +flash_status_type flash_bank2_operation_status_get(void); +flash_status_type flash_operation_wait_for(uint32_t time_out); +flash_status_type flash_bank1_operation_wait_for(uint32_t time_out); +flash_status_type flash_bank2_operation_wait_for(uint32_t time_out); +void flash_unlock(void); +void flash_bank1_unlock(void); +void flash_bank2_unlock(void); +void flash_lock(void); +void flash_bank1_lock(void); +void flash_bank2_lock(void); +flash_status_type flash_sector_erase(uint32_t sector_address); +flash_status_type flash_block_erase(uint32_t block_address); +flash_status_type flash_internal_all_erase(void); +flash_status_type flash_bank1_erase(void); +flash_status_type flash_bank2_erase(void); +flash_status_type flash_user_system_data_erase(void); +flash_status_type flash_eopb0_config(flash_usd_eopb0_type data); +flash_status_type flash_word_program(uint32_t address, uint32_t data); +flash_status_type flash_halfword_program(uint32_t address, uint16_t data); +flash_status_type flash_byte_program(uint32_t address, uint8_t data); +flash_status_type flash_user_system_data_program(uint32_t address, uint8_t data); +flash_status_type flash_epp_set(uint32_t *sector_bits); +void flash_epp_status_get(uint32_t *sector_bits); +flash_status_type flash_fap_enable(confirm_state new_state); +flag_status flash_fap_status_get(void); +flash_status_type flash_ssb_set(uint8_t usd_ssb); +uint8_t flash_ssb_status_get(void); +void flash_interrupt_enable(uint32_t flash_int, confirm_state new_state); +flash_status_type flash_slib_enable(uint32_t pwd, uint16_t start_sector, uint16_t inst_start_sector, uint16_t end_sector); +error_status flash_slib_disable(uint32_t pwd); +uint32_t flash_slib_remaining_count_get(void); +flag_status flash_slib_state_get(void); +uint16_t flash_slib_start_sector_get(void); +uint16_t flash_slib_inststart_sector_get(void); +uint16_t flash_slib_end_sector_get(void); +uint32_t flash_crc_calibrate(uint32_t start_sector, uint32_t sector_cnt); +void flash_nzw_boost_enable(confirm_state new_state); +void flash_continue_read_enable(confirm_state new_state); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_gpio.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_gpio.h new file mode 100644 index 0000000000..a4d7c0be34 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_gpio.h @@ -0,0 +1,565 @@ +/** + ************************************************************************** + * @file at32f435_437_gpio.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 gpio header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_GPIO_H +#define __AT32F435_437_GPIO_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup GPIO + * @{ + */ + +/** @defgroup GPIO_pins_number_definition + * @{ + */ + +#define GPIO_PINS_0 0x0001 /*!< gpio pins number 0 */ +#define GPIO_PINS_1 0x0002 /*!< gpio pins number 1 */ +#define GPIO_PINS_2 0x0004 /*!< gpio pins number 2 */ +#define GPIO_PINS_3 0x0008 /*!< gpio pins number 3 */ +#define GPIO_PINS_4 0x0010 /*!< gpio pins number 4 */ +#define GPIO_PINS_5 0x0020 /*!< gpio pins number 5 */ +#define GPIO_PINS_6 0x0040 /*!< gpio pins number 6 */ +#define GPIO_PINS_7 0x0080 /*!< gpio pins number 7 */ +#define GPIO_PINS_8 0x0100 /*!< gpio pins number 8 */ +#define GPIO_PINS_9 0x0200 /*!< gpio pins number 9 */ +#define GPIO_PINS_10 0x0400 /*!< gpio pins number 10 */ +#define GPIO_PINS_11 0x0800 /*!< gpio pins number 11 */ +#define GPIO_PINS_12 0x1000 /*!< gpio pins number 12 */ +#define GPIO_PINS_13 0x2000 /*!< gpio pins number 13 */ +#define GPIO_PINS_14 0x4000 /*!< gpio pins number 14 */ +#define GPIO_PINS_15 0x8000 /*!< gpio pins number 15 */ +#define GPIO_PINS_ALL 0xFFFF /*!< gpio all pins */ + +/** + * @} + */ + +/** @defgroup GPIO_exported_types + * @{ + */ + +/** + * @brief gpio mode select + */ +typedef enum +{ + GPIO_MODE_INPUT = 0x00, /*!< gpio input mode */ + GPIO_MODE_OUTPUT = 0x01, /*!< gpio output mode */ + GPIO_MODE_MUX = 0x02, /*!< gpio mux function mode */ + GPIO_MODE_ANALOG = 0x03 /*!< gpio analog in/out mode */ +} gpio_mode_type; + +/** + * @brief gpio output drive strength select + */ +typedef enum +{ + GPIO_DRIVE_STRENGTH_STRONGER = 0x01, /*!< stronger sourcing/sinking strength */ + GPIO_DRIVE_STRENGTH_MODERATE = 0x02 /*!< moderate sourcing/sinking strength */ +} gpio_drive_type; + +/** + * @brief gpio output type + */ +typedef enum +{ + GPIO_OUTPUT_PUSH_PULL = 0x00, /*!< output push-pull */ + GPIO_OUTPUT_OPEN_DRAIN = 0x01 /*!< output open-drain */ +} gpio_output_type; + +/** + * @brief gpio pull type + */ +typedef enum +{ + GPIO_PULL_NONE = 0x00, /*!< floating for input, no pull for output */ + GPIO_PULL_UP = 0x01, /*!< pull-up */ + GPIO_PULL_DOWN = 0x02 /*!< pull-down */ +} gpio_pull_type; + +/** + * @brief gpio init type + */ +typedef struct +{ + uint32_t gpio_pins; /*!< pins number selection */ + gpio_output_type gpio_out_type; /*!< output type selection */ + gpio_pull_type gpio_pull; /*!< pull type selection */ + gpio_mode_type gpio_mode; /*!< mode selection */ + gpio_drive_type gpio_drive_strength; /*!< drive strength selection */ +} gpio_init_type; + +/** + * @brief gpio pins source type + */ +typedef enum +{ + GPIO_PINS_SOURCE0 = 0x00, /*!< gpio pins source number 0 */ + GPIO_PINS_SOURCE1 = 0x01, /*!< gpio pins source number 1 */ + GPIO_PINS_SOURCE2 = 0x02, /*!< gpio pins source number 2 */ + GPIO_PINS_SOURCE3 = 0x03, /*!< gpio pins source number 3 */ + GPIO_PINS_SOURCE4 = 0x04, /*!< gpio pins source number 4 */ + GPIO_PINS_SOURCE5 = 0x05, /*!< gpio pins source number 5 */ + GPIO_PINS_SOURCE6 = 0x06, /*!< gpio pins source number 6 */ + GPIO_PINS_SOURCE7 = 0x07, /*!< gpio pins source number 7 */ + GPIO_PINS_SOURCE8 = 0x08, /*!< gpio pins source number 8 */ + GPIO_PINS_SOURCE9 = 0x09, /*!< gpio pins source number 9 */ + GPIO_PINS_SOURCE10 = 0x0A, /*!< gpio pins source number 10 */ + GPIO_PINS_SOURCE11 = 0x0B, /*!< gpio pins source number 11 */ + GPIO_PINS_SOURCE12 = 0x0C, /*!< gpio pins source number 12 */ + GPIO_PINS_SOURCE13 = 0x0D, /*!< gpio pins source number 13 */ + GPIO_PINS_SOURCE14 = 0x0E, /*!< gpio pins source number 14 */ + GPIO_PINS_SOURCE15 = 0x0F /*!< gpio pins source number 15 */ +} gpio_pins_source_type; + +/** + * @brief gpio muxing function selection type + */ +typedef enum +{ + GPIO_MUX_0 = 0x00, /*!< gpio muxing function selection 0 */ + GPIO_MUX_1 = 0x01, /*!< gpio muxing function selection 1 */ + GPIO_MUX_2 = 0x02, /*!< gpio muxing function selection 2 */ + GPIO_MUX_3 = 0x03, /*!< gpio muxing function selection 3 */ + GPIO_MUX_4 = 0x04, /*!< gpio muxing function selection 4 */ + GPIO_MUX_5 = 0x05, /*!< gpio muxing function selection 5 */ + GPIO_MUX_6 = 0x06, /*!< gpio muxing function selection 6 */ + GPIO_MUX_7 = 0x07, /*!< gpio muxing function selection 7 */ + GPIO_MUX_8 = 0x08, /*!< gpio muxing function selection 8 */ + GPIO_MUX_9 = 0x09, /*!< gpio muxing function selection 9 */ + GPIO_MUX_10 = 0x0A, /*!< gpio muxing function selection 10 */ + GPIO_MUX_11 = 0x0B, /*!< gpio muxing function selection 11 */ + GPIO_MUX_12 = 0x0C, /*!< gpio muxing function selection 12 */ + GPIO_MUX_13 = 0x0D, /*!< gpio muxing function selection 13 */ + GPIO_MUX_14 = 0x0E, /*!< gpio muxing function selection 14 */ + GPIO_MUX_15 = 0x0F /*!< gpio muxing function selection 15 */ +} gpio_mux_sel_type; + +/** + * @brief type define gpio register all + */ +typedef struct +{ + /** + * @brief gpio mode register, offset:0x00 + */ + union + { + __IO uint32_t cfgr; + struct + { + __IO uint32_t iomc0 : 2; /* [1:0] */ + __IO uint32_t iomc1 : 2; /* [3:2] */ + __IO uint32_t iomc2 : 2; /* [5:4] */ + __IO uint32_t iomc3 : 2; /* [7:6] */ + __IO uint32_t iomc4 : 2; /* [9:8] */ + __IO uint32_t iomc5 : 2; /* [11:10] */ + __IO uint32_t iomc6 : 2; /* [13:12] */ + __IO uint32_t iomc7 : 2; /* [15:14] */ + __IO uint32_t iomc8 : 2; /* [17:16] */ + __IO uint32_t iomc9 : 2; /* [19:18] */ + __IO uint32_t iomc10 : 2; /* [21:20] */ + __IO uint32_t iomc11 : 2; /* [23:22] */ + __IO uint32_t iomc12 : 2; /* [25:24] */ + __IO uint32_t iomc13 : 2; /* [27:26] */ + __IO uint32_t iomc14 : 2; /* [29:28] */ + __IO uint32_t iomc15 : 2; /* [31:30] */ + } cfgr_bit; + }; + + /** + * @brief gpio output type register, offset:0x04 + */ + union + { + __IO uint32_t omode; + struct + { + __IO uint32_t om0 : 1; /* [0] */ + __IO uint32_t om1 : 1; /* [1] */ + __IO uint32_t om2 : 1; /* [2] */ + __IO uint32_t om3 : 1; /* [3] */ + __IO uint32_t om4 : 1; /* [4] */ + __IO uint32_t om5 : 1; /* [5] */ + __IO uint32_t om6 : 1; /* [6] */ + __IO uint32_t om7 : 1; /* [7] */ + __IO uint32_t om8 : 1; /* [8] */ + __IO uint32_t om9 : 1; /* [9] */ + __IO uint32_t om10 : 1; /* [10] */ + __IO uint32_t om11 : 1; /* [11] */ + __IO uint32_t om12 : 1; /* [12] */ + __IO uint32_t om13 : 1; /* [13] */ + __IO uint32_t om14 : 1; /* [14] */ + __IO uint32_t om15 : 1; /* [15] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } omode_bit; + }; + + /** + * @brief gpio output driver register, offset:0x08 + */ + union + { + __IO uint32_t odrvr; + struct + { + __IO uint32_t odrv0 : 2; /* [1:0] */ + __IO uint32_t odrv1 : 2; /* [3:2] */ + __IO uint32_t odrv2 : 2; /* [5:4] */ + __IO uint32_t odrv3 : 2; /* [7:6] */ + __IO uint32_t odrv4 : 2; /* [9:8] */ + __IO uint32_t odrv5 : 2; /* [11:10] */ + __IO uint32_t odrv6 : 2; /* [13:12] */ + __IO uint32_t odrv7 : 2; /* [15:14] */ + __IO uint32_t odrv8 : 2; /* [17:16] */ + __IO uint32_t odrv9 : 2; /* [19:18] */ + __IO uint32_t odrv10 : 2; /* [21:20] */ + __IO uint32_t odrv11 : 2; /* [23:22] */ + __IO uint32_t odrv12 : 2; /* [25:24] */ + __IO uint32_t odrv13 : 2; /* [27:26] */ + __IO uint32_t odrv14 : 2; /* [29:28] */ + __IO uint32_t odrv15 : 2; /* [31:30] */ + } odrvr_bit; + }; + + /** + * @brief gpio pull up/down register, offset:0x0C + */ + union + { + __IO uint32_t pull; + struct + { + __IO uint32_t pull0 : 2; /* [1:0] */ + __IO uint32_t pull1 : 2; /* [3:2] */ + __IO uint32_t pull2 : 2; /* [5:4] */ + __IO uint32_t pull3 : 2; /* [7:6] */ + __IO uint32_t pull4 : 2; /* [9:8] */ + __IO uint32_t pull5 : 2; /* [11:10] */ + __IO uint32_t pull6 : 2; /* [13:12] */ + __IO uint32_t pull7 : 2; /* [15:14] */ + __IO uint32_t pull8 : 2; /* [17:16] */ + __IO uint32_t pull9 : 2; /* [19:18] */ + __IO uint32_t pull10 : 2; /* [21:20] */ + __IO uint32_t pull11 : 2; /* [23:22] */ + __IO uint32_t pull12 : 2; /* [25:24] */ + __IO uint32_t pull13 : 2; /* [27:26] */ + __IO uint32_t pull14 : 2; /* [29:28] */ + __IO uint32_t pull15 : 2; /* [31:30] */ + } pull_bit; + }; + + /** + * @brief gpio input data register, offset:0x10 + */ + union + { + __IO uint32_t idt; + struct + { + __IO uint32_t idt0 : 1; /* [0] */ + __IO uint32_t idt1 : 1; /* [1] */ + __IO uint32_t idt2 : 1; /* [2] */ + __IO uint32_t idt3 : 1; /* [3] */ + __IO uint32_t idt4 : 1; /* [4] */ + __IO uint32_t idt5 : 1; /* [5] */ + __IO uint32_t idt6 : 1; /* [6] */ + __IO uint32_t idt7 : 1; /* [7] */ + __IO uint32_t idt8 : 1; /* [8] */ + __IO uint32_t idt9 : 1; /* [9] */ + __IO uint32_t idt10 : 1; /* [10] */ + __IO uint32_t idt11 : 1; /* [11] */ + __IO uint32_t idt12 : 1; /* [12] */ + __IO uint32_t idt13 : 1; /* [13] */ + __IO uint32_t idt14 : 1; /* [14] */ + __IO uint32_t idt15 : 1; /* [15] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } idt_bit; + }; + + /** + * @brief gpio output data register, offset:0x14 + */ + union + { + __IO uint32_t odt; + struct + { + __IO uint32_t odt0 : 1; /* [0] */ + __IO uint32_t odt1 : 1; /* [1] */ + __IO uint32_t odt2 : 1; /* [2] */ + __IO uint32_t odt3 : 1; /* [3] */ + __IO uint32_t odt4 : 1; /* [4] */ + __IO uint32_t odt5 : 1; /* [5] */ + __IO uint32_t odt6 : 1; /* [6] */ + __IO uint32_t odt7 : 1; /* [7] */ + __IO uint32_t odt8 : 1; /* [8] */ + __IO uint32_t odt9 : 1; /* [9] */ + __IO uint32_t odt10 : 1; /* [10] */ + __IO uint32_t odt11 : 1; /* [11] */ + __IO uint32_t odt12 : 1; /* [12] */ + __IO uint32_t odt13 : 1; /* [13] */ + __IO uint32_t odt14 : 1; /* [14] */ + __IO uint32_t odt15 : 1; /* [15] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } odt_bit; + }; + + /** + * @brief gpio scr register, offset:0x18 + */ + union + { + __IO uint32_t scr; + struct + { + __IO uint32_t iosb0 : 1; /* [0] */ + __IO uint32_t iosb1 : 1; /* [1] */ + __IO uint32_t iosb2 : 1; /* [2] */ + __IO uint32_t iosb3 : 1; /* [3] */ + __IO uint32_t iosb4 : 1; /* [4] */ + __IO uint32_t iosb5 : 1; /* [5] */ + __IO uint32_t iosb6 : 1; /* [6] */ + __IO uint32_t iosb7 : 1; /* [7] */ + __IO uint32_t iosb8 : 1; /* [8] */ + __IO uint32_t iosb9 : 1; /* [9] */ + __IO uint32_t iosb10 : 1; /* [10] */ + __IO uint32_t iosb11 : 1; /* [11] */ + __IO uint32_t iosb12 : 1; /* [12] */ + __IO uint32_t iosb13 : 1; /* [13] */ + __IO uint32_t iosb14 : 1; /* [14] */ + __IO uint32_t iosb15 : 1; /* [15] */ + __IO uint32_t iocb0 : 1; /* [16] */ + __IO uint32_t iocb1 : 1; /* [17] */ + __IO uint32_t iocb2 : 1; /* [18] */ + __IO uint32_t iocb3 : 1; /* [19] */ + __IO uint32_t iocb4 : 1; /* [20] */ + __IO uint32_t iocb5 : 1; /* [21] */ + __IO uint32_t iocb6 : 1; /* [22] */ + __IO uint32_t iocb7 : 1; /* [23] */ + __IO uint32_t iocb8 : 1; /* [24] */ + __IO uint32_t iocb9 : 1; /* [25] */ + __IO uint32_t iocb10 : 1; /* [26] */ + __IO uint32_t iocb11 : 1; /* [27] */ + __IO uint32_t iocb12 : 1; /* [28] */ + __IO uint32_t iocb13 : 1; /* [29] */ + __IO uint32_t iocb14 : 1; /* [30] */ + __IO uint32_t iocb15 : 1; /* [31] */ + } scr_bit; + }; + + /** + * @brief gpio wpen register, offset:0x1C + */ + union + { + __IO uint32_t wpr; + struct + { + __IO uint32_t wpen0 : 1; /* [0] */ + __IO uint32_t wpen1 : 1; /* [1] */ + __IO uint32_t wpen2 : 1; /* [2] */ + __IO uint32_t wpen3 : 1; /* [3] */ + __IO uint32_t wpen4 : 1; /* [4] */ + __IO uint32_t wpen5 : 1; /* [5] */ + __IO uint32_t wpen6 : 1; /* [6] */ + __IO uint32_t wpen7 : 1; /* [7] */ + __IO uint32_t wpen8 : 1; /* [8] */ + __IO uint32_t wpen9 : 1; /* [9] */ + __IO uint32_t wpen10 : 1; /* [10] */ + __IO uint32_t wpen11 : 1; /* [11] */ + __IO uint32_t wpen12 : 1; /* [12] */ + __IO uint32_t wpen13 : 1; /* [13] */ + __IO uint32_t wpen14 : 1; /* [14] */ + __IO uint32_t wpen15 : 1; /* [15] */ + __IO uint32_t wpseq : 1; /* [16] */ + __IO uint32_t reserved1 : 15;/* [31:17] */ + } wpr_bit; + }; + + /** + * @brief gpio muxl register, offset:0x20 + */ + union + { + __IO uint32_t muxl; + struct + { + __IO uint32_t muxl0 : 4; /* [3:0] */ + __IO uint32_t muxl1 : 4; /* [7:4] */ + __IO uint32_t muxl2 : 4; /* [11:8] */ + __IO uint32_t muxl3 : 4; /* [15:12] */ + __IO uint32_t muxl4 : 4; /* [19:16] */ + __IO uint32_t muxl5 : 4; /* [23:20] */ + __IO uint32_t muxl6 : 4; /* [27:24] */ + __IO uint32_t muxl7 : 4; /* [31:28] */ + } muxl_bit; + }; + + /** + * @brief gpio muxh register, offset:0x24 + */ + union + { + __IO uint32_t muxh; + struct + { + __IO uint32_t muxh8 : 4; /* [3:0] */ + __IO uint32_t muxh9 : 4; /* [7:4] */ + __IO uint32_t muxh10 : 4; /* [11:8] */ + __IO uint32_t muxh11 : 4; /* [15:12] */ + __IO uint32_t muxh12 : 4; /* [19:16] */ + __IO uint32_t muxh13 : 4; /* [23:20] */ + __IO uint32_t muxh14 : 4; /* [27:24] */ + __IO uint32_t muxh15 : 4; /* [31:28] */ + } muxh_bit; + }; + + /** + * @brief gpio clr register, offset:0x28 + */ + union + { + __IO uint32_t clr; + struct + { + __IO uint32_t iocb0 : 1; /* [0] */ + __IO uint32_t iocb1 : 1; /* [1] */ + __IO uint32_t iocb2 : 1; /* [2] */ + __IO uint32_t iocb3 : 1; /* [3] */ + __IO uint32_t iocb4 : 1; /* [4] */ + __IO uint32_t iocb5 : 1; /* [5] */ + __IO uint32_t iocb6 : 1; /* [6] */ + __IO uint32_t iocb7 : 1; /* [7] */ + __IO uint32_t iocb8 : 1; /* [8] */ + __IO uint32_t iocb9 : 1; /* [9] */ + __IO uint32_t iocb10 : 1; /* [10] */ + __IO uint32_t iocb11 : 1; /* [11] */ + __IO uint32_t iocb12 : 1; /* [12] */ + __IO uint32_t iocb13 : 1; /* [13] */ + __IO uint32_t iocb14 : 1; /* [14] */ + __IO uint32_t iocb15 : 1; /* [15] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } clr_bit; + }; + + /** + * @brief gpio reserved1 register, offset:0x2C~0x38 + */ + __IO uint32_t reserved1[4]; + + /** + * @brief gpio hdrv register, offset:0x3C + */ + union + { + __IO uint32_t hdrv; + struct + { + __IO uint32_t hdrv0 : 1; /* [0] */ + __IO uint32_t hdrv1 : 1; /* [1] */ + __IO uint32_t hdrv2 : 1; /* [2] */ + __IO uint32_t hdrv3 : 1; /* [3] */ + __IO uint32_t hdrv4 : 1; /* [4] */ + __IO uint32_t hdrv5 : 1; /* [5] */ + __IO uint32_t hdrv6 : 1; /* [6] */ + __IO uint32_t hdrv7 : 1; /* [7] */ + __IO uint32_t hdrv8 : 1; /* [8] */ + __IO uint32_t hdrv9 : 1; /* [9] */ + __IO uint32_t hdrv10 : 1; /* [10] */ + __IO uint32_t hdrv11 : 1; /* [11] */ + __IO uint32_t hdrv12 : 1; /* [12] */ + __IO uint32_t hdrv13 : 1; /* [13] */ + __IO uint32_t hdrv14 : 1; /* [14] */ + __IO uint32_t hdrv15 : 1; /* [15] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } hdrv_bit; + }; + +} gpio_type; + +/** + * @} + */ + +#define GPIOA ((gpio_type *) GPIOA_BASE) +#define GPIOB ((gpio_type *) GPIOB_BASE) +#define GPIOC ((gpio_type *) GPIOC_BASE) +#define GPIOD ((gpio_type *) GPIOD_BASE) +#define GPIOE ((gpio_type *) GPIOE_BASE) +#define GPIOF ((gpio_type *) GPIOF_BASE) +#define GPIOG ((gpio_type *) GPIOG_BASE) +#define GPIOH ((gpio_type *) GPIOH_BASE) + +/** @defgroup GPIO_exported_functions + * @{ + */ + +void gpio_reset(gpio_type *gpio_x); +void gpio_init(gpio_type *gpio_x, gpio_init_type *gpio_init_struct); +void gpio_default_para_init(gpio_init_type *gpio_init_struct); +flag_status gpio_input_data_bit_read(gpio_type *gpio_x, uint16_t pins); +uint16_t gpio_input_data_read(gpio_type *gpio_x); +flag_status gpio_output_data_bit_read(gpio_type *gpio_x, uint16_t pins); +uint16_t gpio_output_data_read(gpio_type *gpio_x); +void gpio_bits_set(gpio_type *gpio_x, uint16_t pins); +void gpio_bits_reset(gpio_type *gpio_x, uint16_t pins); +void gpio_bits_write(gpio_type *gpio_x, uint16_t pins, confirm_state bit_state); +void gpio_port_write(gpio_type *gpio_x, uint16_t port_value); +void gpio_pin_wp_config(gpio_type *gpio_x, uint16_t pins); +void gpio_pins_huge_driven_config(gpio_type *gpio_x, uint16_t pins, confirm_state new_state); +void gpio_pin_mux_config(gpio_type *gpio_x, gpio_pins_source_type gpio_pin_source, gpio_mux_sel_type gpio_mux); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_i2c.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_i2c.h new file mode 100644 index 0000000000..89b308e9d4 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_i2c.h @@ -0,0 +1,479 @@ +/** + ************************************************************************** + * @file at32f435_437_i2c.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 i2c header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_I2C_H +#define __AT32F435_437_I2C_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup I2C + * @{ + */ + +/** + * @brief maximum number of single transfers + */ +#define MAX_TRANSFER_CNT 255 /*!< maximum number of single transfers */ + +/** @defgroup I2C_interrupts_definition + * @brief i2c interrupt + * @{ + */ + +#define I2C_TD_INT ((uint32_t)0x00000002) /*!< i2c transmit data interrupt */ +#define I2C_RD_INT ((uint32_t)0x00000004) /*!< i2c receive data interrupt */ +#define I2C_ADDR_INT ((uint32_t)0x00000008) /*!< i2c address match interrupt */ +#define I2C_ACKFIAL_INT ((uint32_t)0x00000010) /*!< i2c ack fail interrupt */ +#define I2C_STOP_INT ((uint32_t)0x00000020) /*!< i2c stop detect interrupt */ +#define I2C_TDC_INT ((uint32_t)0x00000040) /*!< i2c transmit data complete interrupt */ +#define I2C_ERR_INT ((uint32_t)0x00000080) /*!< i2c bus error interrupt */ + +/** + * @} + */ + +/** @defgroup I2C_flags_definition + * @brief i2c flag + * @{ + */ + +#define I2C_TDBE_FLAG ((uint32_t)0x00000001) /*!< i2c transmit data buffer empty flag */ +#define I2C_TDIS_FLAG ((uint32_t)0x00000002) /*!< i2c send interrupt status */ +#define I2C_RDBF_FLAG ((uint32_t)0x00000004) /*!< i2c receive data buffer full flag */ +#define I2C_ADDRF_FLAG ((uint32_t)0x00000008) /*!< i2c 0~7 bit address match flag */ +#define I2C_ACKFAIL_FLAG ((uint32_t)0x00000010) /*!< i2c acknowledge failure flag */ +#define I2C_STOPF_FLAG ((uint32_t)0x00000020) /*!< i2c stop condition generation complete flag */ +#define I2C_TDC_FLAG ((uint32_t)0x00000040) /*!< i2c transmit data complete flag */ +#define I2C_TCRLD_FLAG ((uint32_t)0x00000080) /*!< i2c transmission is complete, waiting to load data */ +#define I2C_BUSERR_FLAG ((uint32_t)0x00000100) /*!< i2c bus error flag */ +#define I2C_ARLOST_FLAG ((uint32_t)0x00000200) /*!< i2c arbitration lost flag */ +#define I2C_OUF_FLAG ((uint32_t)0x00000400) /*!< i2c overflow or underflow flag */ +#define I2C_PECERR_FLAG ((uint32_t)0x00000800) /*!< i2c pec receive error flag */ +#define I2C_TMOUT_FLAG ((uint32_t)0x00001000) /*!< i2c smbus timeout flag */ +#define I2C_ALERTF_FLAG ((uint32_t)0x00002000) /*!< i2c smbus alert flag */ +#define I2C_BUSYF_FLAG ((uint32_t)0x00008000) /*!< i2c bus busy flag transmission mode */ +#define I2C_SDIR_FLAG ((uint32_t)0x00010000) /*!< i2c slave data transmit direction */ + +/** + * @} + */ + +/** @defgroup I2C_exported_types + * @{ + */ + +/** + * @brief i2c smbus mode set + */ +typedef enum +{ + I2C_SMBUS_MODE_DEVICE = 0x00, /*!< smbus device mode */ + I2C_SMBUS_MODE_HOST = 0x01 /*!< smbus host mode */ +} i2c_smbus_mode_type; + +/** + * @brief i2c address mode + */ +typedef enum +{ + I2C_ADDRESS_MODE_7BIT = 0x00, /*!< 7bit address mode */ + I2C_ADDRESS_MODE_10BIT = 0x01 /*!< 10bit address mode */ +} i2c_address_mode_type; + +/** + * @brief i2c transfer direction + */ +typedef enum +{ + I2C_DIR_TRANSMIT = 0x00, /*!< master request a write transfer */ + I2C_DIR_RECEIVE = 0x01 /*!< master request a read transfer */ +} i2c_transfer_dir_type; + +/** + * @brief i2c dma requests direction + */ +typedef enum +{ + I2C_DMA_REQUEST_TX = 0x00, /*!< dma transmit request */ + I2C_DMA_REQUEST_RX = 0x01 /*!< dma receive request */ +} i2c_dma_request_type; + +/** + * @brief i2c smbus alert pin set + */ +typedef enum +{ + I2C_SMBUS_ALERT_HIGH = 0x00, /*!< smbus alert pin set high */ + I2C_SMBUS_ALERT_LOW = 0x01 /*!< smbus alert pin set low */ +} i2c_smbus_alert_set_type; + +/** + * @brief i2c clock timeout detection mode + */ +typedef enum +{ + I2C_TIMEOUT_DETCET_LOW = 0x00, /*!< detect low level timeout */ + I2C_TIMEOUT_DETCET_HIGH = 0x01 /*!< detect high level timeout */ +} i2c_timeout_detcet_type; + +/** + * @brief i2c own address2 mask + */ +typedef enum +{ + I2C_ADDR2_NOMASK = 0x00, /*!< compare bit [7:1] */ + I2C_ADDR2_MASK01 = 0x01, /*!< only compare bit [7:2] */ + I2C_ADDR2_MASK02 = 0x02, /*!< only compare bit [7:2] */ + I2C_ADDR2_MASK03 = 0x03, /*!< only compare bit [7:3] */ + I2C_ADDR2_MASK04 = 0x04, /*!< only compare bit [7:4] */ + I2C_ADDR2_MASK05 = 0x05, /*!< only compare bit [7:5] */ + I2C_ADDR2_MASK06 = 0x06, /*!< only compare bit [7:6] */ + I2C_ADDR2_MASK07 = 0x07 /*!< only compare bit [7] */ +} i2c_addr2_mask_type; + +/** + * @brief i2c reload end mode + */ +typedef enum +{ + I2C_AUTO_STOP_MODE = 0x02000000, /*!< auto generate stop mode */ + I2C_SOFT_STOP_MODE = 0x00000000, /*!< soft generate stop mode */ + I2C_RELOAD_MODE = 0x01000000 /*!< reload mode */ +} i2c_reload_stop_mode_type; + +/** + * @brief i2c start mode + */ +typedef enum +{ + I2C_WITHOUT_START = 0x00000000, /*!< transfer data without start condition */ + I2C_GEN_START_READ = 0x00002400, /*!< read data and generate start */ + I2C_GEN_START_WRITE = 0x00002000 /*!< send data and generate start */ +} i2c_start_mode_type; + +/** + * @brief type define i2c register all + */ +typedef struct +{ + /** + * @brief i2c ctrl1 register, offset:0x00 + */ + union + { + __IO uint32_t ctrl1; + struct + { + __IO uint32_t i2cen : 1; /* [0] */ + __IO uint32_t tdien : 1; /* [1] */ + __IO uint32_t rdien : 1; /* [2] */ + __IO uint32_t addrien : 1; /* [3] */ + __IO uint32_t ackfailien : 1; /* [4] */ + __IO uint32_t stopien : 1; /* [5] */ + __IO uint32_t tdcien : 1; /* [6] */ + __IO uint32_t errien : 1; /* [7] */ + __IO uint32_t dflt : 4; /* [11:8] */ + __IO uint32_t reserved1 : 2; /* [13:12] */ + __IO uint32_t dmaten : 1; /* [14] */ + __IO uint32_t dmaren : 1; /* [15] */ + __IO uint32_t sctrl : 1; /* [16] */ + __IO uint32_t stretch : 1; /* [17] */ + __IO uint32_t reserved2 : 1; /* [18] */ + __IO uint32_t gcaen : 1; /* [19] */ + __IO uint32_t haddren : 1; /* [20] */ + __IO uint32_t devaddren : 1; /* [21] */ + __IO uint32_t smbalert : 1; /* [22] */ + __IO uint32_t pecen : 1; /* [23] */ + __IO uint32_t reserved3 : 8; /* [31:24] */ + } ctrl1_bit; + }; + + /** + * @brief i2c ctrl2 register, offset:0x04 + */ + union + { + __IO uint32_t ctrl2; + struct + { + __IO uint32_t saddr : 10;/* [9:0] */ + __IO uint32_t dir : 1; /* [10] */ + __IO uint32_t addr10 : 1; /* [11] */ + __IO uint32_t readh10 : 1; /* [12] */ + __IO uint32_t genstart : 1; /* [13] */ + __IO uint32_t genstop : 1; /* [14] */ + __IO uint32_t nacken : 1; /* [15] */ + __IO uint32_t cnt : 8; /* [23:16] */ + __IO uint32_t rlden : 1; /* [24] */ + __IO uint32_t astopen : 1; /* [25] */ + __IO uint32_t pecten : 1; /* [26] */ + __IO uint32_t reserved1 : 5; /* [31:27] */ + } ctrl2_bit; + }; + + /** + * @brief i2c oaddr1 register, offset:0x08 + */ + union + { + __IO uint32_t oaddr1; + struct + { + __IO uint32_t addr1 : 10;/* [9:0] */ + __IO uint32_t addr1mode : 1; /* [10] */ + __IO uint32_t reserved1 : 4; /* [14:11] */ + __IO uint32_t addr1en : 1; /* [15] */ + __IO uint32_t reserved2 : 16;/* [31:16] */ + } oaddr1_bit; + }; + + /** + * @brief i2c oaddr2 register, offset:0x0c + */ + union + { + __IO uint32_t oaddr2; + struct + { + __IO uint32_t reserved1 : 1; /* [0] */ + __IO uint32_t addr2 : 7; /* [7:1] */ + __IO uint32_t addr2mask : 3; /* [10:8] */ + __IO uint32_t reserved2 : 4; /* [14:11] */ + __IO uint32_t addr2en : 1; /* [15] */ + __IO uint32_t reserved3 : 16;/* [31:16] */ + } oaddr2_bit; + }; + + /** + * @brief i2c clkctrl register, offset:0x10 + */ + union + { + __IO uint32_t clkctrl; + struct + { + __IO uint32_t scll : 8; /* [7:0] */ + __IO uint32_t sclh : 8; /* [15:8] */ + __IO uint32_t sdad : 4; /* [19:16] */ + __IO uint32_t scld : 4; /* [23:20] */ + __IO uint32_t divh : 4; /* [27:24] */ + __IO uint32_t divl : 4; /* [31:28] */ + } clkctrl_bit; + }; + + /** + * @brief i2c timeout register, offset:0x14 + */ + union + { + __IO uint32_t timeout; + struct + { + __IO uint32_t totime : 12;/* [11:0] */ + __IO uint32_t tomode : 1; /* [12] */ + __IO uint32_t reserved1 : 2; /* [14:13] */ + __IO uint32_t toen : 1; /* [15] */ + __IO uint32_t exttime : 12;/* [27:16] */ + __IO uint32_t reserved2 : 3; /* [30:28] */ + __IO uint32_t exten : 1; /* [31] */ + } timeout_bit; + }; + + /** + * @brief i2c sts register, offset:0x18 + */ + union + { + __IO uint32_t sts; + struct + { + __IO uint32_t tdbe : 1; /* [0] */ + __IO uint32_t tdis : 1; /* [1] */ + __IO uint32_t rdbf : 1; /* [2] */ + __IO uint32_t addrf : 1; /* [3] */ + __IO uint32_t ackfail : 1; /* [4] */ + __IO uint32_t stopf : 1; /* [5] */ + __IO uint32_t tdc : 1; /* [6] */ + __IO uint32_t tcrld : 1; /* [7] */ + __IO uint32_t buserr : 1; /* [8] */ + __IO uint32_t arlost : 1; /* [9] */ + __IO uint32_t ouf : 1; /* [10] */ + __IO uint32_t pecerr : 1; /* [11] */ + __IO uint32_t tmout : 1; /* [12] */ + __IO uint32_t alertf : 1; /* [13] */ + __IO uint32_t reserved1 : 1; /* [14] */ + __IO uint32_t busyf : 1; /* [15] */ + __IO uint32_t sdir : 1; /* [16] */ + __IO uint32_t addr : 7; /* [23:17] */ + __IO uint32_t reserved2 : 8; /* [31:24] */ + } sts_bit; + }; + + /** + * @brief i2c clr register, offset:0x1c + */ + union + { + __IO uint32_t clr; + struct + { + __IO uint32_t reserved1 : 3; /* [2:0] */ + __IO uint32_t addrc : 1; /* [3] */ + __IO uint32_t ackfailc : 1; /* [4] */ + __IO uint32_t stopc : 1; /* [5] */ + __IO uint32_t reserved2 : 2; /* [6:7] */ + __IO uint32_t buserrc : 1; /* [8] */ + __IO uint32_t arlostc : 1; /* [9] */ + __IO uint32_t oufc : 1; /* [10] */ + __IO uint32_t pecerrc : 1; /* [11] */ + __IO uint32_t tmoutc : 1; /* [12] */ + __IO uint32_t alertc : 1; /* [13] */ + __IO uint32_t reserved3 : 18;/* [31:14] */ + } clr_bit; + }; + + /** + * @brief i2c pec register, offset:0x20 + */ + union + { + __IO uint32_t pec; + struct + { + __IO uint32_t pecval : 8; /* [7:0] */ + __IO uint32_t reserved1 : 24;/* [31:8] */ + } pec_bit; + }; + + /** + * @brief i2c rxdt register, offset:0x20 + */ + union + { + __IO uint32_t rxdt; + struct + { + __IO uint32_t dt : 8; /* [7:0] */ + __IO uint32_t reserved1 : 24;/* [31:8] */ + } rxdt_bit; + }; + + /** + * @brief i2c txdt register, offset:0x20 + */ + union + { + __IO uint32_t txdt; + struct + { + __IO uint32_t dt : 8; /* [7:0] */ + __IO uint32_t reserved1 : 24;/* [31:8] */ + } txdt_bit; + }; + +} i2c_type; + +/** + * @} + */ + +#define I2C1 ((i2c_type *) I2C1_BASE) +#define I2C2 ((i2c_type *) I2C2_BASE) +#define I2C3 ((i2c_type *) I2C3_BASE) + +/** @defgroup I2C_exported_functions + * @{ + */ + +void i2c_reset(i2c_type *i2c_x); +void i2c_init(i2c_type *i2c_x, uint8_t dfilters, uint32_t clk); +void i2c_own_address1_set(i2c_type *i2c_x, i2c_address_mode_type mode, uint16_t address); +void i2c_own_address2_set(i2c_type *i2c_x, uint8_t address, i2c_addr2_mask_type mask); +void i2c_own_address2_enable(i2c_type *i2c_x, confirm_state new_state); +void i2c_smbus_enable(i2c_type *i2c_x, i2c_smbus_mode_type mode, confirm_state new_state); +void i2c_enable(i2c_type *i2c_x, confirm_state new_state); +void i2c_clock_stretch_enable(i2c_type *i2c_x, confirm_state new_state); +void i2c_ack_enable(i2c_type *i2c_x, confirm_state new_state); +void i2c_addr10_mode_enable(i2c_type *i2c_x, confirm_state new_state); +void i2c_transfer_addr_set(i2c_type *i2c_x, uint16_t address); +uint16_t i2c_transfer_addr_get(i2c_type *i2c_x); +void i2c_transfer_dir_set(i2c_type *i2c_x, i2c_transfer_dir_type i2c_direction); +i2c_transfer_dir_type i2c_transfer_dir_get(i2c_type *i2c_x); +uint8_t i2c_matched_addr_get(i2c_type *i2c_x); +void i2c_auto_stop_enable(i2c_type *i2c_x, confirm_state new_state); +void i2c_reload_enable(i2c_type *i2c_x, confirm_state new_state); +void i2c_cnt_set(i2c_type *i2c_x, uint8_t cnt); +void i2c_addr10_header_enable(i2c_type *i2c_x, confirm_state new_state); +void i2c_general_call_enable(i2c_type *i2c_x, confirm_state new_state); +void i2c_smbus_alert_set(i2c_type *i2c_x, i2c_smbus_alert_set_type level); +void i2c_slave_data_ctrl_enable(i2c_type *i2c_x, confirm_state new_state); +void i2c_pec_calculate_enable(i2c_type *i2c_x, confirm_state new_state); +void i2c_pec_transmit_enable(i2c_type *i2c_x, confirm_state new_state); +uint8_t i2c_pec_value_get(i2c_type *i2c_x); +void i2c_timeout_set(i2c_type *i2c_x, uint16_t timeout); +void i2c_timeout_detcet_set(i2c_type *i2c_x, i2c_timeout_detcet_type mode); +void i2c_timeout_enable(i2c_type *i2c_x, confirm_state new_state); +void i2c_ext_timeout_set(i2c_type *i2c_x, uint16_t timeout); +void i2c_ext_timeout_enable(i2c_type *i2c_x, confirm_state new_state); +void i2c_interrupt_enable(i2c_type *i2c_x, uint32_t source, confirm_state new_state); +flag_status i2c_interrupt_get(i2c_type *i2c_x, uint16_t source); +void i2c_dma_enable(i2c_type *i2c_x, i2c_dma_request_type dma_req, confirm_state new_state); +void i2c_transmit_set(i2c_type *i2c_x, uint16_t address, uint8_t cnt, i2c_reload_stop_mode_type rld_stop, i2c_start_mode_type start); +void i2c_start_generate(i2c_type *i2c_x); +void i2c_stop_generate(i2c_type *i2c_x); +void i2c_data_send(i2c_type *i2c_x, uint8_t data); +uint8_t i2c_data_receive(i2c_type *i2c_x); +flag_status i2c_flag_get(i2c_type *i2c_x, uint32_t flag); +void i2c_flag_clear(i2c_type *i2c_x, uint32_t flag); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_misc.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_misc.h new file mode 100644 index 0000000000..d965d02cc2 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_misc.h @@ -0,0 +1,125 @@ +/** + ************************************************************************** + * @file at32f435_437_misc.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 misc header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_MISC_H +#define __AT32F435_437_MISC_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup MISC + * @{ + */ + +/** @defgroup MISC_vector_table_base_address + * @{ + */ + +#define NVIC_VECTTAB_RAM ((uint32_t)0x20000000) /*!< nvic vector table based ram address */ +#define NVIC_VECTTAB_FLASH ((uint32_t)0x08000000) /*!< nvic vector table based flash address */ + +/** + * @} + */ + +/** @defgroup MISC_exported_types + * @{ + */ + +/** + * @brief nvic interrupt priority group + */ +typedef enum +{ + NVIC_PRIORITY_GROUP_0 = ((uint32_t)0x7), /*!< 0 bits for preemption priority, 4 bits for subpriority */ + NVIC_PRIORITY_GROUP_1 = ((uint32_t)0x6), /*!< 1 bits for preemption priority, 3 bits for subpriority */ + NVIC_PRIORITY_GROUP_2 = ((uint32_t)0x5), /*!< 2 bits for preemption priority, 2 bits for subpriority */ + NVIC_PRIORITY_GROUP_3 = ((uint32_t)0x4), /*!< 3 bits for preemption priority, 1 bits for subpriority */ + NVIC_PRIORITY_GROUP_4 = ((uint32_t)0x3) /*!< 4 bits for preemption priority, 0 bits for subpriority */ +} nvic_priority_group_type; + +/** + * @brief nvic low power mode + */ +typedef enum +{ + NVIC_LP_SLEEPONEXIT = 0x02, /*!< enable sleep-on-exit feature */ + NVIC_LP_SLEEPDEEP = 0x04, /*!< enable sleep-deep output signal when entering sleep mode */ + NVIC_LP_SEVONPEND = 0x10 /*!< send event on pending */ +} nvic_lowpower_mode_type; + +/** + * @brief systick clock source + */ +typedef enum +{ + SYSTICK_CLOCK_SOURCE_AHBCLK_DIV8 = ((uint32_t)0x00000000), /*!< systick clock source from core clock div8 */ + SYSTICK_CLOCK_SOURCE_AHBCLK_NODIV = ((uint32_t)0x00000004) /*!< systick clock source from core clock */ +} systick_clock_source_type; + +/** + * @} + */ + +/** @defgroup MISC_exported_functions + * @{ + */ + +void nvic_system_reset(void); +void nvic_irq_enable(IRQn_Type irqn, uint32_t preempt_priority, uint32_t sub_priority); +void nvic_irq_disable(IRQn_Type irqn); +void nvic_priority_group_config(nvic_priority_group_type priority_group); +void nvic_vector_table_set(uint32_t base, uint32_t offset); +void nvic_lowpower_mode_config(nvic_lowpower_mode_type lp_mode, confirm_state new_state); +void systick_clock_source_config(systick_clock_source_type source); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_pwc.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_pwc.h new file mode 100644 index 0000000000..16304be763 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_pwc.h @@ -0,0 +1,232 @@ +/** + ************************************************************************** + * @file at32f435_437_pwc.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 pwr header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_PWC_H +#define __AT32F435_437_PWC_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup PWC + * @{ + */ + +/** @defgroup PWC_flags_definition + * @brief pwc flag + * @{ + */ + +#define PWC_WAKEUP_FLAG ((uint32_t)0x00000001) /*!< wakeup flag */ +#define PWC_STANDBY_FLAG ((uint32_t)0x00000002) /*!< standby flag */ +#define PWC_PVM_OUTPUT_FLAG ((uint32_t)0x00000004) /*!< pvm output flag */ + +/** + * @} + */ + +/** + * @brief pwc wakeup pin num definition + */ +#define PWC_WAKEUP_PIN_1 ((uint32_t)0x00000100) /*!< standby wake-up pin1 */ +#define PWC_WAKEUP_PIN_2 ((uint32_t)0x00000200) /*!< standby wake-up pin2 */ + +/** + * @brief select ldo output voltage. + * @param val: set the ldo output voltage. + * this parameter can be one of the following values: + * - PWC_LDO_OUTPUT_1V3: system clock up to 288MHz. + * - PWC_LDO_OUTPUT_1V2: system clock up to 240MHz. + * - PWC_LDO_OUTPUT_1V1: system clock up to 192MHz. + * - PWC_LDO_OUTPUT_1V0: system clock up to 144MHz. + * @note useage limited. + * PWC_LDO_OUTPUT_1V3: operation temperature range -40~85 degree, VDD must over 3.0V. + */ +#define pwc_ldo_output_voltage_set(val) (PWC->ldoov_bit.ldoovsel = val) + +/** @defgroup PWC_exported_types + * @{ + */ + +/** + * @brief pwc pvm voltage type + */ +typedef enum +{ + PWC_PVM_VOLTAGE_2V3 = 0x01, /*!< power voltage monitoring boundary 2.3v */ + PWC_PVM_VOLTAGE_2V4 = 0x02, /*!< power voltage monitoring boundary 2.4v */ + PWC_PVM_VOLTAGE_2V5 = 0x03, /*!< power voltage monitoring boundary 2.5v */ + PWC_PVM_VOLTAGE_2V6 = 0x04, /*!< power voltage monitoring boundary 2.6v */ + PWC_PVM_VOLTAGE_2V7 = 0x05, /*!< power voltage monitoring boundary 2.7v */ + PWC_PVM_VOLTAGE_2V8 = 0x06, /*!< power voltage monitoring boundary 2.8v */ + PWC_PVM_VOLTAGE_2V9 = 0x07 /*!< power voltage monitoring boundary 2.9v */ +} pwc_pvm_voltage_type; + +/** + * @brief pwc ldo output voltage type + */ +typedef enum +{ + PWC_LDO_OUTPUT_1V3 = 0x01, /*!< ldo output voltage is 1.3v */ + PWC_LDO_OUTPUT_1V2 = 0x00, /*!< ldo output voltage is 1.2v */ + PWC_LDO_OUTPUT_1V1 = 0x04, /*!< ldo output voltage is 1.1v */ + PWC_LDO_OUTPUT_1V0 = 0x05, /*!< ldo output voltage is 1.0v */ +} pwc_ldo_output_voltage_type; + +/** + * @brief pwc sleep enter type + */ +typedef enum +{ + PWC_SLEEP_ENTER_WFI = 0x00, /*!< use wfi enter sleep mode */ + PWC_SLEEP_ENTER_WFE = 0x01 /*!< use wfe enter sleep mode */ +} pwc_sleep_enter_type ; + +/** + * @brief pwc deep sleep enter type + */ +typedef enum +{ + PWC_DEEP_SLEEP_ENTER_WFI = 0x00, /*!< use wfi enter deepsleep mode */ + PWC_DEEP_SLEEP_ENTER_WFE = 0x01 /*!< use wfe enter deepsleep mode */ +} pwc_deep_sleep_enter_type ; + +/** + * @brief pwc regulator type + */ +typedef enum +{ + PWC_REGULATOR_ON = 0x00, /*!< voltage regulator state on when deepsleep mode */ + PWC_REGULATOR_LOW_POWER = 0x01 /*!< voltage regulator state low power when deepsleep mode */ +} pwc_regulator_type ; + +/** + * @brief type define pwc register all + */ +typedef struct +{ + /** + * @brief pwc ctrl register, offset:0x00 + */ + union + { + __IO uint32_t ctrl; + struct + { + __IO uint32_t vrsel : 1; /* [0] */ + __IO uint32_t lpsel : 1; /* [1] */ + __IO uint32_t clswef : 1; /* [2] */ + __IO uint32_t clsef : 1; /* [3] */ + __IO uint32_t pvmen : 1; /* [4] */ + __IO uint32_t pvmsel : 3; /* [7:5] */ + __IO uint32_t bpwen : 1; /* [8] */ + __IO uint32_t reserved1 : 23;/* [31:9] */ + } ctrl_bit; + }; + + /** + * @brief pwc ctrlsts register, offset:0x04 + */ + union + { + __IO uint32_t ctrlsts; + struct + { + __IO uint32_t swef : 1; /* [0] */ + __IO uint32_t sef : 1; /* [1] */ + __IO uint32_t pvmof : 1; /* [2] */ + __IO uint32_t reserved1 : 5; /* [7:3] */ + __IO uint32_t swpen1 : 1; /* [8] */ + __IO uint32_t swpen2 : 1; /* [9] */ + __IO uint32_t reserved2 : 22;/* [31:10] */ + } ctrlsts_bit; + }; + + __IO uint32_t reserved1[2]; + + /** + * @brief pwc ldoov register, offset:0x10 + */ + union + { + __IO uint32_t ldoov; + struct + { + __IO uint32_t ldoovsel : 3; /* [2:0] */ + __IO uint32_t reserved1 : 29;/* [31:3] */ + } ldoov_bit; + }; + +} pwc_type; + +/** + * @} + */ + +#define PWC ((pwc_type *) PWC_BASE) + +/** @defgroup PWC_exported_functions + * @{ + */ + +void pwc_reset(void); +void pwc_battery_powered_domain_access(confirm_state new_state); +void pwc_pvm_level_select(pwc_pvm_voltage_type pvm_voltage); +void pwc_power_voltage_monitor_enable(confirm_state new_state); +void pwc_wakeup_pin_enable(uint32_t pin_num, confirm_state new_state); +void pwc_flag_clear(uint32_t pwc_flag); +flag_status pwc_flag_get(uint32_t pwc_flag); +void pwc_sleep_mode_enter(pwc_sleep_enter_type pwc_sleep_enter); +void pwc_deep_sleep_mode_enter(pwc_deep_sleep_enter_type pwc_deep_sleep_enter); +void pwc_voltage_regulate_set(pwc_regulator_type pwc_regulator); +void pwc_standby_mode_enter(void); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_qspi.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_qspi.h new file mode 100644 index 0000000000..6e3315eeae --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_qspi.h @@ -0,0 +1,555 @@ +/** + ************************************************************************** + * @file at32f435_437_qspi.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 qspi header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_QSPI_H +#define __AT32F435_437_QSPI_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup QSPI + * @{ + */ + +/** @defgroup QSPI_flags_definition + * @brief qspi flag + * @{ + */ + +#define QSPI_CMDSTS_FLAG ((uint32_t)0x00000001) /*!< qspi command complete status flag */ +#define QSPI_RXFIFORDY_FLAG ((uint32_t)0x00000002) /*!< qspi rxfifo ready status flag */ +#define QSPI_TXFIFORDY_FLAG ((uint32_t)0x00000004) /*!< qspi txfifo ready status flag */ + +/** + * @} + */ + +/** @defgroup QSPI_exported_types + * @{ + */ + +/** + * @brief qspi xip read access mode type + */ +typedef enum +{ + QSPI_XIPR_SEL_MODED = 0x00, /*!< qspi xip read select mode d */ + QSPI_XIPR_SEL_MODET = 0x01 /*!< qspi xip read select mode t */ +} qspi_xip_read_sel_type; + +/** + * @brief qspi xip write access mode type + */ +typedef enum +{ + QSPI_XIPW_SEL_MODED = 0x00, /*!< qspi xip write select mode d */ + QSPI_XIPW_SEL_MODET = 0x01 /*!< qspi xip write select mode t */ +} qspi_xip_write_sel_type; + +/** + * @brief qspi busy bit offset position in status register type + */ +typedef enum +{ + QSPI_BUSY_OFFSET_0 = 0x00, /*!< qspi busy bit offset position 0 */ + QSPI_BUSY_OFFSET_1 = 0x01, /*!< qspi busy bit offset position 1 */ + QSPI_BUSY_OFFSET_2 = 0x02, /*!< qspi busy bit offset position 2 */ + QSPI_BUSY_OFFSET_3 = 0x03, /*!< qspi busy bit offset position 3 */ + QSPI_BUSY_OFFSET_4 = 0x04, /*!< qspi busy bit offset position 4 */ + QSPI_BUSY_OFFSET_5 = 0x05, /*!< qspi busy bit offset position 5 */ + QSPI_BUSY_OFFSET_6 = 0x06, /*!< qspi busy bit offset position 6 */ + QSPI_BUSY_OFFSET_7 = 0x07 /*!< qspi busy bit offset position 7 */ +} qspi_busy_pos_type; + +/** + * @brief qspi read status configure type + */ +typedef enum +{ + QSPI_RSTSC_HW_AUTO = 0x00, /*!< qspi read status by hardware */ + QSPI_RSTSC_SW_ONCE = 0x01 /*!< qspi read status by software */ +} qspi_read_status_conf_type; + +/** + * @brief qspi operate mode type + */ +typedef enum +{ + QSPI_OPERATE_MODE_111 = 0x00, /*!< qspi serial mode */ + QSPI_OPERATE_MODE_112 = 0x01, /*!< qspi dual mode */ + QSPI_OPERATE_MODE_114 = 0x02, /*!< qspi quad mode */ + QSPI_OPERATE_MODE_122 = 0x03, /*!< qspi dual i/o mode */ + QSPI_OPERATE_MODE_144 = 0x04, /*!< qspi quad i/o mode */ + QSPI_OPERATE_MODE_222 = 0x05, /*!< qspi instruction 2-bit mode */ + QSPI_OPERATE_MODE_444 = 0x06 /*!< qspi instruction 4-bit mode(qpi) */ +} qspi_operate_mode_type; + +/** + * @brief qspi clock division type + */ +typedef enum +{ + QSPI_CLK_DIV_2 = 0x00, /*!< qspi clk divide by 2 */ + QSPI_CLK_DIV_4 = 0x01, /*!< qspi clk divide by 4 */ + QSPI_CLK_DIV_6 = 0x02, /*!< qspi clk divide by 6 */ + QSPI_CLK_DIV_8 = 0x03, /*!< qspi clk divide by 8 */ + QSPI_CLK_DIV_3 = 0x04, /*!< qspi clk divide by 3 */ + QSPI_CLK_DIV_5 = 0x05, /*!< qspi clk divide by 5 */ + QSPI_CLK_DIV_10 = 0x06, /*!< qspi clk divide by 10 */ + QSPI_CLK_DIV_12 = 0x07 /*!< qspi clk divide by 12 */ +} qspi_clk_div_type; + +/** + * @brief qspi command port address length type + */ +typedef enum +{ + QSPI_CMD_ADRLEN_0_BYTE = 0x00, /*!< qspi no address */ + QSPI_CMD_ADRLEN_1_BYTE = 0x01, /*!< qspi address length 1 byte */ + QSPI_CMD_ADRLEN_2_BYTE = 0x02, /*!< qspi address length 2 byte */ + QSPI_CMD_ADRLEN_3_BYTE = 0x03, /*!< qspi address length 3 byte */ + QSPI_CMD_ADRLEN_4_BYTE = 0x04 /*!< qspi address length 4 byte */ +} qspi_cmd_adrlen_type; + +/** + * @brief qspi command port instruction length type + */ +typedef enum +{ + QSPI_CMD_INSLEN_0_BYTE = 0x00, /*!< qspi no instruction code */ + QSPI_CMD_INSLEN_1_BYTE = 0x01, /*!< qspi instruction code 1 byte */ + QSPI_CMD_INSLEN_2_BYTE = 0x02 /*!< qspi instruction code 2 byte(repeat) */ +} qspi_cmd_inslen_type; + +/** + * @brief qspi xip r/w address length type + */ +typedef enum +{ + QSPI_XIP_ADDRLEN_3_BYTE = 0x00, /*!< qspi xip address length 3 byte */ + QSPI_XIP_ADDRLEN_4_BYTE = 0x01 /*!< qspi xip address length 4 byte */ +} qspi_xip_addrlen_type; + +/** + * @brief qspi sckout mode type + */ +typedef enum +{ + QSPI_SCK_MODE_0 = 0x00, /*!< qspi sck mode 0 */ + QSPI_SCK_MODE_3 = 0x01 /*!< qspi sck mode 3 */ +} qspi_clk_mode_type; + +/** + * @brief qspi dma tx/rx fifo threshold type + */ +typedef enum +{ + QSPI_DMA_FIFO_THOD_WORD08 = 0x00, /*!< qspi dma fifo threshold 8 words */ + QSPI_DMA_FIFO_THOD_WORD16 = 0x01, /*!< qspi dma fifo threshold 16 words */ + QSPI_DMA_FIFO_THOD_WORD32 = 0x02 /*!< qspi dma fifo threshold 32 words */ +} qspi_dma_fifo_thod_type; + +/** + * @brief qspi cmd type + */ +typedef struct +{ + confirm_state pe_mode_enable; /*!< perfornance enhance mode enable */ + uint8_t pe_mode_operate_code; /*!< performance enhance mode operate code */ + uint8_t instruction_code; /*!< instruction code */ + qspi_cmd_inslen_type instruction_length; /*!< instruction code length */ + uint32_t address_code; /*!< address code */ + qspi_cmd_adrlen_type address_length; /*!< address legnth */ + uint32_t data_counter; /*!< read/write data counter */ + uint8_t second_dummy_cycle_num; /*!< number of second dummy state cycle 0~32 */ + qspi_operate_mode_type operation_mode; /*!< operation mode */ + qspi_read_status_conf_type read_status_config; /*!< config to read status */ + confirm_state read_status_enable; /*!< config to read status */ + confirm_state write_data_enable; /*!< enable to write data */ +} qspi_cmd_type; + +/** + * @brief qspi xip type + */ +typedef struct +{ + uint8_t read_instruction_code; /*!< read instruction code */ + qspi_xip_addrlen_type read_address_length; /*!< read address legnth */ + qspi_operate_mode_type read_operation_mode; /*!< read operation mode */ + uint8_t read_second_dummy_cycle_num; /*!< read number of second dummy state cycle 0~32 */ + uint8_t write_instruction_code; /*!< write instruction code */ + qspi_xip_addrlen_type write_address_length; /*!< write address legnth */ + qspi_operate_mode_type write_operation_mode; /*!< write operation mode */ + uint8_t write_second_dummy_cycle_num; /*!< write number of second dummy state cycle 0~32 */ + qspi_xip_write_sel_type write_select_mode; /*!< write mode d or mode t selection */ + uint8_t write_time_counter; /*!< write count for mode t */ + uint8_t write_data_counter; /*!< write count for mode d */ + qspi_xip_read_sel_type read_select_mode; /*!< read mode d or mode t selection */ + uint8_t read_time_counter; /*!< read count for mode t */ + uint8_t read_data_counter; /*!< read count for mode d */ +} qspi_xip_type; + +/** + * @brief type define qspi register all + */ +typedef struct +{ + /** + * @brief qspi cmd_w0 register, offset:0x00 + */ + union + { + __IO uint32_t cmd_w0; + struct + { + + __IO uint32_t spiadr : 32;/* [31:0] */ + } cmd_w0_bit; + }; + + /** + * @brief qspi cmd_w1 register, offset:0x04 + */ + union + { + __IO uint32_t cmd_w1; + struct + { + __IO uint32_t adrlen : 3; /* [2:0] */ + __IO uint32_t reserved1 : 13;/* [15:3] */ + __IO uint32_t dum2 : 8; /* [23:16] */ + __IO uint32_t inslen : 2; /* [25:24] */ + __IO uint32_t reserved2 : 2; /* [27:26] */ + __IO uint32_t pemen : 1; /* [28] */ + __IO uint32_t reserved3 : 3; /* [31:29] */ + } cmd_w1_bit; + }; + + /** + * @brief qspi cmd_w2 register, offset:0x08 + */ + union + { + __IO uint32_t cmd_w2; + struct + { + __IO uint32_t dcnt : 32;/* [31:0] */ + } cmd_w2_bit; + }; + + /** + * @brief qspi cmd_w3 register, offset:0x0C + */ + union + { + __IO uint32_t cmd_w3; + struct + { + __IO uint32_t reserved1 : 1; /* [0] */ + __IO uint32_t wen : 1; /* [1] */ + __IO uint32_t rstsen : 1; /* [2] */ + __IO uint32_t rstsc : 1; /* [3] */ + __IO uint32_t reserved2 : 1; /* [4] */ + __IO uint32_t opmode : 3; /* [7:5] */ + __IO uint32_t reserved3 : 8; /* [15:8] */ + __IO uint32_t pemopc : 8; /* [23:16] */ + __IO uint32_t insc : 8; /* [31:24] */ + } cmd_w3_bit; + }; + + /** + * @brief qspi ctrl register, offset:0x10 + */ + union + { + __IO uint32_t ctrl; + struct + { + __IO uint32_t clkdiv : 3; /* [2:0] */ + __IO uint32_t reserved1 : 1; /* [3] */ + __IO uint32_t sckmode : 1; /* [4] */ + __IO uint32_t reserved2 : 2; /* [6:5] */ + __IO uint32_t xipidle : 1; /* [7] */ + __IO uint32_t abort : 1; /* [8] */ + __IO uint32_t reserved3 : 7; /* [15:9] */ + __IO uint32_t busy : 3; /* [18:16] */ + __IO uint32_t xiprcmdf : 1; /* [19] */ + __IO uint32_t xipsel : 1; /* [20] */ + __IO uint32_t keyen : 1; /* [21] */ + __IO uint32_t reserved4 : 10;/* [31:22] */ + } ctrl_bit; + }; + + /** + * @brief qspi actr register, offset:0x14 + */ + union + { + __IO uint32_t actr; + struct + { + __IO uint32_t csdly : 4; /* [3:0] */ + __IO uint32_t reserved1 : 28;/* [31:4] */ + } actr_bit; + }; + + /** + * @brief qspi fifosts register, offset:0x18 + */ + union + { + __IO uint32_t fifosts; + struct + { + __IO uint32_t txfifordy : 1; /* [0] */ + __IO uint32_t rxfifordy : 1; /* [1] */ + __IO uint32_t reserved1 : 30;/* [31:2] */ + } fifosts_bit; + }; + + /** + * @brief qspi reserved register, offset:0x1C + */ + __IO uint32_t reserved1; + + /** + * @brief qspi ctrl2 register, offset:0x20 + */ + union + { + __IO uint32_t ctrl2; + struct + { + __IO uint32_t dmaen : 1; /* [0] */ + __IO uint32_t cmdie : 1; /* [1] */ + __IO uint32_t reserved1 : 6; /* [7:2] */ + __IO uint32_t txfifo_thod : 2; /* [9:8] */ + __IO uint32_t reserved2 : 2; /* [11:10] */ + __IO uint32_t rxfifo_thod : 2; /* [13:12] */ + __IO uint32_t reserved3 : 18;/* [31:14] */ + } ctrl2_bit; + }; + + /** + * @brief qspi cmdsts register, offset:0x24 + */ + union + { + __IO uint32_t cmdsts; + struct + { + __IO uint32_t cmdsts : 1; /* [0] */ + __IO uint32_t reserved1 : 31;/* [31:1] */ + } cmdsts_bit; + }; + + /** + * @brief qspi rsts register, offset:0x28 + */ + union + { + __IO uint32_t rsts; + struct + { + __IO uint32_t spists : 8; /* [7:0] */ + __IO uint32_t reserved1 : 24;/* [31:8] */ + } rsts_bit; + }; + + /** + * @brief qspi fsize register, offset:0x2C + */ + union + { + __IO uint32_t fsize; + struct + { + __IO uint32_t spifsize : 32;/* [31:0] */ + } fsize_bit; + }; + + /** + * @brief qspi xip_cmd_w0 register, offset:0x30 + */ + union + { + __IO uint32_t xip_cmd_w0; + struct + { + __IO uint32_t xipr_dum2 : 8; /* [7:0] */ + __IO uint32_t xipr_opmode : 3; /* [10:8] */ + __IO uint32_t xipr_adrlen : 1; /* [11] */ + __IO uint32_t xipr_insc : 8; /* [19:12] */ + __IO uint32_t reserved1 : 12;/* [31:20] */ + } xip_cmd_w0_bit; + }; + + /** + * @brief qspi xip_cmd_w1 register, offset:0x34 + */ + union + { + __IO uint32_t xip_cmd_w1; + struct + { + __IO uint32_t xipr_dum2 : 8; /* [7:0] */ + __IO uint32_t xipr_opmode : 3; /* [10:8] */ + __IO uint32_t xipr_adrlen : 1; /* [11] */ + __IO uint32_t xipr_insc : 8; /* [19:12] */ + __IO uint32_t reserved1 : 12;/* [31:20] */ + } xip_cmd_w1_bit; + }; + + /** + * @brief qspi xip_cmd_w2 register, offset:0x38 + */ + union + { + __IO uint32_t xip_cmd_w2; + struct + { + __IO uint32_t xipr_dcnt : 6; /* [5:0] */ + __IO uint32_t reserved1 : 2; /* [7:6] */ + __IO uint32_t xipr_tcnt : 7; /* [14:8] */ + __IO uint32_t xipr_sel : 1; /* [15] */ + __IO uint32_t xipw_dcnt : 6; /* [21:16] */ + __IO uint32_t reserved2 : 2; /* [23:22] */ + __IO uint32_t xipw_tcnt : 7; /* [30:24] */ + __IO uint32_t xipw_sel : 1; /* [31] */ + } xip_cmd_w2_bit; + }; + + /** + * @brief qspi xip_cmd_w3 register, offset:0x3C + */ + union + { + __IO uint32_t xip_cmd_w3; + struct + { + __IO uint32_t bypassc : 1; /* [0] */ + __IO uint32_t reserved1 : 2; /* [2:1] */ + __IO uint32_t csts : 1; /* [3] */ + __IO uint32_t reserved2 : 28;/* [31:4] */ + } xip_cmd_w3_bit; + }; + + /** + * @brief qspi reserved register, offset:0x40~4C + */ + __IO uint32_t reserved2[4]; + + /** + * @brief qspi rev register, offset:0x50 + */ + union + { + __IO uint32_t rev; + struct + { + __IO uint32_t rev : 32;/* [31:0] */ + } rev_bit; + }; + + /** + * @brief qspi reserved register, offset:0x54~FC + */ + __IO uint32_t reserved3[43]; + + /** + * @brief qspi dt register, offset:0x100 + */ + union + { + __IO uint8_t dt_u8; + __IO uint16_t dt_u16; + __IO uint32_t dt; + struct + { + __IO uint32_t dt : 32;/* [31:0] */ + } dt_bit; + }; + +} qspi_type; + +/** + * @} + */ + +#define QSPI1 ((qspi_type*)QSPI1_REG_BASE) +#define QSPI2 ((qspi_type*)QSPI2_REG_BASE) + +/** @defgroup QSPI_exported_functions + * @{ + */ + +void qspi_encryption_enable(qspi_type* qspi_x, confirm_state new_state); +void qspi_sck_mode_set(qspi_type* qspi_x, qspi_clk_mode_type new_mode); +void qspi_clk_division_set(qspi_type* qspi_x, qspi_clk_div_type new_clkdiv); +void qspi_xip_cache_bypass_set(qspi_type* qspi_x, confirm_state new_state); +void qspi_interrupt_enable(qspi_type* qspi_x, confirm_state new_state); +flag_status qspi_flag_get(qspi_type* qspi_x, uint32_t flag); +void qspi_flag_clear(qspi_type* qspi_x, uint32_t flag); +void qspi_dma_rx_threshold_set(qspi_type* qspi_x, qspi_dma_fifo_thod_type new_threshold); +void qspi_dma_tx_threshold_set(qspi_type* qspi_x, qspi_dma_fifo_thod_type new_threshold); +void qspi_dma_enable(qspi_type* qspi_x, confirm_state new_state); +void qspi_busy_config(qspi_type* qspi_x, qspi_busy_pos_type busy_pos); +void qspi_xip_enable(qspi_type* qspi_x, confirm_state new_state); +void qspi_cmd_operation_kick(qspi_type* qspi_x, qspi_cmd_type* qspi_cmd_struct); +void qspi_xip_init(qspi_type* qspi_x, qspi_xip_type* xip_init_struct); +uint8_t qspi_byte_read(qspi_type* qspi_x); +uint16_t qspi_half_word_read(qspi_type* qspi_x); +uint32_t qspi_word_read(qspi_type* qspi_x); +void qspi_word_write(qspi_type* qspi_x, uint32_t value); +void qspi_half_word_write(qspi_type* qspi_x, uint16_t value); +void qspi_byte_write(qspi_type* qspi_x, uint8_t value); +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_scfg.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_scfg.h new file mode 100644 index 0000000000..3fdf033095 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_scfg.h @@ -0,0 +1,323 @@ +/** + ************************************************************************** + * @file at32f435_437_scfg.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 system config header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_SCFG_H +#define __AT32F435_437_SCFG_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup SCFG + * @{ + */ + +#define SCFG_REG(value) PERIPH_REG(SCFG_BASE, value) +#define SCFG_REG_BIT(value) PERIPH_REG_BIT(value) + +/** @defgroup SCFG_exported_types + * @{ + */ + +/** + * @brief scfg xmc addres mapping swap type + */ +typedef enum +{ + SCFG_XMC_SWAP_NONE = 0x00, /* no swap */ + SCFG_XMC_SWAP_MODE1 = 0x01, /* sdram 0x60000000 and 0x70000000, nor psram sram nand2 0xC00000000 and 0xD0000000 */ + SCFG_XMC_SWAP_MODE2 = 0x02, /* qspi2 0x80000000, nand3 0xB0000000 */ + SCFG_XMC_SWAP_MODE3 = 0x03 /* sdram 0x60000000 and 0x70000000, nor psram sram nand2 0xC00000000 and 0xD0000000, qspi2 0x80000000, nand3 0xB0000000 */ +} scfg_xmc_swap_type; + +/** + * @brief scfg infrared modulation signal source selecting type + */ +typedef enum +{ + SCFG_IR_SOURCE_TMR10 = 0x00, /* infrared signal source select tmr10 */ + SCFG_IR_SOURCE_USART1 = 0x01, /* infrared signal source select usart1 */ + SCFG_IR_SOURCE_USART2 = 0x02 /* infrared signal source select usart2 */ +} scfg_ir_source_type; + +/** + * @brief scfg infrared output polarity selecting type + */ +typedef enum +{ + SCFG_IR_POLARITY_NO_AFFECTE = 0x00, /* infrared output polarity no affecte */ + SCFG_IR_POLARITY_REVERSE = 0x01 /* infrared output polarity reverse */ +} scfg_ir_polarity_type; + +/** + * @brief scfg memory address mapping selecting type + */ +typedef enum +{ + SCFG_MEM_MAP_MAIN_MEMORY = 0x00, /* 0x00000000 address mapping from main memory */ + SCFG_MEM_MAP_BOOT_MEMORY = 0x01, /* 0x00000000 address mapping from boot memory */ + SCFG_MEM_MAP_XMC_BANK1 = 0x02, /* 0x00000000 address mapping from xmc bank1 */ + SCFG_MEM_MAP_INTERNAL_SRAM = 0x03, /* 0x00000000 address mapping from internal sram */ + SCFG_MEM_MAP_XMC_SDRAM_BANK1 = 0x04 /* 0x00000000 address mapping from xmc sdram bank1 */ +} scfg_mem_map_type; + +/** + * @brief scfg pin source type + */ +typedef enum +{ + SCFG_PINS_SOURCE0 = 0x00, + SCFG_PINS_SOURCE1 = 0x01, + SCFG_PINS_SOURCE2 = 0x02, + SCFG_PINS_SOURCE3 = 0x03, + SCFG_PINS_SOURCE4 = 0x04, + SCFG_PINS_SOURCE5 = 0x05, + SCFG_PINS_SOURCE6 = 0x06, + SCFG_PINS_SOURCE7 = 0x07, + SCFG_PINS_SOURCE8 = 0x08, + SCFG_PINS_SOURCE9 = 0x09, + SCFG_PINS_SOURCE10 = 0x0A, + SCFG_PINS_SOURCE11 = 0x0B, + SCFG_PINS_SOURCE12 = 0x0C, + SCFG_PINS_SOURCE13 = 0x0D, + SCFG_PINS_SOURCE14 = 0x0E, + SCFG_PINS_SOURCE15 = 0x0F +} scfg_pins_source_type; + +/** + * @brief gpio port source type + */ +typedef enum +{ + SCFG_PORT_SOURCE_GPIOA = 0x00, + SCFG_PORT_SOURCE_GPIOB = 0x01, + SCFG_PORT_SOURCE_GPIOC = 0x02, + SCFG_PORT_SOURCE_GPIOD = 0x03, + SCFG_PORT_SOURCE_GPIOE = 0x04, + SCFG_PORT_SOURCE_GPIOF = 0x05, + SCFG_PORT_SOURCE_GPIOG = 0x06, + SCFG_PORT_SOURCE_GPIOH = 0x07 +} scfg_port_source_type; + +/** + * @brief scfg emac interface selecting type + */ +typedef enum +{ + SCFG_EMAC_SELECT_MII = 0x00, /* emac interface select mii mode */ + SCFG_EMAC_SELECT_RMII = 0x01 /* emac interface select rmii mode */ +} scfg_emac_interface_type; + +/** + * @brief scfg ultra high sourcing/sinking strength pins type + */ +typedef enum +{ + SCFG_ULTRA_DRIVEN_PB3 = MAKE_VALUE(0x2C, 0), + SCFG_ULTRA_DRIVEN_PB9 = MAKE_VALUE(0x2C, 1), + SCFG_ULTRA_DRIVEN_PB10 = MAKE_VALUE(0x2C, 2), + SCFG_ULTRA_DRIVEN_PD12 = MAKE_VALUE(0x2C, 5), + SCFG_ULTRA_DRIVEN_PD13 = MAKE_VALUE(0x2C, 6), + SCFG_ULTRA_DRIVEN_PD14 = MAKE_VALUE(0x2C, 7), + SCFG_ULTRA_DRIVEN_PD15 = MAKE_VALUE(0x2C, 8), + SCFG_ULTRA_DRIVEN_PF14 = MAKE_VALUE(0x2C, 9), + SCFG_ULTRA_DRIVEN_PF15 = MAKE_VALUE(0x2C, 10) +} scfg_ultra_driven_pins_type; + +/** + * @brief type define system config register all + */ +typedef struct +{ + /** + * @brief scfg cfg1 register, offset:0x00 + */ + union + { + __IO uint32_t cfg1; + struct + { + __IO uint32_t mem_map_sel : 3; /* [2:0] */ + __IO uint32_t reserved1 : 2; /* [4:3] */ + __IO uint32_t ir_pol : 1; /* [5] */ + __IO uint32_t ir_src_sel : 2; /* [7:6] */ + __IO uint32_t reserved2 : 2; /* [9:8] */ + __IO uint32_t swap_xmc : 2; /* [11:10] */ + __IO uint32_t reserved3 : 20;/* [31:12] */ + } cfg1_bit; + }; + + /** + * @brief scfg cfg2 register, offset:0x04 + */ + union + { + __IO uint32_t cfg2; + struct + { + __IO uint32_t reserved1 : 23;/* [22:0] */ + __IO uint32_t mii_rmii_sel : 1; /* [23] */ + __IO uint32_t reserved2 : 8; /* [31:24] */ + } cfg2_bit; + }; + + /** + * @brief scfg exintc1 register, offset:0x08 + */ + union + { + __IO uint32_t exintc1; + struct + { + __IO uint32_t exint0 : 4; /* [3:0] */ + __IO uint32_t exint1 : 4; /* [7:4] */ + __IO uint32_t exint2 : 4; /* [11:8] */ + __IO uint32_t exint3 : 4; /* [15:12] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } exintc1_bit; + }; + + /** + * @brief scfg exintc2 register, offset:0x0C + */ + union + { + __IO uint32_t exintc2; + struct + { + __IO uint32_t exint4 : 4; /* [3:0] */ + __IO uint32_t exint5 : 4; /* [7:4] */ + __IO uint32_t exint6 : 4; /* [11:8] */ + __IO uint32_t exint7 : 4; /* [15:12] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } exintc2_bit; + }; + + /** + * @brief scfg exintc3 register, offset:0x10 + */ + union + { + __IO uint32_t exintc3; + struct + { + __IO uint32_t exint8 : 4; /* [3:0] */ + __IO uint32_t exint9 : 4; /* [7:4] */ + __IO uint32_t exint10 : 4; /* [11:8] */ + __IO uint32_t exint11 : 4; /* [15:12] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } exintc3_bit; + }; + + /** + * @brief scfg exintc4 register, offset:0x14 + */ + union + { + __IO uint32_t exintc4; + struct + { + __IO uint32_t exint12 : 4; /* [3:0] */ + __IO uint32_t exint13 : 4; /* [7:4] */ + __IO uint32_t exint14 : 4; /* [11:8] */ + __IO uint32_t exint15 : 4; /* [15:12] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } exintc4_bit; + }; + + /** + * @brief crm reserved1 register, offset:0x18~0x28 + */ + __IO uint32_t reserved1[5]; + + /** + * @brief scfg uhdrv register, offset:0x2C + */ + union + { + __IO uint32_t uhdrv; + struct + { + __IO uint32_t pb3_uh : 1; /* [0] */ + __IO uint32_t pb9_uh : 1; /* [1] */ + __IO uint32_t pb10_uh : 1; /* [2] */ + __IO uint32_t reserved1 : 2; /* [4:3] */ + __IO uint32_t pd12_uh : 1; /* [5] */ + __IO uint32_t pd13_uh : 1; /* [6] */ + __IO uint32_t pd14_uh : 1; /* [7] */ + __IO uint32_t pd15_uh : 1; /* [8] */ + __IO uint32_t pf14_uh : 1; /* [9] */ + __IO uint32_t pf15_uh : 1; /* [10] */ + __IO uint32_t reserved2 : 21;/* [31:11] */ + } uhdrv_bit; + }; + +} scfg_type; + +/** + * @} + */ + +#define SCFG ((scfg_type *) SCFG_BASE) + +/** @defgroup SCFG_exported_functions + * @{ + */ + +void scfg_reset(void); +void scfg_xmc_mapping_swap_set(scfg_xmc_swap_type xmc_swap); +void scfg_infrared_config(scfg_ir_source_type source, scfg_ir_polarity_type polarity); +void scfg_mem_map_set(scfg_mem_map_type mem_map); +void scfg_emac_interface_set(scfg_emac_interface_type mode); +void scfg_exint_line_config(scfg_port_source_type port_source, scfg_pins_source_type pin_source); +void scfg_pins_ultra_driven_enable(scfg_ultra_driven_pins_type value, confirm_state new_state); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_sdio.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_sdio.h new file mode 100644 index 0000000000..5c4180bf83 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_sdio.h @@ -0,0 +1,624 @@ +/** + ************************************************************************** + * @file at32f435_437_sdio.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 sdio header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_SDIO_H +#define __AT32F435_437_SDIO_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup SDIO + * @{ + */ + +/** @defgroup SDIO_interrupts_definition + * @brief sdio interrupt + * @{ + */ + +#define SDIO_CMDFAIL_INT ((uint32_t)0x00000001) /*!< command response received check failed interrupt */ +#define SDIO_DTFAIL_INT ((uint32_t)0x00000002) /*!< data block sent/received check failed interrupt */ +#define SDIO_CMDTIMEOUT_INT ((uint32_t)0x00000004) /*!< command response timerout interrupt */ +#define SDIO_DTTIMEOUT_INT ((uint32_t)0x00000008) /*!< data timeout interrupt */ +#define SDIO_TXERRU_INT ((uint32_t)0x00000010) /*!< transmit underrun error interrupt */ +#define SDIO_RXERRO_INT ((uint32_t)0x00000020) /*!< received overrun error interrupt */ +#define SDIO_CMDRSPCMPL_INT ((uint32_t)0x00000040) /*!< command response received interrupt */ +#define SDIO_CMDCMPL_INT ((uint32_t)0x00000080) /*!< command sent interrupt */ +#define SDIO_DTCMP_INT ((uint32_t)0x00000100) /*!< data sent interrupt */ +#define SDIO_SBITERR_INT ((uint32_t)0x00000200) /*!< start bit not detected on data bus interrupt */ +#define SDIO_DTBLKCMPL_INT ((uint32_t)0x00000400) /*!< data block sent/received interrupt */ +#define SDIO_DOCMD_INT ((uint32_t)0x00000800) /*!< command transfer in progress interrupt */ +#define SDIO_DOTX_INT ((uint32_t)0x00001000) /*!< data transmit in progress interrupt */ +#define SDIO_DORX_INT ((uint32_t)0x00002000) /*!< data receive in progress interrupt */ +#define SDIO_TXBUFH_INT ((uint32_t)0x00004000) /*!< transmit buf half empty interrupt */ +#define SDIO_RXBUFH_INT ((uint32_t)0x00008000) /*!< receive buf half full interrupt */ +#define SDIO_TXBUFF_INT ((uint32_t)0x00010000) /*!< transmit buf full interrupt */ +#define SDIO_RXBUFF_INT ((uint32_t)0x00020000) /*!< receive buf full interrupt */ +#define SDIO_TXBUFE_INT ((uint32_t)0x00040000) /*!< transmit buf empty interrupt */ +#define SDIO_RXBUFE_INT ((uint32_t)0x00080000) /*!< receive buf empty interrupt */ +#define SDIO_TXBUF_INT ((uint32_t)0x00100000) /*!< data available in transmit interrupt */ +#define SDIO_RXBUF_INT ((uint32_t)0x00200000) /*!< data available in receive interrupt */ +#define SDIO_SDIOIF_INT ((uint32_t)0x00400000) /*!< sdio interface received interrupt */ + +/** + * @} + */ + +/** @defgroup SDIO_flags_definition + * @brief sdio flag + * @{ + */ + +#define SDIO_CMDFAIL_FLAG ((uint32_t)0x00000001) /*!< command response received check failed flag */ +#define SDIO_DTFAIL_FLAG ((uint32_t)0x00000002) /*!< data block sent/received check failed flag */ +#define SDIO_CMDTIMEOUT_FLAG ((uint32_t)0x00000004) /*!< command response timerout flag */ +#define SDIO_DTTIMEOUT_FLAG ((uint32_t)0x00000008) /*!< data timeout flag */ +#define SDIO_TXERRU_FLAG ((uint32_t)0x00000010) /*!< transmit underrun error flag */ +#define SDIO_RXERRO_FLAG ((uint32_t)0x00000020) /*!< received overrun error flag */ +#define SDIO_CMDRSPCMPL_FLAG ((uint32_t)0x00000040) /*!< command response received flag */ +#define SDIO_CMDCMPL_FLAG ((uint32_t)0x00000080) /*!< command sent flag */ +#define SDIO_DTCMPL_FLAG ((uint32_t)0x00000100) /*!< data sent flag */ +#define SDIO_SBITERR_FLAG ((uint32_t)0x00000200) /*!< start bit not detected on data bus flag */ +#define SDIO_DTBLKCMPL_FLAG ((uint32_t)0x00000400) /*!< data block sent/received flag */ +#define SDIO_DOCMD_FLAG ((uint32_t)0x00000800) /*!< command transfer in progress flag */ +#define SDIO_DOTX_FLAG ((uint32_t)0x00001000) /*!< data transmit in progress flag */ +#define SDIO_DORX_FLAG ((uint32_t)0x00002000) /*!< data receive in progress flag */ +#define SDIO_TXBUFH_FLAG ((uint32_t)0x00004000) /*!< transmit buf half empty flag */ +#define SDIO_RXBUFH_FLAG ((uint32_t)0x00008000) /*!< receive buf half full flag */ +#define SDIO_TXBUFF_FLAG ((uint32_t)0x00010000) /*!< transmit buf full flag */ +#define SDIO_RXBUFF_FLAG ((uint32_t)0x00020000) /*!< receive buf full flag */ +#define SDIO_TXBUFE_FLAG ((uint32_t)0x00040000) /*!< transmit buf empty flag */ +#define SDIO_RXBUFE_FLAG ((uint32_t)0x00080000) /*!< receive buf empty flag */ +#define SDIO_TXBUF_FLAG ((uint32_t)0x00100000) /*!< data available in transmit flag */ +#define SDIO_RXBUF_FLAG ((uint32_t)0x00200000) /*!< data available in receive flag */ +#define SDIO_SDIOIF_FLAG ((uint32_t)0x00400000) /*!< sdio interface received flag */ + +/** + * @} + */ + +/** @defgroup SDIO_exported_types + * @{ + */ + +/** + * @brief sdio power state + */ +typedef enum +{ + SDIO_POWER_OFF = 0x00, /*!< power-off, clock to card is stopped */ + SDIO_POWER_ON = 0x03 /*!< power-on, the card is clocked */ +} sdio_power_state_type; + +/** + * @brief sdio edge phase + */ +typedef enum +{ + SDIO_CLOCK_EDGE_RISING = 0x00, /*!< sdio bus clock generated on the rising edge of the master clock */ + SDIO_CLOCK_EDGE_FALLING = 0x01 /*!< sdio bus clock generated on the falling edge of the master clock */ +} sdio_edge_phase_type; + +/** + * @brief sdio bus width + */ +typedef enum +{ + SDIO_BUS_WIDTH_D1 = 0x00, /*!< sdio wide bus select 1-bit */ + SDIO_BUS_WIDTH_D4 = 0x01, /*!< sdio wide bus select 4-bit */ + SDIO_BUS_WIDTH_D8 = 0x02 /*!< sdio wide bus select 8-bit */ +} sdio_bus_width_type; + +/** + * @brief sdio response type + */ +typedef enum +{ + SDIO_RESPONSE_NO = 0x00, /*!< no response */ + SDIO_RESPONSE_SHORT = 0x01, /*!< short response */ + SDIO_RESPONSE_LONG = 0x03 /*!< long response */ +} sdio_reponse_type; + +/** + * @brief sdio wait type + */ +typedef enum +{ + SDIO_WAIT_FOR_NO = 0x00, /*!< no wait */ + SDIO_WAIT_FOR_INT = 0x01, /*!< wait interrupt request */ + SDIO_WAIT_FOR_PEND = 0x02 /*!< wait end of transfer */ +} sdio_wait_type; + +/** + * @brief sdio response register index + */ +typedef enum +{ + SDIO_RSP1_INDEX = 0x00, /*!< response index 1, corresponding to sdio_rsp register 1 */ + SDIO_RSP2_INDEX = 0x01, /*!< response index 2, corresponding to sdio_rsp register 2 */ + SDIO_RSP3_INDEX = 0x02, /*!< response index 3, corresponding to sdio_rsp register 3 */ + SDIO_RSP4_INDEX = 0x03 /*!< response index 4, corresponding to sdio_rsp register 4 */ +} sdio_rsp_index_type; + +/** + * @brief sdio data block size + */ +typedef enum +{ + SDIO_DATA_BLOCK_SIZE_1B = 0x00, /*!< data block size 1 byte */ + SDIO_DATA_BLOCK_SIZE_2B = 0x01, /*!< data block size 2 bytes */ + SDIO_DATA_BLOCK_SIZE_4B = 0x02, /*!< data block size 4 bytes */ + SDIO_DATA_BLOCK_SIZE_8B = 0x03, /*!< data block size 8 bytes */ + SDIO_DATA_BLOCK_SIZE_16B = 0x04, /*!< data block size 16 bytes */ + SDIO_DATA_BLOCK_SIZE_32B = 0x05, /*!< data block size 32 bytes */ + SDIO_DATA_BLOCK_SIZE_64B = 0x06, /*!< data block size 64 bytes */ + SDIO_DATA_BLOCK_SIZE_128B = 0x07, /*!< data block size 128 bytes */ + SDIO_DATA_BLOCK_SIZE_256B = 0x08, /*!< data block size 256 bytes */ + SDIO_DATA_BLOCK_SIZE_512B = 0x09, /*!< data block size 512 bytes */ + SDIO_DATA_BLOCK_SIZE_1024B = 0x0A, /*!< data block size 1024 bytes */ + SDIO_DATA_BLOCK_SIZE_2048B = 0x0B, /*!< data block size 2048 bytes */ + SDIO_DATA_BLOCK_SIZE_4096B = 0x0C, /*!< data block size 4096 bytes */ + SDIO_DATA_BLOCK_SIZE_8192B = 0x0D, /*!< data block size 8192 bytes */ + SDIO_DATA_BLOCK_SIZE_16384B = 0x0E /*!< data block size 16384 bytes */ +} sdio_block_size_type; + +/** + * @brief sdio data transfer mode + */ +typedef enum +{ + SDIO_DATA_BLOCK_TRANSFER = 0x00, /*!< the sdio block transfer mode */ + SDIO_DATA_STREAM_TRANSFER = 0x01 /*!< the sdio stream transfer mode */ +} sdio_transfer_mode_type; + +/** + * @brief sdio data transfer direction + */ +typedef enum +{ + SDIO_DATA_TRANSFER_TO_CARD = 0x00, /*!< the sdio controller write */ + SDIO_DATA_TRANSFER_TO_CONTROLLER = 0x01 /*!< the sdio controller read */ +} sdio_transfer_direction_type; + +/** + * @brief sdio read wait mode + */ +typedef enum +{ + SDIO_READ_WAIT_CONTROLLED_BY_D2 = 0x00, /*!< the sdio read wait on data2 line */ + SDIO_READ_WAIT_CONTROLLED_BY_CK = 0x01 /*!< the sdio read wait on clock line */ +} sdio_read_wait_mode_type; + +/** + * @brief sdio command structure + */ +typedef struct +{ + uint32_t argument; /*!< the sdio command argument is sent to a card as part of command message */ + uint8_t cmd_index; /*!< the sdio command index */ + sdio_reponse_type rsp_type; /*!< the sdio response type */ + sdio_wait_type wait_type; /*!< the sdio wait for interrupt request is enabled or disable */ +} sdio_command_struct_type; + +/** + * @brief sdio data structure + */ +typedef struct +{ + uint32_t timeout; /*!< the sdio data timeout period in car bus clock periods */ + uint32_t data_length; /*!< the sdio data length */ + sdio_block_size_type block_size; /*!< the sdio data block size of block transfer mode */ + sdio_transfer_mode_type transfer_mode; /*!< the sdio transfer mode, block or stream */ + sdio_transfer_direction_type transfer_direction; /*!< the sdio data transfer direction */ +} sdio_data_struct_type; + +/** + * @brief type define sdio register all + */ +typedef struct +{ + /** + * @brief sdio pwrctrl register, offset:0x00 + */ + union + { + __IO uint32_t pwrctrl; + struct + { + __IO uint32_t ps : 2; /* [1:0] */ + __IO uint32_t reserved1 : 30;/* [31:2] */ + } pwrctrl_bit; + }; + + /** + * @brief sdio clkctrl register, offset:0x04 + */ + union + { + __IO uint32_t clkctrl; + struct + { + __IO uint32_t clkdiv_l : 8; /* [7:0] */ + __IO uint32_t clkoen : 1; /* [8] */ + __IO uint32_t pwrsven : 1; /* [9] */ + __IO uint32_t bypsen : 1; /* [10] */ + __IO uint32_t busws : 2; /* [12:11] */ + __IO uint32_t clkegs : 1; /* [13] */ + __IO uint32_t hfcen : 1; /* [14] */ + __IO uint32_t clkdiv_h : 2; /* [16:15] */ + __IO uint32_t reserved1 : 15;/* [31:17] */ + } clkctrl_bit; + }; + + /** + * @brief sdio argu register, offset:0x08 + */ + union + { + __IO uint32_t argu; + struct + { + __IO uint32_t argu : 32;/* [31:0] */ + } argu_bit; + }; + + /** + * @brief sdio cmdctrl register, offset:0x0C + */ + union + { + __IO uint32_t cmdctrl; + struct + { + __IO uint32_t cmdidx : 6; /* [5:0] */ + __IO uint32_t rspwt : 2; /* [7:6] */ + __IO uint32_t intwt : 1; /* [8] */ + __IO uint32_t pndwt : 1; /* [9] */ + __IO uint32_t ccsmen : 1; /* [10] */ + __IO uint32_t iosusp : 1; /* [11] */ + __IO uint32_t reserved1 : 20;/* [31:12] */ + } cmdctrl_bit; + }; + + /** + * @brief sdio rspcmd register, offset:0x10 + */ + union + { + __IO uint32_t rspcmd; + struct + { + __IO uint32_t rspcmd : 6; /* [5:0] */ + __IO uint32_t reserved1 : 26;/* [31:6] */ + } rspcmd_bit; + }; + + /** + * @brief sdio rsp1 register, offset:0x14 + */ + union + { + __IO uint32_t rsp1; + struct + { + __IO uint32_t cardsts1 : 32;/* [31:0] */ + } rsp1_bit; + }; + + /** + * @brief sdio rsp2 register, offset:0x18 + */ + union + { + __IO uint32_t rsp2; + struct + { + __IO uint32_t cardsts2 : 32;/* [31:0] */ + } rsp2_bit; + }; + + /** + * @brief sdio rsp3 register, offset:0x1C + */ + union + { + __IO uint32_t rsp3; + struct + { + __IO uint32_t cardsts3 : 32;/* [31:0] */ + } rsp3_bit; + }; + + /** + * @brief sdio rsp4 register, offset:0x20 + */ + union + { + __IO uint32_t rsp4; + struct + { + __IO uint32_t cardsts4 : 32;/* [31:0] */ + } rsp4_bit; + }; + + /** + * @brief sdio dttmr register, offset:0x24 + */ + union + { + __IO uint32_t dttmr; + struct + { + __IO uint32_t timeout : 32;/* [31:0] */ + } dttmr_bit; + }; + + /** + * @brief sdio dtlen register, offset:0x28 + */ + union + { + __IO uint32_t dtlen; + struct + { + __IO uint32_t dtlen : 25;/* [24:0] */ + __IO uint32_t reserved1 : 7; /* [31:25] */ + } dtlen_bit; + }; + + /** + * @brief sdio dtctrl register, offset:0x2C + */ + union + { + __IO uint32_t dtctrl; + struct + { + __IO uint32_t tfren : 1; /* [0] */ + __IO uint32_t tfrdir : 1; /* [1] */ + __IO uint32_t tfrmode : 1; /* [2] */ + __IO uint32_t dmaen : 1; /* [3] */ + __IO uint32_t blksize : 4; /* [7:4] */ + __IO uint32_t rdwtstart : 1; /* [8] */ + __IO uint32_t rdwtstop : 1; /* [9] */ + __IO uint32_t rdwtmode : 1; /* [10] */ + __IO uint32_t ioen : 1; /* [11] */ + __IO uint32_t reserved1 : 20;/* [31:12] */ + } dtctrl_bit; + }; + + /** + * @brief sdio dtcnt register, offset:0x30 + */ + union + { + __IO uint32_t dtcnt; + struct + { + __IO uint32_t cnt : 25;/* [24:0] */ + __IO uint32_t reserved1 : 7; /* [31:25] */ + } dtcnt_bit; + }; + + /** + * @brief sdio sts register, offset:0x34 + */ + union + { + __IO uint32_t sts; + struct + { + __IO uint32_t cmdfail : 1; /* [0] */ + __IO uint32_t dtfail : 1; /* [1] */ + __IO uint32_t cmdtimeout : 1; /* [2] */ + __IO uint32_t dttimeout : 1; /* [3] */ + __IO uint32_t txerru : 1; /* [4] */ + __IO uint32_t rxerro : 1; /* [5] */ + __IO uint32_t cmdrspcmpl : 1; /* [6] */ + __IO uint32_t cmdcmpl : 1; /* [7] */ + __IO uint32_t dtcmpl : 1; /* [8] */ + __IO uint32_t sbiterr : 1; /* [9] */ + __IO uint32_t dtblkcmpl : 1; /* [10] */ + __IO uint32_t docmd : 1; /* [11] */ + __IO uint32_t dotx : 1; /* [12] */ + __IO uint32_t dorx : 1; /* [13] */ + __IO uint32_t txbufh : 1; /* [14] */ + __IO uint32_t rxbufh : 1; /* [15] */ + __IO uint32_t txbuff : 1; /* [16] */ + __IO uint32_t rxbuff : 1; /* [17] */ + __IO uint32_t txbufe : 1; /* [18] */ + __IO uint32_t rxbufe : 1; /* [19] */ + __IO uint32_t txbuf : 1; /* [20] */ + __IO uint32_t rxbuf : 1; /* [21] */ + __IO uint32_t ioif : 1; /* [22] */ + __IO uint32_t reserved1 : 9; /* [31:23] */ + } sts_bit; + }; + + /** + * @brief sdio intclr register, offset:0x38 + */ + union + { + __IO uint32_t intclr; + struct + { + __IO uint32_t cmdfail : 1; /* [0] */ + __IO uint32_t dtfail : 1; /* [1] */ + __IO uint32_t cmdtimeout : 1; /* [2] */ + __IO uint32_t dttimeout : 1; /* [3] */ + __IO uint32_t txerru : 1; /* [4] */ + __IO uint32_t rxerro : 1; /* [5] */ + __IO uint32_t cmdrspcmpl : 1; /* [6] */ + __IO uint32_t cmdcmpl : 1; /* [7] */ + __IO uint32_t dtcmpl : 1; /* [8] */ + __IO uint32_t sbiterr : 1; /* [9] */ + __IO uint32_t dtblkcmpl : 1; /* [10] */ + __IO uint32_t reserved1 : 11;/* [21:11] */ + __IO uint32_t ioif : 1; /* [22] */ + __IO uint32_t reserved2 : 9; /* [31:23] */ + } intclr_bit; + }; + + /** + * @brief sdio inten register, offset:0x3C + */ + union + { + __IO uint32_t inten; + struct + { + __IO uint32_t cmdfailien : 1; /* [0] */ + __IO uint32_t dtfailien : 1; /* [1] */ + __IO uint32_t cmdtimeoutien : 1; /* [2] */ + __IO uint32_t dttimeoutien : 1; /* [3] */ + __IO uint32_t txerruien : 1; /* [4] */ + __IO uint32_t rxerroien : 1; /* [5] */ + __IO uint32_t cmdrspcmplien : 1; /* [6] */ + __IO uint32_t cmdcmplien : 1; /* [7] */ + __IO uint32_t dtcmplien : 1; /* [8] */ + __IO uint32_t sbiterrien : 1; /* [9] */ + __IO uint32_t dtblkcmplien : 1; /* [10] */ + __IO uint32_t docmdien : 1; /* [11] */ + __IO uint32_t dotxien : 1; /* [12] */ + __IO uint32_t dorxien : 1; /* [13] */ + __IO uint32_t txbufhien : 1; /* [14] */ + __IO uint32_t rxbufhien : 1; /* [15] */ + __IO uint32_t txbuffien : 1; /* [16] */ + __IO uint32_t rxbuffien : 1; /* [17] */ + __IO uint32_t txbufeien : 1; /* [18] */ + __IO uint32_t rxbufeien : 1; /* [19] */ + __IO uint32_t txbufien : 1; /* [20] */ + __IO uint32_t rxbufien : 1; /* [21] */ + __IO uint32_t ioifien : 1; /* [22] */ + __IO uint32_t reserved1 : 9; /* [31:23] */ + } inten_bit; + }; + + /** + * @brief sdio reserved1 register, offset:0x40~0x44 + */ + __IO uint32_t reserved1[2]; + + /** + * @brief sdio bufcnt register, offset:0x48 + */ + union + { + __IO uint32_t bufcnt; + struct + { + __IO uint32_t cnt : 24;/* [23:0] */ + __IO uint32_t reserved1 : 8; /* [31:24] */ + } bufcnt_bit; + }; + + /** + * @brief sdio reserved2 register, offset:0x4C~0x7C + */ + __IO uint32_t reserved2[13]; + + /** + * @brief sdio buf register, offset:0x80 + */ + union + { + __IO uint32_t buf; + struct + { + __IO uint32_t dt : 32;/* [31:0] */ + } buf_bit; + }; + +} sdio_type; + +/** + * @} + */ + +#define SDIO1 ((sdio_type *) SDIO1_BASE) +#define SDIO2 ((sdio_type *) SDIO2_BASE) + +/** @defgroup SDIO_exported_functions + * @{ + */ + +void sdio_reset(sdio_type *sdio_x); +void sdio_power_set(sdio_type *sdio_x, sdio_power_state_type power_state); +sdio_power_state_type sdio_power_status_get(sdio_type *sdio_x); +void sdio_clock_config(sdio_type *sdio_x, uint16_t clk_div, sdio_edge_phase_type clk_edg); +void sdio_bus_width_config(sdio_type *sdio_x, sdio_bus_width_type width); +void sdio_clock_bypass(sdio_type *sdio_x, confirm_state new_state); +void sdio_power_saving_mode_enable(sdio_type *sdio_x, confirm_state new_state); +void sdio_flow_control_enable(sdio_type *sdio_x, confirm_state new_state); +void sdio_clock_enable(sdio_type *sdio_x, confirm_state new_state); +void sdio_dma_enable(sdio_type *sdio_x, confirm_state new_state); +void sdio_interrupt_enable(sdio_type *sdio_x, uint32_t int_opt, confirm_state new_state); +flag_status sdio_flag_get(sdio_type *sdio_x, uint32_t flag); +void sdio_flag_clear(sdio_type *sdio_x, uint32_t flag); +void sdio_command_config(sdio_type *sdio_x, sdio_command_struct_type *command_struct); +void sdio_command_state_machine_enable(sdio_type *sdio_x, confirm_state new_state); +uint8_t sdio_command_response_get(sdio_type *sdio_x); +uint32_t sdio_response_get(sdio_type *sdio_x, sdio_rsp_index_type reg_index); +void sdio_data_config(sdio_type *sdio_x, sdio_data_struct_type *data_struct); +void sdio_data_state_machine_enable(sdio_type *sdio_x, confirm_state new_state); +uint32_t sdio_data_counter_get(sdio_type *sdio_x); +uint32_t sdio_data_read(sdio_type *sdio_x); +uint32_t sdio_buffer_counter_get(sdio_type *sdio_x); +void sdio_data_write(sdio_type *sdio_x, uint32_t data); +void sdio_read_wait_mode_set(sdio_type *sdio_x, sdio_read_wait_mode_type mode); +void sdio_read_wait_start(sdio_type *sdio_x, confirm_state new_state); +void sdio_read_wait_stop(sdio_type *sdio_x, confirm_state new_state); +void sdio_io_function_enable(sdio_type *sdio_x, confirm_state new_state); +void sdio_io_suspend_command_set(sdio_type *sdio_x, confirm_state new_state); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_spi.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_spi.h new file mode 100644 index 0000000000..bba723a86f --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_spi.h @@ -0,0 +1,505 @@ +/** + ************************************************************************** + * @file at32f435_437_spi.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 spi header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_SPI_H +#define __AT32F435_437_SPI_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup SPI + * @{ + */ + +/** + * @defgroup SPI_I2S_flags_definition + * @brief spi i2s flag + * @{ + */ + +#define SPI_I2S_RDBF_FLAG 0x0001 /*!< spi or i2s receive data buffer full flag */ +#define SPI_I2S_TDBE_FLAG 0x0002 /*!< spi or i2s transmit data buffer empty flag */ +#define I2S_ACS_FLAG 0x0004 /*!< i2s audio channel state flag */ +#define I2S_TUERR_FLAG 0x0008 /*!< i2s transmitter underload error flag */ +#define SPI_CCERR_FLAG 0x0010 /*!< spi crc calculation error flag */ +#define SPI_MMERR_FLAG 0x0020 /*!< spi master mode error flag */ +#define SPI_I2S_ROERR_FLAG 0x0040 /*!< spi or i2s receiver overflow error flag */ +#define SPI_I2S_BF_FLAG 0x0080 /*!< spi or i2s busy flag */ +#define SPI_CSPAS_FLAG 0x0100 /*!< spi cs pulse abnormal setting fiag */ + +/** + * @} + */ + +/** + * @defgroup SPI_I2S_interrupts_definition + * @brief spi i2s interrupt + * @{ + */ + +#define SPI_I2S_ERROR_INT 0x0020 /*!< error interrupt */ +#define SPI_I2S_RDBF_INT 0x0040 /*!< receive data buffer full interrupt */ +#define SPI_I2S_TDBE_INT 0x0080 /*!< transmit data buffer empty interrupt */ + +/** + * @} + */ + +/** @defgroup SPI_exported_types + * @{ + */ + +/** + * @brief spi frame bit num type + */ +typedef enum +{ + SPI_FRAME_8BIT = 0x00, /*!< 8-bit data frame format */ + SPI_FRAME_16BIT = 0x01 /*!< 16-bit data frame format */ +} spi_frame_bit_num_type; + +/** + * @brief spi master/slave mode type + */ +typedef enum +{ + SPI_MODE_SLAVE = 0x00, /*!< select as slave mode */ + SPI_MODE_MASTER = 0x01 /*!< select as master mode */ +} spi_master_slave_mode_type; + +/** + * @brief spi clock polarity (clkpol) type + */ +typedef enum +{ + SPI_CLOCK_POLARITY_LOW = 0x00, /*!< sck keeps low at idle state */ + SPI_CLOCK_POLARITY_HIGH = 0x01 /*!< sck keeps high at idle state */ +} spi_clock_polarity_type; + +/** + * @brief spi clock phase (clkpha) type + */ +typedef enum +{ + SPI_CLOCK_PHASE_1EDGE = 0x00, /*!< data capture start from the first clock edge */ + SPI_CLOCK_PHASE_2EDGE = 0x01 /*!< data capture start from the second clock edge */ +} spi_clock_phase_type; + +/** + * @brief spi cs mode type + */ +typedef enum +{ + SPI_CS_HARDWARE_MODE = 0x00, /*!< cs is hardware mode */ + SPI_CS_SOFTWARE_MODE = 0x01 /*!< cs is software mode */ +} spi_cs_mode_type; + +/** + * @brief spi master clock frequency division type + */ +typedef enum +{ + SPI_MCLK_DIV_2 = 0x00, /*!< master clock frequency division 2 */ + SPI_MCLK_DIV_3 = 0x0A, /*!< master clock frequency division 3 */ + SPI_MCLK_DIV_4 = 0x01, /*!< master clock frequency division 4 */ + SPI_MCLK_DIV_8 = 0x02, /*!< master clock frequency division 8 */ + SPI_MCLK_DIV_16 = 0x03, /*!< master clock frequency division 16 */ + SPI_MCLK_DIV_32 = 0x04, /*!< master clock frequency division 32 */ + SPI_MCLK_DIV_64 = 0x05, /*!< master clock frequency division 64 */ + SPI_MCLK_DIV_128 = 0x06, /*!< master clock frequency division 128 */ + SPI_MCLK_DIV_256 = 0x07, /*!< master clock frequency division 256 */ + SPI_MCLK_DIV_512 = 0x08, /*!< master clock frequency division 512 */ + SPI_MCLK_DIV_1024 = 0x09 /*!< master clock frequency division 1024 */ +} spi_mclk_freq_div_type; + +/** + * @brief spi transmit first bit (lsb/msb) type + */ +typedef enum +{ + SPI_FIRST_BIT_MSB = 0x00, /*!< the frame format is msb first */ + SPI_FIRST_BIT_LSB = 0x01 /*!< the frame format is lsb first */ +} spi_first_bit_type; + +/** + * @brief spi transmission mode type + */ +typedef enum +{ + SPI_TRANSMIT_FULL_DUPLEX = 0x00, /*!< dual line unidirectional full-duplex mode(slben = 0 and ora = 0) */ + SPI_TRANSMIT_SIMPLEX_RX = 0x01, /*!< dual line unidirectional simplex receive-only mode(slben = 0 and ora = 1) */ + SPI_TRANSMIT_HALF_DUPLEX_RX = 0x02, /*!< single line bidirectional half duplex mode-receiving(slben = 1 and slbtd = 0) */ + SPI_TRANSMIT_HALF_DUPLEX_TX = 0x03 /*!< single line bidirectional half duplex mode-transmitting(slben = 1 and slbtd = 1) */ +} spi_transmission_mode_type; + +/** + * @brief spi crc direction type + */ +typedef enum +{ + SPI_CRC_RX = 0x0014, /*!< crc direction is rx */ + SPI_CRC_TX = 0x0018 /*!< crc direction is tx */ +} spi_crc_direction_type; + +/** + * @brief spi single line bidirectional direction type + */ +typedef enum +{ + SPI_HALF_DUPLEX_DIRECTION_RX = 0x00, /*!< single line bidirectional half duplex mode direction: receive(slbtd = 0) */ + SPI_HALF_DUPLEX_DIRECTION_TX = 0x01 /*!< single line bidirectional half duplex mode direction: transmit(slbtd = 1) */ +} spi_half_duplex_direction_type; + +/** + * @brief spi software cs internal level type + */ +typedef enum +{ + SPI_SWCS_INTERNAL_LEVEL_LOW = 0x00, /*!< internal level low */ + SPI_SWCS_INTERNAL_LEVEL_HIGHT = 0x01 /*!< internal level high */ +} spi_software_cs_level_type; + +/** + * @brief i2s audio protocol type + */ +typedef enum +{ + I2S_AUDIO_PROTOCOL_PHILLIPS = 0x00, /*!< i2s philip standard */ + I2S_AUDIO_PROTOCOL_MSB = 0x01, /*!< msb-justified standard */ + I2S_AUDIO_PROTOCOL_LSB = 0x02, /*!< lsb-justified standard */ + I2S_AUDIO_PROTOCOL_PCM_SHORT = 0x03, /*!< pcm standard-short frame */ + I2S_AUDIO_PROTOCOL_PCM_LONG = 0x04 /*!< pcm standard-long frame */ +} i2s_audio_protocol_type; + +/** + * @brief i2s audio frequency type + */ +typedef enum +{ + I2S_AUDIO_FREQUENCY_DEFAULT = 2, /*!< i2s audio sampling frequency default */ + I2S_AUDIO_FREQUENCY_8K = 8000, /*!< i2s audio sampling frequency 8k */ + I2S_AUDIO_FREQUENCY_11_025K = 11025, /*!< i2s audio sampling frequency 11.025k */ + I2S_AUDIO_FREQUENCY_16K = 16000, /*!< i2s audio sampling frequency 16k */ + I2S_AUDIO_FREQUENCY_22_05K = 22050, /*!< i2s audio sampling frequency 22.05k */ + I2S_AUDIO_FREQUENCY_32K = 32000, /*!< i2s audio sampling frequency 32k */ + I2S_AUDIO_FREQUENCY_44_1K = 44100, /*!< i2s audio sampling frequency 44.1k */ + I2S_AUDIO_FREQUENCY_48K = 48000, /*!< i2s audio sampling frequency 48k */ + I2S_AUDIO_FREQUENCY_96K = 96000, /*!< i2s audio sampling frequency 96k */ + I2S_AUDIO_FREQUENCY_192K = 192000 /*!< i2s audio sampling frequency 192k */ +} i2s_audio_sampling_freq_type; + +/** + * @brief i2s data bit num and channel bit num type + */ +typedef enum +{ + I2S_DATA_16BIT_CHANNEL_16BIT = 0x01, /*!< 16-bit data packed in 16-bit channel frame */ + I2S_DATA_16BIT_CHANNEL_32BIT = 0x02, /*!< 16-bit data packed in 32-bit channel frame */ + I2S_DATA_24BIT_CHANNEL_32BIT = 0x03, /*!< 24-bit data packed in 32-bit channel frame */ + I2S_DATA_32BIT_CHANNEL_32BIT = 0x04 /*!< 32-bit data packed in 32-bit channel frame */ +} i2s_data_channel_format_type; + +/** + * @brief i2s operation mode type + */ +typedef enum +{ + I2S_MODE_SLAVE_TX = 0x00, /*!< slave transmission mode */ + I2S_MODE_SLAVE_RX = 0x01, /*!< slave reception mode */ + I2S_MODE_MASTER_TX = 0x02, /*!< master transmission mode */ + I2S_MODE_MASTER_RX = 0x03 /*!< master reception mode */ +} i2s_operation_mode_type; + +/** + * @brief i2s clock polarity type + */ +typedef enum +{ + I2S_CLOCK_POLARITY_LOW = 0x00, /*!< i2s clock steady state is low level */ + I2S_CLOCK_POLARITY_HIGH = 0x01 /*!< i2s clock steady state is high level */ +} i2s_clock_polarity_type; + +/** + * @brief spi init type + */ +typedef struct +{ + spi_transmission_mode_type transmission_mode; /*!< transmission mode selection */ + spi_master_slave_mode_type master_slave_mode; /*!< master or slave mode selection */ + spi_mclk_freq_div_type mclk_freq_division; /*!< master clock frequency division selection */ + spi_first_bit_type first_bit_transmission;/*!< transmit lsb or msb selection */ + spi_frame_bit_num_type frame_bit_num; /*!< frame bit num 8 or 16 bit selection */ + spi_clock_polarity_type clock_polarity; /*!< clock polarity selection */ + spi_clock_phase_type clock_phase; /*!< clock phase selection */ + spi_cs_mode_type cs_mode_selection; /*!< hardware or software cs mode selection */ +} spi_init_type; + +/** + * @brief i2s init type + */ +typedef struct +{ + i2s_operation_mode_type operation_mode; /*!< operation mode selection */ + i2s_audio_protocol_type audio_protocol; /*!< audio protocol selection */ + i2s_audio_sampling_freq_type audio_sampling_freq; /*!< audio frequency selection */ + i2s_data_channel_format_type data_channel_format; /*!< data bit num and channel bit num selection */ + i2s_clock_polarity_type clock_polarity; /*!< clock polarity selection */ + confirm_state mclk_output_enable; /*!< mclk_output selection */ +} i2s_init_type; + +/** + * @brief type define spi register all + */ +typedef struct +{ + + /** + * @brief spi ctrl1 register, offset:0x00 + */ + union + { + __IO uint32_t ctrl1; + struct + { + __IO uint32_t clkpha : 1; /* [0] */ + __IO uint32_t clkpol : 1; /* [1] */ + __IO uint32_t msten : 1; /* [2] */ + __IO uint32_t mdiv_l : 3; /* [5:3] */ + __IO uint32_t spien : 1; /* [6] */ + __IO uint32_t ltf : 1; /* [7] */ + __IO uint32_t swcsil : 1; /* [8] */ + __IO uint32_t swcsen : 1; /* [9] */ + __IO uint32_t ora : 1; /* [10] */ + __IO uint32_t fbn : 1; /* [11] */ + __IO uint32_t ntc : 1; /* [12] */ + __IO uint32_t ccen : 1; /* [13] */ + __IO uint32_t slbtd : 1; /* [14] */ + __IO uint32_t slben : 1; /* [15] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } ctrl1_bit; + }; + + /** + * @brief spi ctrl2 register, offset:0x04 + */ + union + { + __IO uint32_t ctrl2; + struct + { + __IO uint32_t dmaren : 1; /* [0] */ + __IO uint32_t dmaten : 1; /* [1] */ + __IO uint32_t hwcsoe : 1; /* [2] */ + __IO uint32_t reserved1 : 1; /* [3] */ + __IO uint32_t tien : 1; /* [4] */ + __IO uint32_t errie : 1; /* [5] */ + __IO uint32_t rdbfie : 1; /* [6] */ + __IO uint32_t tdbeie : 1; /* [7] */ + __IO uint32_t mdiv_h : 1; /* [8] */ + __IO uint32_t mdiv3en : 1; /* [9] */ + __IO uint32_t reserved2 : 22;/* [31:10] */ + } ctrl2_bit; + }; + + /** + * @brief spi sts register, offset:0x08 + */ + union + { + __IO uint32_t sts; + struct + { + __IO uint32_t rdbf : 1; /* [0] */ + __IO uint32_t tdbe : 1; /* [1] */ + __IO uint32_t acs : 1; /* [2] */ + __IO uint32_t tuerr : 1; /* [3] */ + __IO uint32_t ccerr : 1; /* [4] */ + __IO uint32_t mmerr : 1; /* [5] */ + __IO uint32_t roerr : 1; /* [6] */ + __IO uint32_t bf : 1; /* [7] */ + __IO uint32_t cspas : 1; /* [8] */ + __IO uint32_t reserved1 : 23;/* [31:9] */ + } sts_bit; + }; + + /** + * @brief spi dt register, offset:0x0C + */ + union + { + __IO uint32_t dt; + struct + { + __IO uint32_t dt : 16;/* [15:0] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } dt_bit; + }; + + /** + * @brief spi cpoly register, offset:0x10 + */ + union + { + __IO uint32_t cpoly; + struct + { + __IO uint32_t cpoly : 16;/* [15:0] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } cpoly_bit; + }; + + /** + * @brief spi rcrc register, offset:0x14 + */ + union + { + __IO uint32_t rcrc; + struct + { + __IO uint32_t rcrc : 16;/* [15:0] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } rcrc_bit; + }; + + /** + * @brief spi tcrc register, offset:0x18 + */ + union + { + __IO uint32_t tcrc; + struct + { + __IO uint32_t tcrc : 16;/* [15:0] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } tcrc_bit; + }; + + /** + * @brief spi i2sctrl register, offset:0x1C + */ + union + { + __IO uint32_t i2sctrl; + struct + { + __IO uint32_t i2scbn : 1; /* [0] */ + __IO uint32_t i2sdbn : 2; /* [2:1] */ + __IO uint32_t i2sclkpol : 1; /* [3] */ + __IO uint32_t stdsel : 2; /* [5:4] */ + __IO uint32_t reserved1 : 1; /* [6] */ + __IO uint32_t pcmfssel : 1; /* [7] */ + __IO uint32_t opersel : 2; /* [9:8] */ + __IO uint32_t i2sen : 1; /* [10] */ + __IO uint32_t i2smsel : 1; /* [11] */ + __IO uint32_t reserved2 : 20;/* [31:12] */ + } i2sctrl_bit; + }; + + /** + * @brief spi i2sclk register, offset:0x20 + */ + union + { + __IO uint32_t i2sclk; + struct + { + __IO uint32_t i2sdiv_l : 8; /* [7:0] */ + __IO uint32_t i2sodd : 1; /* [8] */ + __IO uint32_t i2smclkoe : 1; /* [9] */ + __IO uint32_t i2sdiv_h : 2; /* [11:10] */ + __IO uint32_t reserved1 : 20;/* [31:12] */ + } i2sclk_bit; + }; + +} spi_type; + +/** + * @} + */ + +#define SPI1 ((spi_type *) SPI1_BASE) +#define SPI2 ((spi_type *) SPI2_BASE) +#define SPI3 ((spi_type *) SPI3_BASE) +#define SPI4 ((spi_type *) SPI4_BASE) +#define I2S2EXT ((spi_type *) I2S2EXT_BASE) +#define I2S3EXT ((spi_type *) I2S3EXT_BASE) + +/** @defgroup SPI_exported_functions + * @{ + */ + +void spi_i2s_reset(spi_type *spi_x); +void spi_default_para_init(spi_init_type* spi_init_struct); +void spi_init(spi_type* spi_x, spi_init_type* spi_init_struct); +void spi_ti_mode_enable(spi_type* spi_x, confirm_state new_state); +void spi_crc_next_transmit(spi_type* spi_x); +void spi_crc_polynomial_set(spi_type* spi_x, uint16_t crc_poly); +uint16_t spi_crc_polynomial_get(spi_type* spi_x); +void spi_crc_enable(spi_type* spi_x, confirm_state new_state); +uint16_t spi_crc_value_get(spi_type* spi_x, spi_crc_direction_type crc_direction); +void spi_hardware_cs_output_enable(spi_type* spi_x, confirm_state new_state); +void spi_software_cs_internal_level_set(spi_type* spi_x, spi_software_cs_level_type level); +void spi_frame_bit_num_set(spi_type* spi_x, spi_frame_bit_num_type bit_num); +void spi_half_duplex_direction_set(spi_type* spi_x, spi_half_duplex_direction_type direction); +void spi_enable(spi_type* spi_x, confirm_state new_state); +void i2s_default_para_init(i2s_init_type* i2s_init_struct); +void i2s_init(spi_type* spi_x, i2s_init_type* i2s_init_struct); +void i2s_enable(spi_type* spi_x, confirm_state new_state); +void spi_i2s_interrupt_enable(spi_type* spi_x, uint32_t spi_i2s_int, confirm_state new_state); +void spi_i2s_dma_transmitter_enable(spi_type* spi_x, confirm_state new_state); +void spi_i2s_dma_receiver_enable(spi_type* spi_x, confirm_state new_state); +void spi_i2s_data_transmit(spi_type* spi_x, uint16_t tx_data); +uint16_t spi_i2s_data_receive(spi_type* spi_x); +flag_status spi_i2s_flag_get(spi_type* spi_x, uint32_t spi_i2s_flag); +void spi_i2s_flag_clear(spi_type* spi_x, uint32_t spi_i2s_flag); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_tmr.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_tmr.h new file mode 100644 index 0000000000..1e4256bb1e --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_tmr.h @@ -0,0 +1,1006 @@ +/** + ************************************************************************** + * @file at32f435_437_tmr.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 tmr header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_TMR_H +#define __AT32F435_437_TMR_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup TMR + * @{ + */ + +/** @defgroup TMR_flags_definition + * @brief tmr flag + * @{ + */ + +#define TMR_OVF_FLAG ((uint32_t)0x000001) /*!< tmr flag overflow */ +#define TMR_C1_FLAG ((uint32_t)0x000002) /*!< tmr flag channel 1 */ +#define TMR_C2_FLAG ((uint32_t)0x000004) /*!< tmr flag channel 2 */ +#define TMR_C3_FLAG ((uint32_t)0x000008) /*!< tmr flag channel 3 */ +#define TMR_C4_FLAG ((uint32_t)0x000010) /*!< tmr flag channel 4 */ +#define TMR_C5_FLAG ((uint32_t)0x010000) /*!< tmr flag channel 5 */ +#define TMR_HALL_FLAG ((uint32_t)0x000020) /*!< tmr flag hall */ +#define TMR_TRIGGER_FLAG ((uint32_t)0x000040) /*!< tmr flag trigger */ +#define TMR_BRK_FLAG ((uint32_t)0x000080) /*!< tmr flag brake */ +#define TMR_C1_RECAPTURE_FLAG ((uint32_t)0x000200) /*!< tmr flag channel 1 recapture */ +#define TMR_C2_RECAPTURE_FLAG ((uint32_t)0x000400) /*!< tmr flag channel 2 recapture */ +#define TMR_C3_RECAPTURE_FLAG ((uint32_t)0x000800) /*!< tmr flag channel 3 recapture */ +#define TMR_C4_RECAPTURE_FLAG ((uint32_t)0x001000) /*!< tmr flag channel 4 recapture */ + +/** + * @} + */ + +/** @defgroup TMR_interrupt_select_type_definition + * @brief tmr interrupt select type + * @{ + */ + +#define TMR_OVF_INT ((uint32_t)0x000001) /*!< tmr interrupt overflow */ +#define TMR_C1_INT ((uint32_t)0x000002) /*!< tmr interrupt channel 1 */ +#define TMR_C2_INT ((uint32_t)0x000004) /*!< tmr interrupt channel 2 */ +#define TMR_C3_INT ((uint32_t)0x000008) /*!< tmr interrupt channel 3 */ +#define TMR_C4_INT ((uint32_t)0x000010) /*!< tmr interrupt channel 4 */ +#define TMR_HALL_INT ((uint32_t)0x000020) /*!< tmr interrupt hall */ +#define TMR_TRIGGER_INT ((uint32_t)0x000040) /*!< tmr interrupt trigger */ +#define TMR_BRK_INT ((uint32_t)0x000080) /*!< tmr interrupt brake */ + +/** + * @} + */ + +/** @defgroup TMR_exported_types + * @{ + */ + +/** + * @brief tmr clock division type + */ +typedef enum +{ + TMR_CLOCK_DIV1 = 0x00, /*!< tmr clock division 1 */ + TMR_CLOCK_DIV2 = 0x01, /*!< tmr clock division 2 */ + TMR_CLOCK_DIV4 = 0x02 /*!< tmr clock division 4 */ +} tmr_clock_division_type; + +/** + * @brief tmr counter mode type + */ +typedef enum +{ + TMR_COUNT_UP = 0x00, /*!< tmr counter mode up */ + TMR_COUNT_DOWN = 0x01, /*!< tmr counter mode down */ + TMR_COUNT_TWO_WAY_1 = 0x02, /*!< tmr counter mode two way 1 */ + TMR_COUNT_TWO_WAY_2 = 0x04, /*!< tmr counter mode two way 2 */ + TMR_COUNT_TWO_WAY_3 = 0x06 /*!< tmr counter mode two way 3 */ +} tmr_count_mode_type; + +/** + * @brief tmr primary mode select type + */ +typedef enum +{ + TMR_PRIMARY_SEL_RESET = 0x00, /*!< tmr primary mode select reset */ + TMR_PRIMARY_SEL_ENABLE = 0x01, /*!< tmr primary mode select enable */ + TMR_PRIMARY_SEL_OVERFLOW = 0x02, /*!< tmr primary mode select overflow */ + TMR_PRIMARY_SEL_COMPARE = 0x03, /*!< tmr primary mode select compare */ + TMR_PRIMARY_SEL_C1ORAW = 0x04, /*!< tmr primary mode select c1oraw */ + TMR_PRIMARY_SEL_C2ORAW = 0x05, /*!< tmr primary mode select c2oraw */ + TMR_PRIMARY_SEL_C3ORAW = 0x06, /*!< tmr primary mode select c3oraw */ + TMR_PRIMARY_SEL_C4ORAW = 0x07 /*!< tmr primary mode select c4oraw */ +} tmr_primary_select_type; + +/** + * @brief tmr subordinate mode input select type + */ +typedef enum +{ + TMR_SUB_INPUT_SEL_IS0 = 0x00, /*!< subordinate mode input select is0 */ + TMR_SUB_INPUT_SEL_IS1 = 0x01, /*!< subordinate mode input select is1 */ + TMR_SUB_INPUT_SEL_IS2 = 0x02, /*!< subordinate mode input select is2 */ + TMR_SUB_INPUT_SEL_IS3 = 0x03, /*!< subordinate mode input select is3 */ + TMR_SUB_INPUT_SEL_C1INC = 0x04, /*!< subordinate mode input select c1inc */ + TMR_SUB_INPUT_SEL_C1DF1 = 0x05, /*!< subordinate mode input select c1df1 */ + TMR_SUB_INPUT_SEL_C2DF2 = 0x06, /*!< subordinate mode input select c2df2 */ + TMR_SUB_INPUT_SEL_EXTIN = 0x07 /*!< subordinate mode input select extin */ +} sub_tmr_input_sel_type; + +/** + * @brief tmr subordinate mode select type + */ +typedef enum +{ + TMR_SUB_MODE_DIABLE = 0x00, /*!< subordinate mode disable */ + TMR_SUB_ENCODER_MODE_A = 0x01, /*!< subordinate mode select encoder mode a */ + TMR_SUB_ENCODER_MODE_B = 0x02, /*!< subordinate mode select encoder mode b */ + TMR_SUB_ENCODER_MODE_C = 0x03, /*!< subordinate mode select encoder mode c */ + TMR_SUB_RESET_MODE = 0x04, /*!< subordinate mode select reset */ + TMR_SUB_HANG_MODE = 0x05, /*!< subordinate mode select hang */ + TMR_SUB_TRIGGER_MODE = 0x06, /*!< subordinate mode select trigger */ + TMR_SUB_EXTERNAL_CLOCK_MODE_A = 0x07 /*!< subordinate mode external clock mode a */ +} tmr_sub_mode_select_type; + +/** + * @brief tmr encoder mode type + */ +typedef enum +{ + TMR_ENCODER_MODE_A = TMR_SUB_ENCODER_MODE_A, /*!< tmr encoder mode a */ + TMR_ENCODER_MODE_B = TMR_SUB_ENCODER_MODE_B, /*!< tmr encoder mode b */ + TMR_ENCODER_MODE_C = TMR_SUB_ENCODER_MODE_C /*!< tmr encoder mode c */ +} tmr_encoder_mode_type; + +/** + * @brief tmr output control mode type + */ +typedef enum +{ + TMR_OUTPUT_CONTROL_OFF = 0x00, /*!< tmr output control mode off */ + TMR_OUTPUT_CONTROL_HIGH = 0x01, /*!< tmr output control mode high */ + TMR_OUTPUT_CONTROL_LOW = 0x02, /*!< tmr output control mode low */ + TMR_OUTPUT_CONTROL_SWITCH = 0x03, /*!< tmr output control mode switch */ + TMR_OUTPUT_CONTROL_FORCE_LOW = 0x04, /*!< tmr output control mode force low */ + TMR_OUTPUT_CONTROL_FORCE_HIGH = 0x05, /*!< tmr output control mode force high */ + TMR_OUTPUT_CONTROL_PWM_MODE_A = 0x06, /*!< tmr output control mode pwm a */ + TMR_OUTPUT_CONTROL_PWM_MODE_B = 0x07 /*!< tmr output control mode pwm b */ +} tmr_output_control_mode_type; + +/** + * @brief tmr force output type + */ +typedef enum +{ + TMR_FORCE_OUTPUT_HIGH = TMR_OUTPUT_CONTROL_FORCE_HIGH, /*!< tmr force output high */ + TMR_FORCE_OUTPUT_LOW = TMR_OUTPUT_CONTROL_FORCE_LOW /*!< tmr force output low */ +} tmr_force_output_type; + +/** + * @brief tmr output channel polarity type + */ +typedef enum +{ + TMR_OUTPUT_ACTIVE_HIGH = 0x00, /*!< tmr output channel polarity high */ + TMR_OUTPUT_ACTIVE_LOW = 0x01 /*!< tmr output channel polarity low */ +} tmr_output_polarity_type; + +/** + * @brief tmr input channel polarity type + */ +typedef enum +{ + TMR_INPUT_RISING_EDGE = 0x00, /*!< tmr input channel polarity rising */ + TMR_INPUT_FALLING_EDGE = 0x01, /*!< tmr input channel polarity falling */ + TMR_INPUT_BOTH_EDGE = 0x03 /*!< tmr input channel polarity both edge */ +} tmr_input_polarity_type; + +/** + * @brief tmr channel select type + */ +typedef enum +{ + TMR_SELECT_CHANNEL_1 = 0x00, /*!< tmr channel select channel 1 */ + TMR_SELECT_CHANNEL_1C = 0x01, /*!< tmr channel select channel 1 complementary */ + TMR_SELECT_CHANNEL_2 = 0x02, /*!< tmr channel select channel 2 */ + TMR_SELECT_CHANNEL_2C = 0x03, /*!< tmr channel select channel 2 complementary */ + TMR_SELECT_CHANNEL_3 = 0x04, /*!< tmr channel select channel 3 */ + TMR_SELECT_CHANNEL_3C = 0x05, /*!< tmr channel select channel 3 complementary */ + TMR_SELECT_CHANNEL_4 = 0x06, /*!< tmr channel select channel 4 */ + TMR_SELECT_CHANNEL_5 = 0x07 /*!< tmr channel select channel 5 */ +} tmr_channel_select_type; + +/** + * @brief tmr channel1 input connected type + */ +typedef enum +{ + TMR_CHANEL1_CONNECTED_C1IRAW = 0x00, /*!< channel1 pins is only connected to C1IRAW input */ + TMR_CHANEL1_2_3_CONNECTED_C1IRAW_XOR = 0x01 /*!< channel1/2/3 pins are connected to C1IRAW input after xored */ +} tmr_channel1_input_connected_type; + +/** + * @brief tmr input channel mapped type channel direction + */ +typedef enum +{ + TMR_CC_CHANNEL_MAPPED_DIRECT = 0x01, /*!< channel is configured as input, mapped direct */ + TMR_CC_CHANNEL_MAPPED_INDIRECT = 0x02, /*!< channel is configured as input, mapped indirect */ + TMR_CC_CHANNEL_MAPPED_STI = 0x03 /*!< channel is configured as input, mapped trc */ +} tmr_input_direction_mapped_type; + +/** + * @brief tmr input divider type + */ +typedef enum +{ + TMR_CHANNEL_INPUT_DIV_1 = 0x00, /*!< tmr channel input divider 1 */ + TMR_CHANNEL_INPUT_DIV_2 = 0x01, /*!< tmr channel input divider 2 */ + TMR_CHANNEL_INPUT_DIV_4 = 0x02, /*!< tmr channel input divider 4 */ + TMR_CHANNEL_INPUT_DIV_8 = 0x03 /*!< tmr channel input divider 8 */ +} tmr_channel_input_divider_type; + +/** + * @brief tmr dma request source select type + */ +typedef enum +{ + TMR_DMA_REQUEST_BY_CHANNEL = 0x00, /*!< tmr dma request source select channel */ + TMR_DMA_REQUEST_BY_OVERFLOW = 0x01 /*!< tmr dma request source select overflow */ +} tmr_dma_request_source_type; + +/** + * @brief tmr dma request type + */ +typedef enum +{ + TMR_OVERFLOW_DMA_REQUEST = 0x00000100, /*!< tmr dma request select overflow */ + TMR_C1_DMA_REQUEST = 0x00000200, /*!< tmr dma request select channel 1 */ + TMR_C2_DMA_REQUEST = 0x00000400, /*!< tmr dma request select channel 2 */ + TMR_C3_DMA_REQUEST = 0x00000800, /*!< tmr dma request select channel 3 */ + TMR_C4_DMA_REQUEST = 0x00001000, /*!< tmr dma request select channel 4 */ + TMR_HALL_DMA_REQUEST = 0x00002000, /*!< tmr dma request select hall */ + TMR_TRIGGER_DMA_REQUEST = 0x00004000 /*!< tmr dma request select trigger */ +} tmr_dma_request_type; + +/** + * @brief tmr event triggered by software type + */ +typedef enum +{ + TMR_OVERFLOW_SWTRIG = 0x00000001, /*!< tmr event triggered by software of overflow */ + TMR_C1_SWTRIG = 0x00000002, /*!< tmr event triggered by software of channel 1 */ + TMR_C2_SWTRIG = 0x00000004, /*!< tmr event triggered by software of channel 2 */ + TMR_C3_SWTRIG = 0x00000008, /*!< tmr event triggered by software of channel 3 */ + TMR_C4_SWTRIG = 0x00000010, /*!< tmr event triggered by software of channel 4 */ + TMR_HALL_SWTRIG = 0x00000020, /*!< tmr event triggered by software of hall */ + TMR_TRIGGER_SWTRIG = 0x00000040, /*!< tmr event triggered by software of trigger */ + TMR_BRK_SWTRIG = 0x00000080 /*!< tmr event triggered by software of brake */ +}tmr_event_trigger_type; + +/** + * @brief tmr polarity active type + */ +typedef enum +{ + TMR_POLARITY_ACTIVE_HIGH = 0x00, /*!< tmr polarity active high */ + TMR_POLARITY_ACTIVE_LOW = 0x01, /*!< tmr polarity active low */ + TMR_POLARITY_ACTIVE_BOTH = 0x02 /*!< tmr polarity active both high ande low */ +}tmr_polarity_active_type; + +/** + * @brief tmr external signal divider type + */ +typedef enum +{ + TMR_ES_FREQUENCY_DIV_1 = 0x00, /*!< tmr external signal frequency divider 1 */ + TMR_ES_FREQUENCY_DIV_2 = 0x01, /*!< tmr external signal frequency divider 2 */ + TMR_ES_FREQUENCY_DIV_4 = 0x02, /*!< tmr external signal frequency divider 4 */ + TMR_ES_FREQUENCY_DIV_8 = 0x03 /*!< tmr external signal frequency divider 8 */ +}tmr_external_signal_divider_type; + +/** + * @brief tmr external signal polarity type + */ +typedef enum +{ + TMR_ES_POLARITY_NON_INVERTED = 0x00, /*!< tmr external signal polarity non-inerted */ + TMR_ES_POLARITY_INVERTED = 0x01 /*!< tmr external signal polarity inerted */ +}tmr_external_signal_polarity_type; + +/** + * @brief tmr dma transfer length type + */ +typedef enum +{ + TMR_DMA_TRANSFER_1BYTE = 0x00, /*!< tmr dma transfer length 1 byte */ + TMR_DMA_TRANSFER_2BYTES = 0x01, /*!< tmr dma transfer length 2 bytes */ + TMR_DMA_TRANSFER_3BYTES = 0x02, /*!< tmr dma transfer length 3 bytes */ + TMR_DMA_TRANSFER_4BYTES = 0x03, /*!< tmr dma transfer length 4 bytes */ + TMR_DMA_TRANSFER_5BYTES = 0x04, /*!< tmr dma transfer length 5 bytes */ + TMR_DMA_TRANSFER_6BYTES = 0x05, /*!< tmr dma transfer length 6 bytes */ + TMR_DMA_TRANSFER_7BYTES = 0x06, /*!< tmr dma transfer length 7 bytes */ + TMR_DMA_TRANSFER_8BYTES = 0x07, /*!< tmr dma transfer length 8 bytes */ + TMR_DMA_TRANSFER_9BYTES = 0x08, /*!< tmr dma transfer length 9 bytes */ + TMR_DMA_TRANSFER_10BYTES = 0x09, /*!< tmr dma transfer length 10 bytes */ + TMR_DMA_TRANSFER_11BYTES = 0x0A, /*!< tmr dma transfer length 11 bytes */ + TMR_DMA_TRANSFER_12BYTES = 0x0B, /*!< tmr dma transfer length 12 bytes */ + TMR_DMA_TRANSFER_13BYTES = 0x0C, /*!< tmr dma transfer length 13 bytes */ + TMR_DMA_TRANSFER_14BYTES = 0x0D, /*!< tmr dma transfer length 14 bytes */ + TMR_DMA_TRANSFER_15BYTES = 0x0E, /*!< tmr dma transfer length 15 bytes */ + TMR_DMA_TRANSFER_16BYTES = 0x0F, /*!< tmr dma transfer length 16 bytes */ + TMR_DMA_TRANSFER_17BYTES = 0x10, /*!< tmr dma transfer length 17 bytes */ + TMR_DMA_TRANSFER_18BYTES = 0x11 /*!< tmr dma transfer length 18 bytes */ +}tmr_dma_transfer_length_type; + +/** + * @brief tmr dma base address type + */ +typedef enum +{ + TMR_CTRL1_ADDRESS = 0x0000, /*!< tmr dma base address ctrl1 */ + TMR_CTRL2_ADDRESS = 0x0001, /*!< tmr dma base address ctrl2 */ + TMR_STCTRL_ADDRESS = 0x0002, /*!< tmr dma base address stctrl */ + TMR_IDEN_ADDRESS = 0x0003, /*!< tmr dma base address iden */ + TMR_ISTS_ADDRESS = 0x0004, /*!< tmr dma base address ists */ + TMR_SWEVT_ADDRESS = 0x0005, /*!< tmr dma base address swevt */ + TMR_CM1_ADDRESS = 0x0006, /*!< tmr dma base address cm1 */ + TMR_CM2_ADDRESS = 0x0007, /*!< tmr dma base address cm2 */ + TMR_CCTRL_ADDRESS = 0x0008, /*!< tmr dma base address cctrl */ + TMR_CVAL_ADDRESS = 0x0009, /*!< tmr dma base address cval */ + TMR_DIV_ADDRESS = 0x000A, /*!< tmr dma base address div */ + TMR_PR_ADDRESS = 0x000B, /*!< tmr dma base address pr */ + TMR_RPR_ADDRESS = 0x000C, /*!< tmr dma base address rpr */ + TMR_C1DT_ADDRESS = 0x000D, /*!< tmr dma base address c1dt */ + TMR_C2DT_ADDRESS = 0x000E, /*!< tmr dma base address c2dt */ + TMR_C3DT_ADDRESS = 0x000F, /*!< tmr dma base address c3dt */ + TMR_C4DT_ADDRESS = 0x0010, /*!< tmr dma base address c4dt */ + TMR_BRK_ADDRESS = 0x0011, /*!< tmr dma base address brake */ + TMR_DMACTRL_ADDRESS = 0x0012 /*!< tmr dma base address dmactrl */ +}tmr_dma_address_type; + +/** + * @brief tmr brk polarity type + */ +typedef enum +{ + TMR_BRK_INPUT_ACTIVE_LOW = 0x00, /*!< tmr brk input channel active low */ + TMR_BRK_INPUT_ACTIVE_HIGH = 0x01 /*!< tmr brk input channel active high */ +}tmr_brk_polarity_type; + +/** + * @brief tmr write protect level type + */ +typedef enum +{ + TMR_WP_OFF = 0x00, /*!< tmr write protect off */ + TMR_WP_LEVEL_3 = 0x01, /*!< tmr write protect level 3 */ + TMR_WP_LEVEL_2 = 0x02, /*!< tmr write protect level 2 */ + TMR_WP_LEVEL_1 = 0x03 /*!< tmr write protect level 1 */ +}tmr_wp_level_type; + +/** + * @brief tmr input remap type + */ +typedef enum +{ + TMR2_TMR8TRGOUT_TMR5_GPIO = 0x00, /*!< tmr2 input remap to tmr8_trgout or tmr5 remap to gpio */ + TMR2_PTP_TMR5_LICK = 0x01, /*!< tmr2 input remap to ptp or tmr5 remap to lick */ + TMR2_OTG1FS_TMR5_LEXT = 0x02, /*!< tmr2 input remap to otg1fs or tmr5 remap to lext */ + TMR2_OTG2FS_TMR5_ERTC = 0x03 /*!< tmr2 input remap to otg2fs or tmr5 remap to ertc */ +}tmr_input_remap_type ; +/** + + * @brief tmr output config type + */ +typedef struct +{ + tmr_output_control_mode_type oc_mode; /*!< output channel mode */ + confirm_state oc_idle_state; /*!< output channel idle state */ + confirm_state occ_idle_state; /*!< output channel complementary idle state */ + tmr_output_polarity_type oc_polarity; /*!< output channel polarity */ + tmr_output_polarity_type occ_polarity; /*!< output channel complementary polarity */ + confirm_state oc_output_state; /*!< output channel enable */ + confirm_state occ_output_state; /*!< output channel complementary enable */ +} tmr_output_config_type; + +/** + * @brief tmr input capture config type + */ +typedef struct +{ + tmr_channel_select_type input_channel_select; /*!< tmr input channel select */ + tmr_input_polarity_type input_polarity_select; /*!< tmr input polarity select */ + tmr_input_direction_mapped_type input_mapped_select; /*!< tmr channel mapped direct or indirect */ + uint8_t input_filter_value; /*!< tmr channel filter value */ +} tmr_input_config_type; + +/** + * @brief tmr brkdt config type + */ +typedef struct +{ + uint8_t deadtime; /*!< dead-time generator setup */ + tmr_brk_polarity_type brk_polarity; /*!< tmr brake polarity */ + tmr_wp_level_type wp_level; /*!< write protect configuration */ + confirm_state auto_output_enable; /*!< automatic output enable */ + confirm_state fcsoen_state; /*!< frozen channel status when output enable */ + confirm_state fcsodis_state; /*!< frozen channel status when output disable */ + confirm_state brk_enable; /*!< tmr brk enale */ +} tmr_brkdt_config_type; + +/** + * @brief type define tmr register all + */ +typedef struct +{ + /** + * @brief tmr ctrl1 register, offset:0x00 + */ + union + { + __IO uint32_t ctrl1; + struct + { + __IO uint32_t tmren : 1; /* [0] */ + __IO uint32_t ovfen : 1; /* [1] */ + __IO uint32_t ovfs : 1; /* [2] */ + __IO uint32_t ocmen : 1; /* [3] */ + __IO uint32_t cnt_dir : 3; /* [6:4] */ + __IO uint32_t prben : 1; /* [7] */ + __IO uint32_t clkdiv : 2; /* [9:8] */ + __IO uint32_t pmen : 1; /* [10] */ + __IO uint32_t reserved1 : 21;/* [31:11] */ + } ctrl1_bit; + }; + + /** + * @brief tmr ctrl2 register, offset:0x04 + */ + union + { + __IO uint32_t ctrl2; + struct + { + __IO uint32_t cbctrl : 1; /* [0] */ + __IO uint32_t reserved1 : 1; /* [1] */ + __IO uint32_t ccfs : 1; /* [2] */ + __IO uint32_t drs : 1; /* [3] */ + __IO uint32_t ptos : 3; /* [6:4] */ + __IO uint32_t c1insel : 1; /* [7] */ + __IO uint32_t c1ios : 1; /* [8] */ + __IO uint32_t c1cios : 1; /* [9] */ + __IO uint32_t c2ios : 1; /* [10] */ + __IO uint32_t c2cios : 1; /* [11] */ + __IO uint32_t c3ios : 1; /* [12] */ + __IO uint32_t c3cios : 1; /* [13] */ + __IO uint32_t c4ios : 1; /* [14] */ + __IO uint32_t reserved2 : 16;/* [30:15] */ + __IO uint32_t trgout2en : 1; /* [31] */ + } ctrl2_bit; + }; + + /** + * @brief tmr smc register, offset:0x08 + */ + union + { + __IO uint32_t stctrl; + struct + { + __IO uint32_t smsel : 3; /* [2:0] */ + __IO uint32_t reserved1 : 1; /* [3] */ + __IO uint32_t stis : 3; /* [6:4] */ + __IO uint32_t sts : 1; /* [7] */ + __IO uint32_t esf : 4; /* [11:8] */ + __IO uint32_t esdiv : 2; /* [13:12] */ + __IO uint32_t ecmben : 1; /* [14] */ + __IO uint32_t esp : 1; /* [15] */ + __IO uint32_t reserved2 : 16;/* [31:16] */ + } stctrl_bit; + }; + + /** + * @brief tmr die register, offset:0x0C + */ + union + { + __IO uint32_t iden; + struct + { + __IO uint32_t ovfien : 1; /* [0] */ + __IO uint32_t c1ien : 1; /* [1] */ + __IO uint32_t c2ien : 1; /* [2] */ + __IO uint32_t c3ien : 1; /* [3] */ + __IO uint32_t c4ien : 1; /* [4] */ + __IO uint32_t hallien : 1; /* [5] */ + __IO uint32_t tien : 1; /* [6] */ + __IO uint32_t brkie : 1; /* [7] */ + __IO uint32_t ovfden : 1; /* [8] */ + __IO uint32_t c1den : 1; /* [9] */ + __IO uint32_t c2den : 1; /* [10] */ + __IO uint32_t c3den : 1; /* [11] */ + __IO uint32_t c4den : 1; /* [12] */ + __IO uint32_t hallde : 1; /* [13] */ + __IO uint32_t tden : 1; /* [14] */ + __IO uint32_t reserved1 : 17;/* [31:15] */ + } iden_bit; + }; + + /** + * @brief tmr ists register, offset:0x10 + */ + union + { + __IO uint32_t ists; + struct + { + __IO uint32_t ovfif : 1; /* [0] */ + __IO uint32_t c1if : 1; /* [1] */ + __IO uint32_t c2if : 1; /* [2] */ + __IO uint32_t c3if : 1; /* [3] */ + __IO uint32_t c4if : 1; /* [4] */ + __IO uint32_t hallif : 1; /* [5] */ + __IO uint32_t trgif : 1; /* [6] */ + __IO uint32_t brkif : 1; /* [7] */ + __IO uint32_t reserved1 : 1; /* [8] */ + __IO uint32_t c1rf : 1; /* [9] */ + __IO uint32_t c2rf : 1; /* [10] */ + __IO uint32_t c3rf : 1; /* [11] */ + __IO uint32_t c4rf : 1; /* [12] */ + __IO uint32_t reserved2 : 19;/* [31:13] */ + } ists_bit; + }; + + /** + * @brief tmr eveg register, offset:0x14 + */ + union + { + __IO uint32_t swevt; + struct + { + __IO uint32_t ovfswtr : 1; /* [0] */ + __IO uint32_t c1swtr : 1; /* [1] */ + __IO uint32_t c2swtr : 1; /* [2] */ + __IO uint32_t c3swtr : 1; /* [3] */ + __IO uint32_t c4swtr : 1; /* [4] */ + __IO uint32_t hallswtr : 1; /* [5] */ + __IO uint32_t trgswtr : 1; /* [6] */ + __IO uint32_t brkswtr : 1; /* [7] */ + __IO uint32_t reserved : 24;/* [31:8] */ + } swevt_bit; + }; + + /** + * @brief tmr ccm1 register, offset:0x18 + */ + union + { + __IO uint32_t cm1; + + /** + * @brief channel mode + */ + struct + { + __IO uint32_t c1c : 2; /* [1:0] */ + __IO uint32_t c1oien : 1; /* [2] */ + __IO uint32_t c1oben : 1; /* [3] */ + __IO uint32_t c1octrl : 3; /* [6:4] */ + __IO uint32_t c1osen : 1; /* [7] */ + __IO uint32_t c2c : 2; /* [9:8] */ + __IO uint32_t c2oien : 1; /* [10] */ + __IO uint32_t c2oben : 1; /* [11] */ + __IO uint32_t c2octrl : 3; /* [14:12] */ + __IO uint32_t c2osen : 1; /* [15] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } cm1_output_bit; + + /** + * @brief input capture mode + */ + struct + { + __IO uint32_t c1c : 2; /* [1:0] */ + __IO uint32_t c1idiv : 2; /* [3:2] */ + __IO uint32_t c1df : 4; /* [7:4] */ + __IO uint32_t c2c : 2; /* [9:8] */ + __IO uint32_t c2idiv : 2; /* [11:10] */ + __IO uint32_t c2df : 4; /* [15:12] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } cm1_input_bit; + }; + + /** + * @brief tmr ccm2 register, offset:0x1C + */ + union + { + __IO uint32_t cm2; + + /** + * @brief channel mode + */ + struct + { + __IO uint32_t c3c : 2; /* [1:0] */ + __IO uint32_t c3oien : 1; /* [2] */ + __IO uint32_t c3oben : 1; /* [3] */ + __IO uint32_t c3octrl : 3; /* [6:4] */ + __IO uint32_t c3osen : 1; /* [7] */ + __IO uint32_t c4c : 2; /* [9:8] */ + __IO uint32_t c4oien : 1; /* [10] */ + __IO uint32_t c4oben : 1; /* [11] */ + __IO uint32_t c4octrl : 3; /* [14:12] */ + __IO uint32_t c4osen : 1; /* [15] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } cm2_output_bit; + + /** + * @brief input capture mode + */ + struct + { + __IO uint32_t c3c : 2; /* [1:0] */ + __IO uint32_t c3idiv : 2; /* [3:2] */ + __IO uint32_t c3df : 4; /* [7:4] */ + __IO uint32_t c4c : 2; /* [9:8] */ + __IO uint32_t c4idiv : 2; /* [11:10] */ + __IO uint32_t c4df : 4; /* [15:12] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } cm2_input_bit; + }; + + /** + * @brief tmr cce register, offset:0x20 + */ + union + { + uint32_t cctrl; + struct + { + __IO uint32_t c1en : 1; /* [0] */ + __IO uint32_t c1p : 1; /* [1] */ + __IO uint32_t c1cen : 1; /* [2] */ + __IO uint32_t c1cp : 1; /* [3] */ + __IO uint32_t c2en : 1; /* [4] */ + __IO uint32_t c2p : 1; /* [5] */ + __IO uint32_t c2cen : 1; /* [6] */ + __IO uint32_t c2cp : 1; /* [7] */ + __IO uint32_t c3en : 1; /* [8] */ + __IO uint32_t c3p : 1; /* [9] */ + __IO uint32_t c3cen : 1; /* [10] */ + __IO uint32_t c3cp : 1; /* [11] */ + __IO uint32_t c4en : 1; /* [12] */ + __IO uint32_t c4p : 1; /* [13] */ + __IO uint32_t reserved1 : 18;/* [31:14] */ + } cctrl_bit; + }; + + /** + * @brief tmr cnt register, offset:0x24 + */ + union + { + __IO uint32_t cval; + struct + { + __IO uint32_t cval : 32;/* [31:0] */ + } cval_bit; + }; + + /** + * @brief tmr div, offset:0x28 + */ + union + { + __IO uint32_t div; + struct + { + __IO uint32_t div : 16;/* [15:0] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } div_bit; + }; + + /** + * @brief tmr pr register, offset:0x2C + */ + union + { + __IO uint32_t pr; + struct + { + __IO uint32_t pr : 32;/* [31:0] */ + } pr_bit; + }; + + /** + * @brief tmr rpr register, offset:0x30 + */ + union + { + __IO uint32_t rpr; + struct + { + __IO uint32_t rpr : 16;/* [15:0] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } rpr_bit; + }; + + /** + * @brief tmr c1dt register, offset:0x34 + */ + union + { + uint32_t c1dt; + struct + { + __IO uint32_t c1dt : 32;/* [31:0] */ + } c1dt_bit; + }; + + /** + * @brief tmr c2dt register, offset:0x38 + */ + union + { + uint32_t c2dt; + struct + { + __IO uint32_t c2dt : 32;/* [31:0] */ + } c2dt_bit; + }; + + /** + * @brief tmr c3dt register, offset:0x3C + */ + union + { + __IO uint32_t c3dt; + struct + { + __IO uint32_t c3dt : 32;/* [31:0] */ + } c3dt_bit; + }; + + /** + * @brief tmr c4dt register, offset:0x40 + */ + union + { + __IO uint32_t c4dt; + struct + { + __IO uint32_t c4dt : 32;/* [31:0] */ + } c4dt_bit; + }; + + /** + * @brief tmr brk register, offset:0x44 + */ + union + { + __IO uint32_t brk; + struct + { + __IO uint32_t dtc : 8; /* [7:0] */ + __IO uint32_t wpc : 2; /* [9:8] */ + __IO uint32_t fcsodis : 1; /* [10] */ + __IO uint32_t fcsoen : 1; /* [11] */ + __IO uint32_t brken : 1; /* [12] */ + __IO uint32_t brkv : 1; /* [13] */ + __IO uint32_t aoen : 1; /* [14] */ + __IO uint32_t oen : 1; /* [15] */ + __IO uint32_t reserved1 : 16; /* [31:16] */ + } brk_bit; + }; + /** + * @brief tmr dmactrl register, offset:0x48 + */ + union + { + __IO uint32_t dmactrl; + struct + { + __IO uint32_t addr : 5; /* [4:0] */ + __IO uint32_t reserved1 : 3; /* [7:5] */ + __IO uint32_t dtb : 5; /* [12:8] */ + __IO uint32_t reserved2 : 19;/* [31:13] */ + } dmactrl_bit; + }; + + /** + * @brief tmr dmadt register, offset:0x4C + */ + union + { + __IO uint32_t dmadt; + struct + { + __IO uint32_t dmadt : 16;/* [15:0] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } dmadt_bit; + }; + + /** + * @brief tmr rmp register, offset:0x50 + */ + union + { + __IO uint32_t rmp; + struct + { + __IO uint32_t reserved1 : 6; /* [5:0] */ + __IO uint32_t tmr5_ch4_irmp : 2; /* [7:6] */ + __IO uint32_t reserved2 : 2; /* [9:8] */ + __IO uint32_t tmr2_ch1_irmp : 2; /* [11:10] */ + __IO uint32_t reserved3 : 20;/* [31:16] */ + } rmp_bit; + }; + + /** + * @brief tmr reserved0 register, offset:0x54-0x6C + */ + __IO uint32_t reserved1[7]; + + /** + * @brief tmr cm3 register, offset:0x70 + */ + union + { + __IO uint32_t cm3; + struct + { + __IO uint32_t reserved1 : 2; /* [1:0] */ + __IO uint32_t c5oien : 1; /* [2] */ + __IO uint32_t c5oben : 1; /* [3] */ + __IO uint32_t c5octrl : 3; /* [6:4] */ + __IO uint32_t c5osen : 1; /* [7] */ + __IO uint32_t reserved2 : 24;/* [31:8] */ + } cm3_output_bit; + }; + + /** + * @brief tmr c5dt register, offset:0x74 + */ + union + { + __IO uint32_t c5dt; + struct + { + __IO uint32_t c5dt : 32;/* [31:0] */ + } c5dt_bit; + }; +} tmr_type; + +/** + * @} + */ + +#define TMR1 ((tmr_type *) TMR1_BASE) +#define TMR2 ((tmr_type *) TMR2_BASE) +#define TMR3 ((tmr_type *) TMR3_BASE) +#define TMR4 ((tmr_type *) TMR4_BASE) +#define TMR5 ((tmr_type *) TMR5_BASE) +#define TMR6 ((tmr_type *) TMR6_BASE) +#define TMR7 ((tmr_type *) TMR7_BASE) +#define TMR8 ((tmr_type *) TMR8_BASE) +#define TMR9 ((tmr_type *) TMR9_BASE) +#define TMR10 ((tmr_type *) TMR10_BASE) +#define TMR11 ((tmr_type *) TMR11_BASE) +#define TMR12 ((tmr_type *) TMR12_BASE) +#define TMR13 ((tmr_type *) TMR13_BASE) +#define TMR14 ((tmr_type *) TMR14_BASE) +#define TMR20 ((tmr_type *) TMR20_BASE) + +/** @defgroup TMR_exported_functions + * @{ + */ + +void tmr_reset(tmr_type *tmr_x); +void tmr_counter_enable(tmr_type *tmr_x, confirm_state new_state); +void tmr_output_default_para_init(tmr_output_config_type *tmr_output_struct); +void tmr_input_default_para_init(tmr_input_config_type *tmr_input_struct); +void tmr_brkdt_default_para_init(tmr_brkdt_config_type *tmr_brkdt_struct); +void tmr_base_init(tmr_type* tmr_x, uint32_t tmr_pr, uint32_t tmr_div); +void tmr_clock_source_div_set(tmr_type *tmr_x, tmr_clock_division_type tmr_clock_div); +void tmr_cnt_dir_set(tmr_type *tmr_x, tmr_count_mode_type tmr_cnt_dir); +void tmr_repetition_counter_set(tmr_type *tmr_x, uint8_t tmr_rpr_value); +void tmr_counter_value_set(tmr_type *tmr_x, uint32_t tmr_cnt_value); +uint32_t tmr_counter_value_get(tmr_type *tmr_x); +void tmr_div_value_set(tmr_type *tmr_x, uint32_t tmr_div_value); +uint32_t tmr_div_value_get(tmr_type *tmr_x); +void tmr_output_channel_config(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + tmr_output_config_type *tmr_output_struct); +void tmr_output_channel_mode_select(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + tmr_output_control_mode_type oc_mode); +void tmr_period_value_set(tmr_type *tmr_x, uint32_t tmr_pr_value); +uint32_t tmr_period_value_get(tmr_type *tmr_x); +void tmr_channel_value_set(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + uint32_t tmr_channel_value); +uint32_t tmr_channel_value_get(tmr_type *tmr_x, tmr_channel_select_type tmr_channel); +void tmr_period_buffer_enable(tmr_type *tmr_x, confirm_state new_state); +void tmr_output_channel_buffer_enable(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + confirm_state new_state); +void tmr_output_channel_immediately_set(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + confirm_state new_state); +void tmr_output_channel_switch_set(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + confirm_state new_state); +void tmr_one_cycle_mode_enable(tmr_type *tmr_x, confirm_state new_state); +void tmr_32_bit_function_enable (tmr_type *tmr_x, confirm_state new_state); +void tmr_overflow_request_source_set(tmr_type *tmr_x, confirm_state new_state); +void tmr_overflow_event_disable(tmr_type *tmr_x, confirm_state new_state); +void tmr_input_channel_init(tmr_type *tmr_x, tmr_input_config_type *input_struct, \ + tmr_channel_input_divider_type divider_factor); +void tmr_channel_enable(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, confirm_state new_state); +void tmr_input_channel_filter_set(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + uint16_t filter_value); +void tmr_pwm_input_config(tmr_type *tmr_x, tmr_input_config_type *input_struct, \ + tmr_channel_input_divider_type divider_factor); +void tmr_channel1_input_select(tmr_type *tmr_x, tmr_channel1_input_connected_type ch1_connect); +void tmr_input_channel_divider_set(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + tmr_channel_input_divider_type divider_factor); +void tmr_primary_mode_select(tmr_type *tmr_x, tmr_primary_select_type primary_mode); +void tmr_sub_mode_select(tmr_type *tmr_x, tmr_sub_mode_select_type sub_mode); +void tmr_channel_dma_select(tmr_type *tmr_x, tmr_dma_request_source_type cc_dma_select); +void tmr_hall_select(tmr_type *tmr_x, confirm_state new_state); +void tmr_channel_buffer_enable(tmr_type *tmr_x, confirm_state new_state); +void tmr_trgout2_enable(tmr_type *tmr_x, confirm_state new_state); +void tmr_trigger_input_select(tmr_type *tmr_x, sub_tmr_input_sel_type trigger_select); +void tmr_sub_sync_mode_set(tmr_type *tmr_x, confirm_state new_state); +void tmr_dma_request_enable(tmr_type *tmr_x, tmr_dma_request_type dma_request, confirm_state new_state); +void tmr_interrupt_enable(tmr_type *tmr_x, uint32_t tmr_interrupt, confirm_state new_state); +flag_status tmr_flag_get(tmr_type *tmr_x, uint32_t tmr_flag); +void tmr_flag_clear(tmr_type *tmr_x, uint32_t tmr_flag); +void tmr_event_sw_trigger(tmr_type *tmr_x, tmr_event_trigger_type tmr_event); +void tmr_output_enable(tmr_type *tmr_x, confirm_state new_state); +void tmr_internal_clock_set(tmr_type *tmr_x); +void tmr_output_channel_polarity_set(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + tmr_polarity_active_type oc_polarity); +void tmr_external_clock_config(tmr_type *tmr_x, tmr_external_signal_divider_type es_divide, \ + tmr_external_signal_polarity_type es_polarity, uint16_t es_filter); +void tmr_external_clock_mode1_config(tmr_type *tmr_x, tmr_external_signal_divider_type es_divide, \ + tmr_external_signal_polarity_type es_polarity, uint16_t es_filter); +void tmr_external_clock_mode2_config(tmr_type *tmr_x, tmr_external_signal_divider_type es_divide, \ + tmr_external_signal_polarity_type es_polarity, uint16_t es_filter); +void tmr_encoder_mode_config(tmr_type *tmr_x, tmr_encoder_mode_type encoder_mode, tmr_input_polarity_type \ + ic1_polarity, tmr_input_polarity_type ic2_polarity); +void tmr_force_output_set(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + tmr_force_output_type force_output); +void tmr_dma_control_config(tmr_type *tmr_x, tmr_dma_transfer_length_type dma_length, \ + tmr_dma_address_type dma_base_address); +void tmr_brkdt_config(tmr_type *tmr_x, tmr_brkdt_config_type *brkdt_struct); +void tmr_iremap_config(tmr_type *tmr_x, tmr_input_remap_type input_remap); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_usart.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_usart.h new file mode 100644 index 0000000000..e7f2741815 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_usart.h @@ -0,0 +1,412 @@ +/** + ************************************************************************** + * @file at32f435_437_usart.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 usart header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_USART_H +#define __AT32F435_437_USART_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup USART + * @{ + */ + +/** @defgroup USART_flags_definition + * @brief usart flag + * @{ + */ + +#define USART_PERR_FLAG ((uint32_t)0x00000001) /*!< usart parity error flag */ +#define USART_FERR_FLAG ((uint32_t)0x00000002) /*!< usart framing error flag */ +#define USART_NERR_FLAG ((uint32_t)0x00000004) /*!< usart noise error flag */ +#define USART_ROERR_FLAG ((uint32_t)0x00000008) /*!< usart receiver overflow error flag */ +#define USART_IDLEF_FLAG ((uint32_t)0x00000010) /*!< usart idle flag */ +#define USART_RDBF_FLAG ((uint32_t)0x00000020) /*!< usart receive data buffer full flag */ +#define USART_TDC_FLAG ((uint32_t)0x00000040) /*!< usart transmit data complete flag */ +#define USART_TDBE_FLAG ((uint32_t)0x00000080) /*!< usart transmit data buffer empty flag */ +#define USART_BFF_FLAG ((uint32_t)0x00000100) /*!< usart break frame flag */ +#define USART_CTSCF_FLAG ((uint32_t)0x00000200) /*!< usart cts change flag */ + +/** + * @} + */ + +/** @defgroup USART_interrupts_definition + * @brief usart interrupt + * @{ + */ + +#define USART_IDLE_INT MAKE_VALUE(0x0C,0x04) /*!< usart idle interrupt */ +#define USART_RDBF_INT MAKE_VALUE(0x0C,0x05) /*!< usart receive data buffer full interrupt */ +#define USART_TDC_INT MAKE_VALUE(0x0C,0x06) /*!< usart transmit data complete interrupt */ +#define USART_TDBE_INT MAKE_VALUE(0x0C,0x07) /*!< usart transmit data buffer empty interrupt */ +#define USART_PERR_INT MAKE_VALUE(0x0C,0x08) /*!< usart parity error interrupt */ +#define USART_BF_INT MAKE_VALUE(0x10,0x06) /*!< usart break frame interrupt */ +#define USART_ERR_INT MAKE_VALUE(0x14,0x00) /*!< usart error interrupt */ +#define USART_CTSCF_INT MAKE_VALUE(0x14,0x0A) /*!< usart cts change interrupt */ + +/** + * @} + */ + +/** @defgroup USART_exported_types + * @{ + */ + +/** + * @brief usart parity selection type + */ +typedef enum +{ + USART_PARITY_NONE = 0x00, /*!< usart no parity */ + USART_PARITY_EVEN = 0x01, /*!< usart even parity */ + USART_PARITY_ODD = 0x02 /*!< usart odd parity */ +} usart_parity_selection_type; + +/** + * @brief usart wakeup mode type + */ +typedef enum +{ + USART_WAKEUP_BY_IDLE_FRAME = 0x00, /*!< usart wakeup by idle frame */ + USART_WAKEUP_BY_MATCHING_ID = 0x01 /*!< usart wakeup by matching id */ +} usart_wakeup_mode_type; + +/** + * @brief usart data bit num type + */ +typedef enum +{ + USART_DATA_7BITS = 0x00, /*!< usart data size is 7 bits */ + USART_DATA_8BITS = 0x01, /*!< usart data size is 8 bits */ + USART_DATA_9BITS = 0x02 /*!< usart data size is 9 bits */ +} usart_data_bit_num_type; + +/** + * @brief usart break frame bit num type + */ +typedef enum +{ + USART_BREAK_10BITS = 0x00, /*!< usart lin mode berak frame detection 10 bits */ + USART_BREAK_11BITS = 0x01 /*!< usart lin mode berak frame detection 11 bits */ +} usart_break_bit_num_type; + +/** + * @brief usart phase of the clock type + */ +typedef enum +{ + USART_CLOCK_PHASE_1EDGE = 0x00, /*!< usart data capture is done on the clock leading edge */ + USART_CLOCK_PHASE_2EDGE = 0x01 /*!< usart data capture is done on the clock trailing edge */ +} usart_clock_phase_type; + +/** + * @brief usart polarity of the clock type + */ +typedef enum +{ + USART_CLOCK_POLARITY_LOW = 0x00, /*!< usart clock stay low level outside transmission window */ + USART_CLOCK_POLARITY_HIGH = 0x01 /*!< usart clock stay high level outside transmission window */ +} usart_clock_polarity_type; + +/** + * @brief usart last bit clock pulse type + */ +typedef enum +{ + USART_CLOCK_LAST_BIT_NONE = 0x00, /*!< usart clock pulse of the last data bit is not outputted */ + USART_CLOCK_LAST_BIT_OUTPUT = 0x01 /*!< usart clock pulse of the last data bit is outputted */ +} usart_lbcp_type; + +/** + * @brief usart stop bit num type + */ +typedef enum +{ + USART_STOP_1_BIT = 0x00, /*!< usart stop bits num is 1 */ + USART_STOP_0_5_BIT = 0x01, /*!< usart stop bits num is 0.5 */ + USART_STOP_2_BIT = 0x02, /*!< usart stop bits num is 2 */ + USART_STOP_1_5_BIT = 0x03 /*!< usart stop bits num is 1.5 */ +} usart_stop_bit_num_type; + +/** + * @brief usart hardware flow control type + */ +typedef enum +{ + USART_HARDWARE_FLOW_NONE = 0x00, /*!< usart without hardware flow */ + USART_HARDWARE_FLOW_RTS = 0x01, /*!< usart hardware flow only rts */ + USART_HARDWARE_FLOW_CTS = 0x02, /*!< usart hardware flow only cts */ + USART_HARDWARE_FLOW_RTS_CTS = 0x03 /*!< usart hardware flow both rts and cts */ +} usart_hardware_flow_control_type; + +/** + * @brief usart identification bit num type + */ +typedef enum +{ + USART_ID_FIXED_4_BIT = 0x00, /*!< usart id bit num fixed 4 bits */ + USART_ID_RELATED_DATA_BIT = 0x01 /*!< usart id bit num related data bits */ +} usart_identification_bit_num_type; + +/** + * @brief usart de polarity type + */ +typedef enum +{ + USART_DE_POLARITY_HIGH = 0x00, /*!< usart de polarity high */ + USART_DE_POLARITY_LOW = 0x01 /*!< usart de polarity low */ +} usart_de_polarity_type; + +/** + * @brief type define usart register all + */ +typedef struct +{ + /** + * @brief usart sts register, offset:0x00 + */ + union + { + __IO uint32_t sts; + struct + { + __IO uint32_t perr : 1; /* [0] */ + __IO uint32_t ferr : 1; /* [1] */ + __IO uint32_t nerr : 1; /* [2] */ + __IO uint32_t roerr : 1; /* [3] */ + __IO uint32_t idlef : 1; /* [4] */ + __IO uint32_t rdbf : 1; /* [5] */ + __IO uint32_t tdc : 1; /* [6] */ + __IO uint32_t tdbe : 1; /* [7] */ + __IO uint32_t bff : 1; /* [8] */ + __IO uint32_t ctscf : 1; /* [9] */ + __IO uint32_t reserved1 : 22;/* [31:10] */ + } sts_bit; + }; + + /** + * @brief usart dt register, offset:0x04 + */ + union + { + __IO uint32_t dt; + struct + { + __IO uint32_t dt : 9; /* [8:0] */ + __IO uint32_t reserved1 : 23;/* [31:9] */ + } dt_bit; + }; + + /** + * @brief usart baudr register, offset:0x08 + */ + union + { + __IO uint32_t baudr; + struct + { + __IO uint32_t div : 16;/* [15:0] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } baudr_bit; + }; + + /** + * @brief usart ctrl1 register, offset:0x0C + */ + union + { + __IO uint32_t ctrl1; + struct + { + __IO uint32_t sbf : 1; /* [0] */ + __IO uint32_t rm : 1; /* [1] */ + __IO uint32_t ren : 1; /* [2] */ + __IO uint32_t ten : 1; /* [3] */ + __IO uint32_t idleien : 1; /* [4] */ + __IO uint32_t rdbfien : 1; /* [5] */ + __IO uint32_t tdcien : 1; /* [6] */ + __IO uint32_t tdbeien : 1; /* [7] */ + __IO uint32_t perrien : 1; /* [8] */ + __IO uint32_t psel : 1; /* [9] */ + __IO uint32_t pen : 1; /* [10] */ + __IO uint32_t wum : 1; /* [11] */ + __IO uint32_t dbn_l : 1; /* [12] */ + __IO uint32_t uen : 1; /* [13] */ + __IO uint32_t reserved1 : 2; /* [15:14] */ + __IO uint32_t tcdt : 5; /* [20:16] */ + __IO uint32_t tsdt : 5; /* [25:21] */ + __IO uint32_t reserved2 : 2; /* [27:26] */ + __IO uint32_t dbn_h : 1; /* [28] */ + __IO uint32_t reserved3 : 3; /* [31:29] */ + } ctrl1_bit; + }; + + /** + * @brief usart ctrl2 register, offset:0x10 + */ + union + { + __IO uint32_t ctrl2; + struct + { + __IO uint32_t id_l : 4; /* [3:0] */ + __IO uint32_t idbn : 1; /* [4] */ + __IO uint32_t bfbn : 1; /* [5] */ + __IO uint32_t bfien : 1; /* [6] */ + __IO uint32_t reserved1 : 1; /* [7] */ + __IO uint32_t lbcp : 1; /* [8] */ + __IO uint32_t clkpha : 1; /* [9] */ + __IO uint32_t clkpol : 1; /* [10] */ + __IO uint32_t clken : 1; /* [11] */ + __IO uint32_t stopbn : 2; /* [13:12] */ + __IO uint32_t linen : 1; /* [14] */ + __IO uint32_t trpswap : 1; /* [15] */ + __IO uint32_t reserved2 : 12;/* [27:16] */ + __IO uint32_t id_h : 4; /* [31:28] */ + } ctrl2_bit; + }; + + /** + * @brief usart ctrl3 register, offset:0x14 + */ + union + { + __IO uint32_t ctrl3; + struct + { + __IO uint32_t errien : 1; /* [0] */ + __IO uint32_t irdaen : 1; /* [1] */ + __IO uint32_t irdalp : 1; /* [2] */ + __IO uint32_t slben : 1; /* [3] */ + __IO uint32_t scnacken : 1; /* [4] */ + __IO uint32_t scmen : 1; /* [5] */ + __IO uint32_t dmaren : 1; /* [6] */ + __IO uint32_t dmaten : 1; /* [7] */ + __IO uint32_t rtsen : 1; /* [8] */ + __IO uint32_t ctsen : 1; /* [9] */ + __IO uint32_t ctscfien : 1; /* [10] */ + __IO uint32_t reserved1 : 3; /* [13:11] */ + __IO uint32_t rs485en : 1; /* [14] */ + __IO uint32_t dep : 1; /* [15] */ + __IO uint32_t reserved2 : 16;/* [31:16] */ + } ctrl3_bit; + }; + + /** + * @brief usart gdiv register, offset:0x18 + */ + union + { + __IO uint32_t gdiv; + struct + { + __IO uint32_t isdiv : 8; /* [7:0] */ + __IO uint32_t scgt : 8; /* [15:8] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } gdiv_bit; + }; +} usart_type; + +/** + * @} + */ + +#define USART1 ((usart_type *) USART1_BASE) +#define USART2 ((usart_type *) USART2_BASE) +#define USART3 ((usart_type *) USART3_BASE) +#define UART4 ((usart_type *) UART4_BASE) +#define UART5 ((usart_type *) UART5_BASE) +#define USART6 ((usart_type *) USART6_BASE) +#define UART7 ((usart_type *) UART7_BASE) +#define UART8 ((usart_type *) UART8_BASE) + +/** @defgroup USART_exported_functions + * @{ + */ + +void usart_reset(usart_type* usart_x); +void usart_init(usart_type* usart_x, uint32_t baud_rate, usart_data_bit_num_type data_bit, usart_stop_bit_num_type stop_bit); +void usart_parity_selection_config(usart_type* usart_x, usart_parity_selection_type parity); +void usart_enable(usart_type* usart_x, confirm_state new_state); +void usart_transmitter_enable(usart_type* usart_x, confirm_state new_state); +void usart_receiver_enable(usart_type* usart_x, confirm_state new_state); +void usart_clock_config(usart_type* usart_x, usart_clock_polarity_type clk_pol, usart_clock_phase_type clk_pha, usart_lbcp_type clk_lb); +void usart_clock_enable(usart_type* usart_x, confirm_state new_state); +void usart_interrupt_enable(usart_type* usart_x, uint32_t usart_int, confirm_state new_state); +void usart_dma_transmitter_enable(usart_type* usart_x, confirm_state new_state); +void usart_dma_receiver_enable(usart_type* usart_x, confirm_state new_state); +void usart_wakeup_id_set(usart_type* usart_x, uint8_t usart_id); +void usart_wakeup_mode_set(usart_type* usart_x, usart_wakeup_mode_type wakeup_mode); +void usart_receiver_mute_enable(usart_type* usart_x, confirm_state new_state); +void usart_break_bit_num_set(usart_type* usart_x, usart_break_bit_num_type break_bit); +void usart_lin_mode_enable(usart_type* usart_x, confirm_state new_state); +void usart_data_transmit(usart_type* usart_x, uint16_t data); +uint16_t usart_data_receive(usart_type* usart_x); +void usart_break_send(usart_type* usart_x); +void usart_smartcard_guard_time_set(usart_type* usart_x, uint8_t guard_time_val); +void usart_irda_smartcard_division_set(usart_type* usart_x, uint8_t div_val); +void usart_smartcard_mode_enable(usart_type* usart_x, confirm_state new_state); +void usart_smartcard_nack_set(usart_type* usart_x, confirm_state new_state); +void usart_single_line_halfduplex_select(usart_type* usart_x, confirm_state new_state); +void usart_irda_mode_enable(usart_type* usart_x, confirm_state new_state); +void usart_irda_low_power_enable(usart_type* usart_x, confirm_state new_state); +void usart_hardware_flow_control_set(usart_type* usart_x,usart_hardware_flow_control_type flow_state); +flag_status usart_flag_get(usart_type* usart_x, uint32_t flag); +void usart_flag_clear(usart_type* usart_x, uint32_t flag); +void usart_rs485_delay_time_config(usart_type* usart_x, uint8_t start_delay_time, uint8_t complete_delay_time); +void usart_transmit_receive_pin_swap(usart_type* usart_x, confirm_state new_state); +void usart_id_bit_num_set(usart_type* usart_x, usart_identification_bit_num_type id_bit_num); +void usart_de_polarity_set(usart_type* usart_x, usart_de_polarity_type de_polarity); +void usart_rs485_mode_enable(usart_type* usart_x, confirm_state new_state); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_usb.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_usb.h new file mode 100644 index 0000000000..c6ab3b6399 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_usb.h @@ -0,0 +1,1423 @@ +/** + ************************************************************************** + * @file at32f435_437_usb.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 usb header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_USB_H +#define __AT32F435_437_USB_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup USB + * @{ + */ + +/** @defgroup USB_global_interrupts_definition + * @brief usb global interrupt mask + * @{ + */ + +#define USB_OTG_MODEMIS_INT ((uint32_t)0x00000002) /*!< usb otg mode mismatch interrupt */ +#define USB_OTG_OTGINT_INT ((uint32_t)0x00000004) /*!< usb otg interrupt */ +#define USB_OTG_SOF_INT ((uint32_t)0x00000008) /*!< usb otg sof interrupt */ +#define USB_OTG_RXFLVL_INT ((uint32_t)0x00000010) /*!< usb otg receive fifo non-empty interrupt */ +#define USB_OTG_NPTXFEMP_INT ((uint32_t)0x00000020) /*!< usb otg non-periodic tx fifo empty interrupt */ +#define USB_OTG_GINNAKEFF_INT ((uint32_t)0x00000040) /*!< usb otg global non-periodic in nak effective interrupt */ +#define USB_OTG_GOUTNAKEFF_INT ((uint32_t)0x00000080) /*!< usb otg global out nak effective interrupt */ +#define USB_OTG_ERLYSUSP_INT ((uint32_t)0x00000400) /*!< usb otg early suspend interrupt */ +#define USB_OTG_USBSUSP_INT ((uint32_t)0x00000800) /*!< usb otg suspend interrupt */ +#define USB_OTG_USBRST_INT ((uint32_t)0x00001000) /*!< usb otg reset interrupt */ +#define USB_OTG_ENUMDONE_INT ((uint32_t)0x00002000) /*!< usb otg enumeration done interrupt */ +#define USB_OTG_ISOOUTDROP_INT ((uint32_t)0x00004000) /*!< usb otg isochronous out packet dropped interrut */ +#define USB_OTG_EOPF_INT ((uint32_t)0x00008000) /*!< usb otg eop interrupt */ +#define USB_OTG_IEPT_INT ((uint32_t)0x00040000) /*!< usb otg in endpoint interrupt */ +#define USB_OTG_OEPT_INT ((uint32_t)0x00080000) /*!< usb otg out endpoint interrupt */ +#define USB_OTG_INCOMISOIN_INT ((uint32_t)0x00100000) /*!< usb otg incomplete isochronous in transfer interrupt */ +#define USB_OTG_INCOMPIP_INCOMPISOOUT_INT ((uint32_t)0x00200000) /*!< usb otg incomplete periodic transfer/isochronous out interrupt */ +#define USB_OTG_PRT_INT ((uint32_t)0x01000000) /*!< usb otg host port interrupt */ +#define USB_OTG_HCH_INT ((uint32_t)0x02000000) /*!< usb otg host channel interrupt */ +#define USB_OTG_PTXFEMP_INT ((uint32_t)0x04000000) /*!< usb otg periodic txfifo empty interrupt */ +#define USB_OTG_CONIDSCHG_INT ((uint32_t)0x10000000) /*!< usb otg connector id status change interrupt */ +#define USB_OTG_DISCON_INT ((uint32_t)0x20000000) /*!< usb otg disconnect detected interrupt */ +#define USB_OTG_WKUP_INT ((uint32_t)0x80000000) /*!< usb otg wakeup interrupt */ + +/** + * @} + */ + +/** @defgroup USB_global_interrupt_flags_definition + * @brief usb global interrupt flag + * @{ + */ + +#define USB_OTG_CURMODE ((uint32_t)0x00000001) /*!< usb otg current mode */ +#define USB_OTG_MODEMIS_FLAG ((uint32_t)0x00000002) /*!< usb otg mode mismatch flag */ +#define USB_OTG_OTGINT_FLAG ((uint32_t)0x00000004) /*!< usb otg flag */ +#define USB_OTG_SOF_FLAG ((uint32_t)0x00000008) /*!< usb otg sof flag */ +#define USB_OTG_RXFLVL_FLAG ((uint32_t)0x00000010) /*!< usb otg receive fifo non-empty flag */ +#define USB_OTG_NPTXFEMP_FLAG ((uint32_t)0x00000020) /*!< usb otg non-periodic tx fifo empty flag */ +#define USB_OTG_GINNAKEFF_FLAG ((uint32_t)0x00000040) /*!< usb otg global non-periodic in nak effective flag */ +#define USB_OTG_GOUTNAKEFF_FLAG ((uint32_t)0x00000080) /*!< usb otg global out nak effective flag */ +#define USB_OTG_ERLYSUSP_FLAG ((uint32_t)0x00000400) /*!< usb otg early suspend flag */ +#define USB_OTG_USBSUSP_FLAG ((uint32_t)0x00000800) /*!< usb otg suspend flag */ +#define USB_OTG_USBRST_FLAG ((uint32_t)0x00001000) /*!< usb otg reset flag */ +#define USB_OTG_ENUMDONE_FLAG ((uint32_t)0x00002000) /*!< usb otg enumeration done flag */ +#define USB_OTG_ISOOUTDROP_FLAG ((uint32_t)0x00004000) /*!< usb otg isochronous out packet dropped flag */ +#define USB_OTG_EOPF_FLAG ((uint32_t)0x00008000) /*!< usb otg eop flag */ +#define USB_OTG_IEPT_FLAG ((uint32_t)0x00040000) /*!< usb otg in endpoint flag */ +#define USB_OTG_OEPT_FLAG ((uint32_t)0x00080000) /*!< usb otg out endpoint flag */ +#define USB_OTG_INCOMISOIN_FLAG ((uint32_t)0x00100000) /*!< usb otg incomplete isochronous in transfer flag */ +#define USB_OTG_INCOMPIP_INCOMPISOOUT_FLAG ((uint32_t)0x00200000) /*!< usb otg incomplete periodic transfer/isochronous out flag */ +#define USB_OTG_PRT_FLAG ((uint32_t)0x01000000) /*!< usb otg host port flag */ +#define USB_OTG_HCH_FLAG ((uint32_t)0x02000000) /*!< usb otg host channel flag */ +#define USB_OTG_PTXFEMP_FLAG ((uint32_t)0x04000000) /*!< usb otg periodic txfifo empty flag */ +#define USB_OTG_CONIDSCHG_FLAG ((uint32_t)0x10000000) /*!< usb otg connector id status change flag */ +#define USB_OTG_DISCON_FLAG ((uint32_t)0x20000000) /*!< usb otg disconnect detected flag */ +#define USB_OTG_WKUP_FLAG ((uint32_t)0x80000000) /*!< usb otg wakeup flag */ + +/** + * @} + */ + + +/** @defgroup USB_global_setting_definition + * @brief usb global setting + * @{ + */ + +/** + * @brief usb turnaround time + */ +#define USB_TRDTIM_8 0x9 /*!< usb turn around time 8 */ +#define USB_TRDTIM_16 0x5 /*!< usb turn around time 16 */ + +/** + * @brief usb receive status + */ +#define USB_OTG_GRXSTSP_EPTNUM ((uint32_t)0x0000000F) /*!< usb device receive packet endpoint number*/ +#define USB_OTG_GRXSTSP_CHNUM ((uint32_t)0x0000000F) /*!< usb host receive packet channel number*/ +#define USB_OTG_GRXSTSP_BCNT ((uint32_t)0x00007FF0) /*!< usb receive packet byte count */ +#define USB_OTG_GRXSTSP_DPID ((uint32_t)0x00018000) /*!< usb receive packet pid */ +#define USB_OTG_GRXSTSP_PKTSTS ((uint32_t)0x001E0000) /*!< usb receive packet status */ + +/** + * @brief usb host packet status + */ +#define PKTSTS_IN_DATA_PACKET_RECV 0x2 /*!< usb host in data packet received */ +#define PKTSTS_IN_TRANSFER_COMPLETE 0x3 /*!< usb host in transfer completed */ +#define PKTSTS_DATA_BIT_ERROR 0x5 /*!< usb host data toggle error */ +#define PKTSTS_CHANNEL_STOP 0x7 /*!< usb host channel halted */ + +/** + * @brief usb device packet status + */ +#define USB_OUT_STS_NAK 0x1 /*!< usb device global out nak */ +#define USB_OUT_STS_DATA 0x2 /*!< usb device out data packet received */ +#define USB_OUT_STS_COMP 0x3 /*!< usb device out transfer completed */ +#define USB_SETUP_STS_COMP 0x4 /*!< usb device setup transcation completed */ +#define USB_SETUP_STS_DATA 0x6 /*!< usb device setup data packet received */ + +/** + * @} + */ + +/** @defgroup USB_host_config_definition + * @{ + */ + +/** + * @brief usb host phy clock + */ +#define USB_HCFG_CLK_60M 0 /*!< usb host phy clock 60mhz */ +#define USB_HCFG_CLK_48M 1 /*!< usb host phy clock 48mhz */ +#define USB_HCFG_CLK_6M 2 /*!< usb host phy clock 6mhz */ + +/** + * @brief usb host port status + */ +#define USB_OTG_HPRT_PRTCONSTS ((uint32_t)0x00000001) /*!< usb host port connect status */ +#define USB_OTG_HPRT_PRTCONDET ((uint32_t)0x00000002) /*!< usb host port connect detected */ +#define USB_OTG_HPRT_PRTENA ((uint32_t)0x00000004) /*!< usb host port enable */ +#define USB_OTG_HPRT_PRTENCHNG ((uint32_t)0x00000008) /*!< usb host port enable/disable change */ +#define USB_OTG_HPRT_PRTOVRCACT ((uint32_t)0x00000010) /*!< usb host port overcurrent active */ +#define USB_OTG_HPRT_PRTOVRCCHNG ((uint32_t)0x00000020) /*!< usb host port overcurrent change */ +#define USB_OTG_HPRT_PRTRES ((uint32_t)0x00000040) /*!< usb host port resume */ +#define USB_OTG_HPRT_PRTSUSP ((uint32_t)0x00000080) /*!< usb host port suspend */ +#define USB_OTG_HPRT_PRTRST ((uint32_t)0x00000100) /*!< usb host port reset */ +#define USB_OTG_HPRT_PRTLNSTS ((uint32_t)0x00000C00) /*!< usb host port line status */ +#define USB_OTG_HPRT_PRTPWR ((uint32_t)0x00001000) /*!< usb host port power */ +#define USB_OTG_HPRT_PRTSPD ((uint32_t)0x00060000) /*!< usb host port speed */ + +/** + * @brief usb port speed + */ +#define USB_PRTSPD_HIGH_SPEED 0 /*!< usb host port high speed */ +#define USB_PRTSPD_FULL_SPEED 1 /*!< usb host port full speed */ +#define USB_PRTSPD_LOW_SPEED 2 /*!< usb host port low speed */ + +/** + * @brief usb host register hcchar bit define + */ +#define USB_OTG_HCCHAR_MPS ((uint32_t)0x000007FF) /*!< channel maximum packet size */ +#define USB_OTG_HCCHAR_EPTNUM ((uint32_t)0x00007800) /*!< endpoint number */ +#define USB_OTG_HCCHAR_EPTDIR ((uint32_t)0x00008000) /*!< endpoint direction */ +#define USB_OTG_HCCHAR_LSPDDEV ((uint32_t)0x00020000) /*!< low speed device */ +#define USB_OTG_HCCHAR_EPTYPE ((uint32_t)0x000C0000) /*!< endpoint type */ +#define USB_OTG_HCCHAR_MC ((uint32_t)0x00300000) /*!< multi count */ +#define USB_OTG_HCCHAR_DEVADDR ((uint32_t)0x1FC00000) /*!< device address */ +#define USB_OTG_HCCHAR_ODDFRM ((uint32_t)0x20000000) /*!< odd frame */ +#define USB_OTG_HCCHAR_CHDIS ((uint32_t)0x40000000) /*!< channel disable */ +#define USB_OTG_HCCHAR_CHENA ((uint32_t)0x80000000) /*!< channel enable */ + +/** + * @brief usb host register hctsiz bit define + */ +#define USB_OTG_HCTSIZ_XFERSIZE ((uint32_t)0x0007FFFF) /*!< channel transfer size */ +#define USB_OTG_HCTSIZ_PKTCNT ((uint32_t)0x1FF80000) /*!< channel packet count */ +#define USB_OTG_HCTSIZ_PID ((uint32_t)0x60000000) /*!< channel pid */ + +/** + * @brief usb host channel interrupt mask + */ +#define USB_OTG_HC_XFERCM_INT ((uint32_t)0x00000001) /*!< channel transfer complete interrupt */ +#define USB_OTG_HC_CHHLTDM_INT ((uint32_t)0x00000002) /*!< channel halted interrupt */ +#define USB_OTG_HC_STALLM_INT ((uint32_t)0x00000008) /*!< channel stall interrupt */ +#define USB_OTG_HC_NAKM_INT ((uint32_t)0x00000010) /*!< channel nak interrupt */ +#define USB_OTG_HC_ACKM_INT ((uint32_t)0x00000020) /*!< channel ack interrupt */ +#define USB_OTG_HC_NYETM_INT ((uint32_t)0x00000040) /*!< channel nyet interrupt */ +#define USB_OTG_HC_XACTERRM_INT ((uint32_t)0x00000080) /*!< channel transaction error interrupt */ +#define USB_OTG_HC_BBLERRM_INT ((uint32_t)0x00000100) /*!< channel babble error interrupt */ +#define USB_OTG_HC_FRMOVRRUN_INT ((uint32_t)0x00000200) /*!< channel frame overrun interrupt */ +#define USB_OTG_HC_DTGLERRM_INT ((uint32_t)0x00000400) /*!< channel data toggle interrupt */ + +/** + * @brief usb host channel interrupt flag + */ +#define USB_OTG_HC_XFERC_FLAG ((uint32_t)0x00000001) /*!< channel transfer complete flag */ +#define USB_OTG_HC_CHHLTD_FLAG ((uint32_t)0x00000002) /*!< channel halted flag */ +#define USB_OTG_HC_STALL_FLAG ((uint32_t)0x00000008) /*!< channel stall flag */ +#define USB_OTG_HC_NAK_FLAG ((uint32_t)0x00000010) /*!< channel nak flag */ +#define USB_OTG_HC_ACK_FLAG ((uint32_t)0x00000020) /*!< channel ack flag */ +#define USB_OTG_HC_NYET_FLAG ((uint32_t)0x00000040) /*!< channel nyet flag */ +#define USB_OTG_HC_XACTERR_FLAG ((uint32_t)0x00000080) /*!< channel transaction error flag */ +#define USB_OTG_HC_BBLERR_FLAG ((uint32_t)0x00000100) /*!< channel babble error flag */ +#define USB_OTG_HC_FRMOVRRUN_FLAG ((uint32_t)0x00000200) /*!< channel frame overrun flag */ +#define USB_OTG_HC_DTGLERR_FLAG ((uint32_t)0x00000400) /*!< channel data toggle flag */ + +/** + * @} + */ + + +/** @defgroup USB_device_config_definition + * @{ + */ +/** + * @brief usb device periodic frame interval + */ +typedef enum +{ + DCFG_PERFRINT_80 = 0x00, /*!< periodic frame interval 80% */ + DCFG_PERFRINT_85 = 0x01, /*!< periodic frame interval 85% */ + DCFG_PERFRINT_90 = 0x02, /*!< periodic frame interval 90% */ + DCFG_PERFRINT_95 = 0x03 /*!< periodic frame interval 95% */ +} dcfg_perfrint_type; + + +/** + * @brief usb device full speed + */ +#define USB_DCFG_FULL_SPEED 3 /*!< device full speed */ + +/** + * @brief usb device ctrl define + */ +#define USB_OTG_DCTL_RWKUPSIG ((uint32_t)0x00000001) /*!< usb device remote wakeup signaling */ +#define USB_OTG_DCTL_SFTDISCON ((uint32_t)0x00000002) /*!< usb device soft disconnect */ +#define USB_OTG_DCTL_GNPINNAKSTS ((uint32_t)0x00000004) /*!< usb device global non-periodic in nak status */ +#define USB_OTG_DCTL_GOUTNAKSTS ((uint32_t)0x00000008) /*!< usb device global out nak status */ +#define USB_OTG_DCTL_SGNPINNAK ((uint32_t)0x00000080) /*!< usb device set global non-periodic in nak */ +#define USB_OTG_DCTL_CGNPINNAK ((uint32_t)0x00000100) /*!< usb device clear global non-periodic in nak */ +#define USB_OTG_DCTL_SGOUTNAK ((uint32_t)0x00000200) /*!< usb device set global out nak status */ +#define USB_OTG_DCTL_CGOUTNAK ((uint32_t)0x00000400) /*!< usb device clear global out nak status */ +#define USB_OTG_DCTL_PWROPRGDNE ((uint32_t)0x00000800) /*!< usb device power on programming done */ + +/** + * @brief usb device in endpoint flag + */ +#define USB_OTG_DIEPINT_XFERC_FLAG ((uint32_t)0x00000001) /*!< usb device in transfer completed flag */ +#define USB_OTG_DIEPINT_EPTDISD_FLAG ((uint32_t)0x00000002) /*!< usb device endpoint disable flag */ +#define USB_OTG_DIEPINT_TIMEOUT_FLAG ((uint32_t)0x00000008) /*!< usb device in timeout */ +#define USB_OTG_DIEPINT_INTKNTXFEMP_FLAG ((uint32_t)0x00000010) /*!< usb device in token received when tx fifo is empty flag */ +#define USB_OTG_DIEPINT_INEPTNAK_FLAG ((uint32_t)0x00000040) /*!< usb device in endpoint nak effective flag */ +#define USB_OTG_DIEPINT_TXFEMP_FLAG ((uint32_t)0x00000080) /*!< usb device transmit fifo empty flag */ + +/** + * @brief usb device out endpoint flag + */ +#define USB_OTG_DOEPINT_XFERC_FLAG ((uint32_t)0x00000001) /*!< usb device out transfer completed flag */ +#define USB_OTG_DOEPINT_EPTDISD_FLAG ((uint32_t)0x00000002) /*!< usb device endpoint disable flag */ +#define USB_OTG_DOEPINT_SETUP_FLAG ((uint32_t)0x00000008) /*!< usb device setup flag */ +#define USB_OTG_DOEPINT_OUTTEPD_FLAG ((uint32_t)0x00000010) /*!< usb device out token recevied when endpoint disable flag */ +#define USB_OTG_DOEPINT_B2BSTUP_FLAG ((uint32_t)0x00000040) /*!< back-to-back setup packets received */ + +/** + * @brief usb device in endpoint fifo space mask + */ +#define USB_OTG_DTXFSTS_INEPTFSAV ((uint32_t)0x0000FFFF) /*!< usb device in endpoint tx fifo space avail */ + +/** + * @brief endpoint0 maximum packet size + */ +#define USB_EPT0_MPS_64 0 /*!< usb device endpoint 0 maximum packet size 64byte */ +#define USB_EPT0_MPS_32 1 /*!< usb device endpoint 0 maximum packet size 32byte */ +#define USB_EPT0_MPS_16 2 /*!< usb device endpoint 0 maximum packet size 16byte */ +#define USB_EPT0_MPS_8 3 /*!< usb device endpoint 0 maximum packet size 8byte */ + +/** + * @} + */ + +/** + * @brief otg fifo size (word) + */ +#define OTG_FIFO_SIZE 320 /*!< otg usb total fifo size */ + +/** + * @brief otg host max buffer length (byte) + */ +#define USB_MAX_DATA_LENGTH 0x200 /*!< usb host maximum buffer size */ + +#define OTGFS_USB_GLOBAL +#define OTGFS_USB_DEVICE +#define OTGFS_USB_HOST + +/** @defgroup USB_exported_enum_types + * @{ + */ + +/** + * @brief usb mode define(device, host, drd) + */ +typedef enum +{ + OTG_DEVICE_MODE, /*!< usb device mode */ + OTG_HOST_MODE, /*!< usb host mode */ + OTG_DRD_MODE /*!< usb drd mode */ +} otg_mode_type; + +/** + * @brief endpoint type define + */ +typedef enum +{ + EPT_CONTROL_TYPE = 0x00, /*!< usb endpoint type control */ + EPT_ISO_TYPE = 0x01, /*!< usb endpoint type iso */ + EPT_BULK_TYPE = 0x02, /*!< usb endpoint type bulk */ + EPT_INT_TYPE = 0x03 /*!< usb endpoint type interrupt */ +} endpoint_trans_type; + +/** + * @brief usb endpoint number define type + */ +typedef enum +{ + USB_EPT0 = 0x00, /*!< usb endpoint 0 */ + USB_EPT1 = 0x01, /*!< usb endpoint 1 */ + USB_EPT2 = 0x02, /*!< usb endpoint 2 */ + USB_EPT3 = 0x03, /*!< usb endpoint 3 */ + USB_EPT4 = 0x04, /*!< usb endpoint 4 */ + USB_EPT5 = 0x05, /*!< usb endpoint 5 */ + USB_EPT6 = 0x06, /*!< usb endpoint 6 */ + USB_EPT7 = 0x07 /*!< usb endpoint 7 */ +} usb_endpoint_number_type; + +/** + * @brief usb endpoint max num define + */ +#ifndef USB_EPT_MAX_NUM +#define USB_EPT_MAX_NUM 8 /*!< usb device support endpoint number */ +#endif +/** + * @brief usb channel max num define + */ +#ifndef USB_HOST_CHANNEL_NUM +#define USB_HOST_CHANNEL_NUM 16 /*!< usb host support channel number */ +#endif + +/** + * @brief endpoint trans dir type + */ +typedef enum +{ + EPT_DIR_IN = 0x00, /*!< usb transfer direction in */ + EPT_DIR_OUT = 0x01 /*!< usb transfer direction out */ +} endpoint_dir_type; + +/** + * @brief otgfs1 and otgfs2 select type + */ +typedef enum +{ + USB_OTG1_ID, /*!< usb otg 1 id */ + USB_OTG2_ID /*!< usb otg 2 id */ +} otg_id_type; + +/** + * @brief usb clock select + */ +typedef enum +{ + USB_CLK_HICK, /*!< usb clock use hick */ + USB_CLK_HEXT /*!< usb clock use hext */ +}usb_clk48_s; + +/** + * @} + */ + + + +/** @defgroup USB_exported_types + * @{ + */ + +/** + * @brief usb endpoint infomation structure definition + */ +typedef struct +{ + uint8_t eptn; /*!< endpoint register number (0~7) */ + uint8_t ept_address; /*!< endpoint address */ + uint8_t inout; /*!< endpoint dir EPT_DIR_IN or EPT_DIR_OUT */ + uint8_t trans_type; /*!< endpoint type: + EPT_CONTROL_TYPE, EPT_BULK_TYPE, EPT_INT_TYPE, EPT_ISO_TYPE*/ + uint16_t tx_addr; /*!< endpoint tx buffer offset address */ + uint16_t rx_addr; /*!< endpoint rx buffer offset address */ + uint32_t maxpacket; /*!< endpoint max packet*/ + uint8_t is_double_buffer; /*!< endpoint double buffer flag */ + uint8_t stall; /*!< endpoint is stall state */ + uint32_t status; + + /* transmission buffer and count */ + uint8_t *trans_buf; /*!< endpoint transmission buffer */ + uint32_t total_len; /*!< endpoint transmission lengtg */ + uint32_t trans_len; /*!< endpoint transmission length*/ + + uint32_t last_len; /*!< last transfer length */ + uint32_t rem0_len; /*!< rem transfer length */ + uint32_t ept0_slen; /*!< endpoint 0 transfer sum length */ +} usb_ept_info; + + +/** + * @brief usb host channel infomation structure definition + */ +typedef struct +{ + uint8_t ch_num; /*!< host channel number */ + uint8_t address; /*!< device address */ + uint8_t dir; /*!< transmission direction */ + uint8_t ept_num; /*!< device endpoint number */ + uint8_t ept_type; /*!< channel transmission type */ + uint32_t maxpacket; /*!< support max packet size */ + uint8_t data_pid; /*!< data pid */ + uint8_t speed; /*!< usb speed */ + uint8_t stall; /*!< channel stall flag */ + uint32_t status; /*!< channel status */ + uint32_t state; /*!< channel state */ + uint32_t urb_sts; /*!< usb channel request block state */ + + uint8_t toggle_in; /*!< channel in transfer toggle */ + uint8_t toggle_out; /*!< channel out transfer toggle */ + + /* transmission buffer and count */ + uint8_t *trans_buf; /* host channel buffer */ + uint32_t trans_len; /* host channel transmission len */ + uint32_t trans_count; /* host channel transmission count*/ +} usb_hch_type; + + +typedef struct +{ + /** + * @brief otgfs control and status register, offset:0x00 + */ + union + { + __IO uint32_t gotgctrl; + struct + { + __IO uint32_t reserved1 : 16; /* [15:0] */ + __IO uint32_t cidsts : 1; /* [16] */ + __IO uint32_t reserved2 : 4; /* [20:17] */ + __IO uint32_t curmod : 1; /* [21] */ + __IO uint32_t reserved3 : 10; /* [31:22] */ + } gotgctrl_bit; + }; + + /** + * @brief otgfs interrupt register, offset:0x04 + */ + union + { + __IO uint32_t gotgint; + struct + { + __IO uint32_t reserved1 : 2; /* [1:0] */ + __IO uint32_t sesenddet : 1; /* [2] */ + __IO uint32_t reserved2 : 29; /* [31:3] */ + + } gotgint_bit; + }; + + /** + * @brief otgfs gahbcfg configuration register, offset:0x08 + */ + union + { + __IO uint32_t gahbcfg; + struct + { + __IO uint32_t glbintmsk : 1; /* [0] */ + __IO uint32_t reserved1 : 6; /* [6:1] */ + __IO uint32_t nptxfemplvl : 1; /* [7] */ + __IO uint32_t ptxfemplvl : 1; /* [8] */ + __IO uint32_t reserved2 : 23; /* [31:9] */ + } gahbcfg_bit; + }; + + /** + * @brief otgfs usb configuration register, offset:0x0C + */ + union + { + __IO uint32_t gusbcfg; + struct + { + __IO uint32_t toutcal : 3; /* [2:0] */ + __IO uint32_t reserved1 : 7; /* [9:3] */ + __IO uint32_t usbtrdtim : 4; /* [13:10] */ + __IO uint32_t reserved2 : 15; /* [28:14] */ + __IO uint32_t fhstmode : 1; /* [29] */ + __IO uint32_t fdevmode : 1; /* [30] */ + __IO uint32_t cotxpkt : 1; /* [31] */ + } gusbcfg_bit; + }; + + /** + * @brief otgfs reset register, offset:0x10 + */ + union + { + __IO uint32_t grstctl; + struct + { + __IO uint32_t csftrst : 1; /* [0] */ + __IO uint32_t piusftrst : 1; /* [1] */ + __IO uint32_t frmcntrst : 1; /* [2] */ + __IO uint32_t reserved1 : 1; /* [3] */ + __IO uint32_t rxfflsh : 1; /* [4] */ + __IO uint32_t txfflsh : 1; /* [5] */ + __IO uint32_t txfnum : 5; /* [10:6] */ + __IO uint32_t reserved2 : 20; /* [30:11] */ + __IO uint32_t ahbidle : 1; /* [31] */ + } grstctl_bit; + }; + + /** + * @brief otgfs core interrupt register, offset:0x14 + */ + union + { + __IO uint32_t gintsts; + struct + { + __IO uint32_t curmode : 1; /* [0] */ + __IO uint32_t modemis : 1; /* [1] */ + __IO uint32_t otgint : 1; /* [2] */ + __IO uint32_t sof : 1; /* [3] */ + __IO uint32_t rxflvl : 1; /* [4] */ + __IO uint32_t nptxfemp : 1; /* [5] */ + __IO uint32_t ginnakeff : 1; /* [6] */ + __IO uint32_t goutnakeff : 1; /* [7] */ + __IO uint32_t reserved1 : 2; /* [9:8]] */ + __IO uint32_t erlysusp : 1; /* [10] */ + __IO uint32_t usbsusp : 1; /* [11] */ + __IO uint32_t usbrst : 1; /* [12] */ + __IO uint32_t enumdone : 1; /* [13] */ + __IO uint32_t isooutdrop : 1; /* [14] */ + __IO uint32_t eopf : 1; /* [15] */ + __IO uint32_t reserved2 : 2; /* [17:16]] */ + __IO uint32_t ieptint : 1; /* [18] */ + __IO uint32_t oeptint : 1; /* [19] */ + __IO uint32_t incompisoin : 1; /* [20] */ + __IO uint32_t incompip_incompisoout : 1; /* [21] */ + __IO uint32_t reserved3 : 2; /* [23:22] */ + __IO uint32_t prtint : 1; /* [24] */ + __IO uint32_t hchint : 1; /* [25] */ + __IO uint32_t ptxfemp : 1; /* [26] */ + __IO uint32_t reserved4 : 1; /* [27] */ + __IO uint32_t conidschg : 1; /* [28] */ + __IO uint32_t disconint : 1; /* [29] */ + __IO uint32_t reserved5 : 1; /* [30] */ + __IO uint32_t wkupint : 1; /* [31] */ + } gintsts_bit; + }; + + /** + * @brief otgfs interrupt mask register, offset:0x18 + */ + union + { + __IO uint32_t gintmsk; + struct + { + __IO uint32_t reserved1 : 1; /* [0] */ + __IO uint32_t modemismsk : 1; /* [1] */ + __IO uint32_t otgintmsk : 1; /* [2] */ + __IO uint32_t sofmsk : 1; /* [3] */ + __IO uint32_t rxflvlmsk : 1; /* [4] */ + __IO uint32_t nptxfempmsk : 1; /* [5] */ + __IO uint32_t ginnakeffmsk : 1; /* [6] */ + __IO uint32_t goutnakeffmsk : 1; /* [7] */ + __IO uint32_t reserved2 : 2; /* [9:8]] */ + __IO uint32_t erlysuspmsk : 1; /* [10] */ + __IO uint32_t usbsuspmsk : 1; /* [11] */ + __IO uint32_t usbrstmsk : 1; /* [12] */ + __IO uint32_t enumdonemsk : 1; /* [13] */ + __IO uint32_t isooutdropmsk : 1; /* [14] */ + __IO uint32_t eopfmsk : 1; /* [15] */ + __IO uint32_t reserved3 : 2; /* [17:16]] */ + __IO uint32_t ieptintmsk : 1; /* [18] */ + __IO uint32_t oeptintmsk : 1; /* [19] */ + __IO uint32_t incompisoinmsk : 1; /* [20] */ + __IO uint32_t incompip_incompisooutmsk : 1; /* [21] */ + __IO uint32_t reserved4 : 2; /* [23:22] */ + __IO uint32_t prtintmsk : 1; /* [24] */ + __IO uint32_t hchintmsk : 1; /* [25] */ + __IO uint32_t ptxfempmsk : 1; /* [26] */ + __IO uint32_t reserved5 : 1; /* [27] */ + __IO uint32_t conidschgmsk : 1; /* [28] */ + __IO uint32_t disconintmsk : 1; /* [29] */ + __IO uint32_t reserved6 : 1; /* [30] */ + __IO uint32_t wkupintmsk : 1; /* [31] */ + } gintmsk_bit; + }; + + /** + * @brief otgfs rx status debug read register, offset:0x1C + */ + union + { + __IO uint32_t grxstsr; + struct + { + __IO uint32_t eptnum : 4; /* [3:0] */ + __IO uint32_t bcnt : 11; /* [14:4] */ + __IO uint32_t dpid : 2; /* [16:15] */ + __IO uint32_t pktsts : 4; /* [20:17] */ + __IO uint32_t fn : 4; /* [24:21] */ + __IO uint32_t reserved1 : 7; /* [31:25] */ + } grxstsr_bit; + }; + + /** + * @brief otgfs rx status read and pop register, offset:0x20 + */ + union + { + __IO uint32_t grxstsp; + struct + { + __IO uint32_t chnum : 4; /* [3:0] */ + __IO uint32_t bcnt : 11; /* [14:4] */ + __IO uint32_t dpid : 2; /* [16:15] */ + __IO uint32_t pktsts : 4; /* [20:17] */ + __IO uint32_t reserved1 : 11; /* [31:21] */ + } grxstsp_bit; + }; + + /** + * @brief otgfs rx fifo size register, offset:0x24 + */ + union + { + __IO uint32_t grxfsiz; + struct + { + __IO uint32_t rxfdep : 16; /* [15:0] */ + __IO uint32_t reserved1 : 16; /* [31:16] */ + } grxfsiz_bit; + }; + + /** + * @brief otgfs non-periodic and ept0 tx fifo size register, offset:0x28 + */ + union + { + __IO uint32_t gnptxfsiz_ept0tx; + struct + { + __IO uint32_t nptxfstaddr : 16; /* [15:0] */ + __IO uint32_t nptxfdep : 16; /* [31:16] */ + } gnptxfsiz_ept0tx_bit; + }; + + /** + * @brief otgfs non-periodic tx fifo request queue status register, offset:0x2C + */ + union + { + __IO uint32_t gnptxsts; + struct + { + __IO uint32_t nptxfspcavail : 16; /* [15:0] */ + __IO uint32_t nptxqspcavail : 8; /* [23:16] */ + __IO uint32_t nptxqtop : 7; /* [30:24] */ + } gnptxsts_bit; + }; + + __IO uint32_t reserved2[2]; + + /** + * @brief otgfs general core configuration register, offset:0x38 + */ + union + { + __IO uint32_t gccfg; + struct + { + __IO uint32_t reserved1 : 16; /* [15:0] */ + __IO uint32_t pwrdown : 1; /* [16] */ + __IO uint32_t lp_mode : 1; /* [17] */ + __IO uint32_t reserved2 : 2; /* [19:18] */ + __IO uint32_t sofouten : 1; /* [20] */ + __IO uint32_t vbusig : 1; /* [21] */ + __IO uint32_t reserved3 : 10; /* [31:22] */ + } gccfg_bit; + }; + + /** + * @brief otgfs core id register, offset:0x3C + */ + union + { + __IO uint32_t guid; + struct + { + __IO uint32_t userid : 32; /* [31:0] */ + } guid_bit; + }; + + __IO uint32_t reserved3[48]; + + /** + * @brief otgfs host periodic tx fifo size register, offset:0x100 + */ + union + { + __IO uint32_t hptxfsiz; + struct + { + __IO uint32_t ptxfstaddr : 16; /* [15:0] */ + __IO uint32_t ptxfsize : 16; /* [31:16] */ + } hptxfsiz_bit; + }; + + /** + * @brief otgfs host periodic tx fifo size register, offset:0x100 + */ + union + { + __IO uint32_t dieptxfn[7]; + struct + { + __IO uint32_t ineptxfstaddr : 16; /* [15:0] */ + __IO uint32_t ineptxfdep : 16; /* [31:16] */ + } dieptxfn_bit[7]; + }; +} otg_global_type; + + +typedef struct +{ + /** + * @brief otgfs host mode configuration register, offset:0x400 + */ + union + { + __IO uint32_t hcfg; + struct + { + __IO uint32_t fslspclksel : 2; /* [1:0] */ + __IO uint32_t fslssupp : 1; /* [2] */ + __IO uint32_t reserved1 : 29; /* [31:3] */ + } hcfg_bit; + }; + + /** + * @brief otgfs host frame interval register, offset:0x404 + */ + union + { + __IO uint32_t hfir; + struct + { + __IO uint32_t frint : 16; /* [15:0] */ + __IO uint32_t reserved1 : 16; /* [31:15] */ + } hfir_bit; + }; + + /** + * @brief otgfs host frame number and time remaining register, offset:0x408 + */ + union + { + __IO uint32_t hfnum; + struct + { + __IO uint32_t frnum : 16; /* [15:0] */ + __IO uint32_t ftrem : 16; /* [31:15] */ + } hfnum_bit; + }; + + __IO uint32_t reserved1; + + /** + * @brief otgfs host periodic tx fifo request queue register, offset:0x410 + */ + union + { + __IO uint32_t hptxsts; + struct + { + __IO uint32_t ptxfspcavil : 16; /* [15:0] */ + __IO uint32_t ptxqspcavil : 8; /* [23:16] */ + __IO uint32_t ptxqtop : 8; /* [31:24] */ + } hptxsts_bit; + }; + + /** + * @brief otgfs host all channel interrupt register, offset:0x414 + */ + union + { + __IO uint32_t haint; + struct + { + __IO uint32_t haint : 16; /* [15:0] */ + __IO uint32_t reserved1 : 16; /* [32:16] */ + } haint_bit; + }; + + /** + * @brief otgfs host all channel interrupt mask register, offset:0x418 + */ + union + { + __IO uint32_t haintmsk; + struct + { + __IO uint32_t haintmsk : 16; /* [15:0] */ + __IO uint32_t reserved1 : 16; /* [32:16] */ + } haintmsk_bit; + }; + + __IO uint32_t reserved2[9]; + + /** + * @brief otgfs host port control and status register, offset:0x440 + */ + union + { + __IO uint32_t hprt; + struct + { + __IO uint32_t prtconsts : 1; /* [0] */ + __IO uint32_t prtcondet : 1; /* [1] */ + __IO uint32_t prtena : 1; /* [2] */ + __IO uint32_t prtenchng : 1; /* [3] */ + __IO uint32_t prtovrcact : 1; /* [4] */ + __IO uint32_t prtovrcchng : 1; /* [5] */ + __IO uint32_t prtres : 1; /* [6] */ + __IO uint32_t prtsusp : 1; /* [7] */ + __IO uint32_t prtrst : 1; /* [8] */ + __IO uint32_t reserved1 : 1; /* [9] */ + __IO uint32_t prtlnsts : 2; /* [11:10] */ + __IO uint32_t prtpwr : 1; /* [12] */ + __IO uint32_t prttsctl : 4; /* [16:13] */ + __IO uint32_t prtspd : 2; /* [18:17] */ + __IO uint32_t reserved2 : 13; /* [31:19] */ + + } hprt_bit; + }; +} otg_host_type; + +typedef struct +{ + /** + * @brief otgfs host channel x characterisic register, offset:0x500 + */ + union + { + __IO uint32_t hcchar; + struct + { + __IO uint32_t mps : 11; /* [10:0] */ + __IO uint32_t eptnum : 4; /* [14:11] */ + __IO uint32_t eptdir : 1; /* [15] */ + __IO uint32_t reserved1 : 1; /* [16] */ + __IO uint32_t lspddev : 1; /* [17] */ + __IO uint32_t eptype : 2; /* [19:18] */ + __IO uint32_t mc : 2; /* [21:20] */ + __IO uint32_t devaddr : 7; /* [28:22] */ + __IO uint32_t oddfrm : 1; /* [29] */ + __IO uint32_t chdis : 1; /* [30] */ + __IO uint32_t chena : 1; /* [31] */ + } hcchar_bit; + }; + + /** + * @brief otgfs host channel split control register, offset:0x504 + */ + union + { + __IO uint32_t hcsplt; + struct + { + __IO uint32_t prtaddr : 7; /* [6:0] */ + __IO uint32_t hubaddr : 7; /* [13:7] */ + __IO uint32_t xactpos : 2; /* [15:14] */ + __IO uint32_t compsplt : 1; /* [16] */ + __IO uint32_t reserved1 : 14; /* [30:17] */ + __IO uint32_t spltena : 1; /* [31] */ + } hcsplt_bit; + }; + + /** + * @brief otgfs host channel interrupt register, offset:0x508 + */ + union + { + __IO uint32_t hcint; + struct + { + __IO uint32_t xferc : 1; /* [0] */ + __IO uint32_t chhltd : 1; /* [1] */ + __IO uint32_t reserved1 : 1; /* [2] */ + __IO uint32_t stall : 1; /* [3] */ + __IO uint32_t nak : 1; /* [4] */ + __IO uint32_t ack : 1; /* [5] */ + __IO uint32_t reserved2 : 1; /* [6] */ + __IO uint32_t xacterr : 1; /* [7] */ + __IO uint32_t bblerr : 1; /* [8] */ + __IO uint32_t frmovrun : 1; /* [9] */ + __IO uint32_t dtglerr : 1; /* [10] */ + __IO uint32_t reserved3 : 21; /* [31:11] */ + } hcint_bit; + }; + + /** + * @brief otgfs host channel interrupt mask register, offset:0x50C + */ + union + { + __IO uint32_t hcintmsk; + struct + { + __IO uint32_t xfercmsk : 1; /* [0] */ + __IO uint32_t chhltdmsk : 1; /* [1] */ + __IO uint32_t reserved1 : 1; /* [2] */ + __IO uint32_t stallmsk : 1; /* [3] */ + __IO uint32_t nakmsk : 1; /* [4] */ + __IO uint32_t ackmsk : 1; /* [5] */ + __IO uint32_t reserved2 : 1; /* [6] */ + __IO uint32_t xacterrmsk : 1; /* [7] */ + __IO uint32_t bblerrmsk : 1; /* [8] */ + __IO uint32_t frmovrunmsk : 1; /* [9] */ + __IO uint32_t dtglerrmsk : 1; /* [10] */ + __IO uint32_t reserved3 : 21; /* [31:11] */ + } hcintmsk_bit; + }; + + /** + * @brief otgfs host channel transfer size register, offset:0x510 + */ + union + { + __IO uint32_t hctsiz; + struct + { + __IO uint32_t xfersize : 19; /* [18:0] */ + __IO uint32_t pktcnt : 10; /* [28:19] */ + __IO uint32_t pid : 2; /* [30:29] */ + __IO uint32_t reserved1 : 1; /* [31] */ + } hctsiz_bit; + }; + __IO uint32_t reserved3[3]; + +}otg_hchannel_type; + + +typedef struct +{ + /** + * @brief otgfs device configuration register, offset:0x800 + */ + union + { + __IO uint32_t dcfg; + struct + { + __IO uint32_t devspd : 2; /* [1:0] */ + __IO uint32_t nzstsouthshk : 1; /* [2] */ + __IO uint32_t reserved1 : 1; /* [3] */ + __IO uint32_t devaddr : 7; /* [10:4] */ + __IO uint32_t perfrint : 2; /* [12:11] */ + __IO uint32_t reserved2 : 19; /* [31:13] */ + } dcfg_bit; + }; + + /** + * @brief otgfs device controls register, offset:0x804 + */ + union + { + __IO uint32_t dctl; + struct + { + __IO uint32_t rwkupsig : 1; /* [0] */ + __IO uint32_t sftdiscon : 1; /* [1] */ + __IO uint32_t gnpinnaksts : 1; /* [2] */ + __IO uint32_t goutnaksts : 1; /* [3] */ + __IO uint32_t tstctl : 3; /* [6:4] */ + __IO uint32_t sgnpinak : 1; /* [7] */ + __IO uint32_t cgnpinak : 1; /* [8] */ + __IO uint32_t sgoutnak : 1; /* [9] */ + __IO uint32_t cgoutnak : 1; /* [10] */ + __IO uint32_t pwroprgdne : 1; /* [11] */ + __IO uint32_t reserved1 : 20; /* [31:12] */ + } dctl_bit; + }; + + /** + * @brief otgfs device status register, offset:0x80C + */ + union + { + __IO uint32_t dsts; + struct + { + __IO uint32_t suspsts : 1; /* [0] */ + __IO uint32_t enumspd : 2; /* [2:1] */ + __IO uint32_t eticerr : 1; /* [3] */ + __IO uint32_t reserved1 : 4; /* [7:4] */ + __IO uint32_t soffn : 14; /* [21:8] */ + __IO uint32_t reserved2 : 10; /* [31:22] */ + } dsts_bit; + }; + + __IO uint32_t reserved1; + /** + * @brief otgfs device in endpoint general interrupt mask register, offset:0x810 + */ + union + { + __IO uint32_t diepmsk; + struct + { + __IO uint32_t xfercmsk : 1; /* [0] */ + __IO uint32_t eptdismsk : 1; /* [1] */ + __IO uint32_t reserved1 : 1; /* [2] */ + __IO uint32_t timeoutmsk : 1; /* [3] */ + __IO uint32_t intkntxfempmsk : 1; /* [4] */ + __IO uint32_t intkneptmismsk : 1; /* [5] */ + __IO uint32_t ineptnakmsk : 1; /* [6] */ + __IO uint32_t reserved2 : 1; /* [7] */ + __IO uint32_t txfifoudrmsk : 1; /* [8] */ + __IO uint32_t bnainmsk : 1; /* [9] */ + __IO uint32_t reserved3 : 22; /* [31:10] */ + } diepmsk_bit; + }; + + /** + * @brief otgfs device out endpoint general interrupt mask register, offset:0x814 + */ + union + { + __IO uint32_t doepmsk; + struct + { + __IO uint32_t xfercmsk : 1; /* [0] */ + __IO uint32_t eptdismsk : 1; /* [1] */ + __IO uint32_t reserved1 : 1; /* [2] */ + __IO uint32_t setupmsk : 1; /* [3] */ + __IO uint32_t outtepdmsk : 1; /* [4] */ + __IO uint32_t reserved2 : 1; /* [5] */ + __IO uint32_t b2bsetupmsk : 1; /* [6] */ + __IO uint32_t reserved3 : 1; /* [7] */ + __IO uint32_t outperrmsk : 1; /* [8] */ + __IO uint32_t bnaoutmsk : 1; /* [9] */ + __IO uint32_t reserved4 : 22; /* [31:10] */ + } doepmsk_bit; + }; + + /** + * @brief otgfs device all endpoint interrupt register, offset:0x818 + */ + union + { + __IO uint32_t daint; + struct + { + __IO uint32_t ineptint : 16; /* [15:0] */ + __IO uint32_t outeptint : 16; /* [31:16] */ + } daint_bit; + }; + + /** + * @brief otgfs device all endpoint interrupt mask register, offset:0x81C + */ + union + { + __IO uint32_t daintmsk; + struct + { + __IO uint32_t ineptmsk : 16; /* [15:0] */ + __IO uint32_t outeptmsk : 16; /* [31:16] */ + } daintmsk_bit; + }; + + __IO uint32_t reserved2[5]; + + /** + * @brief otgfs device in endpoint fifo empty interrupt mask register, offset:0x834 + */ + union + { + __IO uint32_t diepempmsk; + struct + { + __IO uint32_t ineptxfemsk : 16; /* [15:0] */ + __IO uint32_t reserved1 : 16; /* [31:16] */ + } diepempmsk_bit; + }; + +} otg_device_type; + +typedef struct +{ + /** + * @brief otgfs device out endpoint control register, offset:0x900 + */ + union + { + __IO uint32_t diepctl; + struct + { + __IO uint32_t mps : 11; /* [10:0] */ + __IO uint32_t reserved1 : 4; /* [14:11] */ + __IO uint32_t usbacept : 1; /* [15] */ + __IO uint32_t dpid : 1; /* [16] */ + __IO uint32_t naksts : 1; /* [17] */ + __IO uint32_t eptype : 2; /* [19:18] */ + __IO uint32_t reserved2 : 1; /* [20] */ + __IO uint32_t stall : 1; /* [21] */ + __IO uint32_t txfnum : 4; /* [25:22] */ + __IO uint32_t cnak : 1; /* [26] */ + __IO uint32_t snak : 1; /* [27] */ + __IO uint32_t setd0pid : 1; /* [28] */ + __IO uint32_t setd1pid : 1; /* [29] */ + __IO uint32_t eptdis : 1; /* [30] */ + __IO uint32_t eptena : 1; /* [31] */ + } diepctl_bit; + }; + __IO uint32_t reserved1; + + /** + * @brief otgfs device in endpoint interrupt register, offset:0x908 + */ + union + { + __IO uint32_t diepint; + struct + { + __IO uint32_t xferc : 1; /* [0] */ + __IO uint32_t epdisd : 1; /* [1] */ + __IO uint32_t reserved1 : 1; /* [2] */ + __IO uint32_t timeout : 1; /* [3] */ + __IO uint32_t intkntxfemp : 1; /* [4] */ + __IO uint32_t reserved2 : 1; /* [5] */ + __IO uint32_t ineptnak : 1; /* [6] */ + __IO uint32_t txfemp : 1; /* [7] */ + __IO uint32_t reserved3 : 24; /* [31:8] */ + } diepint_bit; + }; + __IO uint32_t reserved2; + + /** + * @brief otgfs device in endpoint transfer size register, offset:0x910 + endpoint number * 0x20 + */ + union + { + __IO uint32_t dieptsiz; + struct + { + __IO uint32_t xfersize : 19; /* [18:0] */ + __IO uint32_t pktcnt : 10; /* [28:19] */ + __IO uint32_t mc : 2; /* [30:29] */ + __IO uint32_t reserved1 : 1; /* [31] */ + } dieptsiz_bit; + }; + + __IO uint32_t reserved3; + + /** + * @brief otgfs device in endpoint tx fifo status register, offset:0x918 + endpoint number * 0x20 + */ + union + { + __IO uint32_t dtxfsts; + struct + { + __IO uint32_t ineptxfsav : 16; /* [15:0] */ + __IO uint32_t reserved1 : 16; /* [31:16] */ + } dtxfsts_bit; + }; + +} otg_eptin_type; + +typedef struct +{ + /** + * @brief otgfs device out endpoint control register, offset:0xb00 + endpoint number * 0x20 + */ + union + { + __IO uint32_t doepctl; + struct + { + __IO uint32_t mps : 11; /* [10:0] */ + __IO uint32_t reserved1 : 4; /* [14:11] */ + __IO uint32_t usbacept : 1; /* [15] */ + __IO uint32_t dpid : 1; /* [16] */ + __IO uint32_t naksts : 1; /* [17] */ + __IO uint32_t eptype : 2; /* [19:18] */ + __IO uint32_t snpm : 1; /* [20] */ + __IO uint32_t stall : 1; /* [21] */ + __IO uint32_t reserved2 : 4; /* [25:22] */ + __IO uint32_t cnak : 1; /* [26] */ + __IO uint32_t snak : 1; /* [27] */ + __IO uint32_t setd0pid : 1; /* [28] */ + __IO uint32_t setd1pid : 1; /* [29] */ + __IO uint32_t eptdis : 1; /* [30] */ + __IO uint32_t eptena : 1; /* [31] */ + } doepctl_bit; + }; + __IO uint32_t reserved1; + + /** + * @brief otgfs device out endpoint interrupt register, offset:0xb08 + endpoint number * 0x20 + */ + union + { + __IO uint32_t doepint; + struct + { + __IO uint32_t xferc : 1; /* [0] */ + __IO uint32_t epdisd : 1; /* [1] */ + __IO uint32_t reserved1 : 1; /* [2] */ + __IO uint32_t setup : 1; /* [3] */ + __IO uint32_t outtepd : 1; /* [4] */ + __IO uint32_t reserved2 : 1; /* [5] */ + __IO uint32_t b2pstup : 1; /* [6] */ + __IO uint32_t reserved3 : 25; /* [31:7] */ + } doepint_bit; + }; + __IO uint32_t reserved2; + + /** + * @brief otgfs device out endpoint transfer size register, offset:0xb10 + endpoint number * 0x20 + */ + union + { + __IO uint32_t doeptsiz; + struct + { + __IO uint32_t xfersize : 19; /* [18:0] */ + __IO uint32_t pktcnt : 10; /* [28:19] */ + __IO uint32_t rxdpid_setupcnt : 2; /* [30:29] */ + __IO uint32_t reserved1 : 1; /* [31] */ + } doeptsiz_bit; + }; +} otg_eptout_type; + +typedef struct +{ + /** + * @brief otgfs power and clock gating control registers, offset:0xe00 + */ + union + { + __IO uint32_t pcgcctl; + struct + { + __IO uint32_t stoppclk : 1; /* [0] */ + __IO uint32_t reserved1 : 3; /* [3:1] */ + __IO uint32_t suspendm : 1; /* [4] */ + __IO uint32_t reserved2 : 27; /* [31:5] */ + } pcgcctl_bit; + }; +} otg_pcgcctl_type; + +/** + * @} + */ + +/** @defgroup USB_exported_functions + * @{ + */ + +/** + * @brief usb host and device offset address + */ +#define OTG_HOST_ADDR_OFFSET 0x400 /*!< usb host register offset address */ +#define OTG_HOST_CHANNEL_ADDR_OFFSET 0x500 /*!< usb host channel register offset address */ +#define OTG_DEVICE_ADDR_OFFSET 0x800 /*!< usb device register offset address */ +#define OTG_DEVICE_EPTIN_ADDR_OFFSET 0x900 /*!< usb device endpoint in register offset address */ +#define OTG_DEVICE_EPTOUT_ADDR_OFFSET 0xB00 /*!< usb device endpoint out register offset address */ +#define OTG_PCGCCTL_ADDR_OFFSET 0xE00 /*!< usb power and clock control register offset address */ +#define OTG_FIFO_ADDR_OFFSET 0x1000 /*!< usb fifo offset address */ + +/** + * @brief usb host and device register define + */ +#define OTG1_GLOBAL ((otg_global_type *)(OTGFS1_BASE)) /*!< usb otg1 global register */ +#define OTG2_GLOBAL ((otg_global_type *)(OTGFS2_BASE)) /*!< usb otg2 global register */ +#define OTG_PCGCCTL(usbx) ((otg_pcgcctl_type *)((uint32_t)usbx + OTG_PCGCCTL_ADDR_OFFSET)) /*!< usb power and clock control register */ +#define OTG_DEVICE(usbx) ((otg_device_type *)((uint32_t)usbx + OTG_DEVICE_ADDR_OFFSET)) /*!< usb device register */ +#define OTG_HOST(usbx) ((otg_host_type *)((uint32_t)usbx + OTG_HOST_ADDR_OFFSET)) /*!< usb host register */ +#define USB_CHL(usbx, n) ((otg_hchannel_type *)((uint32_t)usbx + OTG_HOST_CHANNEL_ADDR_OFFSET + n * 0x20)) /*!< usb channel n register */ +#define USB_INEPT(usbx, eptn) ((otg_eptin_type *)((uint32_t)usbx + OTG_DEVICE_EPTIN_ADDR_OFFSET + eptn * 0x20)) /*!< usb device endpoint in register */ +#define USB_OUTEPT(usbx, eptn) ((otg_eptout_type *)((uint32_t)usbx + OTG_DEVICE_EPTOUT_ADDR_OFFSET + eptn * 0x20)) /*!< usb device endpoint out register */ +#define USB_FIFO(usbx, eptn) *(__IO uint32_t *)((uint32_t)usbx + OTG_FIFO_ADDR_OFFSET + eptn * 0x1000) /*!< usb fifo address */ + + + +typedef otg_global_type usb_reg_type; + +/** @defgroup USB_exported_functions + * @{ + */ + +#ifdef OTGFS_USB_GLOBAL +error_status usb_global_reset(otg_global_type *usbx); +void usb_global_init(otg_global_type *usbx); +otg_global_type *usb_global_select_core(uint8_t usb_id); +void usb_flush_tx_fifo(otg_global_type *usbx, uint32_t fifo_num); +void usb_flush_rx_fifo(otg_global_type *usbx); +void usb_global_interrupt_enable(otg_global_type *usbx, uint16_t interrupt, confirm_state new_state); +uint32_t usb_global_get_all_interrupt(otg_global_type *usbx); +void usb_global_clear_interrupt(otg_global_type *usbx, uint32_t flag); +void usb_interrupt_enable(otg_global_type *usbx); +void usb_interrupt_disable(otg_global_type *usbx); +void usb_set_rx_fifo(otg_global_type *usbx, uint16_t size); +void usb_set_tx_fifo(otg_global_type *usbx, uint8_t txfifo, uint16_t size); +void usb_global_set_mode(otg_global_type *usbx, uint32_t mode); +void usb_global_power_on(otg_global_type *usbx); +void usb_write_packet(otg_global_type *usbx, uint8_t *pusr_buf, uint16_t num, uint16_t nbytes); +void usb_read_packet(otg_global_type *usbx, uint8_t *pusr_buf, uint16_t num, uint16_t nbytes); +void usb_stop_phy_clk(otg_global_type *usbx); +void usb_open_phy_clk(otg_global_type *usbx); +#endif + +#ifdef OTGFS_USB_DEVICE +void usb_ept_open(otg_global_type *usbx, usb_ept_info *ept_info); +void usb_ept_close(otg_global_type *usbx, usb_ept_info *ept_info); +void usb_ept_stall(otg_global_type *usbx, usb_ept_info *ept_info); +void usb_ept_clear_stall(otg_global_type *usbx, usb_ept_info *ept_info); +uint32_t usb_get_all_out_interrupt(otg_global_type *usbx); +uint32_t usb_get_all_in_interrupt(otg_global_type *usbx); +uint32_t usb_ept_out_interrupt(otg_global_type *usbx, uint32_t eptn); +uint32_t usb_ept_in_interrupt(otg_global_type *usbx, uint32_t eptn); +void usb_ept_out_clear(otg_global_type *usbx, uint32_t eptn, uint32_t flag); +void usb_ept_in_clear(otg_global_type *usbx, uint32_t eptn, uint32_t flag); +void usb_set_address(otg_global_type *usbx, uint8_t address); +void usb_ept0_start(otg_global_type *usbx); +void usb_ept0_setup(otg_global_type *usbx); +void usb_connect(otg_global_type *usbx); +void usb_disconnect(otg_global_type *usbx); +void usb_remote_wkup_set(otg_global_type *usbx); +void usb_remote_wkup_clear(otg_global_type *usbx); +uint8_t usb_suspend_status_get(otg_global_type *usbx); +#endif + +#ifdef OTGFS_USB_HOST +void usb_port_power_on(otg_global_type *usbx, confirm_state state); +uint32_t usbh_get_frame(otg_global_type *usbx); +void usb_hc_enable(otg_global_type *usbx, + uint8_t chn, + uint8_t ept_num, + uint8_t dev_address, + uint8_t type, + uint16_t maxpacket, + uint8_t speed); +uint32_t usb_hch_read_interrupt(otg_global_type *usbx); +void usb_host_disable(otg_global_type *usbx); +void usb_hch_halt(otg_global_type *usbx, uint8_t chn); +void usbh_fsls_clksel(otg_global_type *usbx, uint8_t clk); +#endif +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_wdt.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_wdt.h new file mode 100644 index 0000000000..e0a509b61c --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_wdt.h @@ -0,0 +1,197 @@ +/** + ************************************************************************** + * @file at32f435_437_wdt.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 wdt header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_WDT_H +#define __AT32F435_437_WDT_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup WDT + * @{ + */ + + +/** @defgroup WDT_flags_definition + * @brief wdt flag + * @{ + */ + +#define WDT_DIVF_UPDATE_FLAG ((uint16_t)0x0001) /*!< wdt division value update complete flag */ +#define WDT_RLDF_UPDATE_FLAG ((uint16_t)0x0002) /*!< wdt reload value update complete flag */ +#define WDT_WINF_UPDATE_FLAG ((uint16_t)0x0004) /*!< wdt window value update complete flag */ + +/** + * @} + */ + +/** @defgroup WDT_exported_types + * @{ + */ + +/** + * @brief wdt division value type + */ +typedef enum +{ + WDT_CLK_DIV_4 = 0x00, /*!< wdt clock divider value is 4 */ + WDT_CLK_DIV_8 = 0x01, /*!< wdt clock divider value is 8 */ + WDT_CLK_DIV_16 = 0x02, /*!< wdt clock divider value is 16 */ + WDT_CLK_DIV_32 = 0x03, /*!< wdt clock divider value is 32 */ + WDT_CLK_DIV_64 = 0x04, /*!< wdt clock divider value is 64 */ + WDT_CLK_DIV_128 = 0x05, /*!< wdt clock divider value is 128 */ + WDT_CLK_DIV_256 = 0x06 /*!< wdt clock divider value is 256 */ +} wdt_division_type; + +/** + * @brief wdt cmd value type + */ +typedef enum +{ + WDT_CMD_LOCK = 0x0000, /*!< disable write protection command */ + WDT_CMD_UNLOCK = 0x5555, /*!< enable write protection command */ + WDT_CMD_ENABLE = 0xCCCC, /*!< enable wdt command */ + WDT_CMD_RELOAD = 0xAAAA /*!< reload command */ +} wdt_cmd_value_type; + +/** + * @brief type define wdt register all + */ +typedef struct +{ + + /** + * @brief wdt cmd register, offset:0x00 + */ + union + { + __IO uint32_t cmd; + struct + { + __IO uint32_t cmd : 16;/* [15:0] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } cmd_bit; + }; + + /** + * @brief wdt div register, offset:0x04 + */ + union + { + __IO uint32_t div; + struct + { + __IO uint32_t div : 3; /* [2:0] */ + __IO uint32_t reserved1 : 29;/* [31:3] */ + } div_bit; + }; + + /** + * @brief wdt rld register, offset:0x08 + */ + union + { + __IO uint32_t rld; + struct + { + __IO uint32_t rld : 12;/* [11:0] */ + __IO uint32_t reserved1 : 20;/* [31:12] */ + } rld_bit; + }; + + /** + * @brief wdt sts register, offset:0x0C + */ + union + { + __IO uint32_t sts; + struct + { + __IO uint32_t divf : 1; /* [0] */ + __IO uint32_t rldf : 1; /* [1] */ + __IO uint32_t reserved1 : 30;/* [31:2] */ + } sts_bit; + }; + + /** + * @brief wdt win register, offset:0x10 + */ + union + { + __IO uint32_t win; + struct + { + __IO uint32_t win : 12;/* [11:0] */ + __IO uint32_t reserved1 : 20;/* [31:12] */ + } win_bit; + }; +} wdt_type; + +/** + * @} + */ + +#define WDT ((wdt_type *) WDT_BASE) + +/** @defgroup WDT_exported_functions + * @{ + */ + +void wdt_enable(void); +void wdt_counter_reload(void); +void wdt_reload_value_set(uint16_t reload_value); +void wdt_divider_set(wdt_division_type division); +void wdt_register_write_enable( confirm_state new_state); +flag_status wdt_flag_get(uint16_t wdt_flag); +void wdt_window_counter_set(uint16_t window_cnt); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_wwdt.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_wwdt.h new file mode 100644 index 0000000000..f7999c9eb9 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_wwdt.h @@ -0,0 +1,158 @@ +/** + ************************************************************************** + * @file at32f435_437_wwdt.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 wwdt header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_WWDT_H +#define __AT32F435_437_WWDT_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup WWDT + * @{ + */ + +/** @defgroup WWDT_enable_bit_definition + * @brief wwdt enable bit + * @{ + */ + +#define WWDT_EN_BIT ((uint32_t)0x00000080) /*!< wwdt enable bit */ + +/** + * @} + */ + +/** @defgroup WWDT_exported_types + * @{ + */ + +/** + * @brief wwdt division type + */ +typedef enum +{ + WWDT_PCLK1_DIV_4096 = 0x00, /*!< wwdt counter clock = (pclk1/4096)/1) */ + WWDT_PCLK1_DIV_8192 = 0x01, /*!< wwdt counter clock = (pclk1/4096)/2) */ + WWDT_PCLK1_DIV_16384 = 0x02, /*!< wwdt counter clock = (pclk1/4096)/4) */ + WWDT_PCLK1_DIV_32768 = 0x03 /*!< wwdt counter clock = (pclk1/4096)/8) */ +} wwdt_division_type; + +/** + * @brief type define wwdt register all + */ +typedef struct +{ + + /** + * @brief wwdt ctrl register, offset:0x00 + */ + union + { + __IO uint32_t ctrl; + struct + { + __IO uint32_t cnt : 7; /* [6:0] */ + __IO uint32_t wwdten : 1; /* [7] */ + __IO uint32_t reserved1 : 24;/* [31:8] */ + } ctrl_bit; + }; + + /** + * @brief wwdt cfg register, offset:0x04 + */ + union + { + __IO uint32_t cfg; + struct + { + __IO uint32_t win : 7; /* [6:0] */ + __IO uint32_t div : 2; /* [8:7] */ + __IO uint32_t rldien : 1; /* [9] */ + __IO uint32_t reserved1 : 22;/* [31:10] */ + } cfg_bit; + }; + + /** + * @brief wwdt cfg register, offset:0x08 + */ + union + { + __IO uint32_t sts; + struct + { + __IO uint32_t rldf : 1; /* [0] */ + __IO uint32_t reserved1 : 31;/* [31:1] */ + } sts_bit; + }; + +} wwdt_type; + +/** + * @} + */ + +#define WWDT ((wwdt_type *) WWDT_BASE) + +/** @defgroup WWDT_exported_functions + * @{ + */ + +void wwdt_reset(void); +void wwdt_divider_set(wwdt_division_type division); +void wwdt_flag_clear(void); +void wwdt_enable(uint8_t wwdt_cnt); +void wwdt_interrupt_enable(void); +flag_status wwdt_flag_get(void); +void wwdt_counter_set(uint8_t wwdt_cnt); +void wwdt_window_counter_set(uint8_t window_cnt); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_xmc.h b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_xmc.h new file mode 100644 index 0000000000..462594d903 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/inc/at32f435_437_xmc.h @@ -0,0 +1,1075 @@ +/** + ************************************************************************** + * @file at32f435_437_xmc.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 xmc header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_XMC_H +#define __AT32F435_437_XMC_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @addtogroup XMC + * @{ + */ + +/** @defgroup XMC_exported_types + * @{ + */ + +/** + * @brief xmc data address bus multiplexing type + */ +typedef enum +{ + XMC_DATA_ADDR_MUX_DISABLE = 0x00000000, /*!< xmc address/data multiplexing disable */ + XMC_DATA_ADDR_MUX_ENABLE = 0x00000002 /*!< xmc address/data multiplexing enable */ +} xmc_data_addr_mux_type; + +/** + * @brief xmc burst access mode type + */ +typedef enum +{ + XMC_BURST_MODE_DISABLE = 0x00000000, /*!< xmc burst mode disable */ + XMC_BURST_MODE_ENABLE = 0x00000100 /*!< xmc burst mode enable */ +} xmc_burst_access_mode_type; + +/** + * @brief xmc asynchronous wait type + */ +typedef enum +{ + XMC_ASYN_WAIT_DISABLE = 0x00000000, /*!< xmc wait signal during asynchronous transfers disbale */ + XMC_ASYN_WAIT_ENABLE = 0x00008000 /*!< xmc wait signal during asynchronous transfers enable */ +} xmc_asyn_wait_type; + +/** + * @brief xmc wrapped mode type + */ +typedef enum +{ + XMC_WRAPPED_MODE_DISABLE = 0x00000000, /*!< xmc direct wrapped burst is disbale */ + XMC_WRAPPED_MODE_ENABLE = 0x00000400 /*!< xmc direct wrapped burst is enable */ +} xmc_wrap_mode_type; + +/** + * @brief xmc write operation type + */ +typedef enum +{ + XMC_WRITE_OPERATION_DISABLE = 0x00000000, /*!< xmc write operations is disable */ + XMC_WRITE_OPERATION_ENABLE = 0x00001000 /*!< xmc write operations is enable */ +} xmc_write_operation_type; + +/** + * @brief xmc wait signal type + */ +typedef enum +{ + XMC_WAIT_SIGNAL_DISABLE = 0x00000000, /*!< xmc nwait signal is disable */ + XMC_WAIT_SIGNAL_ENABLE = 0x00002000 /*!< xmc nwait signal is enable */ +} xmc_wait_signal_type; + +/** + * @brief xmc write burst type + */ +typedef enum +{ + XMC_WRITE_BURST_SYN_DISABLE = 0x00000000, /*!< xmc write operations are always performed in asynchronous mode */ + XMC_WRITE_BURST_SYN_ENABLE = 0x00080000 /*!< xmc write operations are performed in synchronous mode */ +} xmc_write_burst_type; + +/** + * @brief xmc extended mode type + */ +typedef enum +{ + XMC_WRITE_TIMING_DISABLE = 0x00000000, /*!< xmc write timing disable */ + XMC_WRITE_TIMING_ENABLE = 0x00004000 /*!< xmc write timing enable */ +} xmc_extended_mode_type; + +/** + * @brief xmc pccard wait type + */ +typedef enum +{ + XMC_WAIT_OPERATION_DISABLE = 0x00000000, /*!< xmc wait operation for the pc card/nand flash memory bank disable */ + XMC_WAIT_OPERATION_ENABLE = 0x00000002 /*!< xmc wait operation for the pc card/nand flash memory bank enable */ +} xmc_nand_pccard_wait_type; + +/** + * @brief xmc ecc enable type + */ +typedef enum +{ + XMC_ECC_OPERATION_DISABLE = 0x00000000, /*!< xmc ecc module disable */ + XMC_ECC_OPERATION_ENABLE = 0x00000040 /*!< xmc ecc module enable */ +} xmc_ecc_enable_type; + +/** + * @brief xmc nor/sram subbank type + */ +typedef enum +{ + XMC_BANK1_NOR_SRAM1 = 0x00000000, /*!< xmc nor/sram subbank1 */ + XMC_BANK1_NOR_SRAM2 = 0x00000001, /*!< xmc nor/sram subbank2 */ + XMC_BANK1_NOR_SRAM3 = 0x00000002, /*!< xmc nor/sram subbank3 */ + XMC_BANK1_NOR_SRAM4 = 0x00000003 /*!< xmc nor/sram subbank4 */ +} xmc_nor_sram_subbank_type; + +/** + * @brief xmc class bank type + */ +typedef enum +{ + XMC_BANK2_NAND = 0x00000000, /*!< xmc nand flash bank2 */ + XMC_BANK3_NAND = 0x00000001, /*!< xmc nand flash bank3 */ + XMC_BANK4_PCCARD = 0x00000002, /*!< xmc pc card bank4 */ + XMC_BANK5_6_SDRAM = 0x00000003 /*!< xmc sdram bank5/6 */ +} xmc_class_bank_type; + +/** + * @brief xmc memory type + */ +typedef enum +{ + XMC_DEVICE_SRAM = 0x00000000, /*!< xmc device choice sram */ + XMC_DEVICE_PSRAM = 0x00000004, /*!< xmc device choice psram */ + XMC_DEVICE_NOR = 0x00000008 /*!< xmc device choice nor flash */ +} xmc_memory_type; + +/** + * @brief xmc data width type + */ +typedef enum +{ + XMC_BUSTYPE_8_BITS = 0x00000000, /*!< xmc databuss width 8bits */ + XMC_BUSTYPE_16_BITS = 0x00000010 /*!< xmc databuss width 16bits */ +} xmc_data_width_type; + +/** + * @brief xmc wait signal polarity type + */ +typedef enum +{ + XMC_WAIT_SIGNAL_LEVEL_LOW = 0x00000000, /*!< xmc nwait active low */ + XMC_WAIT_SIGNAL_LEVEL_HIGH = 0x00000200 /*!< xmc nwait active high */ +} xmc_wait_signal_polarity_type; + +/** + * @brief xmc wait timing type + */ +typedef enum +{ + XMC_WAIT_SIGNAL_SYN_BEFORE = 0x00000000, /*!< xmc nwait signal is active one data cycle before wait state */ + XMC_WAIT_SIGNAL_SYN_DURING = 0x00000800 /*!< xmc nwait signal is active during wait state */ +} xmc_wait_timing_type; + +/** + * @brief xmc access mode type + */ +typedef enum +{ + XMC_ACCESS_MODE_A = 0x00000000, /*!< xmc access mode A */ + XMC_ACCESS_MODE_B = 0x10000000, /*!< xmc access mode B */ + XMC_ACCESS_MODE_C = 0x20000000, /*!< xmc access mode C */ + XMC_ACCESS_MODE_D = 0x30000000 /*!< xmc access mode D */ +} xmc_access_mode_type; + +/** + * @brief xmc ecc page size type + */ +typedef enum +{ + XMC_ECC_PAGESIZE_256_BYTES = 0x00000000, /*!< xmc ecc page size 256 bytes */ + XMC_ECC_PAGESIZE_512_BYTES = 0x00020000, /*!< xmc ecc page size 512 bytes */ + XMC_ECC_PAGESIZE_1024_BYTES = 0x00040000, /*!< xmc ecc page size 1024 bytes */ + XMC_ECC_PAGESIZE_2048_BYTES = 0x00060000, /*!< xmc ecc page size 2048 bytes */ + XMC_ECC_PAGESIZE_4096_BYTES = 0x00080000, /*!< xmc ecc page size 4096 bytes */ + XMC_ECC_PAGESIZE_8192_BYTES = 0x000A0000 /*!< xmc ecc page size 8192 bytes */ +} xmc_ecc_pagesize_type; + +/** + * @brief xmc interrupt sources type + */ +typedef enum +{ + XMC_INT_RISING_EDGE = 0x00000008, /*!< xmc rising edge detection interrupt enable */ + XMC_INT_LEVEL = 0x00000010, /*!< xmc high-level edge detection interrupt enable */ + XMC_INT_FALLING_EDGE = 0x00000020, /*!< xmc falling edge detection interrupt enable */ + XMC_INT_ERR = 0x00004000 /*!< xmc sdram error interrupt enable */ +} xmc_interrupt_sources_type; + +/** + * @brief xmc interrupt flag type + */ +typedef enum +{ + XMC_RISINGEDGE_FLAG = 0x00000001, /*!< xmc interrupt rising edge detection flag */ + XMC_LEVEL_FLAG = 0x00000002, /*!< xmc interrupt high-level edge detection flag */ + XMC_FALLINGEDGE_FLAG = 0x00000004, /*!< xmc interrupt falling edge detection flag */ + XMC_FEMPT_FLAG = 0x00000040, /*!< xmc fifo empty flag */ + XMC_ERR_FLAG = 0x00000001, /*!< xmc sdram error flag */ + XMC_BUSY_FLAG = 0x00000020 /*!< xmc sdram busy flag */ +} xmc_interrupt_flag_type; + +/** + * @brief xmc sdram number of column address type + */ +typedef enum +{ + XMC_COLUMN_8 = 0x00000000, /*!< xmc sdram column address 8bit */ + XMC_COLUMN_9 = 0x00000001, /*!< xmc sdram column address 9bit */ + XMC_COLUMN_10 = 0x00000002, /*!< xmc sdram column address 10bit */ + XMC_COLUMN_11 = 0x00000003 /*!< xmc sdram column address 11bit */ +}xmc_sdram_column_type; + +/** + * @brief xmc sdram number of row address type + */ +typedef enum +{ + XMC_ROW_11 = 0x00000000, /*!< xmc sdram row address 11bit */ + XMC_ROW_12 = 0x00000001, /*!< xmc sdram row address 12bit */ + XMC_ROW_13 = 0x00000002 /*!< xmc sdram row address 13bit */ +}xmc_sdram_row_type; + +/** + * @brief xmc sdram memory data bus width type + */ +typedef enum +{ + XMC_MEM_WIDTH_8 = 0x00000000, /*!< xmc sdram data bus width 8 */ + XMC_MEM_WIDTH_16 = 0x00000001 /*!< xmc sdram data bus width 16 */ +}xmc_sdram_width_type; + +/** + * @brief xmc sdram number of internal banks type + */ +typedef enum +{ + XMC_INBK_2 = 0x00000000, /*!< xmc sdram 2 internal banks */ + XMC_INBK_4 = 0x00000001 /*!< xmc sdram 4 internal banks */ +}xmc_sdram_inbk_type; + +/** + * @brief xmc sdram cas latency type + */ +typedef enum +{ + XMC_CAS_1 = 0x00000001, /*!< xmc sdram cas 1 */ + XMC_CAS_2 = 0x00000002, /*!< xmc sdram cas 2 */ + XMC_CAS_3 = 0x00000003 /*!< xmc sdram cas 3 */ +}xmc_sdram_cas_type; + +/** + * @brief xmc sdram clock div type + */ +typedef enum +{ + XMC_NO_CLK = 0x00000000, /*!< xmc sdram disable clock */ + XMC_CLKDIV_2 = 0x00000002, /*!< xmc sdram clock div 2 */ + XMC_CLKDIV_3 = 0x00000003, /*!< xmc sdram clock div 3 */ + XMC_CLKDIV_4 = 0x00000001 /*!< xmc sdram clock div 4 */ +}xmc_sdram_clkdiv_type; + +/** + * @brief xmc sdram read delay + */ +typedef enum +{ + XMC_READ_DELAY_0 = 0x00000000, /*!< xmc sdram no delay */ + XMC_READ_DELAY_1 = 0x00000001, /*!< xmc sdram delay 1 clock*/ + XMC_READ_DELAY_2 = 0x00000002, /*!< xmc sdram delay 2 clock */ +}xmc_sdram_rd_delay_type; + +/** + * @brief xmc sdram bank type + */ +typedef enum +{ + XMC_SDRAM_BANK1 = 0x00000000, /*!< xmc sdram bank 1 */ + XMC_SDRAM_BANK2 = 0x00000001 /*!< xmc sdram bank 2 */ +}xmc_sdram_bank_type; + + +/** + * @brief xmc sdram timing delay cycle type + */ +typedef enum +{ + XMC_DELAY_CYCLE_1 = 0x00000000, /*!< xmc sdram timming delay 1 cycle */ + XMC_DELAY_CYCLE_2 = 0x00000001, /*!< xmc sdram timming delay 2 cycle */ + XMC_DELAY_CYCLE_3 = 0x00000002, /*!< xmc sdram timming delay 3 cycle */ + XMC_DELAY_CYCLE_4 = 0x00000003, /*!< xmc sdram timming delay 4 cycle */ + XMC_DELAY_CYCLE_5 = 0x00000004, /*!< xmc sdram timming delay 5 cycle */ + XMC_DELAY_CYCLE_6 = 0x00000005, /*!< xmc sdram timming delay 6 cycle */ + XMC_DELAY_CYCLE_7 = 0x00000006, /*!< xmc sdram timming delay 7 cycle */ + XMC_DELAY_CYCLE_8 = 0x00000007, /*!< xmc sdram timming delay 8 cycle */ + XMC_DELAY_CYCLE_9 = 0x00000008, /*!< xmc sdram timming delay 9 cycle */ + XMC_DELAY_CYCLE_10 = 0x00000009, /*!< xmc sdram timming delay 10 cycle */ + XMC_DELAY_CYCLE_11 = 0x0000000A, /*!< xmc sdram timming delay 11 cycle */ + XMC_DELAY_CYCLE_12 = 0x0000000B, /*!< xmc sdram timming delay 12 cycle */ + XMC_DELAY_CYCLE_13 = 0x0000000C, /*!< xmc sdram timming delay 13 cycle */ + XMC_DELAY_CYCLE_14 = 0x0000000D, /*!< xmc sdram timming delay 14 cycle */ + XMC_DELAY_CYCLE_15 = 0x0000000E, /*!< xmc sdram timming delay 15 cycle */ + XMC_DELAY_CYCLE_16 = 0x0000000F /*!< xmc sdram timming delay 16 cycle */ +}xmc_sdram_delay_type; + + +/** + * @brief xmc sdram command type + */ +typedef enum +{ + XMC_CMD_NORMAL = 0x00000000, /*!< xmc sdram command normal */ + XMC_CMD_CLK = 0x00000001, /*!< xmc sdram command clock enable */ + XMC_CMD_PRECHARG_ALL = 0x00000002, /*!< xmc sdram command precharg all bank */ + XMC_CMD_AUTO_REFRESH = 0x00000003, /*!< xmc sdram command auto refresh */ + XMC_CMD_LOAD_MODE = 0x00000004, /*!< xmc sdram command load mode register */ + XMC_CMD_SELF_REFRESH = 0x00000005, /*!< xmc sdram command self refresh */ + XMC_CMD_POWER_DOWN = 0x00000006 /*!< xmc sdram command power down */ +}xmc_command_type; + +/** + * @brief xmc sdram command bank select type + */ +typedef enum +{ + XMC_CMD_BANK1 = 0x00000010, /*!< send xmc sdram command to bank1 */ + XMC_CMD_BANK2 = 0x00000008, /*!< send xmc sdram command to bank2 */ + XMC_CMD_BANK1_2 = 0x00000018 /*!< send xmc sdram command to bank1 and bank2 */ +}xmc_cmd_bank1_2_type; + + +/** + * @brief xmc sdram bank status type + */ +typedef enum +{ + XMC_STATUS_NORMAL = 0x00000000, /*!< xmc sdram status normal */ + XMC_STATUS_SELF_REFRESH = 0x00000001, /*!< xmc sdram status self refresh */ + XMC_STATUS_POWER_DOWN = 0x00000002, /*!< xmc sdram power down */ + XMC_STATUS_MASK = 0x00000003 /*!< xmc sdram mask */ +}xmc_bank_status_type; + + +/** + * @brief nor/sram banks timing parameters + */ +typedef struct +{ + xmc_nor_sram_subbank_type subbank; /*!< xmc nor/sram subbank */ + xmc_extended_mode_type write_timing_enable; /*!< xmc nor/sram write timing enable */ + uint32_t addr_setup_time; /*!< xmc nor/sram address setup time */ + uint32_t addr_hold_time; /*!< xmc nor/sram address hold time */ + uint32_t data_setup_time; /*!< xmc nor/sram data setup time */ + uint32_t bus_latency_time; /*!< xmc nor/sram bus latency time */ + uint32_t clk_psc; /*!< xmc nor/sram clock prescale */ + uint32_t data_latency_time; /*!< xmc nor/sram data latency time */ + xmc_access_mode_type mode; /*!< xmc nor/sram access mode */ +} xmc_norsram_timing_init_type; + +/** + * @brief xmc nor/sram init structure definition + */ +typedef struct +{ + xmc_nor_sram_subbank_type subbank; /*!< xmc nor/sram subbank */ + xmc_data_addr_mux_type data_addr_multiplex; /*!< xmc nor/sram address/data multiplexing enable */ + xmc_memory_type device; /*!< xmc nor/sram memory device */ + xmc_data_width_type bus_type; /*!< xmc nor/sram data bus width */ + xmc_burst_access_mode_type burst_mode_enable; /*!< xmc nor/sram burst mode enable */ + xmc_asyn_wait_type asynwait_enable; /*!< xmc nor/sram nwait in asynchronous transfer enable */ + xmc_wait_signal_polarity_type wait_signal_lv; /*!< xmc nor/sram nwait polarity */ + xmc_wrap_mode_type wrapped_mode_enable; /*!< xmc nor/sram wrapped enable */ + xmc_wait_timing_type wait_signal_config; /*!< xmc nor/sram nwait timing configuration */ + xmc_write_operation_type write_enable; /*!< xmc nor/sram write enable */ + xmc_wait_signal_type wait_signal_enable; /*!< xmc nor/sram nwait in synchronous transfer enable */ + xmc_extended_mode_type write_timing_enable; /*!< xmc nor/sram read-write timing different */ + xmc_write_burst_type write_burst_syn; /*!< xmc nor/sram memory write mode control */ +} xmc_norsram_init_type; + +/** + * @brief nand and pccard timing parameters xmc + */ + +typedef struct +{ + xmc_class_bank_type class_bank; /*!< xmc nand/pccard bank */ + uint32_t mem_setup_time; /*!< xmc nand/pccard memory setup time */ + uint32_t mem_waite_time; /*!< xmc nand/pccard memory wait time */ + uint32_t mem_hold_time; /*!< xmc nand/pccard memory hold time */ + uint32_t mem_hiz_time; /*!< xmc nand/pccard memory databus high resistance time */ +} xmc_nand_pccard_timinginit_type; + +/** + * @brief xmc nand init structure definition + */ + +typedef struct +{ + xmc_class_bank_type nand_bank; /*!< xmc nand bank */ + xmc_nand_pccard_wait_type wait_enable; /*!< xmc wait feature enable */ + xmc_data_width_type bus_type; /*!< xmc nand bus width */ + xmc_ecc_enable_type ecc_enable; /*!< xmc nand ecc enable */ + xmc_ecc_pagesize_type ecc_pagesize; /*!< xmc nand ecc page size */ + uint32_t delay_time_cycle; /*!< xmc nand cle to re delay */ + uint32_t delay_time_ar; /*!< xmc nand ale to re delay */ +} xmc_nand_init_type; + +/** + * @brief xmc pccard init structure definition + */ + +typedef struct +{ + xmc_nand_pccard_wait_type enable_wait; /*!< xmc pccard wait feature enable */ + uint32_t delay_time_cr; /*!< xmc pccard cle to re delay */ + uint32_t delay_time_ar; /*!< xmc pccard ale to re delay */ +} xmc_pccard_init_type; + +/** + * @brief xmc sdram init structure definition + */ + +typedef struct +{ + xmc_sdram_bank_type sdram_bank; /*!< xmc sdram bank bype */ + xmc_sdram_inbk_type internel_banks; /*!< xmc sdram internal banks */ + xmc_sdram_clkdiv_type clkdiv; /*!< xmc sdram clock div */ + uint8_t write_protection; /*!< xmc sdram write protection */ + uint8_t burst_read; /*!< xmc sdram burst read */ + uint8_t read_delay; /*!< xmc sdram read delay */ + xmc_sdram_column_type column_address; /*!< xmc sdram column address */ + xmc_sdram_row_type row_address; /*!< xmc sdram row address */ + xmc_sdram_cas_type cas; /*!< xmc sdram cas */ + xmc_sdram_width_type width; /*!< xmc sdram data width */ +} xmc_sdram_init_type; + +/** + * @brief xmc sdram timing structure definition + */ + +typedef struct +{ + xmc_sdram_delay_type tmrd; /*!< mode register program to active delay */ + xmc_sdram_delay_type txsr; /*!< exit self-refresh to active delay */ + xmc_sdram_delay_type tras; /*!< self refresh */ + xmc_sdram_delay_type trc; /*!< refresh to active delay */ + xmc_sdram_delay_type twr; /*!< write recovery delay */ + xmc_sdram_delay_type trp; /*!< precharge to active delay */ + xmc_sdram_delay_type trcd; /*!< row active to read/write delay */ +} xmc_sdram_timing_type; + +/** + * @brief xmc sdram command structure definition + */ + +typedef struct +{ + xmc_command_type cmd; /*!< sdram command */ + xmc_cmd_bank1_2_type cmd_banks; /*!< which bank send command */ + uint32_t auto_refresh; /*!< auto refresh times */ + uint32_t data; /*!< mode register data */ +} xmc_sdram_cmd_type; + +typedef struct +{ + /** + * @brief xmc bank1 bk1ctrl register, offset:0x00+0x08*(x-1) x= 1...4 + */ + union + { + __IO uint32_t bk1ctrl; + struct + { + __IO uint32_t en : 1; /* [0] */ + __IO uint32_t admuxen : 1; /* [1] */ + __IO uint32_t dev : 2; /* [3:2] */ + __IO uint32_t extmdbw : 2; /* [5:4] */ + __IO uint32_t noren : 1; /* [6] */ + __IO uint32_t reserved1 : 1; /* [7] */ + __IO uint32_t syncben : 1; /* [8] */ + __IO uint32_t nwpol : 1; /* [9] */ + __IO uint32_t wrapen : 1; /* [10] */ + __IO uint32_t nwtcfg : 1; /* [11] */ + __IO uint32_t wen : 1; /* [12] */ + __IO uint32_t nwsen : 1; /* [13] */ + __IO uint32_t rwtd : 1; /* [14] */ + __IO uint32_t nwasen : 1; /* [15] */ + __IO uint32_t crpgs : 3; /* [18:16] */ + __IO uint32_t mwmc : 1; /* [19] */ + __IO uint32_t reserved2 : 12;/* [31:20] */ + } bk1ctrl_bit; + }; + + /** + * @brief xmc bank1 bk1tmg register, offset:0x04+0x08*(x-1) x= 1...4 + */ + union + { + __IO uint32_t bk1tmg; + struct + { + __IO uint32_t addrst : 4; /* [3:0] */ + __IO uint32_t addrht : 4; /* [7:4] */ + __IO uint32_t dtst : 8; /* [15:8] */ + __IO uint32_t buslat : 4; /* [19:16] */ + __IO uint32_t clkpsc : 4; /* [23:20] */ + __IO uint32_t dtlat : 4; /* [27:24] */ + __IO uint32_t asyncm : 2; /* [29:28] */ + __IO uint32_t reserved1 : 2; /* [31:30] */ + } bk1tmg_bit; + }; + +} xmc_bank1_ctrl_tmg_reg_type; + +typedef struct +{ + /** + * @brief xmc bank1 bk1tmgwr register, offset:0x104+0x08*(x-1) x= 1...4 + */ + union + { + __IO uint32_t bk1tmgwr; + struct + { + __IO uint32_t addrst : 4; /* [3:0] */ + __IO uint32_t addrht : 4; /* [7:4] */ + __IO uint32_t dtst : 8; /* [15:8] */ + __IO uint32_t buslat : 4; /* [19:16] */ + __IO uint32_t reserved1 : 8; /* [27:20] */ + __IO uint32_t asyncm : 2; /* [29:28] */ + __IO uint32_t reserved2 : 2; /* [31:30] */ + } bk1tmgwr_bit; + }; + + /** + * @brief xmc bank1 reserved register + */ + __IO uint32_t reserved1; + +} xmc_bank1_tmgwr_reg_type; + +/** + * @brief xmc bank1 registers + */ +typedef struct +{ + /** + * @brief xmc bank1 ctrl and tmg register, offset:0x00~0x1C + */ + xmc_bank1_ctrl_tmg_reg_type ctrl_tmg_group[4]; + + /** + * @brief xmc bank1 reserved register, offset:0x20~0x100 + */ + __IO uint32_t reserved1[57]; + + /** + * @brief xmc bank1 tmgwr register, offset:0x104~0x11C + */ + xmc_bank1_tmgwr_reg_type tmgwr_group[4]; + + /** + * @brief xmc bank1 reserved register, offset:0x120~0x21C + */ + __IO uint32_t reserved2[63]; + + /** + * @brief xmc bank1 ext register, offset:0x220~0x22C + */ + union + { + __IO uint32_t ext[4]; + struct + { + __IO uint32_t buslatw2w : 8; /* [7:0] */ + __IO uint32_t buslatr2r : 8; /* [15:8] */ + __IO uint32_t reserved1 : 16;/* [31:16] */ + } ext_bit[4]; + }; + +} xmc_bank1_type; + +/** + * @brief xmc bank2 registers + */ +typedef struct +{ + /** + * @brief xmc bk2ctrl register, offset:0x60 + */ + union + { + __IO uint32_t bk2ctrl; + struct + { + __IO uint32_t reserved1 : 1; /* [0] */ + __IO uint32_t nwen : 1; /* [1] */ + __IO uint32_t en : 1; /* [2] */ + __IO uint32_t dev : 1; /* [3] */ + __IO uint32_t extmdbw : 2; /* [5:4] */ + __IO uint32_t eccen : 1; /* [6] */ + __IO uint32_t reserved2 : 2; /* [8:7] */ + __IO uint32_t tcr : 4; /* [12:9] */ + __IO uint32_t tar : 4; /* [16:13] */ + __IO uint32_t eccpgs : 3; /* [19:17] */ + __IO uint32_t reserved3 : 12;/* [31:20] */ + } bk2ctrl_bit; + }; + + /** + * @brief xmc bk2is register, offset:0x64 + */ + union + { + __IO uint32_t bk2is; + struct + { + __IO uint32_t res : 1; /* [0] */ + __IO uint32_t hls : 1; /* [1] */ + __IO uint32_t fes : 1; /* [2] */ + __IO uint32_t reien : 1; /* [3] */ + __IO uint32_t hlien : 1; /* [4] */ + __IO uint32_t feien : 1; /* [5] */ + __IO uint32_t fifoe : 1; /* [6] */ + __IO uint32_t reserved1 : 25;/* [31:7] */ + } bk2is_bit; + }; + + /** + * @brief xmc bk2tmgmem register, offset:0x68 + */ + union + { + __IO uint32_t bk2tmgmem; + struct + { + __IO uint32_t cmst : 8; /* [7:0] */ + __IO uint32_t cmwt : 8; /* [15:8] */ + __IO uint32_t cmht : 8; /* [23:16] */ + __IO uint32_t cmdhizt : 8; /* [31:24] */ + } bk2tmgmem_bit; + }; + + /** + * @brief xmc bk2tmgatt register, offset:0x6C + */ + union + { + __IO uint32_t bk2tmgatt; + struct + { + __IO uint32_t amst : 8; /* [7:0] */ + __IO uint32_t amwt : 8; /* [15:8] */ + __IO uint32_t amht : 8; /* [23:16] */ + __IO uint32_t amdhizt : 8; /* [31:24] */ + } bk2tmgatt_bit; + }; + + /** + * @brief xmc reserved register, offset:0x70 + */ + __IO uint32_t reserved1; + + /** + * @brief xmc bk2ecc register, offset:0x74 + */ + union + { + __IO uint32_t bk2ecc; + struct + { + __IO uint32_t ecc : 32; /* [31:0] */ + } bk2ecc_bit; + }; + +} xmc_bank2_type; + +/** + * @brief xmc bank3 registers + */ +typedef struct +{ + /** + * @brief xmc bk3ctrl register, offset:0x80 + */ + union + { + __IO uint32_t bk3ctrl; + struct + { + __IO uint32_t reserved1 : 1; /* [0] */ + __IO uint32_t nwen : 1; /* [1] */ + __IO uint32_t en : 1; /* [2] */ + __IO uint32_t dev : 1; /* [3] */ + __IO uint32_t extmdbw : 2; /* [5:4] */ + __IO uint32_t eccen : 1; /* [6] */ + __IO uint32_t reserved2 : 2; /* [8:7] */ + __IO uint32_t tcr : 4; /* [12:9] */ + __IO uint32_t tar : 4; /* [16:13] */ + __IO uint32_t eccpgs : 3; /* [19:17] */ + __IO uint32_t reserved3 : 12;/* [31:20] */ + } bk3ctrl_bit; + }; + + /** + * @brief xmc bk3is register, offset:0x84 + */ + union + { + __IO uint32_t bk3is; + struct + { + __IO uint32_t res : 1; /* [0] */ + __IO uint32_t hls : 1; /* [1] */ + __IO uint32_t fes : 1; /* [2] */ + __IO uint32_t reien : 1; /* [3] */ + __IO uint32_t hlien : 1; /* [4] */ + __IO uint32_t feien : 1; /* [5] */ + __IO uint32_t fifoe : 1; /* [6] */ + __IO uint32_t reserved1 : 25;/* [31:7] */ + } bk3is_bit; + }; + + /** + * @brief xmc bk3tmgmem register, offset:0x88 + */ + union + { + __IO uint32_t bk3tmgmem; + struct + { + __IO uint32_t cmst : 8; /* [7:0] */ + __IO uint32_t cmwt : 8; /* [15:8] */ + __IO uint32_t cmht : 8; /* [23:16] */ + __IO uint32_t cmdhizt : 8; /* [31:24] */ + } bk3tmgmem_bit; + }; + + /** + * @brief xmc bk3tmgatt register, offset:0x8C + */ + union + { + __IO uint32_t bk3tmgatt; + struct + { + __IO uint32_t amst : 8; /* [7:0] */ + __IO uint32_t amwt : 8; /* [15:8] */ + __IO uint32_t amht : 8; /* [23:16] */ + __IO uint32_t amdhizt : 8; /* [31:24] */ + } bk3tmgatt_bit; + }; + + /** + * @brief xmc reserved register, offset:0x90 + */ + __IO uint32_t reserved1; + + /** + * @brief xmc bk3ecc register, offset:0x94 + */ + union + { + __IO uint32_t bk3ecc; + struct + { + __IO uint32_t ecc : 32; /* [31:0] */ + } bk3ecc_bit; + }; +} xmc_bank3_type; + +/** + * @brief xmc bank4 registers + */ +typedef struct +{ + + /** + * @brief xmc bk4ctrl register, offset:0xA0 + */ + union + { + __IO uint32_t bk4ctrl; + struct + { + __IO uint32_t reserved1 : 1; /* [0] */ + __IO uint32_t nwen : 1; /* [1] */ + __IO uint32_t en : 1; /* [2] */ + __IO uint32_t dev : 1; /* [3] */ + __IO uint32_t extmdbw : 2; /* [5:4] */ + __IO uint32_t eccen : 1; /* [6] */ + __IO uint32_t reserved2 : 2; /* [8:7] */ + __IO uint32_t tcr : 4; /* [12:9] */ + __IO uint32_t tar : 4; /* [16:13] */ + __IO uint32_t eccpgs : 3; /* [19:17] */ + __IO uint32_t reserved3 : 12;/* [31:20] */ + } bk4ctrl_bit; + }; + + /** + * @brief xmc bk4is register, offset:0xA4 + */ + union + { + __IO uint32_t bk4is; + struct + { + __IO uint32_t res : 1; /* [0] */ + __IO uint32_t hls : 1; /* [1] */ + __IO uint32_t fes : 1; /* [2] */ + __IO uint32_t reien : 1; /* [3] */ + __IO uint32_t hlien : 1; /* [4] */ + __IO uint32_t feien : 1; /* [5] */ + __IO uint32_t fifoe : 1; /* [6] */ + __IO uint32_t reserved1 : 25;/* [31:7] */ + } bk4is_bit; + }; + + /** + * @brief xmc bk4tmgmem register, offset:0xA8 + */ + union + { + __IO uint32_t bk4tmgmem; + struct + { + __IO uint32_t cmst : 8; /* [7:0] */ + __IO uint32_t cmwt : 8; /* [15:8] */ + __IO uint32_t cmht : 8; /* [23:16] */ + __IO uint32_t cmdhizt : 8; /* [31:24] */ + } bk4tmgmem_bit; + }; + + /** + * @brief xmc bk4tmgatt register, offset:0xAC + */ + union + { + __IO uint32_t bk4tmgatt; + struct + { + __IO uint32_t amst : 8; /* [7:0] */ + __IO uint32_t amwt : 8; /* [15:8] */ + __IO uint32_t amht : 8; /* [23:16] */ + __IO uint32_t amdhizt : 8; /* [31:24] */ + } bk4tmgatt_bit; + }; + + /** + * @brief xmc bk4tmgio register, offset:0xB0 + */ + union + { + __IO uint32_t bk4tmgio; + struct + { + __IO uint32_t iost : 8; /* [7:0] */ + __IO uint32_t iowt : 8; /* [15:8] */ + __IO uint32_t ioht : 8; /* [23:16] */ + __IO uint32_t iohizt : 8; /* [31:24] */ + } bk4tmgio_bit; + }; +} xmc_bank4_type; + +/** + * @brief xmc sdram type + */ +typedef struct +{ + /** + * @brief xmc sdram ctrl register, offset:0x140~0x144 + */ + union + { + __IO uint32_t ctrl[2]; + struct + { + __IO uint32_t ca : 2; /* [1:0] */ + __IO uint32_t ra : 2; /* [3:2] */ + __IO uint32_t db : 2; /* [5:4] */ + __IO uint32_t inbk : 1; /* [6] */ + __IO uint32_t cas : 2; /* [8:7] */ + __IO uint32_t wrp : 1; /* [9] */ + __IO uint32_t clkdiv : 2; /* [11:10] */ + __IO uint32_t bstr : 1; /* [12] */ + __IO uint32_t rd : 2; /* [14:13] */ + __IO uint32_t reserved1 : 17;/* [31:15] */ + } ctrl_bit[2]; + }; + + /** + * @brief xmc sdram tm register, offset:0x148~0x14C + */ + union + { + __IO uint32_t tm[2]; + struct + { + __IO uint32_t tmrd : 4; /* [3:0] */ + __IO uint32_t txsr : 4; /* [7:4] */ + __IO uint32_t tras : 4; /* [11:8] */ + __IO uint32_t trc : 4; /* [15:12] */ + __IO uint32_t twr : 4; /* [19:16] */ + __IO uint32_t trp : 4; /* [23:20] */ + __IO uint32_t trcd : 4; /* [27:24] */ + __IO uint32_t reserved1 : 4; /* [31:28] */ + } tm_bit[2]; + + }; + +/** + * @brief xmc sdram cmd register, offset:0x150 + */ + union + { + __IO uint32_t cmd; + struct + { + __IO uint32_t cmd : 3; /* [2:0] */ + __IO uint32_t bk2 : 1; /* [3] */ + __IO uint32_t bk1 : 1; /* [4] */ + __IO uint32_t art : 4; /* [8:5] */ + __IO uint32_t mrd : 13;/* [21:9] */ + __IO uint32_t reserved1 : 10;/* [31:22] */ + } cmd_bit; + }; + + /** + * @brief xmc sdram rcnt register, offset:0x154 + */ + union + { + __IO uint32_t rcnt; + struct + { + __IO uint32_t errc : 1; /* [0] */ + __IO uint32_t rc : 13;/* [13:1] */ + __IO uint32_t erien : 1; /* [14] */ + __IO uint32_t reserved1 : 17;/* [31:15] */ + } rcnt_bit; + }; + + /** + * @brief xmc sdram sts register, offset:0x158 + */ + union + { + __IO uint32_t sts; + struct + { + __IO uint32_t err : 1; /* [0] */ + __IO uint32_t bk1sts : 2; /* [2:1] */ + __IO uint32_t bk2sts : 2; /* [4:3] */ + __IO uint32_t busy : 1; /* [5] */ + __IO uint32_t reserved1 : 26;/* [31:6] */ + } sts_bit; + }; +}xmc_sdram_type; + +/** + * @} + */ + +#define XMC_BANK1 ((xmc_bank1_type *) XMC_BANK1_REG_BASE) +#define XMC_BANK2 ((xmc_bank2_type *) XMC_BANK2_REG_BASE) +#define XMC_BANK3 ((xmc_bank3_type *) XMC_BANK3_REG_BASE) +#define XMC_BANK4 ((xmc_bank4_type *) XMC_BANK4_REG_BASE) +#define XMC_SDRAM ((xmc_sdram_type *) XMC_SDRAM_REG_BASE) + +/** @defgroup XMC_exported_functions + * @{ + */ + +void xmc_nor_sram_reset(xmc_nor_sram_subbank_type xmc_subbank); +void xmc_nor_sram_init(xmc_norsram_init_type* xmc_norsram_init_struct); +void xmc_nor_sram_timing_config(xmc_norsram_timing_init_type* xmc_rw_timing_struct, + xmc_norsram_timing_init_type* xmc_w_timing_struct); +void xmc_norsram_default_para_init(xmc_norsram_init_type* xmc_nor_sram_init_struct); +void xmc_norsram_timing_default_para_init(xmc_norsram_timing_init_type* xmc_rw_timing_struct, + xmc_norsram_timing_init_type* xmc_w_timing_struct); +void xmc_nor_sram_enable(xmc_nor_sram_subbank_type xmc_subbank, confirm_state new_state); +void xmc_ext_timing_config(xmc_nor_sram_subbank_type xmc_sub_bank, uint16_t w2w_timing, uint16_t r2r_timing); +void xmc_nand_reset(xmc_class_bank_type xmc_bank); +void xmc_nand_init(xmc_nand_init_type* xmc_nand_init_struct); +void xmc_nand_timing_config(xmc_nand_pccard_timinginit_type* xmc_common_spacetiming_struct, + xmc_nand_pccard_timinginit_type* xmc_attribute_spacetiming_struct); +void xmc_nand_default_para_init(xmc_nand_init_type* xmc_nand_init_struct); +void xmc_nand_timing_default_para_init(xmc_nand_pccard_timinginit_type* xmc_common_spacetiming_struct, + xmc_nand_pccard_timinginit_type* xmc_attribute_spacetiming_struct); +void xmc_nand_enable(xmc_class_bank_type xmc_bank, confirm_state new_state); +void xmc_nand_ecc_enable(xmc_class_bank_type xmc_bank, confirm_state new_state); +uint32_t xmc_ecc_get(xmc_class_bank_type xmc_bank); +void xmc_interrupt_enable(xmc_class_bank_type xmc_bank, xmc_interrupt_sources_type xmc_int, confirm_state new_state); +flag_status xmc_flag_status_get(xmc_class_bank_type xmc_bank, xmc_interrupt_flag_type xmc_flag); +void xmc_flag_clear(xmc_class_bank_type xmc_bank, xmc_interrupt_flag_type xmc_flag); +void xmc_pccard_reset(void); +void xmc_pccard_init(xmc_pccard_init_type* xmc_pccard_init_struct); +void xmc_pccard_timing_config(xmc_nand_pccard_timinginit_type* xmc_common_spacetiming_struct, + xmc_nand_pccard_timinginit_type* xmc_attribute_spacetiming_struct, + xmc_nand_pccard_timinginit_type* xmc_iospace_timing_struct); +void xmc_pccard_default_para_init(xmc_pccard_init_type* xmc_pccard_init_struct); +void xmc_pccard_timing_default_para_init(xmc_nand_pccard_timinginit_type* xmc_common_spacetiming_struct, + xmc_nand_pccard_timinginit_type* xmc_attribute_spacetiming_struct, + xmc_nand_pccard_timinginit_type* xmc_iospace_timing_struct); +void xmc_pccard_enable(confirm_state new_state); +void xmc_sdram_reset(xmc_sdram_bank_type xmc_bank); +void xmc_sdram_init(xmc_sdram_init_type *xmc_sdram_init_struct, xmc_sdram_timing_type *xmc_sdram_timing_struct); +void xmc_sdram_default_para_init(xmc_sdram_init_type *xmc_sdram_init_struct, xmc_sdram_timing_type *xmc_sdram_timing_struct); +void xmc_sdram_cmd(xmc_sdram_cmd_type *xmc_sdram_cmd_struct); +uint32_t xmc_sdram_status_get(xmc_sdram_bank_type xmc_bank); +void xmc_sdram_refresh_counter_set(uint32_t counter); +void xmc_sdram_auto_refresh_set(uint32_t number); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_acc.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_acc.c new file mode 100644 index 0000000000..18afcc3bae --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_acc.c @@ -0,0 +1,231 @@ +/** + ************************************************************************** + * @file at32f435_437_acc.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the acc firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup ACC + * @brief ACC driver modules + * @{ + */ + +#ifdef ACC_MODULE_ENABLED + +/** @defgroup ACC_private_functions + * @{ + */ + +/** + * @brief enable or disable the acc calibration mode. + * @param acc_trim: specifies the acc calibration type. + * this parameter can be one of the following values: + * - ACC_CAL_HICKCAL + * - ACC_CAL_HICKTRIM + * @param new_state: specifies the acc calibration to be enabled or disabled.(TRUE or FALSE) + * @retval none + */ +void acc_calibration_mode_enable(uint16_t acc_trim, confirm_state new_state) +{ + if(acc_trim == ACC_CAL_HICKCAL) + { + ACC->ctrl1_bit.entrim = FALSE; + } + else + { + ACC->ctrl1_bit.entrim = TRUE; + } + ACC->ctrl1_bit.calon = new_state; +} + +/** + * @brief store calibration step data in acc's ctrl1 register. + * @param step_value: value to be stored in the acc's ctrl1 register + * @retval none + */ +void acc_step_set(uint8_t step_value) +{ + ACC->ctrl1_bit.step = step_value; +} + +/** + * @brief select sof sourse for acc in acc's ctrl1 register. + * @param sof_sel: value to be stored in the acc's ctrl1 register + * this parameter can be one of the following values: + * @arg ACC_SOF_OTG1 + * @arg ACC_SOF_OTG2 + * @retval none + */ +void acc_sof_select(uint16_t sof_sel) +{ + ACC->ctrl1 |= sof_sel; +} + +/** + * @brief enable or disable the specified acc interrupts. + * @param acc_int: specifies the acc interrupt sources to be enabled or disabled. + * this parameter can be one of the following values: + * - ACC_CALRDYIEN_INT + * - ACC_EIEN_INT + * @param new_state (TRUE or FALSE) + * @retval none + */ +void acc_interrupt_enable(uint16_t acc_int, confirm_state new_state) +{ + if(acc_int == ACC_CALRDYIEN_INT) + { + ACC->ctrl1_bit.calrdyien = new_state; + } + else + { + ACC->ctrl1_bit.eien = new_state; + } +} + +/** + * @brief return the current acc hicktrim value. + * @param none + * @retval 8-bit hicktrim value. + */ +uint8_t acc_hicktrim_get(void) +{ + return ((uint8_t)(ACC->ctrl2_bit.hicktrim)); +} + +/** + * @brief return the current acc hickcal value. + * @param none + * @retval 8-bit hicktrim value. + */ +uint8_t acc_hickcal_get(void) +{ + return ((uint8_t)(ACC->ctrl2_bit.hickcal)); +} + +/** + * @brief wtire the value to acc c1 register. + * @param acc_c1_value + * @retval none. + */ +void acc_write_c1(uint16_t acc_c1_value) +{ + ACC->c1 = acc_c1_value; +} + +/** + * @brief wtire the value to acc c2 register. + * @param acc_c2_value + * @retval none. + */ +void acc_write_c2(uint16_t acc_c2_value) +{ + ACC->c2 = acc_c2_value; +} + +/** + * @brief wtire the value to acc c3 register. + * @param acc_c3_value + * @retval none. + */ +void acc_write_c3(uint16_t acc_c3_value) +{ + ACC->c3 = acc_c3_value; +} + +/** + * @brief return the current acc c1 value. + * @param none + * @retval 16-bit c1 value. + */ +uint16_t acc_read_c1(void) +{ + return ((uint16_t)(ACC->c1)); +} + +/** + * @brief return the current acc c2 value. + * @param none + * @retval 16-bit c2 value. + */ +uint16_t acc_read_c2(void) +{ + return ((uint16_t)(ACC->c2)); +} + +/** + * @brief return the current acc c3 value. + * @param none + * @retval 16-bit c3 value. + */ +uint16_t acc_read_c3(void) +{ + return ((uint16_t)(ACC->c3)); +} + +/** + * @brief check whether the specified acc flag is set or not. + * @param acc_flag: specifies the flag to check. + * this parameter can be one of the following values: + * - ACC_RSLOST_FLAG + * - ACC_CALRDY_FLAG + * @retval flag_status (SET or RESET) + */ +flag_status acc_flag_get(uint16_t acc_flag) +{ + if(acc_flag == ACC_CALRDY_FLAG) + return (flag_status)(ACC->sts_bit.calrdy); + else + return (flag_status)(ACC->sts_bit.rslost); +} + +/** + * @brief clear the specified acc flag is set or not. + * @param acc_flag: specifies the flag to check. + * this parameter can be any combination of the following values: + * - ACC_RSLOST_FLAG + * - ACC_CALRDY_FLAG + * @retval none + */ +void acc_flag_clear(uint16_t acc_flag) +{ + ACC->sts = ~acc_flag; +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_adc.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_adc.c new file mode 100644 index 0000000000..e0a12df55f --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_adc.c @@ -0,0 +1,1215 @@ +/** + ************************************************************************** + * @file at32f435_437_adc.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the adc firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup ADC + * @brief ADC driver modules + * @{ + */ + +#ifdef ADC_MODULE_ENABLED + +/** @defgroup ADC_private_functions + * @{ + */ + +/** + * @brief deinitialize the adc peripheral registers to their default reset values. + * @param none + * @retval none + */ +void adc_reset(void) +{ + crm_periph_reset(CRM_ADC_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_ADC_PERIPH_RESET, FALSE); +} + +/** + * @brief enable or disable the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param new_state: new state of a/d converter. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void adc_enable(adc_type *adc_x, confirm_state new_state) +{ + adc_x->ctrl2_bit.adcen = new_state; +} + +/** + * @brief adc base default para init. + * @param sequence_mode: set the state of adc sequence mode. + * this parameter can be:TRUE or FALSE + * @param repeat_mode: set the state of adc repeat conversion mode. + * this parameter can be:TRUE or FALSE + * @param data_align: set the state of adc data alignment. + * this parameter can be one of the following values: + * - ADC_RIGHT_ALIGNMENT + * - ADC_LEFT_ALIGNMENT + * @param ordinary_channel_length: configure the adc ordinary channel sequence length. + * this parameter can be: + * - (0x1~0xf) + * @retval none + */ +void adc_base_default_para_init(adc_base_config_type *adc_base_struct) +{ + adc_base_struct->sequence_mode = FALSE; + adc_base_struct->repeat_mode = FALSE; + adc_base_struct->data_align = ADC_RIGHT_ALIGNMENT; + adc_base_struct->ordinary_channel_length = 1; +} + +/** + * @brief initialize the adc peripheral according to the specified parameters. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param sequence_mode: set the state of adc sequence mode. + * this parameter can be:TRUE or FALSE + * @param repeat_mode: set the state of adc repeat conversion mode. + * this parameter can be:TRUE or FALSE + * @param data_align: set the state of adc data alignment. + * this parameter can be one of the following values: + * - ADC_RIGHT_ALIGNMENT + * - ADC_LEFT_ALIGNMENT + * @param ordinary_channel_length: configure the adc ordinary channel sequence length. + * this parameter can be: + * - (0x1~0xf) + * @retval none + */ +void adc_base_config(adc_type *adc_x, adc_base_config_type *adc_base_struct) +{ + adc_x->ctrl1_bit.sqen = adc_base_struct->sequence_mode; + adc_x->ctrl2_bit.rpen = adc_base_struct->repeat_mode; + adc_x->ctrl2_bit.dtalign = adc_base_struct->data_align; + adc_x->osq1_bit.oclen = adc_base_struct->ordinary_channel_length - 1; +} + +/** + * @brief adc common default para init. + * @param combine_mode: configure the adc combine_mode mode. + * this parameter can be one of the following values: + * - ADC_INDEPENDENT_MODE - ADC_ORDINARY_SMLT_PREEMPT_SMLT_ONESLAVE_MODE - ADC_ORDINARY_SMLT_PREEMPT_INTERLTRIG_ONESLAVE_MODE + * - ADC_PREEMPT_SMLT_ONLY_ONESLAVE_MODE - ADC_ORDINARY_SMLT_ONLY_ONESLAVE_MODE - ADC_ORDINARY_SHIFT_ONLY_ONESLAVE_MODE + * - ADC_PREEMPT_INTERLTRIG_ONLY_ONESLAVE_MODE - ADC_ORDINARY_SMLT_PREEMPT_SMLT_TWOSLAVE_MODE - ADC_ORDINARY_SMLT_PREEMPT_INTERLTRIG_TWOSLAVE_MODE + * - ADC_PREEMPT_SMLT_ONLY_TWOSLAVE_MODE - ADC_ORDINARY_SMLT_ONLY_TWOSLAVE_MODE - ADC_ORDINARY_SHIFT_ONLY_TWOSLAVE_MODE + * - ADC_PREEMPT_INTERLTRIG_ONLY_TWOSLAVE_MODE + * @param div: configure the adc division. + * this parameter can be one of the following values: + * - ADC_HCLK_DIV_2 - ADC_HCLK_DIV_3 - ADC_HCLK_DIV_4 - ADC_HCLK_DIV_5 + * - ADC_HCLK_DIV_6 - ADC_HCLK_DIV_7 - ADC_HCLK_DIV_8 - ADC_HCLK_DIV_9 + * - ADC_HCLK_DIV_10 - ADC_HCLK_DIV_11 - ADC_HCLK_DIV_12 - ADC_HCLK_DIV_13 + * - ADC_HCLK_DIV_14 - ADC_HCLK_DIV_15 - ADC_HCLK_DIV_16 - ADC_HCLK_DIV_17 + * @param common_dma_mode: configure the adc common dma mode. + * this parameter can be one of the following values: + * - ADC_COMMON_DMAMODE_DISABLE + * - ADC_COMMON_DMAMODE_1 + * - ADC_COMMON_DMAMODE_2 + * - ADC_COMMON_DMAMODE_3 + * - ADC_COMMON_DMAMODE_4 + * - ADC_COMMON_DMAMODE_5 + * @param common_dma_request_repeat_state: set the adc common dma request repeat state. + * this parameter can be:TRUE or FALSE + * @param sampling_interval: configure the ordinary shifting mode adjacent adc sampling interval. + * this parameter can be one of the following values: + * - ADC_SAMPLING_INTERVAL_5CYCLES - ADC_SAMPLING_INTERVAL_6CYCLES - ADC_SAMPLING_INTERVAL_7CYCLES - ADC_SAMPLING_INTERVAL_8CYCLES + * - ADC_SAMPLING_INTERVAL_9CYCLES - ADC_SAMPLING_INTERVAL_10CYCLES - ADC_SAMPLING_INTERVAL_11CYCLES - ADC_SAMPLING_INTERVAL_12CYCLES + * - ADC_SAMPLING_INTERVAL_13CYCLES - ADC_SAMPLING_INTERVAL_14CYCLES - ADC_SAMPLING_INTERVAL_15CYCLES - ADC_SAMPLING_INTERVAL_16CYCLES + * - ADC_SAMPLING_INTERVAL_17CYCLES - ADC_SAMPLING_INTERVAL_18CYCLES - ADC_SAMPLING_INTERVAL_19CYCLES - ADC_SAMPLING_INTERVAL_20CYCLES + * @param tempervintrv_state: set the adc temperature sensor and vintrv state. + * this parameter can be:TRUE or FALSE + * @param vbat_state: set the adc voltage battery state. + * this parameter can be:TRUE or FALSE + * @retval none + */ +void adc_common_default_para_init(adc_common_config_type *adc_common_struct) +{ + adc_common_struct->combine_mode = ADC_INDEPENDENT_MODE; + adc_common_struct->div = ADC_HCLK_DIV_2; + adc_common_struct->common_dma_mode = ADC_COMMON_DMAMODE_DISABLE; + adc_common_struct->common_dma_request_repeat_state = FALSE; + adc_common_struct->sampling_interval = ADC_SAMPLING_INTERVAL_5CYCLES; + adc_common_struct->tempervintrv_state = FALSE; + adc_common_struct->vbat_state = FALSE; +} + +/** + * @brief adc common default para init. + * @param combine_mode: configure the adc combine_mode mode. + * this parameter can be one of the following values: + * - ADC_INDEPENDENT_MODE - ADC_ORDINARY_SMLT_PREEMPT_SMLT_ONESLAVE_MODE - ADC_ORDINARY_SMLT_PREEMPT_INTERLTRIG_ONESLAVE_MODE + * - ADC_PREEMPT_SMLT_ONLY_ONESLAVE_MODE - ADC_ORDINARY_SMLT_ONLY_ONESLAVE_MODE - ADC_ORDINARY_SHIFT_ONLY_ONESLAVE_MODE + * - ADC_PREEMPT_INTERLTRIG_ONLY_ONESLAVE_MODE - ADC_ORDINARY_SMLT_PREEMPT_SMLT_TWOSLAVE_MODE - ADC_ORDINARY_SMLT_PREEMPT_INTERLTRIG_TWOSLAVE_MODE + * - ADC_PREEMPT_SMLT_ONLY_TWOSLAVE_MODE - ADC_ORDINARY_SMLT_ONLY_TWOSLAVE_MODE - ADC_ORDINARY_SHIFT_ONLY_TWOSLAVE_MODE + * - ADC_PREEMPT_INTERLTRIG_ONLY_TWOSLAVE_MODE + * @param div: configure the adc division. + * this parameter can be one of the following values: + * - ADC_HCLK_DIV_2 - ADC_HCLK_DIV_3 - ADC_HCLK_DIV_4 - ADC_HCLK_DIV_5 + * - ADC_HCLK_DIV_6 - ADC_HCLK_DIV_7 - ADC_HCLK_DIV_8 - ADC_HCLK_DIV_9 + * - ADC_HCLK_DIV_10 - ADC_HCLK_DIV_11 - ADC_HCLK_DIV_12 - ADC_HCLK_DIV_13 + * - ADC_HCLK_DIV_14 - ADC_HCLK_DIV_15 - ADC_HCLK_DIV_16 - ADC_HCLK_DIV_17 + * @param common_dma_mode: configure the adc common dma mode. + * this parameter can be one of the following values: + * - ADC_COMMON_DMAMODE_DISABLE + * - ADC_COMMON_DMAMODE_1 + * - ADC_COMMON_DMAMODE_2 + * - ADC_COMMON_DMAMODE_3 + * - ADC_COMMON_DMAMODE_4 + * - ADC_COMMON_DMAMODE_5 + * @param common_dma_request_repeat_state: set the adc common dma request repeat state. + * this parameter can be:TRUE or FALSE + * @param sampling_interval: configure the ordinary shifting mode adjacent adc sampling interval. + * this parameter can be one of the following values: + * - ADC_SAMPLING_INTERVAL_5CYCLES - ADC_SAMPLING_INTERVAL_6CYCLES - ADC_SAMPLING_INTERVAL_7CYCLES - ADC_SAMPLING_INTERVAL_8CYCLES + * - ADC_SAMPLING_INTERVAL_9CYCLES - ADC_SAMPLING_INTERVAL_10CYCLES - ADC_SAMPLING_INTERVAL_11CYCLES - ADC_SAMPLING_INTERVAL_12CYCLES + * - ADC_SAMPLING_INTERVAL_13CYCLES - ADC_SAMPLING_INTERVAL_14CYCLES - ADC_SAMPLING_INTERVAL_15CYCLES - ADC_SAMPLING_INTERVAL_16CYCLES + * - ADC_SAMPLING_INTERVAL_17CYCLES - ADC_SAMPLING_INTERVAL_18CYCLES - ADC_SAMPLING_INTERVAL_19CYCLES - ADC_SAMPLING_INTERVAL_20CYCLES + * @param tempervintrv_state: set the adc temperature sensor and vintrv state. + * this parameter can be:TRUE or FALSE + * @param vbat_state: set the adc voltage battery state. + * this parameter can be:TRUE or FALSE + * @retval none + */ +void adc_common_config(adc_common_config_type *adc_common_struct) +{ + ADCCOM->cctrl_bit.mssel = adc_common_struct->combine_mode; + ADCCOM->cctrl_bit.adcdiv = adc_common_struct->div; + if(adc_common_struct->common_dma_mode & 0x04) + { + ADCCOM->cctrl_bit.msdmasel_h = TRUE; + } + else + { + ADCCOM->cctrl_bit.msdmasel_h = FALSE; + } + ADCCOM->cctrl_bit.msdmasel_l = adc_common_struct->common_dma_mode &0x03; + ADCCOM->cctrl_bit.msdrcen = adc_common_struct->common_dma_request_repeat_state; + ADCCOM->cctrl_bit.asisel = adc_common_struct->sampling_interval; + ADCCOM->cctrl_bit.itsrven = adc_common_struct->tempervintrv_state; + ADCCOM->cctrl_bit.vbaten = adc_common_struct->vbat_state; +} + +/** + * @brief set resolution of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param resolution: set the conversion resolution. + * this parameter can be one of the following values: + * - ADC_RESOLUTION_12B + * - ADC_RESOLUTION_10B + * - ADC_RESOLUTION_8B + * - ADC_RESOLUTION_6B + * @retval none + */ +void adc_resolution_set(adc_type *adc_x, adc_resolution_type resolution) +{ + adc_x->ctrl1_bit.crsel = resolution; +} + +/** + * @brief enable or disable the adc voltage battery. + * @param new_state: new state of the adc voltage battery. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void adc_voltage_battery_enable(confirm_state new_state) +{ + ADCCOM->cctrl_bit.vbaten = new_state; +} + +/** + * @brief enable or disable the adc dma transfer. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param new_state: new state of the adc dma transfer. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void adc_dma_mode_enable(adc_type *adc_x, confirm_state new_state) +{ + adc_x->ctrl2_bit.ocdmaen = new_state; +} + +/** + * @brief enable or disable the adc dma request repeat. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param new_state: the adc dma request repeat state. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void adc_dma_request_repeat_enable(adc_type *adc_x, confirm_state new_state) +{ + adc_x->ctrl2_bit.ocdrcen = new_state; +} + +/** + * @brief enable or disable the specified adc interrupts. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param adc_int: specifies the adc interrupt sources to be enabled or disabled. + * this parameter can be one of the following values: + * - ADC_OCCE_INT + * - ADC_VMOR_INT + * - ADC_PCCE_INT + * - ADC_OCCO_INT + * @param new_state: new state of the specified adc interrupts. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void adc_interrupt_enable(adc_type *adc_x, uint32_t adc_int, confirm_state new_state) +{ + if(new_state == TRUE) + { + adc_x->ctrl1 |= adc_int; + } + else if(new_state == FALSE) + { + adc_x->ctrl1 &= ~adc_int; + } +} + +/** + * @brief set calibration value of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param adc_calibration_value: calibration value of adc. + * this parameter can be: + * - (0x00~0x7F) + * @retval none + */ +void adc_calibration_value_set(adc_type *adc_x, uint8_t adc_calibration_value) +{ + adc_x->calval = adc_calibration_value; +} + +/** + * @brief initialize calibration register of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @retval none + */ +void adc_calibration_init(adc_type *adc_x) +{ + adc_x->ctrl2_bit.adcalinit = TRUE; +} + +/** + * @brief get calibration register's initialize status of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @retval the new state of reset calibration register status(SET or RESET). + */ +flag_status adc_calibration_init_status_get(adc_type *adc_x) +{ + if(adc_x->ctrl2_bit.adcalinit) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief start calibration process of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @retval none + */ +void adc_calibration_start(adc_type *adc_x) +{ + adc_x->ctrl2_bit.adcal = TRUE; +} + +/** + * @brief get calibration status of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @retval the new state of calibration status(SET or RESET). + */ +flag_status adc_calibration_status_get(adc_type *adc_x) +{ + if(adc_x->ctrl2_bit.adcal) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief enable or disable the voltage monitoring on single/all ordinary or preempt channels of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param adc_voltage_monitoring: choose the adc_voltage_monitoring config. + * this parameter can be one of the following values: + * - ADC_VMONITOR_SINGLE_ORDINARY + * - ADC_VMONITOR_SINGLE_PREEMPT + * - ADC_VMONITOR_SINGLE_ORDINARY_PREEMPT + * - ADC_VMONITOR_ALL_ORDINARY + * - ADC_VMONITOR_ALL_PREEMPT + * - ADC_VMONITOR_ALL_ORDINARY_PREEMPT + * - ADC_VMONITOR_NONE + * @retval none + */ +void adc_voltage_monitor_enable(adc_type *adc_x, adc_voltage_monitoring_type adc_voltage_monitoring) +{ + adc_x->ctrl1_bit.ocvmen = FALSE; + adc_x->ctrl1_bit.pcvmen = FALSE; + adc_x->ctrl1_bit.vmsgen = FALSE; + adc_x->ctrl1 |= adc_voltage_monitoring; +} + +/** + * @brief set voltage monitoring's high and low thresholds value of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param adc_high_threshold: voltage monitoring's high thresholds value. + * this parameter can be: + * - (0x000~0xFFF) + * @param adc_low_threshold: voltage monitoring's low thresholds value. + * this parameter can be: + * - (0x000~0xFFF) + * @retval none + */ +void adc_voltage_monitor_threshold_value_set(adc_type *adc_x, uint16_t adc_high_threshold, uint16_t adc_low_threshold) +{ + adc_x->vmhb_bit.vmhb = adc_high_threshold; + adc_x->vmlb_bit.vmlb = adc_low_threshold; +} + +/** + * @brief select the voltage monitoring's channel of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param adc_channel: select the channel. + * this parameter can be one of the following values: + * - ADC_CHANNEL_0 - ADC_CHANNEL_1 - ADC_CHANNEL_2 - ADC_CHANNEL_3 + * - ADC_CHANNEL_4 - ADC_CHANNEL_5 - ADC_CHANNEL_6 - ADC_CHANNEL_7 + * - ADC_CHANNEL_8 - ADC_CHANNEL_9 - ADC_CHANNEL_10 - ADC_CHANNEL_11 + * - ADC_CHANNEL_12 - ADC_CHANNEL_13 - ADC_CHANNEL_14 - ADC_CHANNEL_15 + * - ADC_CHANNEL_16 - ADC_CHANNEL_17 - ADC_CHANNEL_18 + * @retval none + */ +void adc_voltage_monitor_single_channel_select(adc_type *adc_x, adc_channel_select_type adc_channel) +{ + adc_x->ctrl1_bit.vmcsel = adc_channel; +} + +/** + * @brief set ordinary channel's corresponding rank in the sequencer and sample time of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param adc_channel: select the channel. + * this parameter can be one of the following values: + * - ADC_CHANNEL_0 - ADC_CHANNEL_1 - ADC_CHANNEL_2 - ADC_CHANNEL_3 + * - ADC_CHANNEL_4 - ADC_CHANNEL_5 - ADC_CHANNEL_6 - ADC_CHANNEL_7 + * - ADC_CHANNEL_8 - ADC_CHANNEL_9 - ADC_CHANNEL_10 - ADC_CHANNEL_11 + * - ADC_CHANNEL_12 - ADC_CHANNEL_13 - ADC_CHANNEL_14 - ADC_CHANNEL_15 + * - ADC_CHANNEL_16 - ADC_CHANNEL_17 - ADC_CHANNEL_18 + * @param adc_sequence: set rank in the ordinary group sequencer. + * this parameter must be: + * - between 1 to 16 + * @param adc_sampletime: set the sampletime of adc channel. + * this parameter can be one of the following values: + * - ADC_SAMPLETIME_2_5 + * - ADC_SAMPLETIME_6_5 + * - ADC_SAMPLETIME_12_5 + * - ADC_SAMPLETIME_24_5 + * - ADC_SAMPLETIME_47_5 + * - ADC_SAMPLETIME_92_5 + * - ADC_SAMPLETIME_247_5 + * - ADC_SAMPLETIME_640_5 + * @retval none + */ +void adc_ordinary_channel_set(adc_type *adc_x, adc_channel_select_type adc_channel, uint8_t adc_sequence, adc_sampletime_select_type adc_sampletime) +{ + switch(adc_channel) + { + case ADC_CHANNEL_0: + adc_x->spt2_bit.cspt0 = adc_sampletime; + break; + case ADC_CHANNEL_1: + adc_x->spt2_bit.cspt1 = adc_sampletime; + break; + case ADC_CHANNEL_2: + adc_x->spt2_bit.cspt2 = adc_sampletime; + break; + case ADC_CHANNEL_3: + adc_x->spt2_bit.cspt3 = adc_sampletime; + break; + case ADC_CHANNEL_4: + adc_x->spt2_bit.cspt4 = adc_sampletime; + break; + case ADC_CHANNEL_5: + adc_x->spt2_bit.cspt5 = adc_sampletime; + break; + case ADC_CHANNEL_6: + adc_x->spt2_bit.cspt6 = adc_sampletime; + break; + case ADC_CHANNEL_7: + adc_x->spt2_bit.cspt7 = adc_sampletime; + break; + case ADC_CHANNEL_8: + adc_x->spt2_bit.cspt8 = adc_sampletime; + break; + case ADC_CHANNEL_9: + adc_x->spt2_bit.cspt9 = adc_sampletime; + break; + case ADC_CHANNEL_10: + adc_x->spt1_bit.cspt10 = adc_sampletime; + break; + case ADC_CHANNEL_11: + adc_x->spt1_bit.cspt11 = adc_sampletime; + break; + case ADC_CHANNEL_12: + adc_x->spt1_bit.cspt12 = adc_sampletime; + break; + case ADC_CHANNEL_13: + adc_x->spt1_bit.cspt13 = adc_sampletime; + break; + case ADC_CHANNEL_14: + adc_x->spt1_bit.cspt14 = adc_sampletime; + break; + case ADC_CHANNEL_15: + adc_x->spt1_bit.cspt15 = adc_sampletime; + break; + case ADC_CHANNEL_16: + adc_x->spt1_bit.cspt16 = adc_sampletime; + break; + case ADC_CHANNEL_17: + adc_x->spt1_bit.cspt17 = adc_sampletime; + break; + case ADC_CHANNEL_18: + adc_x->spt1_bit.cspt18 = adc_sampletime; + break; + default: + break; + } + switch(adc_sequence) + { + case 1: + adc_x->osq3_bit.osn1 = adc_channel; + break; + case 2: + adc_x->osq3_bit.osn2 = adc_channel; + break; + case 3: + adc_x->osq3_bit.osn3 = adc_channel; + break; + case 4: + adc_x->osq3_bit.osn4 = adc_channel; + break; + case 5: + adc_x->osq3_bit.osn5 = adc_channel; + break; + case 6: + adc_x->osq3_bit.osn6 = adc_channel; + break; + case 7: + adc_x->osq2_bit.osn7 = adc_channel; + break; + case 8: + adc_x->osq2_bit.osn8 = adc_channel; + break; + case 9: + adc_x->osq2_bit.osn9 = adc_channel; + break; + case 10: + adc_x->osq2_bit.osn10 = adc_channel; + break; + case 11: + adc_x->osq2_bit.osn11 = adc_channel; + break; + case 12: + adc_x->osq2_bit.osn12 = adc_channel; + break; + case 13: + adc_x->osq1_bit.osn13 = adc_channel; + break; + case 14: + adc_x->osq1_bit.osn14 = adc_channel; + break; + case 15: + adc_x->osq1_bit.osn15 = adc_channel; + break; + case 16: + adc_x->osq1_bit.osn16 = adc_channel; + break; + default: + break; + } +} + +/** + * @brief set preempt channel lenghth of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param adc_channel_lenght: set the adc preempt channel lenghth. + * this parameter can be: + * - (0x1~0x4) + * @retval none + */ +void adc_preempt_channel_length_set(adc_type *adc_x, uint8_t adc_channel_lenght) +{ + adc_x->psq_bit.pclen = adc_channel_lenght - 1; +} + +/** + * @brief configure preempt channel's corresponding rank in the sequencer and sample time of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param adc_channel: select the channel. + * this parameter can be one of the following values: + * - ADC_CHANNEL_0 - ADC_CHANNEL_1 - ADC_CHANNEL_2 - ADC_CHANNEL_3 + * - ADC_CHANNEL_4 - ADC_CHANNEL_5 - ADC_CHANNEL_6 - ADC_CHANNEL_7 + * - ADC_CHANNEL_8 - ADC_CHANNEL_9 - ADC_CHANNEL_10 - ADC_CHANNEL_11 + * - ADC_CHANNEL_12 - ADC_CHANNEL_13 - ADC_CHANNEL_14 - ADC_CHANNEL_15 + * - ADC_CHANNEL_16 - ADC_CHANNEL_17 - ADC_CHANNEL_18 + * @param adc_sequence: set rank in the preempt group sequencer. + * this parameter must be: + * - between 1 to 4 + * @param adc_sampletime: config the sampletime of adc channel. + * this parameter can be one of the following values: + * - ADC_SAMPLETIME_2_5 + * - ADC_SAMPLETIME_6_5 + * - ADC_SAMPLETIME_12_5 + * - ADC_SAMPLETIME_24_5 + * - ADC_SAMPLETIME_47_5 + * - ADC_SAMPLETIME_92_5 + * - ADC_SAMPLETIME_247_5 + * - ADC_SAMPLETIME_640_5 + * @retval none + */ +void adc_preempt_channel_set(adc_type *adc_x, adc_channel_select_type adc_channel, uint8_t adc_sequence, adc_sampletime_select_type adc_sampletime) +{ + uint16_t sequence_index=0; + switch(adc_channel) + { + case ADC_CHANNEL_0: + adc_x->spt2_bit.cspt0 = adc_sampletime; + break; + case ADC_CHANNEL_1: + adc_x->spt2_bit.cspt1 = adc_sampletime; + break; + case ADC_CHANNEL_2: + adc_x->spt2_bit.cspt2 = adc_sampletime; + break; + case ADC_CHANNEL_3: + adc_x->spt2_bit.cspt3 = adc_sampletime; + break; + case ADC_CHANNEL_4: + adc_x->spt2_bit.cspt4 = adc_sampletime; + break; + case ADC_CHANNEL_5: + adc_x->spt2_bit.cspt5 = adc_sampletime; + break; + case ADC_CHANNEL_6: + adc_x->spt2_bit.cspt6 = adc_sampletime; + break; + case ADC_CHANNEL_7: + adc_x->spt2_bit.cspt7 = adc_sampletime; + break; + case ADC_CHANNEL_8: + adc_x->spt2_bit.cspt8 = adc_sampletime; + break; + case ADC_CHANNEL_9: + adc_x->spt2_bit.cspt9 = adc_sampletime; + break; + case ADC_CHANNEL_10: + adc_x->spt1_bit.cspt10 = adc_sampletime; + break; + case ADC_CHANNEL_11: + adc_x->spt1_bit.cspt11 = adc_sampletime; + break; + case ADC_CHANNEL_12: + adc_x->spt1_bit.cspt12 = adc_sampletime; + break; + case ADC_CHANNEL_13: + adc_x->spt1_bit.cspt13 = adc_sampletime; + break; + case ADC_CHANNEL_14: + adc_x->spt1_bit.cspt14 = adc_sampletime; + break; + case ADC_CHANNEL_15: + adc_x->spt1_bit.cspt15 = adc_sampletime; + break; + case ADC_CHANNEL_16: + adc_x->spt1_bit.cspt16 = adc_sampletime; + break; + case ADC_CHANNEL_17: + adc_x->spt1_bit.cspt17 = adc_sampletime; + break; + case ADC_CHANNEL_18: + adc_x->spt1_bit.cspt18 = adc_sampletime; + break; + default: + break; + } + sequence_index = adc_sequence + 3 - adc_x->psq_bit.pclen; + switch(sequence_index) + { + case 1: + adc_x->psq_bit.psn1 = adc_channel; + break; + case 2: + adc_x->psq_bit.psn2 = adc_channel; + break; + case 3: + adc_x->psq_bit.psn3 = adc_channel; + break; + case 4: + adc_x->psq_bit.psn4 = adc_channel; + break; + default: + break; + } +} + +/** + * @brief set the ordinary channel's external trigger edge and + * set external trigger event of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param adc_ordinary_trig: select the external trigger event. + * this parameter can be one of the following values: + * - ADC_ORDINARY_TRIG_TMR1CH1 - ADC_ORDINARY_TRIG_TMR1CH2 - ADC_ORDINARY_TRIG_TMR1CH3 - ADC_ORDINARY_TRIG_TMR2CH2 + * - ADC_ORDINARY_TRIG_TMR2CH3 - ADC_ORDINARY_TRIG_TMR2CH4 - ADC_ORDINARY_TRIG_TMR2TRGOUT - ADC_ORDINARY_TRIG_TMR3CH1 + * - ADC_ORDINARY_TRIG_TMR3TRGOUT - ADC_ORDINARY_TRIG_TMR4CH4 - ADC_ORDINARY_TRIG_TMR5CH1 - ADC_ORDINARY_TRIG_TMR5CH2 + * - ADC_ORDINARY_TRIG_TMR5CH3 - ADC_ORDINARY_TRIG_TMR8CH1 - ADC_ORDINARY_TRIG_TMR8TRGOUT - ADC_ORDINARY_TRIG_EXINT11 + * - ADC_ORDINARY_TRIG_TMR20TRGOUT - ADC_ORDINARY_TRIG_TMR20TRGOUT2 - ADC_ORDINARY_TRIG_TMR20CH1 - ADC_ORDINARY_TRIG_TMR20CH2 + * - ADC_ORDINARY_TRIG_TMR20CH3 - ADC_ORDINARY_TRIG_TMR8TRGOUT2 - ADC_ORDINARY_TRIG_TMR1TRGOUT2 - ADC_ORDINARY_TRIG_TMR4TRGOUT + * - ADC_ORDINARY_TRIG_TMR6TRGOUT - ADC_ORDINARY_TRIG_TMR3CH4 - ADC_ORDINARY_TRIG_TMR4CH1 - ADC_ORDINARY_TRIG_TMR1TRGOUT + * - ADC_ORDINARY_TRIG_TMR2CH1 - ADC_ORDINARY_TRIG_TMR7TRGOUT + * @param adc_ordinary_trig_edge: ordinary channel conversion's external_trigger_edge. + * this parameter can be one of the following values: + * - ADC_ORDINARY_TRIG_EDGE_NONE + * - ADC_ORDINARY_TRIG_EDGE_RISING + * - ADC_ORDINARY_TRIG_EDGE_FALLING + * - ADC_ORDINARY_TRIG_EDGE_RISING_FALLING + * @retval none + */ +void adc_ordinary_conversion_trigger_set(adc_type *adc_x, adc_ordinary_trig_select_type adc_ordinary_trig, adc_ordinary_trig_edge_type adc_ordinary_trig_edge) +{ + if(adc_ordinary_trig > ADC_ORDINARY_TRIG_EXINT11) + { + adc_x->ctrl2_bit.octesel_h = 1; + adc_x->ctrl2_bit.octesel_l = adc_ordinary_trig & 0x0F; + } + else + { + adc_x->ctrl2_bit.octesel_h = 0; + adc_x->ctrl2_bit.octesel_l = adc_ordinary_trig & 0x0F; + } + adc_x->ctrl2_bit.ocete = adc_ordinary_trig_edge; +} + +/** + * @brief enable or disable the preempt channel's external trigger and + * set external trigger event of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param adc_preempt_trig: select the external trigger event. + * this parameter can be one of the following values: + * - ADC_PREEMPT_TRIG_TMR1CH4 - ADC_PREEMPT_TRIG_TMR1TRGOUT - ADC_PREEMPT_TRIG_TMR2CH1 - ADC_PREEMPT_TRIG_TMR2TRGOUT + * - ADC_PREEMPT_TRIG_TMR3CH2 - ADC_PREEMPT_TRIG_TMR3CH4 - ADC_PREEMPT_TRIG_TMR4CH1 - ADC_PREEMPT_TRIG_TMR4CH2 + * - ADC_PREEMPT_TRIG_TMR4CH3 - ADC_PREEMPT_TRIG_TMR4TRGOUT - ADC_PREEMPT_TRIG_TMR5CH4 - ADC_PREEMPT_TRIG_TMR5TRGOUT + * - ADC_PREEMPT_TRIG_TMR8CH2 - ADC_PREEMPT_TRIG_TMR8CH3 - ADC_PREEMPT_TRIG_TMR8CH4 - ADC_PREEMPT_TRIG_EXINT15 + * - ADC_PREEMPT_TRIG_TMR20TRGOUT - ADC_PREEMPT_TRIG_TMR20TRGOUT2 - ADC_PREEMPT_TRIG_TMR20CH4 - ADC_PREEMPT_TRIG_TMR1TRGOUT2 + * - ADC_PREEMPT_TRIG_TMR8TRGOUT - ADC_PREEMPT_TRIG_TMR8TRGOUT2 - ADC_PREEMPT_TRIG_TMR3CH3 - ADC_PREEMPT_TRIG_TMR3TRGOUT + * - ADC_PREEMPT_TRIG_TMR3CH1 - ADC_PREEMPT_TRIG_TMR6TRGOUT - ADC_PREEMPT_TRIG_TMR4CH4 - ADC_PREEMPT_TRIG_TMR1CH3 + * - ADC_PREEMPT_TRIG_TMR20CH2 - ADC_PREEMPT_TRIG_TMR7TRGOUT + * @param adc_preempt_trig_edge: preempt channel conversion's external_trigger_edge. + * this parameter can be one of the following values: + * - ADC_PREEMPT_TRIG_EDGE_NONE + * - ADC_PREEMPT_TRIG_EDGE_RISING + * - ADC_PREEMPT_TRIG_EDGE_FALLING + * - ADC_PREEMPT_TRIG_EDGE_RISING_FALLING + * @retval none + */ +void adc_preempt_conversion_trigger_set(adc_type *adc_x, adc_preempt_trig_select_type adc_preempt_trig, adc_preempt_trig_edge_type adc_preempt_trig_edge) +{ + if(adc_preempt_trig > ADC_PREEMPT_TRIG_EXINT15) + { + adc_x->ctrl2_bit.pctesel_h = 1; + adc_x->ctrl2_bit.pctesel_l = adc_preempt_trig & 0x0F; + } + else + { + adc_x->ctrl2_bit.pctesel_h = 0; + adc_x->ctrl2_bit.pctesel_l = adc_preempt_trig & 0x0F; + } + adc_x->ctrl2_bit.pcete = adc_preempt_trig_edge; +} + +/** + * @brief set preempt channel's conversion value offset of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param adc_preempt_channel: select the preempt channel. + * this parameter can be one of the following values: + * - ADC_PREEMPT_CHANNEL_1 + * - ADC_PREEMPT_CHANNEL_2 + * - ADC_PREEMPT_CHANNEL_3 + * - ADC_PREEMPT_CHANNEL_4 + * @param adc_offset_value: set the adc preempt channel's conversion value offset. + * this parameter can be: + * - (0x000~0xFFF) + * @retval none + */ +void adc_preempt_offset_value_set(adc_type *adc_x, adc_preempt_channel_type adc_preempt_channel, uint16_t adc_offset_value) +{ + switch(adc_preempt_channel) + { + case ADC_PREEMPT_CHANNEL_1: + adc_x->pcdto1_bit.pcdto1 = adc_offset_value; + break; + case ADC_PREEMPT_CHANNEL_2: + adc_x->pcdto2_bit.pcdto2 = adc_offset_value; + break; + case ADC_PREEMPT_CHANNEL_3: + adc_x->pcdto3_bit.pcdto3 = adc_offset_value; + break; + case ADC_PREEMPT_CHANNEL_4: + adc_x->pcdto4_bit.pcdto4 = adc_offset_value; + break; + default: + break; + } +} + +/** + * @brief set partitioned mode channel count of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param adc_channel_count: configure the adc partitioned mode channel count. + * this parameter can be: + * - (0x1~0x8) + * @retval none + */ +void adc_ordinary_part_count_set(adc_type *adc_x, uint8_t adc_channel_count) +{ + + adc_x->ctrl1_bit.ocpcnt = adc_channel_count - 1; +} + +/** + * @brief enable or disable the partitioned mode on ordinary channel of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param new_state: new state of ordinary channel's partitioned mode. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void adc_ordinary_part_mode_enable(adc_type *adc_x, confirm_state new_state) +{ + adc_x->ctrl1_bit.ocpen = new_state; +} + +/** + * @brief enable or disable the partitioned mode on preempt channel of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param new_state: new state of preempt channel's partitioned mode. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void adc_preempt_part_mode_enable(adc_type *adc_x, confirm_state new_state) +{ + adc_x->ctrl1_bit.pcpen = new_state; +} + +/** + * @brief enable or disable automatic preempt group conversion of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param new_state: new state of automatic preempt group conversion. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void adc_preempt_auto_mode_enable(adc_type *adc_x, confirm_state new_state) +{ + adc_x->ctrl1_bit.pcautoen = new_state; +} + +/** + * @brief stop the ongoing conversion of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @retval none + */ +void adc_conversion_stop(adc_type *adc_x) +{ + adc_x->ctrl2_bit.adabrt = TRUE; +} + +/** + * @brief get stop conversion's status of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @retval the new state of stop conversion's status(SET or RESET). + */ +flag_status adc_conversion_stop_status_get(adc_type *adc_x) +{ + if(adc_x->ctrl2_bit.adabrt) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief enable or disable each ordinary channel conversion set occe flag of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param new_state: new state of each ordinary channel conversion set occe flag. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void adc_occe_each_conversion_enable(adc_type *adc_x, confirm_state new_state) +{ + adc_x->ctrl2_bit.eocsfen = new_state; +} + +/** + * @brief enable or disable ordinary software start conversion of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param new_state: new state of ordinary software start conversion. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void adc_ordinary_software_trigger_enable(adc_type *adc_x, confirm_state new_state) +{ + adc_x->ctrl2_bit.ocswtrg = new_state; +} + +/** + * @brief get ordinary software start conversion status of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @retval the new state of ordinary software start conversion status(SET or RESET). + */ +flag_status adc_ordinary_software_trigger_status_get(adc_type *adc_x) +{ + if(adc_x->ctrl2_bit.ocswtrg) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief enable or disable preempt software start conversion of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param new_state: new state of preempt software start conversion. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void adc_preempt_software_trigger_enable(adc_type *adc_x, confirm_state new_state) +{ + adc_x->ctrl2_bit.pcswtrg = new_state; +} + +/** + * @brief get preempt software start conversion status of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @retval the new state of preempt software start conversion status(SET or RESET). + */ +flag_status adc_preempt_software_trigger_status_get(adc_type *adc_x) +{ + if(adc_x->ctrl2_bit.pcswtrg) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief return the last conversion data for ordinary channel of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @retval the last conversion data for ordinary channel. + */ +uint16_t adc_ordinary_conversion_data_get(adc_type *adc_x) +{ + return (uint16_t)(adc_x->odt_bit.odt); +} + +/** + * @brief return the last ordinary conversion data of combine adc. + * @retval the last conversion data for ordinary channel. + */ +uint32_t adc_combine_ordinary_conversion_data_get(void) +{ + return (uint32_t)(ADCCOM->codt); +} + +/** + * @brief return the conversion data for selection preempt channel of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param adc_preempt_channel: select the preempt channel. + * this parameter can be one of the following values: + * - ADC_PREEMPT_CHANNEL_1 + * - ADC_PREEMPT_CHANNEL_2 + * - ADC_PREEMPT_CHANNEL_3 + * - ADC_PREEMPT_CHANNEL_4 + * @retval the conversion data for selection preempt channel. + */ +uint16_t adc_preempt_conversion_data_get(adc_type *adc_x, adc_preempt_channel_type adc_preempt_channel) +{ + uint16_t preempt_conv_data_index = 0; + switch(adc_preempt_channel) + { + case ADC_PREEMPT_CHANNEL_1: + preempt_conv_data_index = (uint16_t)(adc_x->pdt1_bit.pdt1); + break; + case ADC_PREEMPT_CHANNEL_2: + preempt_conv_data_index = (uint16_t)(adc_x->pdt2_bit.pdt2); + break; + case ADC_PREEMPT_CHANNEL_3: + preempt_conv_data_index = (uint16_t)(adc_x->pdt3_bit.pdt3); + break; + case ADC_PREEMPT_CHANNEL_4: + preempt_conv_data_index = (uint16_t)(adc_x->pdt4_bit.pdt4); + break; + default: + break; + } + return preempt_conv_data_index; +} + +/** + * @brief get flag of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param adc_flag: select the adc flag. + * this parameter can be one of the following values: + * - ADC_VMOR_FLAG + * - ADC_OCCE_FLAG + * - ADC_PCCE_FLAG + * - ADC_PCCS_FLAG(no interrupt associated) + * - ADC_OCCS_FLAG(no interrupt associated) + * - ADC_OCCO_FLAG + * - ADC_RDY_FLAG(no interrupt associated) + * @retval the new state of adc flag status(SET or RESET). + */ +flag_status adc_flag_get(adc_type *adc_x, uint8_t adc_flag) +{ + flag_status status = RESET; + + if((adc_x->sts & adc_flag) == RESET) + { + status = RESET; + } + else + { + status = SET; + } + return status; +} + +/** + * @brief clear flag of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * ADC1, ADC2, ADC3. + * @param adc_flag: select the adc flag. + * this parameter can be any combination of the following values: + * - ADC_VMOR_FLAG + * - ADC_OCCE_FLAG(also can clear by reading the adc_x->odt) + * - ADC_PCCE_FLAG + * - ADC_PCCS_FLAG + * - ADC_OCCS_FLAG + * - ADC_OCCO_FLAG + * - note:"ADC_RDY_FLAG" cannot be choose!rdy bit is readonly bit,it means the adc is ready to accept conversion request + * @retval none + */ +void adc_flag_clear(adc_type *adc_x, uint32_t adc_flag) +{ + adc_x->sts = ~adc_flag; +} + +/** + * @brief enable or disable the ordinary oversampling of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param new_state: new state of ordinary oversampling. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void adc_ordinary_oversample_enable(adc_type *adc_x, confirm_state new_state) +{ + adc_x->ovsp_bit.oosen = new_state; +} + +/** + * @brief enable or disable the preempt oversampling of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param new_state: new state of preempt oversampling. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void adc_preempt_oversample_enable(adc_type *adc_x, confirm_state new_state) +{ + adc_x->ovsp_bit.posen = new_state; +} + +/** + * @brief config the oversampling ratio and shift of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param adc_oversample_ratio: set the oversample ratio. + * this parameter can be one of the following values: + * - ADC_OVERSAMPLE_RATIO_2 + * - ADC_OVERSAMPLE_RATIO_4 + * - ADC_OVERSAMPLE_RATIO_8 + * - ADC_OVERSAMPLE_RATIO_16 + * - ADC_OVERSAMPLE_RATIO_32 + * - ADC_OVERSAMPLE_RATIO_64 + * - ADC_OVERSAMPLE_RATIO_128 + * - ADC_OVERSAMPLE_RATIO_256 + * @param adc_oversample_shift: set the oversample shift. + * this parameter can be one of the following values: + * - ADC_OVERSAMPLE_SHIFT_0 + * - ADC_OVERSAMPLE_SHIFT_1 + * - ADC_OVERSAMPLE_SHIFT_2 + * - ADC_OVERSAMPLE_SHIFT_3 + * - ADC_OVERSAMPLE_SHIFT_4 + * - ADC_OVERSAMPLE_SHIFT_5 + * - ADC_OVERSAMPLE_SHIFT_6 + * - ADC_OVERSAMPLE_SHIFT_7 + * - ADC_OVERSAMPLE_SHIFT_8 + * @retval none + */ +void adc_oversample_ratio_shift_set(adc_type *adc_x, adc_oversample_ratio_type adc_oversample_ratio, adc_oversample_shift_type adc_oversample_shift) +{ + adc_x->ovsp_bit.osrsel = adc_oversample_ratio; + adc_x->ovsp_bit.osssel = adc_oversample_shift; +} + +/** + * @brief enable or disable the ordinary oversampling trigger mode of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param new_state: new state of ordinary oversampling trigger mode. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void adc_ordinary_oversample_trig_enable(adc_type *adc_x, confirm_state new_state) +{ + adc_x->ovsp_bit.oostren = new_state; +} + +/** + * @brief set ordinary oversample restart mode of the specified adc peripheral. + * @param adc_x: select the adc peripheral. + * this parameter can be one of the following values: + * - ADC1, ADC2, ADC3. + * @param adc_or_oversample_restart: ordinary oversample restart mode. + * this parameter can be one of the following values: + * - ADC_OVERSAMPLE_CONTINUE + * - ADC_OVERSAMPLE_RESTART + * @retval none + */ +void adc_ordinary_oversample_restart_set(adc_type *adc_x, adc_ordinary_oversample_restart_type adc_ordinary_oversample_restart) +{ + adc_x->ovsp_bit.oosrsel = adc_ordinary_oversample_restart; +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_can.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_can.c new file mode 100644 index 0000000000..1e6c389f33 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_can.c @@ -0,0 +1,1148 @@ +/** + ************************************************************************** + * @file at32f435_437_can.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the can firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup CAN + * @brief CAN driver modules + * @{ + */ + +#ifdef CAN_MODULE_ENABLED + +/** @defgroup CAN_private_functions + * @{ + */ + +/** + * @brief deinitialize the can peripheral registers to their default reset values. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1,CAN2. + * @retval none. + */ +void can_reset(can_type* can_x) +{ + if(can_x == CAN1) + { + crm_periph_reset(CRM_CAN1_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_CAN1_PERIPH_RESET, FALSE); + } + else if(can_x == CAN2) + { + crm_periph_reset(CRM_CAN2_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_CAN2_PERIPH_RESET, FALSE); + } +} + +/** + * @brief fill each can_baudrate_struct member with its default value. + * @param can_baudrate_struct: pointer to a can_baudrate_type structure which will be initialized. + * @retval none. + */ +void can_baudrate_default_para_init(can_baudrate_type* can_baudrate_struct) +{ + /* reset can baudrate structure parameters values */ + + /* baud rate division */ + can_baudrate_struct->baudrate_div = 1; + + /* resynchronization adjust width */ + can_baudrate_struct->rsaw_size = CAN_RSAW_2TQ; + + /* bit time segment 1 */ + can_baudrate_struct->bts1_size = CAN_BTS1_4TQ; + + /* bit time segment 2 */ + can_baudrate_struct->bts2_size = CAN_BTS2_3TQ; +} + +/** + * @brief set the baudrate of the can peripheral + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1,CAN2. + * @param can_baudrate_struct: pointer to a can_baudrate_type structure which will be set. + * @note baudrate calculate method is: + * baudrate = fpclk/(baudrate_div *(3 + bts1_size + bts2_size)) + * @retval the result of baudrate set + * this parameter can be one of the following values: + * SUCCESS or ERROR + */ +error_status can_baudrate_set(can_type* can_x, can_baudrate_type* can_baudrate_struct) +{ + error_status status_index = ERROR; + uint32_t wait_ack_index = 0x00000000; + /* exit from doze mode */ + can_x->mctrl_bit.dzen = FALSE; + + /* request freeze mode */ + can_x->mctrl_bit.fzen = TRUE; + + /* wait the acknowledge */ + while((!can_x->msts_bit.fzc) && (wait_ack_index != FZC_TIMEOUT)) + { + wait_ack_index++; + } + + /* check acknowledge */ + if(can_x->msts_bit.fzc) + { + can_x->btmg_bit.brdiv = can_baudrate_struct->baudrate_div - 1; + can_x->btmg_bit.rsaw = can_baudrate_struct->rsaw_size; + can_x->btmg_bit.bts1 = can_baudrate_struct->bts1_size; + can_x->btmg_bit.bts2 = can_baudrate_struct->bts2_size; + + /* request leave freeze mode */ + can_x->mctrl_bit.fzen = FALSE; + + /* wait the acknowledge */ + wait_ack_index = 0; + while((can_x->msts_bit.fzc) && (wait_ack_index != FZC_TIMEOUT)) + { + wait_ack_index++; + } + + /* check acknowledged */ + if(can_x->msts_bit.fzc) + { + status_index = ERROR; + } + else + { + status_index = SUCCESS ; + } + } + else + { + status_index = ERROR; + } + + /* return the status of baudrate set */ + return status_index; +} + +/** + * @brief fill each can_init_struct member with its default value. + * @param can_base_struct: pointer to a can_base_type structure which will be initialized. + * @retval none. + */ +void can_default_para_init(can_base_type* can_base_struct) +{ + /* reset can init structure parameters values */ + + /* initialize the time triggered communication mode */ + can_base_struct->ttc_enable = FALSE; + + /* initialize the automatic exit bus-off management */ + can_base_struct->aebo_enable = FALSE; + + /* initialize the automatic exit doze mode */ + can_base_struct->aed_enable = FALSE; + + /* initialize the prohibit retransmission when sending fails */ + can_base_struct->prsf_enable = FALSE; + + /* initialize the message discarding rule select when overflow */ + can_base_struct->mdrsel_selection = CAN_DISCARDING_FIRST_RECEIVED; + + /* initialize the multiple message sending sequence rule */ + can_base_struct->mmssr_selection = CAN_SENDING_BY_ID; + + /* initialize the can_mode */ + can_base_struct->mode_selection = CAN_MODE_COMMUNICATE; +} + +/** + * @brief initialize the can peripheral according to the specified + * parameters in the can_init_struct. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1,CAN2. + * @param can_base_struct: pointer to a can_base_struct structure that contains the configuration information for the can peripheral. + * @retval the status of initialization + * this parameter can be one of the following values: + * SUCCESS or ERROR + */ +error_status can_base_init(can_type* can_x, can_base_type* can_base_struct) +{ + error_status init_status_index = ERROR; + uint32_t wait_ack_index = 0x00000000; + /* exit from doze mode */ + can_x->mctrl_bit.dzen = FALSE; + + /* request freeze mode */ + can_x->mctrl_bit.fzen = TRUE; + + /* wait the acknowledge */ + while((!can_x->msts_bit.fzc) && (wait_ack_index != FZC_TIMEOUT)) + { + wait_ack_index++; + } + + /* check acknowledge */ + if(can_x->msts_bit.fzc) + { + /* set the time triggered communication mode */ + can_x->mctrl_bit.ttcen = can_base_struct->ttc_enable; + + /* set the automatic exit bus-off management */ + can_x->mctrl_bit.aeboen = can_base_struct->aebo_enable; + + /* set the automatic automatic exit doze mode */ + can_x->mctrl_bit.aeden = can_base_struct->aed_enable; + + /* set the prohibit retransmission when sending fails */ + can_x->mctrl_bit.prsfen = can_base_struct->prsf_enable; + + /* set the message discarding rule select when overflow */ + can_x->mctrl_bit.mdrsel = can_base_struct->mdrsel_selection; + + /* set the multiple message sending sequence rule */ + can_x->mctrl_bit.mmssr = can_base_struct->mmssr_selection; + + /* set the test mode */ + can_x->btmg_bit.lben = can_base_struct->mode_selection & 0x01; + can_x->btmg_bit.loen = (can_base_struct->mode_selection >> 1) & 0x01; + + /* request leave freeze mode */ + can_x->mctrl_bit.fzen = FALSE; + + /* wait the acknowledge */ + wait_ack_index = 0; + while((can_x->msts_bit.fzc) && (wait_ack_index != FZC_TIMEOUT)) + { + wait_ack_index++; + } + + /* check acknowledged */ + if(can_x->msts_bit.fzc) + { + init_status_index = ERROR; + } + else + { + init_status_index = SUCCESS ; + } + } + else + { + init_status_index = ERROR; + } + + /* return the status of initialization */ + return init_status_index; +} + +/** + * @brief fill each can_filter_init_struct member with its default value. + * @param can_filter_init_struct: pointer to a can_filter_init_type structure which will be initialized. + * @retval none. + */ +void can_filter_default_para_init(can_filter_init_type* can_filter_init_struct) +{ + /* reset can filter init structure parameters values */ + + /* initialize the filter activate state */ + can_filter_init_struct->filter_activate_enable = FALSE; + + /* filter mode */ + can_filter_init_struct->filter_mode = CAN_FILTER_MODE_ID_MASK; + + /* filter relation fifo select */ + can_filter_init_struct->filter_fifo = CAN_FILTER_FIFO0; + + /* filter number select */ + can_filter_init_struct->filter_number = 0; + + /* initialize the filter bit width */ + can_filter_init_struct->filter_bit = CAN_FILTER_16BIT; + + /* initialize the filters filter data bit */ + can_filter_init_struct->filter_id_high = 0; + can_filter_init_struct->filter_id_low = 0; + can_filter_init_struct->filter_mask_high = 0; + can_filter_init_struct->filter_mask_low = 0; +} + +/** + * @brief initialize the can peripheral according to the specified + * parameters in the can_filter_init_struct. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1,CAN2. + * @param can_filter_init_struct: pointer to a can_filter_init_type structure that contains the configuration information. + * @retval none. + */ +void can_filter_init(can_type* can_x, can_filter_init_type* can_filter_init_struct) +{ + uint32_t filter_number_bit_pos = 0; + filter_number_bit_pos = ((uint32_t)1) << can_filter_init_struct->filter_number; + /* set the filter turn into configuration condition */ + can_x->fctrl_bit.fcs = TRUE; + + /* filter activate disable */ + can_x->facfg &= ~(uint32_t)filter_number_bit_pos; + + /* filter bit width */ + switch(can_filter_init_struct->filter_bit) + { + case CAN_FILTER_16BIT: + can_x->fbwcfg &= ~(uint32_t)filter_number_bit_pos; + /* first 16-bit identifier and first 16-bit mask or first 16-bit identifier and second 16-bit identifier */ + can_x->ffb[can_filter_init_struct->filter_number].ffdb1 = ((0x0000FFFF & (uint32_t)can_filter_init_struct->filter_mask_low) << 16); + can_x->ffb[can_filter_init_struct->filter_number].ffdb1 |= (0x0000FFFF & (uint32_t)can_filter_init_struct->filter_id_low); + + /* second 16-bit identifier and second 16-bit mask or third 16-bit identifier and fourth 16-bit identifier */ + can_x->ffb[can_filter_init_struct->filter_number].ffdb2 = ((0x0000FFFF & (uint32_t)can_filter_init_struct->filter_mask_high) << 16); + can_x->ffb[can_filter_init_struct->filter_number].ffdb2 |= (0x0000FFFF & (uint32_t)can_filter_init_struct->filter_id_high); + + break; + case CAN_FILTER_32BIT: + can_x->fbwcfg |= filter_number_bit_pos; + /* 32-bit identifier or first 32-bit identifier */ + can_x->ffb[can_filter_init_struct->filter_number].ffdb1 = ((0x0000FFFF & (uint32_t)can_filter_init_struct->filter_id_high) << 16); + can_x->ffb[can_filter_init_struct->filter_number].ffdb1 |= (0x0000FFFF & (uint32_t)can_filter_init_struct->filter_id_low); + + /* 32-bit mask or second 32-bit identifier */ + can_x->ffb[can_filter_init_struct->filter_number].ffdb2 = ((0x0000FFFF & (uint32_t)can_filter_init_struct->filter_mask_high) << 16); + can_x->ffb[can_filter_init_struct->filter_number].ffdb2 |= (0x0000FFFF & (uint32_t)can_filter_init_struct->filter_mask_low); + + break; + default: + break; + } + + /* filter mode */ + switch(can_filter_init_struct->filter_mode) + { + case CAN_FILTER_MODE_ID_MASK: + can_x->fmcfg &= ~(uint32_t)filter_number_bit_pos; + break; + case CAN_FILTER_MODE_ID_LIST: + can_x->fmcfg |= (uint32_t)filter_number_bit_pos; + break; + default: + break; + } + + /* filter relation fifo select */ + switch(can_filter_init_struct->filter_fifo) + { + case CAN_FILTER_FIFO0: + can_x->frf &= ~(uint32_t)filter_number_bit_pos; + break; + case CAN_FILTER_FIFO1: + can_x->frf |= (uint32_t)filter_number_bit_pos; + break; + default: + break; + } + + /* filter activate enable */ + switch(can_filter_init_struct->filter_activate_enable) + { + case TRUE: + can_x->facfg |= (uint32_t)filter_number_bit_pos; + break; + case FALSE: + can_x->facfg &= ~(uint32_t)filter_number_bit_pos; + break; + default: + break; + } + + /* set the filter turn into working condition */ + can_x->fctrl_bit.fcs = FALSE; +} + +/** + * @brief enable or disable the debug transmission prohibit of the specified can peripheral. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1,CAN2. + * @param new_state: new state of debug transmission prohibit. + * this parameter can be: TRUE or FALSE. + * @retval none. + */ +void can_debug_transmission_prohibit(can_type* can_x, confirm_state new_state) +{ + can_x->mctrl_bit.ptd = new_state; +} + +/** + * @brief enable or disable time trigger operation communication mode of the specified can peripheral. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1 or CAN2. + * @param new_state : new state of time trigger operation communication mode. + * this parameter can be: TRUE or FALSE. + * @note + * note1: + * when enabled, transmit mailbox time stamp(tmts[15:0]) value is sent in the last two data bytes of + * the 8-byte message: tmts[7:0] in data byte 6 and tmts[15:8] in data byte 7 + * @note + * note2: + * tmdtbl must be programmed as 8 in order time stamp (2 bytes) to be sent over the can bus. + * @retval none + */ +void can_ttc_mode_enable(can_type* can_x, confirm_state new_state) +{ + /* config the ttc mode new_state */ + can_x->mctrl_bit.ttcen = new_state; + + /* config tmtsten bits new_state */ + can_x->tx_mailbox[0].tmc_bit.tmtsten = new_state; + can_x->tx_mailbox[1].tmc_bit.tmtsten = new_state; + can_x->tx_mailbox[2].tmc_bit.tmtsten = new_state; +} + +/** + * @brief fill the transmission message and transmit of the specified can peripheral. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1,CAN2. + * @param tx_message_struct: pointer to a structure which contains the message to be trans. + * @retval the number of the mailbox that is used for transmission: + * this parameter can be one of the following values: + * - CAN_TX_MAILBOX0 + * - CAN_TX_MAILBOX1 + * - CAN_TX_MAILBOX2 + * - CAN_TX_STATUS_NO_EMPTY + */ +uint8_t can_message_transmit(can_type* can_x, can_tx_message_type* tx_message_struct) +{ + uint8_t transmit_mailbox = CAN_TX_STATUS_NO_EMPTY; + + /* select one empty transmit mailbox */ + if(can_x->tsts_bit.tm0ef) + { + transmit_mailbox = CAN_TX_MAILBOX0; + } + else if(can_x->tsts_bit.tm1ef) + { + transmit_mailbox = CAN_TX_MAILBOX1; + } + else if(can_x->tsts_bit.tm2ef) + { + transmit_mailbox = CAN_TX_MAILBOX2; + } + else + { + transmit_mailbox = CAN_TX_STATUS_NO_EMPTY; + } + + if(transmit_mailbox != CAN_TX_STATUS_NO_EMPTY) + { + /* set up the id */ + can_x->tx_mailbox[transmit_mailbox].tmi &= 0x00000001; + can_x->tx_mailbox[transmit_mailbox].tmi_bit.tmidsel = tx_message_struct->id_type; + switch(tx_message_struct->id_type) + { + case CAN_ID_STANDARD: + can_x->tx_mailbox[transmit_mailbox].tmi_bit.tmsid = tx_message_struct->standard_id; + break; + case CAN_ID_EXTENDED: + can_x->tx_mailbox[transmit_mailbox].tmi |= (tx_message_struct->extended_id << 3); + break; + default: + break; + } + can_x->tx_mailbox[transmit_mailbox].tmi_bit.tmfrsel = tx_message_struct->frame_type; + /* set up the dlc */ + can_x->tx_mailbox[transmit_mailbox].tmc_bit.tmdtbl = (tx_message_struct->dlc & ((uint8_t)0x0F)); + + /* set up the data field */ + can_x->tx_mailbox[transmit_mailbox].tmdtl = (((uint32_t)tx_message_struct->data[3] << 24) | + ((uint32_t)tx_message_struct->data[2] << 16) | + ((uint32_t)tx_message_struct->data[1] << 8) | + ((uint32_t)tx_message_struct->data[0])); + can_x->tx_mailbox[transmit_mailbox].tmdth = (((uint32_t)tx_message_struct->data[7] << 24) | + ((uint32_t)tx_message_struct->data[6] << 16) | + ((uint32_t)tx_message_struct->data[5] << 8) | + ((uint32_t)tx_message_struct->data[4])); + + /* request transmission */ + can_x->tx_mailbox[transmit_mailbox].tmi_bit.tmsr = TRUE; + } + return transmit_mailbox; +} + +/** + * @brief check the transmission state of the specified can peripheral. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1 or CAN2. + * @param transmit_mailbox: the number of the mailbox that is used for transmission. + * this parameter can be one of the following values: + * - CAN_TX_MAILBOX0 + * - CAN_TX_MAILBOX1 + * - CAN_TX_MAILBOX2 + * @retval can transmit status + * this parameter can be one of the following values: + * - CAN_TX_STATUS_SUCCESSFUL + * - CAN_TX_STATUS_FAILED + * - CAN_TX_STATUS_PENDING + */ +can_transmit_status_type can_transmit_status_get(can_type* can_x, can_tx_mailbox_num_type transmit_mailbox) +{ + can_transmit_status_type state_index = CAN_TX_STATUS_FAILED; + switch(transmit_mailbox) + { + case CAN_TX_MAILBOX0: + if(can_x->tsts_bit.tm0tcf != RESET) + { + if(can_x->tsts_bit.tm0tsf != RESET) + { + state_index = CAN_TX_STATUS_SUCCESSFUL; + } + else + { + state_index = CAN_TX_STATUS_FAILED; + } + } + else + { + state_index = CAN_TX_STATUS_PENDING; + } + break; + case CAN_TX_MAILBOX1: + if(can_x->tsts_bit.tm1tcf != RESET) + { + if(can_x->tsts_bit.tm1tsf != RESET) + { + state_index = CAN_TX_STATUS_SUCCESSFUL; + } + else + { + state_index = CAN_TX_STATUS_FAILED; + } + } + else + { + state_index = CAN_TX_STATUS_PENDING; + } + break; + case CAN_TX_MAILBOX2: + if(can_x->tsts_bit.tm2tcf != RESET) + { + if(can_x->tsts_bit.tm2tsf != RESET) + { + state_index = CAN_TX_STATUS_SUCCESSFUL; + } + else + { + state_index = CAN_TX_STATUS_FAILED; + } + } + else + { + state_index = CAN_TX_STATUS_PENDING; + } + break; + default: + state_index = CAN_TX_STATUS_FAILED; + break; + } + return state_index; +} + +/** + * @brief cancel a transmit request of the specified can peripheral. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1 or CAN2. + * @param mailbox: mailbox number. + * this parameter can be one of the following values: + * - CAN_TX_MAILBOX0 + * - CAN_TX_MAILBOX1 + * - CAN_TX_MAILBOX2 + * @retval none. + */ +void can_transmit_cancel(can_type* can_x, can_tx_mailbox_num_type transmit_mailbox) +{ + switch (transmit_mailbox) + { + case CAN_TX_MAILBOX0: + can_x->tsts = CAN_TSTS_TM0CT_VAL; + break; + case CAN_TX_MAILBOX1: + can_x->tsts = CAN_TSTS_TM1CT_VAL; + break; + case CAN_TX_MAILBOX2: + can_x->tsts = CAN_TSTS_TM2CT_VAL; + break; + default: + break; + } +} + +/** + * @brief receive message of the specified can peripheral. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1,CAN2. + * @param fifo_number: receive fifo number. + * this parameter can be one of the following values: + * - CAN_RX_FIFO0 + * - CAN_RX_FIFO1 + * @param rx_message_struct: pointer to a structure which store the receive message. + * @retval none. + */ +void can_message_receive(can_type* can_x, can_rx_fifo_num_type fifo_number, can_rx_message_type* rx_message_struct) +{ + /* get the id type */ + rx_message_struct->id_type = (can_identifier_type)can_x->fifo_mailbox[fifo_number].rfi_bit.rfidi; + switch (rx_message_struct->id_type) + { + case CAN_ID_STANDARD: + rx_message_struct->standard_id = can_x->fifo_mailbox[fifo_number].rfi_bit.rfsid; + break; + case CAN_ID_EXTENDED: + rx_message_struct->extended_id = 0x1FFFFFFF & (can_x->fifo_mailbox[fifo_number].rfi >> 3); + break; + default: + break; + } + rx_message_struct->frame_type = (can_trans_frame_type)can_x->fifo_mailbox[fifo_number].rfi_bit.rffri; + /* get the dlc */ + rx_message_struct->dlc = can_x->fifo_mailbox[fifo_number].rfc_bit.rfdtl; + + /* get the filter match number */ + rx_message_struct->filter_index = can_x->fifo_mailbox[fifo_number].rfc_bit.rffmn; + + /* get the data field */ + rx_message_struct->data[0] = can_x->fifo_mailbox[fifo_number].rfdtl_bit.rfdt0; + rx_message_struct->data[1] = can_x->fifo_mailbox[fifo_number].rfdtl_bit.rfdt1; + rx_message_struct->data[2] = can_x->fifo_mailbox[fifo_number].rfdtl_bit.rfdt2; + rx_message_struct->data[3] = can_x->fifo_mailbox[fifo_number].rfdtl_bit.rfdt3; + rx_message_struct->data[4] = can_x->fifo_mailbox[fifo_number].rfdth_bit.rfdt4; + rx_message_struct->data[5] = can_x->fifo_mailbox[fifo_number].rfdth_bit.rfdt5; + rx_message_struct->data[6] = can_x->fifo_mailbox[fifo_number].rfdth_bit.rfdt6; + rx_message_struct->data[7] = can_x->fifo_mailbox[fifo_number].rfdth_bit.rfdt7; + + /* release the fifo */ + can_receive_fifo_release(can_x, fifo_number); +} + +/** + * @brief release the specified fifo of the specified can peripheral. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1,CAN2. + * @param fifo_number: fifo to be release. + * this parameter can be one of the following values: + * - CAN_RX_FIFO0 + * - CAN_RX_FIFO1 + * @retval none. + */ +void can_receive_fifo_release(can_type* can_x, can_rx_fifo_num_type fifo_number) +{ + switch (fifo_number) + { + case CAN_RX_FIFO0: + can_x->rf0 = CAN_RF0_RF0R_VAL; + break; + case CAN_RX_FIFO1: + can_x->rf1 = CAN_RF1_RF1R_VAL; + break; + default: + break; + } +} + +/** + * @brief return the number of pending messages of the specified can peripheral. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1,CAN2. + * @param fifo_number: receive fifo number. + * this parameter can be one of the following values: + * - CAN_RX_FIFO0 + * - CAN_RX_FIFO1 + * @retval the number of message pending in the receive fifo. + */ +uint8_t can_receive_message_pending_get(can_type* can_x, can_rx_fifo_num_type fifo_number) +{ + uint8_t message_pending = 0; + switch (fifo_number) + { + case CAN_RX_FIFO0: + message_pending = can_x->rf0_bit.rf0mn; + break; + case CAN_RX_FIFO1: + message_pending = can_x->rf1_bit.rf1mn; + break; + default: + break; + } + return message_pending; +} + +/** + * @brief set the operation mode of the specified can peripheral. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1,CAN2. + * @param can_operating_mode: can operating mode. + * this parameter can be one of the following values: + * - CAN_OPERATINGMODE_FREEZE + * - CAN_OPERATINGMODE_DOZE + * - CAN_OPERATINGMODE_COMMUNICATE + * @retval status of operation mode set + * this parameter can be one of the following values: + * SUCCESS or ERROR + */ +error_status can_operating_mode_set(can_type* can_x, can_operating_mode_type can_operating_mode) +{ + error_status status = ERROR; + uint32_t time_out_index = FZC_TIMEOUT; + + if (can_operating_mode == CAN_OPERATINGMODE_FREEZE) + { + /* request enter freeze mode */ + can_x->mctrl_bit.dzen = FALSE; + can_x->mctrl_bit.fzen = TRUE; + + while(((can_x->msts_bit.dzc) || (!can_x->msts_bit.fzc)) && (time_out_index != 0)) + { + time_out_index--; + } + if((can_x->msts_bit.dzc) || (!can_x->msts_bit.fzc)) + { + status = ERROR; + } + else + { + status = SUCCESS; + } + } + else if(can_operating_mode == CAN_OPERATINGMODE_DOZE) + { + /* request enter doze mode */ + can_x->mctrl_bit.dzen = TRUE; + can_x->mctrl_bit.fzen = FALSE; + + while(((!can_x->msts_bit.dzc) || (can_x->msts_bit.fzc)) && (time_out_index != 0)) + { + time_out_index--; + } + if((!can_x->msts_bit.dzc) || (can_x->msts_bit.fzc)) + { + status = ERROR; + } + else + { + status = SUCCESS; + } + } + else if(can_operating_mode == CAN_OPERATINGMODE_COMMUNICATE) + { + /* request enter normal mode */ + can_x->mctrl_bit.dzen = FALSE; + can_x->mctrl_bit.fzen = FALSE; + + while(((can_x->msts_bit.dzc) || (can_x->msts_bit.fzc)) && (time_out_index != 0)) + { + time_out_index--; + } + if((can_x->msts_bit.dzc) || (can_x->msts_bit.fzc)) + { + status = ERROR; + } + else + { + status = SUCCESS; + } + } + else + { + status = ERROR; + } + return status; +} + +/** + * @brief enter the low power mode of the specified can peripheral. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1,CAN2. + * @retval status of doze mode enter, the returned value can be: + * - CAN_ENTER_DOZE_SUCCESSFUL + * - CAN_ENTER_DOZE_FAILED + */ +can_enter_doze_status_type can_doze_mode_enter(can_type* can_x) +{ + can_enter_doze_status_type status = CAN_ENTER_DOZE_FAILED; + uint32_t time_out_index = FZC_TIMEOUT; + can_x->mctrl_bit.fzen = FALSE; + can_x->mctrl_bit.dzen = TRUE; + while(((!can_x->msts_bit.dzc) || (can_x->msts_bit.fzc)) && (time_out_index != 0)) + { + time_out_index--; + } + if((!can_x->msts_bit.dzc) || (can_x->msts_bit.fzc)) + { + status = CAN_ENTER_DOZE_FAILED; + } + else + { + status = CAN_ENTER_DOZE_SUCCESSFUL; + } + return status; +} + +/** + * @brief exit the doze mode of the specified can peripheral. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1,CAN2. + * @retval status of doze mode enter, the returned value can be: + * - CAN_QUIT_DOZE_SUCCESSFUL + * - CAN_QUIT_DOZE_FAILED + */ +can_quit_doze_status_type can_doze_mode_exit(can_type* can_x) +{ + can_quit_doze_status_type status = CAN_QUIT_DOZE_FAILED; + uint32_t time_out_index = DZC_TIMEOUT; + can_x->mctrl_bit.dzen = FALSE; + while((can_x->msts_bit.dzc) && (time_out_index != 0)) + { + time_out_index--; + } + if(!can_x->msts_bit.dzc) + { + status = CAN_QUIT_DOZE_SUCCESSFUL; + } + return status; +} + +/** + * @brief return the error type record (etr) of the specified can peripheral. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1,CAN2. + * @retval the value of the error code + * the return can be one of the follow values: + * - CAN_ERRORRECORD_NOERR + * - CAN_ERRORRECORD_STUFFERR, + * - CAN_ERRORRECORD_FORMERR, + * - CAN_ERRORRECORD_ACKERR, + * - CAN_ERRORRECORD_BITRECESSIVEERR, + * - CAN_ERRORRECORD_BITDOMINANTERR, + * - CAN_ERRORRECORD_CRCERR, + * - CAN_ERRORRECORD_SOFTWARESETERR + */ +can_error_record_type can_error_type_record_get(can_type* can_x) +{ + can_error_record_type error_code = CAN_ERRORRECORD_NOERR; + + error_code = (can_error_record_type)can_x->ests_bit.etr; + return error_code; +} + +/** + * @brief return the receive error counter (rec) of the specified can peripheral. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1,CAN2. + * @retval the value of receive error counter. + */ +uint8_t can_receive_error_counter_get(can_type* can_x) +{ + uint8_t counter = 0; + counter = can_x->ests_bit.rec; + return counter; +} + +/** + * @brief return the transmit error counter of the specified can peripheral. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1,CAN2. + * @retval the value of transmit error counter. + */ +uint8_t can_transmit_error_counter_get(can_type* can_x) +{ + uint8_t counter = 0; + counter = can_x->ests_bit.tec; + return counter; +} + +/** + * @brief enable or disable the interrupt of the specified can peripheral. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1,CAN2. + * @param can_int: specifies the can interrupt sources to be enabled or disabled. + * this parameter can be one of the following values: + * - CAN_TCIEN_INT + * - CAN_RF0MIEN_INT + * - CAN_RF0FIEN_INT + * - CAN_RF0OIEN_INT + * - CAN_RF1MIEN_INT + * - CAN_RF1FIEN_INT + * - CAN_RF1OIEN_INT + * - CAN_EAIEN_INT + * - CAN_EPIEN_INT + * - CAN_BOIEN_INT + * - CAN_ETRIEN_INT + * - CAN_EOIEN_INT + * - CAN_QDZIEN_INT + * - CAN_EDZIEN_INT + * @param new_state: new state of the can interrupts. + * this parameter can be: TRUE or FALSE. + * @retval none. + */ +void can_interrupt_enable(can_type* can_x, uint32_t can_int, confirm_state new_state) +{ + if (new_state != FALSE) + { + can_x->inten |= can_int; + } + else + { + can_x->inten &= ~can_int; + } +} + +/** + * @brief get flag of the specified can peripheral. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1,CAN2. + * @param can_flag: select the flag. + * this parameter can be one of the following flags: + * - CAN_EAF_FLAG + * - CAN_EPF_FLAG + * - CAN_BOF_FLAG + * - CAN_ETR_FLAG + * - CAN_EOIF_FLAG + * - CAN_TM0TCF_FLAG + * - CAN_TM1TCF_FLAG + * - CAN_TM2TCF_FLAG + * - CAN_RF0MN_FLAG + * - CAN_RF0FF_FLAG + * - CAN_RF0OF_FLAG + * - CAN_RF1MN_FLAG + * - CAN_RF1FF_FLAG + * - CAN_RF1OF_FLAG + * - CAN_QDZIF_FLAG + * - CAN_EDZC_FLAG + * - CAN_TMEF_FLAG + * note:the state of CAN_EDZC_FLAG need to check dzc and edzif bit + * note:the state of CAN_TMEF_FLAG need to check rqc0,rqc1 and rqc2 bit + * @retval status of can_flag, the returned value can be:SET or RESET. + */ +flag_status can_flag_get(can_type* can_x, uint32_t can_flag) +{ + flag_status bit_status = RESET; + switch(can_flag) + { + case CAN_EAF_FLAG: + bit_status = (flag_status)can_x->ests_bit.eaf; + break; + case CAN_EPF_FLAG: + bit_status = (flag_status)can_x->ests_bit.epf; + break; + case CAN_BOF_FLAG: + bit_status = (flag_status)can_x->ests_bit.bof; + break; + case CAN_ETR_FLAG: + if(can_x->ests_bit.etr != 0) + { + bit_status = SET; + } + else + { + bit_status = RESET; + } + break; + case CAN_EOIF_FLAG: + bit_status = (flag_status)can_x->msts_bit.eoif; + break; + case CAN_TM0TCF_FLAG: + bit_status = (flag_status)can_x->tsts_bit.tm0tcf; + break; + case CAN_TM1TCF_FLAG: + bit_status = (flag_status)can_x->tsts_bit.tm1tcf; + break; + case CAN_TM2TCF_FLAG: + bit_status = (flag_status)can_x->tsts_bit.tm2tcf; + break; + case CAN_RF0MN_FLAG: + if(can_x->rf0_bit.rf0mn != 0) + { + bit_status = SET; + } + else + { + bit_status = RESET; + } + break; + case CAN_RF0FF_FLAG: + bit_status = (flag_status)can_x->rf0_bit.rf0ff; + break; + case CAN_RF0OF_FLAG: + bit_status = (flag_status)can_x->rf0_bit.rf0of; + break; + case CAN_RF1MN_FLAG: + if(can_x->rf1_bit.rf1mn != 0) + { + bit_status = SET; + } + else + { + bit_status = RESET; + } + break; + case CAN_RF1FF_FLAG: + bit_status = (flag_status)can_x->rf1_bit.rf1ff; + break; + case CAN_RF1OF_FLAG: + bit_status = (flag_status)can_x->rf1_bit.rf1of; + break; + case CAN_QDZIF_FLAG: + bit_status = (flag_status)can_x->msts_bit.qdzif; + break; + case CAN_EDZC_FLAG: + if((can_x->msts_bit.dzc != RESET) ||(can_x->msts_bit.edzif != RESET)) + { + bit_status = SET; + } + else + { + bit_status = RESET; + } + break; + case CAN_TMEF_FLAG: + if((can_x->tsts_bit.tm0ef != RESET) || (can_x->tsts_bit.tm1ef != RESET) || (can_x->tsts_bit.tm2ef != RESET)) + { + bit_status = SET; + } + else + { + bit_status = RESET; + } + break; + default: + bit_status = RESET; + break; + } + return bit_status; +} + +/** + * @brief clear flag of the specified can peripheral. + * @param can_x: select the can peripheral. + * this parameter can be one of the following values: + * CAN1,CAN2. + * @param can_flag: select the flag. + * this parameter can be one of the following flags: + * - CAN_EAF_FLAG + * - CAN_EPF_FLAG + * - CAN_BOF_FLAG + * - CAN_ETR_FLAG + * - CAN_EOIF_FLAG + * - CAN_TM0TCF_FLAG + * - CAN_TM1TCF_FLAG + * - CAN_TM2TCF_FLAG + * - CAN_RF0FF_FLAG + * - CAN_RF0OF_FLAG + * - CAN_RF1FF_FLAG + * - CAN_RF1OF_FLAG + * - CAN_QDZIF_FLAG + * - CAN_EDZC_FLAG + * - CAN_TMEF_FLAG + * note:CAN_RF0MN_FLAG and CAN_RF1MN_FLAG can not clear by this function + * @retval none. + */ +void can_flag_clear(can_type* can_x, uint32_t can_flag) +{ + switch(can_flag) + { + case CAN_EAF_FLAG: + case CAN_EPF_FLAG: + case CAN_BOF_FLAG: + case CAN_EOIF_FLAG: + can_x->msts = CAN_MSTS_EOIF_VAL; + break; + case CAN_ETR_FLAG: + can_x->msts = CAN_MSTS_EOIF_VAL; + can_x->ests = 0; + break; + case CAN_TM0TCF_FLAG: + can_x->tsts = CAN_TSTS_TM0TCF_VAL; + break; + case CAN_TM1TCF_FLAG: + can_x->tsts = CAN_TSTS_TM1TCF_VAL; + break; + case CAN_TM2TCF_FLAG: + can_x->tsts = CAN_TSTS_TM2TCF_VAL; + break; + case CAN_RF0FF_FLAG: + can_x->rf0 = CAN_RF0_RF0FF_VAL; + break; + case CAN_RF0OF_FLAG: + can_x->rf0 = CAN_RF0_RF0OF_VAL; + break; + case CAN_RF1FF_FLAG: + can_x->rf1 = CAN_RF1_RF1FF_VAL; + break; + case CAN_RF1OF_FLAG: + can_x->rf1 = CAN_RF1_RF1OF_VAL; + break; + case CAN_QDZIF_FLAG: + can_x->msts = CAN_MSTS_QDZIF_VAL; + break; + case CAN_EDZC_FLAG: + can_x->msts = CAN_MSTS_EDZIF_VAL; + break; + case CAN_TMEF_FLAG: + can_x->tsts = CAN_TSTS_TM0TCF_VAL | CAN_TSTS_TM1TCF_VAL | CAN_TSTS_TM2TCF_VAL; + break; + default: + break; + } +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_crc.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_crc.c new file mode 100644 index 0000000000..326ed49ebe --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_crc.c @@ -0,0 +1,164 @@ +/** + ************************************************************************** + * @file at32f435_437_crc.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the crc firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup CRC + * @brief CRC driver modules + * @{ + */ + +#ifdef CRC_MODULE_ENABLED + +/** @defgroup CRC_private_functions + * @{ + */ + +/** + * @brief reset the crc data register. + * @param none + * @retval none + */ +void crc_data_reset(void) +{ + /* reset crc generator */ + CRC->ctrl_bit.rst = 0x1; +} + +/** + * @brief compute the 32-bit crc of a given data word(32-bit). + * @param data: data word(32-bit) to compute its crc + * @retval 32-bit crc + */ +uint32_t crc_one_word_calculate(uint32_t data) +{ + CRC->dt = data; + return (CRC->dt); +} + +/** + * @brief compute the 32-bit crc of a given buffer of data word(32-bit). + * @param pbuffer: pointer to the buffer containing the data to be computed + * @param length: length of the buffer to be computed + * @retval 32-bit crc + */ +uint32_t crc_block_calculate(uint32_t *pbuffer, uint32_t length) +{ + uint32_t index = 0; + + for(index = 0; index < length; index++) + { + CRC->dt = pbuffer[index]; + } + + return (CRC->dt); +} + +/** + * @brief return the current crc value. + * @param none + * @retval 32-bit crc + */ +uint32_t crc_data_get(void) +{ + return (CRC->dt); +} + +/** + * @brief store a 8-bit data in the common data register. + * @param cdt_value: 8-bit value to be stored in the common data register + * @retval none + */ +void crc_common_data_set(uint8_t cdt_value) +{ + CRC->cdt_bit.cdt = cdt_value; +} + +/** + * @brief return the 8-bit data stored in the common data register + * @param none + * @retval 8-bit value of the common data register + */ +uint8_t crc_common_data_get(void) +{ + return (CRC->cdt_bit.cdt); +} + +/** + * @brief set the 32-bit initial data of crc + * @param value: initial data + * @retval none + */ +void crc_init_data_set(uint32_t value) +{ + CRC->idt = value; +} + +/** + * @brief control the reversal of the bit order in the input data + * @param value + * this parameter can be one of the following values: + * - CRC_REVERSE_INPUT_NO_AFFECTE + * - CRC_REVERSE_INPUT_BY_BYTE + * - CRC_REVERSE_INPUT_BY_HALFWORD + * - CRC_REVERSE_INPUT_BY_WORD + * @retval none. + */ +void crc_reverse_input_data_set(crc_reverse_input_type value) +{ + CRC->ctrl_bit.revid = value; +} + +/** + * @brief control the reversal of the bit order in the output data + * @param value + * this parameter can be one of the following values: + * - CRC_REVERSE_OUTPUT_NO_AFFECTE + * - CRC_REVERSE_OUTPUT_DATA + * @retval none. + */ +void crc_reverse_output_data_set(crc_reverse_output_type value) +{ + CRC->ctrl_bit.revod = value; +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_crm.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_crm.c new file mode 100644 index 0000000000..c8523ba41e --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_crm.c @@ -0,0 +1,986 @@ +/** + ************************************************************************** + * @file at32f435_437_crm.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the crm firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup CRM + * @brief CRM driver modules + * @{ + */ + +#ifdef CRM_MODULE_ENABLED + +/** @defgroup CRM_private_functions + * @{ + */ + +/** + * @brief reset the crm register + * @param none + * @retval none + */ +void crm_reset(void) +{ + /* reset the crm clock configuration to the default reset state(for debug purpose) */ + /* set hicken bit */ + CRM->ctrl_bit.hicken = TRUE; + + /* wait hick stable */ + while(CRM->ctrl_bit.hickstbl != SET); + + /* hick used as system clock */ + CRM->cfg_bit.sclksel = CRM_SCLK_HICK; + + /* wait sclk switch status */ + while(CRM->cfg_bit.sclksts != CRM_SCLK_HICK); + + /* reset hexten, hextbyps, cfden and pllen bits */ + CRM->ctrl &= ~(0x010D0000U); + + /* reset cfg register, include sclk switch, ahbdiv, apb1div, apb2div, adcdiv, clkout bits */ + CRM->cfg = 0; + + /* reset pllms pllns pllfr pllrcs bits */ + CRM->pllcfg = 0x00033002U; + + /* reset clkout[3], usbbufs, hickdiv, clkoutdiv */ + CRM->misc1 = 0; + + /* disable all interrupts enable and clear pending bits */ + CRM->clkint = 0x009F0000U; +} + +/** + * @brief enable or disable crm low speed external crystal bypass + * @param new_state (TRUE or FALSE) + * @retval none + */ +void crm_lext_bypass(confirm_state new_state) +{ + CRM->bpdc_bit.lextbyps = new_state; +} + +/** + * @brief enable or disable crm high speed external crystal bypass + * @param new_state (TRUE or FALSE) + * @retval none + */ +void crm_hext_bypass(confirm_state new_state) +{ + CRM->ctrl_bit.hextbyps = new_state; +} + +/** + * @brief get crm flag status + * @param flag + * this parameter can be one of the following values: + * - CRM_HICK_STABLE_FLAG + * - CRM_HEXT_STABLE_FLAG + * - CRM_PLL_STABLE_FLAG + * - CRM_LEXT_STABLE_FLAG + * - CRM_LICK_STABLE_FLAG + * - CRM_PIN_RESET_FLAG + * - CRM_POR_RESET_FLAG + * - CRM_SW_RESET_FLAG + * - CRM_WDT_RESET_FLAG + * - CRM_WWDT_RESET_FLAG + * - CRM_LOWPOWER_RESET_FLAG + * interrupt flag: + * - CRM_LICK_READY_INT_FLAG + * - CRM_LEXT_READY_INT_FLAG + * - CRM_HICK_READY_INT_FLAG + * - CRM_HEXT_READY_INT_FLAG + * - CRM_PLL_READY_INT_FLAG + * - CRM_CLOCK_FAILURE_INT_FLAG + * @retval flag_status (SET or RESET) + */ +flag_status crm_flag_get(uint32_t flag) +{ + flag_status status = RESET; + if((CRM_REG(flag) & CRM_REG_BIT(flag)) != CRM_REG_BIT(flag)) + { + status = RESET; + } + else + { + status = SET; + } + return status; +} + +/** + * @brief wait for hext stable + * @param none + * @retval error_status (ERROR or SUCCESS) + */ +error_status crm_hext_stable_wait(void) +{ + uint32_t stable_cnt = 0; + error_status status = ERROR; + + while((crm_flag_get(CRM_HEXT_STABLE_FLAG) != SET) && (stable_cnt < HEXT_STARTUP_TIMEOUT)) + { + stable_cnt ++; + } + + if(crm_flag_get(CRM_HEXT_STABLE_FLAG) != SET) + { + status = ERROR; + } + else + { + status = SUCCESS; + } + + return status; +} + +/** + * @brief set the hick trimming value + * @param trim_value (0x00~0x3F) + * @retval none + */ +void crm_hick_clock_trimming_set(uint8_t trim_value) +{ + CRM->ctrl_bit.hicktrim = trim_value; +} + +/** + * @brief set the crm calibration value + * @param cali_value (0x00~0xFF) + * @retval none + */ +void crm_hick_clock_calibration_set(uint8_t cali_value) +{ + /* enable write hick calibration */ + CRM->misc1_bit.hickcal_key = 0x5A; + + /* write hick calibration value */ + CRM->ctrl_bit.hickcal = cali_value; + + /* disable write hick calibration */ + CRM->misc1_bit.hickcal_key = 0x0; +} + +/** + * @brief enable or disable the peripheral clock + * @param value + * this parameter can be one of the following values: + * - CRM_GPIOA_PERIPH_CLOCK - CRM_GPIOB_PERIPH_CLOCK - CRM_GPIOC_PERIPH_CLOCK - CRM_GPIOD_PERIPH_CLOCK + * - CRM_GPIOE_PERIPH_CLOCK - CRM_GPIOF_PERIPH_CLOCK - CRM_GPIOG_PERIPH_CLOCK - CRM_GPIOH_PERIPH_CLOCK + * - CRM_CRC_PERIPH_CLOCK - CRM_EDMA_PERIPH_CLOCK - CRM_DMA1_PERIPH_CLOCK - CRM_DMA2_PERIPH_CLOCK + * - CRM_EMAC_PERIPH_CLOCK - CRM_EMACTX_PERIPH_CLOCK - CRM_EMACRX_PERIPH_CLOCK - CRM_EMACPTP_PERIPH_CLOCK + * - CRM_OTGFS2_PERIPH_CLOCK - CRM_DVP_PERIPH_CLOCK - CRM_OTGFS1_PERIPH_CLOCK - CRM_SDIO1_PERIPH_CLOCK + * - CRM_XMC_PERIPH_CLOCK - CRM_QSPI1_PERIPH_CLOCK - CRM_QSPI2_PERIPH_CLOCK - CRM_SDIO2_PERIPH_CLOCK + * - CRM_TMR2_PERIPH_CLOCK - CRM_TMR3_PERIPH_CLOCK - CRM_TMR4_PERIPH_CLOCK - CRM_TMR5_PERIPH_CLOCK + * - CRM_TMR6_PERIPH_CLOCK - CRM_TMR7_PERIPH_CLOCK - CRM_TMR12_PERIPH_CLOCK - CRM_TMR13_PERIPH_CLOCK + * - CRM_TMR14_PERIPH_CLOCK - CRM_WWDT_PERIPH_CLOCK - CRM_SPI2_PERIPH_CLOCK - CRM_SPI3_PERIPH_CLOCK + * - CRM_USART2_PERIPH_CLOCK - CRM_USART3_PERIPH_CLOCK - CRM_UART4_PERIPH_CLOCK - CRM_UART5_PERIPH_CLOCK + * - CRM_I2C1_PERIPH_CLOCK - CRM_I2C2_PERIPH_CLOCK - CRM_I2C3_PERIPH_CLOCK - CRM_CAN1_PERIPH_CLOCK + * - CRM_CAN2_PERIPH_CLOCK - CRM_PWC_PERIPH_CLOCK - CRM_DAC_PERIPH_CLOCK - CRM_UART7_PERIPH_CLOCK + * - CRM_UART8_PERIPH_CLOCK - CRM_TMR1_PERIPH_CLOCK - CRM_TMR8_PERIPH_CLOCK - CRM_USART1_PERIPH_CLOCK + * - CRM_USART6_PERIPH_CLOCK - CRM_ADC1_PERIPH_CLOCK - CRM_ADC2_PERIPH_CLOCK - CRM_ADC3_PERIPH_CLOCK + * - CRM_SPI1_PERIPH_CLOCK - CRM_SPI4_PERIPH_CLOCK - CRM_SCFG_PERIPH_CLOCK - CRM_TMR9_PERIPH_CLOCK + * - CRM_TMR10_PERIPH_CLOCK - CRM_TMR11_PERIPH_CLOCK - CRM_TMR20_PERIPH_CLOCK - CRM_ACC_PERIPH_CLOCK + * @param new_state (TRUE or FALSE) + * @retval none + */ +void crm_periph_clock_enable(crm_periph_clock_type value, confirm_state new_state) +{ + /* enable periph clock */ + if(TRUE == new_state) + { + CRM_REG(value) |= CRM_REG_BIT(value); + } + /* disable periph clock */ + else + { + CRM_REG(value) &= ~(CRM_REG_BIT(value)); + } +} + +/** + * @brief enable or disable the peripheral reset + * @param value + * this parameter can be one of the following values: + * - CRM_GPIOA_PERIPH_RESET - CRM_GPIOB_PERIPH_RESET - CRM_GPIOC_PERIPH_RESET - CRM_GPIOD_PERIPH_RESET + * - CRM_GPIOE_PERIPH_RESET - CRM_GPIOF_PERIPH_RESET - CRM_GPIOG_PERIPH_RESET - CRM_GPIOH_PERIPH_RESET + * - CRM_CRC_PERIPH_RESET - CRM_EDMA_PERIPH_RESET - CRM_DMA1_PERIPH_RESET - CRM_DMA2_PERIPH_RESET + * - CRM_EMAC_PERIPH_RESET - CRM_OTGFS2_PERIPH_RESET - CRM_DVP_PERIPH_RESET - CRM_OTGFS1_PERIPH_RESET + * - CRM_SDIO1_PERIPH_RESET - CRM_XMC_PERIPH_RESET - CRM_QSPI1_PERIPH_RESET - CRM_QSPI2_PERIPH_RESET + * - CRM_SDIO2_PERIPH_RESET - CRM_TMR2_PERIPH_RESET - CRM_TMR3_PERIPH_RESET - CRM_TMR4_PERIPH_RESET + * - CRM_TMR5_PERIPH_RESET - CRM_TMR6_PERIPH_RESET - CRM_TMR7_PERIPH_RESET - CRM_TMR12_PERIPH_RESET + * - CRM_TMR13_PERIPH_RESET - CRM_TMR14_PERIPH_RESET - CRM_WWDT_PERIPH_RESET - CRM_SPI2_PERIPH_RESET + * - CRM_SPI3_PERIPH_RESET - CRM_USART2_PERIPH_RESET - CRM_USART3_PERIPH_RESET - CRM_UART4_PERIPH_RESET + * - CRM_UART5_PERIPH_RESET - CRM_I2C1_PERIPH_RESET - CRM_I2C2_PERIPH_RESET - CRM_I2C3_PERIPH_RESET + * - CRM_CAN1_PERIPH_RESET - CRM_CAN2_PERIPH_RESET - CRM_PWC_PERIPH_RESET - CRM_DAC_PERIPH_RESET + * - CRM_UART7_PERIPH_RESET - CRM_UART8_PERIPH_RESET - CRM_TMR1_PERIPH_RESET - CRM_TMR8_PERIPH_RESET + * - CRM_USART1_PERIPH_RESET - CRM_USART6_PERIPH_RESET - CRM_ADC_PERIPH_RESET - CRM_SPI1_PERIPH_RESET + * - CRM_SPI4_PERIPH_RESET - CRM_SCFG_PERIPH_RESET - CRM_TMR9_PERIPH_RESET - CRM_TMR10_PERIPH_RESET + * - CRM_TMR11_PERIPH_RESET - CRM_TMR20_PERIPH_RESET - CRM_ACC_PERIPH_RESET + * @param new_state (TRUE or FALSE) + * @retval none + */ +void crm_periph_reset(crm_periph_reset_type value, confirm_state new_state) +{ + /* enable periph reset */ + if(new_state == TRUE) + { + CRM_REG(value) |= (CRM_REG_BIT(value)); + } + /* disable periph reset */ + else + { + CRM_REG(value) &= ~(CRM_REG_BIT(value)); + } +} + +/** + * @brief enable or disable the peripheral clock in lowpower mode + * @param value + * this parameter can be one of the following values: + * - CRM_GPIOA_PERIPH_LOWPOWER - CRM_GPIOB_PERIPH_LOWPOWER - CRM_GPIOC_PERIPH_LOWPOWER - CRM_GPIOD_PERIPH_LOWPOWER + * - CRM_GPIOE_PERIPH_LOWPOWER - CRM_GPIOF_PERIPH_LOWPOWER - CRM_GPIOG_PERIPH_LOWPOWER - CRM_GPIOH_PERIPH_LOWPOWER + * - CRM_CRC_PERIPH_LOWPOWER - CRM_EDMA_PERIPH_LOWPOWER - CRM_DMA1_PERIPH_LOWPOWER - CRM_DMA2_PERIPH_LOWPOWER + * - CRM_EMAC_PERIPH_LOWPOWER - CRM_EMACTX_PERIPH_LOWPOWER - CRM_EMACRX_PERIPH_LOWPOWER - CRM_EMACPTP_PERIPH_LOWPOWER + * - CRM_OTGFS2_PERIPH_LOWPOWER - CRM_DVP_PERIPH_LOWPOWER - CRM_OTGFS1_PERIPH_LOWPOWER - CRM_SDIO1_PERIPH_LOWPOWER + * - CRM_XMC_PERIPH_LOWPOWER - CRM_QSPI1_PERIPH_LOWPOWER - CRM_QSPI2_PERIPH_LOWPOWER - CRM_SDIO2_PERIPH_LOWPOWER + * - CRM_TMR2_PERIPH_LOWPOWER - CRM_TMR3_PERIPH_LOWPOWER - CRM_TMR4_PERIPH_LOWPOWER - CRM_TMR5_PERIPH_LOWPOWER + * - CRM_TMR6_PERIPH_LOWPOWER - CRM_TMR7_PERIPH_LOWPOWER - CRM_TMR12_PERIPH_LOWPOWER - CRM_TMR13_PERIPH_LOWPOWER + * - CRM_TMR14_PERIPH_LOWPOWER - CRM_WWDT_PERIPH_LOWPOWER - CRM_SPI2_PERIPH_LOWPOWER - CRM_SPI3_PERIPH_LOWPOWER + * - CRM_USART2_PERIPH_LOWPOWER - CRM_USART3_PERIPH_LOWPOWER - CRM_UART4_PERIPH_LOWPOWER - CRM_UART5_PERIPH_LOWPOWER + * - CRM_I2C1_PERIPH_LOWPOWER - CRM_I2C2_PERIPH_LOWPOWER - CRM_I2C3_PERIPH_LOWPOWER - CRM_CAN1_PERIPH_LOWPOWER + * - CRM_CAN2_PERIPH_LOWPOWER - CRM_PWC_PERIPH_LOWPOWER - CRM_DAC_PERIPH_LOWPOWER - CRM_UART7_PERIPH_LOWPOWER + * - CRM_UART8_PERIPH_LOWPOWER - CRM_TMR1_PERIPH_LOWPOWER - CRM_TMR8_PERIPH_LOWPOWER - CRM_USART1_PERIPH_LOWPOWER + * - CRM_USART6_PERIPH_LOWPOWER - CRM_ADC1_PERIPH_LOWPOWER - CRM_ADC2_PERIPH_LOWPOWER - CRM_ADC3_PERIPH_LOWPOWER + * - CRM_SPI1_PERIPH_LOWPOWER - CRM_SPI4_PERIPH_LOWPOWER - CRM_SCFG_PERIPH_LOWPOWER - CRM_TMR9_PERIPH_LOWPOWER + * - CRM_TMR10_PERIPH_LOWPOWER - CRM_TMR11_PERIPH_LOWPOWER - CRM_TMR20_PERIPH_LOWPOWER - CRM_ACC_PERIPH_LOWPOWER + * - CRM_FLASH_PERIPH_LOWPOWER - CRM_SRAM1_PERIPH_LOWPOWER - CRM_SRAM2_PERIPH_LOWPOWER + * @param new_state (TRUE or FALSE) + * @retval none + */ +void crm_periph_lowpower_mode_enable(crm_periph_clock_lowpower_type value, confirm_state new_state) +{ + /* enable periph clock in lowpower mode */ + if(new_state == TRUE) + { + CRM_REG(value) |= (CRM_REG_BIT(value)); + } + /* disable periph clock in lowpower mode */ + else + { + CRM_REG(value) &= ~(CRM_REG_BIT(value)); + } +} + +/** + * @brief enable or disable the crm clock source + * @param source + * this parameter can be one of the following values: + * - CRM_CLOCK_SOURCE_HICK + * - CRM_CLOCK_SOURCE_HEXT + * - CRM_CLOCK_SOURCE_PLL + * - CRM_CLOCK_SOURCE_LEXT + * - CRM_CLOCK_SOURCE_LICK + * @param new_state (TRUE or FALSE) + * @retval none + */ +void crm_clock_source_enable(crm_clock_source_type source, confirm_state new_state) +{ + switch(source) + { + case CRM_CLOCK_SOURCE_HICK: + CRM->ctrl_bit.hicken = new_state; + break; + case CRM_CLOCK_SOURCE_HEXT: + CRM->ctrl_bit.hexten = new_state; + break; + case CRM_CLOCK_SOURCE_PLL: + CRM->ctrl_bit.pllen = new_state; + break; + case CRM_CLOCK_SOURCE_LEXT: + CRM->bpdc_bit.lexten = new_state; + break; + case CRM_CLOCK_SOURCE_LICK: + CRM->ctrlsts_bit.licken = new_state; + break; + default: break; + } +} + +/** + * @brief clear the crm reset flags + * @param flag + * this parameter can be one of the following values: + * reset flag: + * - CRM_PIN_RESET_FLAG + * - CRM_POR_RESET_FLAG + * - CRM_SW_RESET_FLAG + * - CRM_WDT_RESET_FLAG + * - CRM_WWDT_RESET_FLAG + * - CRM_LOWPOWER_RESET_FLAG + * - CRM_ALL_RESET_FLAG + * interrupt flag: + * - CRM_LICK_READY_INT_FLAG + * - CRM_LEXT_READY_INT_FLAG + * - CRM_HICK_READY_INT_FLAG + * - CRM_HEXT_READY_INT_FLAG + * - CRM_PLL_READY_INT_FLAG + * - CRM_CLOCK_FAILURE_INT_FLAG + * @retval none + */ +void crm_flag_clear(uint32_t flag) +{ + switch(flag) + { + case CRM_NRST_RESET_FLAG: + case CRM_POR_RESET_FLAG: + case CRM_SW_RESET_FLAG: + case CRM_WDT_RESET_FLAG: + case CRM_WWDT_RESET_FLAG: + case CRM_LOWPOWER_RESET_FLAG: + case CRM_ALL_RESET_FLAG: + CRM->ctrlsts_bit.rstfc = TRUE; + while(CRM->ctrlsts_bit.rstfc == TRUE); + break; + case CRM_LICK_READY_INT_FLAG: + CRM->clkint_bit.lickstblfc = TRUE; + break; + case CRM_LEXT_READY_INT_FLAG: + CRM->clkint_bit.lextstblfc = TRUE; + break; + case CRM_HICK_READY_INT_FLAG: + CRM->clkint_bit.hickstblfc = TRUE; + break; + case CRM_HEXT_READY_INT_FLAG: + CRM->clkint_bit.hextstblfc = TRUE; + break; + case CRM_PLL_READY_INT_FLAG: + CRM->clkint_bit.pllstblfc = TRUE; + break; + case CRM_CLOCK_FAILURE_INT_FLAG: + CRM->clkint_bit.cfdfc = TRUE; + break; + default: + break; + } +} + +/** + * @brief select ertc clock + * @param value + * this parameter can be one of the following values: + * - CRM_ERTC_CLOCK_NOCLK + * - CRM_ERTC_CLOCK_LEXT + * - CRM_ERTC_CLOCK_LICK + * - CRM_ERTC_CLOCK_HEXT_DIV_2 + * - CRM_ERTC_CLOCK_HEXT_DIV_3 + * - CRM_ERTC_CLOCK_HEXT_DIV_4 + * - CRM_ERTC_CLOCK_HEXT_DIV_5 + * - CRM_ERTC_CLOCK_HEXT_DIV_6 + * - CRM_ERTC_CLOCK_HEXT_DIV_7 + * - CRM_ERTC_CLOCK_HEXT_DIV_8 + * - CRM_ERTC_CLOCK_HEXT_DIV_9 + * - CRM_ERTC_CLOCK_HEXT_DIV_10 + * - CRM_ERTC_CLOCK_HEXT_DIV_11 + * - CRM_ERTC_CLOCK_HEXT_DIV_12 + * - CRM_ERTC_CLOCK_HEXT_DIV_13 + * - CRM_ERTC_CLOCK_HEXT_DIV_14 + * - CRM_ERTC_CLOCK_HEXT_DIV_15 + * - CRM_ERTC_CLOCK_HEXT_DIV_16 + * - CRM_ERTC_CLOCK_HEXT_DIV_17 + * - CRM_ERTC_CLOCK_HEXT_DIV_18 + * - CRM_ERTC_CLOCK_HEXT_DIV_19 + * - CRM_ERTC_CLOCK_HEXT_DIV_20 + * - CRM_ERTC_CLOCK_HEXT_DIV_21 + * - CRM_ERTC_CLOCK_HEXT_DIV_22 + * - CRM_ERTC_CLOCK_HEXT_DIV_23 + * - CRM_ERTC_CLOCK_HEXT_DIV_24 + * - CRM_ERTC_CLOCK_HEXT_DIV_25 + * - CRM_ERTC_CLOCK_HEXT_DIV_26 + * - CRM_ERTC_CLOCK_HEXT_DIV_27 + * - CRM_ERTC_CLOCK_HEXT_DIV_28 + * - CRM_ERTC_CLOCK_HEXT_DIV_29 + * - CRM_ERTC_CLOCK_HEXT_DIV_30 + * - CRM_ERTC_CLOCK_HEXT_DIV_31 + * @retval none + */ +void crm_ertc_clock_select(crm_ertc_clock_type value) +{ + CRM->cfg_bit.ertcdiv = ((value & 0x1F0) >> 4); + CRM->bpdc_bit.ertcsel = (value & 0xF); +} + +/** + * @brief enable or disable ertc + * @param new_state (TRUE or FALSE) + * @retval none + */ +void crm_ertc_clock_enable(confirm_state new_state) +{ + CRM->bpdc_bit.ertcen = new_state; +} + +/** + * @brief set crm ahb division + * @param value + * this parameter can be one of the following values: + * - CRM_AHB_DIV_1 + * - CRM_AHB_DIV_2 + * - CRM_AHB_DIV_4 + * - CRM_AHB_DIV_8 + * - CRM_AHB_DIV_16 + * - CRM_AHB_DIV_64 + * - CRM_AHB_DIV_128 + * - CRM_AHB_DIV_256 + * - CRM_AHB_DIV_512 + * @retval none + */ +void crm_ahb_div_set(crm_ahb_div_type value) +{ + CRM->cfg_bit.ahbdiv = value; +} + +/** + * @brief set crm apb1 division + * @param value + * this parameter can be one of the following values: + * - CRM_APB1_DIV_1 + * - CRM_APB1_DIV_2 + * - CRM_APB1_DIV_4 + * - CRM_APB1_DIV_8 + * - CRM_APB1_DIV_16 + * @retval none + */ +void crm_apb1_div_set(crm_apb1_div_type value) +{ + CRM->cfg_bit.apb1div = value; +} + +/** + * @brief set crm apb2 division + * @param value + * this parameter can be one of the following values: + * - CRM_APB2_DIV_1 + * - CRM_APB2_DIV_2 + * - CRM_APB2_DIV_4 + * - CRM_APB2_DIV_8 + * - CRM_APB2_DIV_16 + * @retval none + */ +void crm_apb2_div_set(crm_apb2_div_type value) +{ + CRM->cfg_bit.apb2div = value; +} + +/** + * @brief set usb division + * @param value + * this parameter can be one of the following values: + * - CRM_USB_DIV_1_5 + * - CRM_USB_DIV_1 + * - CRM_USB_DIV_2_5 + * - CRM_USB_DIV_2 + * - CRM_USB_DIV_3_5 + * - CRM_USB_DIV_3 + * - CRM_USB_DIV_4_5 + * - CRM_USB_DIV_4 + * - CRM_USB_DIV_5_5 + * - CRM_USB_DIV_5 + * - CRM_USB_DIV_6_5 + * - CRM_USB_DIV_6 + * - CRM_USB_DIV_7 + * @retval none + */ +void crm_usb_clock_div_set(crm_usb_div_type value) +{ + CRM->misc2_bit.usbdiv = value; +} + +/** + * @brief enable or disable clock failure detection + * @param new_state (TRUE or FALSE) + * @retval none + */ +void crm_clock_failure_detection_enable(confirm_state new_state) +{ + CRM->ctrl_bit.cfden = new_state; +} + +/** + * @brief battery powered domain software reset + * @param new_state (TRUE or FALSE) + * @retval none + */ +void crm_battery_powered_domain_reset(confirm_state new_state) +{ + CRM->bpdc_bit.bpdrst = new_state; +} + +/** + * @brief auto step clock switch enable + * @param new_state (TRUE or FALSE) + * @retval none + */ +void crm_auto_step_mode_enable(confirm_state new_state) +{ + if(new_state == TRUE) + CRM->misc2_bit.auto_step_en = CRM_AUTO_STEP_MODE_ENABLE; + else + CRM->misc2_bit.auto_step_en = CRM_AUTO_STEP_MODE_DISABLE; +} + +/** + * @brief config hick divider select + * @param value + * this parameter can be one of the following values: + * - CRM_HICK48_DIV6 + * - CRM_HICK48_NODIV + * @retval none + */ +void crm_hick_divider_select(crm_hick_div_6_type value) +{ + CRM->misc1_bit.hickdiv = value; +} + +/** + * @brief hick as system clock frequency select + * @param value + * this parameter can be one of the following values: + * - CRM_HICK_SCLK_8MHZ + * - CRM_HICK_SCLK_48MHZ + * @retval none + */ +void crm_hick_sclk_frequency_select(crm_hick_sclk_frequency_type value) +{ + crm_hick_divider_select(CRM_HICK48_NODIV); + CRM->misc1_bit.hick_to_sclk = value; +} + +/** + * @brief usb 48 mhz clock source select + * @param value + * this parameter can be one of the following values: + * - CRM_USB_CLOCK_SOURCE_PLL + * - CRM_USB_CLOCK_SOURCE_HICK + * @retval none + */ +void crm_usb_clock_source_select(crm_usb_clock_source_type value) +{ + if(value == CRM_USB_CLOCK_SOURCE_HICK) + { + crm_hick_sclk_frequency_select(CRM_HICK_SCLK_48MHZ); + } + CRM->misc1_bit.hick_to_usb = value; +} + +/** + * @brief enable or disable clkout direct to tmr10 channel 1 + * @param new_state (TRUE or FALSE) + * @retval none + */ +void crm_clkout_to_tmr10_enable(confirm_state new_state) +{ + CRM->misc2_bit.clk_to_tmr = new_state; +} + +/** + * @brief config crm pll + * pll_rcs_freq * pll_ns + * pll clock = -------------------------------- + * pll_ms * pll_fr_n + * attemtion: + * 31 <= pll_ns <= 500 + * 1 <= pll_ms <= 15 + * + * pll_rcs_freq + * 2mhz <= ---------------------- <= 16mhz + * pll_ms + * + * pll_rcs_freq * pll_ns + * 500mhz <= -------------------------------- <= 1000mhz + * pll_ms + * @param clock_source + * this parameter can be one of the following values: + * - CRM_PLL_SOURCE_HICK + * - CRM_PLL_SOURCE_HEXT + * @param pll_ns (31~500) + * @param pll_ms (1~15) + * @param pll_fr + * this parameter can be one of the following values: + * - CRM_PLL_FR_1 + * - CRM_PLL_FR_2 + * - CRM_PLL_FR_4 + * - CRM_PLL_FR_8 + * - CRM_PLL_FR_16 + * - CRM_PLL_FR_32 + * @retval none + */ +void crm_pll_config(crm_pll_clock_source_type clock_source, uint16_t pll_ns, \ + uint16_t pll_ms, crm_pll_fr_type pll_fr) +{ + /* config pll clock source */ + CRM->pllcfg_bit.pllrcs = clock_source; + + /* config pll multiplication factor */ + CRM->pllcfg_bit.pllns = pll_ns; + CRM->pllcfg_bit.pllms = pll_ms; + CRM->pllcfg_bit.pllfr = pll_fr; +} + +/** + * @brief select system clock source + * @param value + * this parameter can be one of the following values: + * - CRM_SCLK_HICK + * - CRM_SCLK_HEXT + * - CRM_SCLK_PLL + * @retval none + */ +void crm_sysclk_switch(crm_sclk_type value) +{ + CRM->cfg_bit.sclksel = value; +} + +/** + * @brief indicate which clock source is used as system clock + * @param none + * @retval crm_sclk + * this return can be one of the following values: + * - CRM_SCLK_HICK + * - CRM_SCLK_HEXT + * - CRM_SCLK_PLL + */ +crm_sclk_type crm_sysclk_switch_status_get(void) +{ + return (crm_sclk_type)CRM->cfg_bit.sclksts; +} + +/** + * @brief get crm clocks freqency + * @param clocks_struct + * - pointer to the crm_clocks_freq_type structure + * @retval none + */ +void crm_clocks_freq_get(crm_clocks_freq_type *clocks_struct) +{ + uint32_t pll_ns = 0, pll_ms = 0, pll_fr = 0, pll_clock_source = 0, pllrcsfreq = 0; + uint32_t temp = 0, div_value = 0; + crm_sclk_type sclk_source; + + static const uint8_t sclk_ahb_div_table[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9}; + static const uint8_t ahb_apb1_div_table[8] = {0, 0, 0, 0, 1, 2, 3, 4}; + static const uint8_t ahb_apb2_div_table[8] = {0, 0, 0, 0, 1, 2, 3, 4}; + static const uint8_t pll_fr_table[6] = {1, 2, 4, 8, 16, 32}; + + /* get sclk source */ + sclk_source = crm_sysclk_switch_status_get(); + + switch(sclk_source) + { + case CRM_SCLK_HICK: + if(((CRM->misc1_bit.hick_to_sclk) != RESET) && ((CRM->misc1_bit.hickdiv) != RESET)) + clocks_struct->sclk_freq = HICK_VALUE * 6; + else + clocks_struct->sclk_freq = HICK_VALUE; + break; + case CRM_SCLK_HEXT: + clocks_struct->sclk_freq = HEXT_VALUE; + break; + case CRM_SCLK_PLL: + /* get pll clock source */ + pll_clock_source = CRM->pllcfg_bit.pllrcs; + + /* get multiplication factor */ + pll_ns = CRM->pllcfg_bit.pllns; + pll_ms = CRM->pllcfg_bit.pllms; + pll_fr = pll_fr_table[CRM->pllcfg_bit.pllfr]; + + if (pll_clock_source == CRM_PLL_SOURCE_HICK) + { + /* hick selected as pll clock entry */ + pllrcsfreq = HICK_VALUE; + } + else + { + /* hext selected as pll clock entry */ + pllrcsfreq = HEXT_VALUE; + } + + clocks_struct->sclk_freq = (uint32_t)(((uint64_t)pllrcsfreq * pll_ns) / (pll_ms * pll_fr)); + break; + default: + clocks_struct->sclk_freq = HICK_VALUE; + break; + } + + /* compute sclk, ahbclk, abp1clk and apb2clk frequencies */ + /* get ahb division */ + temp = CRM->cfg_bit.ahbdiv; + div_value = sclk_ahb_div_table[temp]; + /* ahbclk frequency */ + clocks_struct->ahb_freq = clocks_struct->sclk_freq >> div_value; + + /* get apb1 division */ + temp = CRM->cfg_bit.apb1div; + div_value = ahb_apb1_div_table[temp]; + /* apb1clk frequency */ + clocks_struct->apb1_freq = clocks_struct->ahb_freq >> div_value; + + /* get apb2 division */ + temp = CRM->cfg_bit.apb2div; + div_value = ahb_apb2_div_table[temp]; + /* apb2clk frequency */ + clocks_struct->apb2_freq = clocks_struct->ahb_freq >> div_value; +} + +/** + * @brief set crm clkout1 + * @param clkout + * this parameter can be one of the following values: + * - CRM_CLKOUT1_HICK + * - CRM_CLKOUT1_LEXT + * - CRM_CLKOUT1_HEXT + * - CRM_CLKOUT1_PLL + * @retval none + */ +void crm_clock_out1_set(crm_clkout1_select_type clkout) +{ + CRM->cfg_bit.clkout1_sel = clkout; +} + +/** + * @brief set crm clkout2 + * @param clkout + * this parameter can be one of the following values: + * - CRM_CLKOUT2_SCLK + * - CRM_CLKOUT2_HEXT + * - CRM_CLKOUT2_PLL + * - CRM_CLKOUT2_USB + * - CRM_CLKOUT2_ADC + * - CRM_CLKOUT2_HICK + * - CRM_CLKOUT2_LICK + * - CRM_CLKOUT2_LEXT + * @retval none + */ +void crm_clock_out2_set(crm_clkout2_select_type clkout) +{ + if(clkout < 0x10) + { + CRM->cfg_bit.clkout2_sel1 = (clkout & 0x3); + } + else + { + CRM->cfg_bit.clkout2_sel1 = 0x1; + CRM->misc1_bit.clkout2_sel2 = (clkout & 0xF); + } +} + +/** + * @brief set crm clkout1 division1 + * @param div1 + * this parameter can be one of the following values: + * - CRM_CLKOUT_INDEX_1 + * - CRM_CLKOUT_INDEX_2 + * @param div1 + * this parameter can be one of the following values: + * - CRM_CLKOUT_DIV1_1 + * - CRM_CLKOUT_DIV1_2 + * - CRM_CLKOUT_DIV1_3 + * - CRM_CLKOUT_DIV1_4 + * - CRM_CLKOUT_DIV1_5 + * @param div2 + * this parameter can be one of the following values: + * - CRM_CLKOUT_DIV2_1 + * - CRM_CLKOUT_DIV2_2 + * - CRM_CLKOUT_DIV2_4 + * - CRM_CLKOUT_DIV2_8 + * - CRM_CLKOUT_DIV2_16 + * - CRM_CLKOUT_DIV2_64 + * - CRM_CLKOUT_DIV2_128 + * - CRM_CLKOUT_DIV2_256 + * - CRM_CLKOUT_DIV2_512 + * @retval none + */ +void crm_clkout_div_set(crm_clkout_index_type index, crm_clkout_div1_type div1, crm_clkout_div2_type div2) +{ + if(index == CRM_CLKOUT_INDEX_1) + { + CRM->cfg_bit.clkout1div1 = div1; + CRM->misc1_bit.clkout1div2 = div2; + } + else + { + CRM->cfg_bit.clkout2div1 = div1; + CRM->misc1_bit.clkout2div2 = div2; + } +} + +/** + * @brief set emac output pulse width + * @param width + * this parameter can be one of the following values: + * - CRM_EMAC_PULSE_125MS + * - CRM_EMAC_PULSE_1SCLK + * @retval none + */ +void crm_emac_output_pulse_set(crm_emac_output_pulse_type width) +{ + CRM->misc2_bit.emac_pps_sel = width; +} + +/** + * @brief config crm interrupt + * @param int + * this parameter can be any combination of the following values: + * - CRM_LICK_STABLE_INT + * - CRM_LEXT_STABLE_INT + * - CRM_HICK_STABLE_INT + * - CRM_HEXT_STABLE_INT + * - CRM_PLL_STABLE_INT + * @param new_state (TRUE or FALSE) + * @retval none + */ +void crm_interrupt_enable(uint32_t crm_int, confirm_state new_state) +{ + if(TRUE == new_state) + CRM->clkint |= crm_int; + else + CRM->clkint &= ~crm_int; +} + +/** + * @brief calculate the pll parameters with pll reference clock and target pll output frequency. + * pll_rcs_freq * pll_ns + * pll clock = -------------------------------- + * pll_ms * pll_fr_n + * attemtion: + * 31 <= pll_ns <= 500 + * 1 <= pll_ms <= 15 + * + * pll_rcs_freq + * 2mhz <= ---------------------- <= 16mhz + * pll_ms + * + * pll_rcs_freq * pll_ns + * 500mhz <= -------------------------------- <= 1000mhz + * pll_ms + * @param pll_rcs + * this parameter can be one of the following values: + * - CRM_PLL_SOURCE_HICK + * - CRM_PLL_SOURCE_HEXT + * @param target_sclk_freq: target pll output frequency, such as 200 mhz (target_sclk_freq: 200000000) + * @param ret_ms: pointer to ms value, return the pll_ms of pll parameters + * @param ret_ns: pointer to ns value, return the pll_ns of pll parameters + * @param ret_fr: pointer to fr value, return the pll_fr of pll parameters + * @retval error_status (SUCCESS or ERROR) + */ +error_status crm_pll_parameter_calculate(crm_pll_clock_source_type pll_rcs, uint32_t target_sclk_freq, \ + uint16_t *ret_ms, uint16_t *ret_ns, uint16_t *ret_fr) +{ + uint32_t pll_rcs_freq = 0, ns = 0, ms = 0, fr = 0; + uint32_t ms_min = 0, ms_max = 0, error_min = 0xFFFFFFFF; + uint32_t result = 0, absolute_value = 0; + + /* reduce calculate accuracy, target_sclk_freq accuracy with khz */ + target_sclk_freq = target_sclk_freq / 1000; + + /* get pll reference clock frequency, accuracy with khz */ + if(pll_rcs == CRM_PLL_SOURCE_HICK) + pll_rcs_freq = HICK_VALUE / 1000; + else + pll_rcs_freq = HEXT_VALUE / 1000; + + /* polling ms range, accuracy with khz */ + for(ms = 1; ms <= 15; ms ++) + { + result = pll_rcs_freq / ms; + if((result >= 2000U) && (result <= 16000U)) + { + if(ms_min == 0) + ms_min = ms; + + ms_max = ms; + } + } + + /* polling pll parameters */ + for(ms = ms_min; ms <= ms_max; ms ++) + { + for(fr = 0; fr <= 5; fr ++) + { + for(ns = 31; ns <= 500; ns ++) + { + result = (pll_rcs_freq * ns) / (ms); + /* check vco frequency range, accuracy with khz */ + if((result < 500000U) || (result > 1000000U)) + { + continue; + } + /* calculate pll output frequency */ + result = result / (0x1 << fr); + /* check frequency */ + if(target_sclk_freq == result) + { + *ret_ms = ms; + *ret_ns = ns; + *ret_fr = fr; + /* the pll parameters that is equal to target_sclk_freq */ + return SUCCESS; + } + /* calculate error range, accuracy with khz */ + absolute_value = (result > target_sclk_freq) ? (result - target_sclk_freq) : (target_sclk_freq - result); + if(absolute_value < error_min) + { + error_min = absolute_value; + *ret_ms = ms; + *ret_ns = ns; + *ret_fr = fr; + } + } + } + } + /* the pll parameters that is the closest approach to target_sclk_freq */ + return ERROR; +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_dac.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_dac.c new file mode 100644 index 0000000000..3d90ff4d59 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_dac.c @@ -0,0 +1,454 @@ +/** + ************************************************************************** + * @file at32f435_437_dac.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the dac firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup DAC + * @brief DAC driver modules + * @{ + */ + +#ifdef DAC_MODULE_ENABLED + +/** @defgroup DAC_private_functions + * @{ + */ + +/** + * @brief dac reset + * @param none + * @retval none + */ +void dac_reset(void) +{ + crm_periph_reset(CRM_DAC_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_DAC_PERIPH_RESET, FALSE); +} + +/** + * @brief enable or disable dac + * @param dac_select + * this parameter can be one of the following values: + * - DAC1_SELECT + * - DAC2_SELECT + * @param new_state (TRUE or FALSE) + * @retval none + */ +void dac_enable(dac_select_type dac_select, confirm_state new_state) +{ + switch(dac_select) + { + case DAC1_SELECT: + DAC->ctrl_bit.d1en = new_state; + break; + case DAC2_SELECT: + DAC->ctrl_bit.d2en = new_state; + break; + default: + break; + } +} + +/** + * @brief enable or disable dac output buffer + * @param dac_select + * this parameter can be one of the following values: + * - DAC1_SELECT + * - DAC2_SELECT + * @param new_state (TRUE or FALSE) + * @retval none + */ +void dac_output_buffer_enable(dac_select_type dac_select, confirm_state new_state) +{ + new_state = (confirm_state)!new_state; + switch(dac_select) + { + case DAC1_SELECT: + DAC->ctrl_bit.d1obdis = new_state; + break; + case DAC2_SELECT: + DAC->ctrl_bit.d2obdis = new_state; + break; + default: + break; + } +} + +/** + * @brief enable or disable dac trigger + * @param dac_select + * this parameter can be one of the following values: + * - DAC1_SELECT + * - DAC2_SELECT + * @param new_state (TRUE or FALSE) + * @retval none + */ +void dac_trigger_enable(dac_select_type dac_select, confirm_state new_state) +{ + switch(dac_select) + { + case DAC1_SELECT: + DAC->ctrl_bit.d1trgen = new_state; + break; + case DAC2_SELECT: + DAC->ctrl_bit.d2trgen = new_state; + break; + default: + break; + } +} + +/** + * @brief select dac trigger + * @param dac_select + * this parameter can be one of the following values: + * - DAC1_SELECT + * - DAC2_SELECT + * @param dac_trigger_source + * this parameter can be one of the following values: + * - DAC_TMR6_TRGOUT_EVENT + * - DAC_TMR8_TRGOUT_EVENT + * - DAC_TMR7_TRGOUT_EVENT + * - DAC_TMR5_TRGOUT_EVENT + * - DAC_TMR2_TRGOUT_EVENT + * - DAC_TMR4_TRGOUT_EVENT + * - DAC_EXTERNAL_INTERRUPT_LINE_9 + * - DAC_SOFTWARE_TRIGGER + * @retval none + */ +void dac_trigger_select(dac_select_type dac_select, dac_trigger_type dac_trigger_source) +{ + switch(dac_select) + { + case DAC1_SELECT: + DAC->ctrl_bit.d1trgsel = dac_trigger_source; + break; + case DAC2_SELECT: + DAC->ctrl_bit.d2trgsel = dac_trigger_source; + break; + default: + break; + } +} + +/** + * @brief generate dac software trigger + * @param dac_select + * this parameter can be one of the following values: + * - DAC1_SELECT + * - DAC2_SELECT + * @retval none + */ +void dac_software_trigger_generate(dac_select_type dac_select) +{ + switch(dac_select) + { + case DAC1_SELECT: + DAC->swtrg_bit.d1swtrg = TRUE; + break; + case DAC2_SELECT: + DAC->swtrg_bit.d2swtrg = TRUE; + break; + default: + break; + } +} + +/** + * @brief generate dac dual software trigger synchronously + * @param none + * @retval none + */ +void dac_dual_software_trigger_generate(void) +{ + DAC->swtrg |= 0x03; +} + +/** + * @brief generate dac wave + * @param dac_select + * this parameter can be one of the following values: + * - DAC1_SELECT + * - DAC2_SELECT + * @param dac_wave + * this parameter can be one of the following values: + * - DAC_WAVE_GENERATE_NONE + * - DAC_WAVE_GENERATE_NOISE + * - DAC_WAVE_GENERATE_TRIANGLE + * @retval none + */ +void dac_wave_generate(dac_select_type dac_select, dac_wave_type dac_wave) +{ + switch(dac_select) + { + case DAC1_SELECT: + DAC->ctrl_bit.d1nm = dac_wave; + break; + case DAC2_SELECT: + DAC->ctrl_bit.d2nm = dac_wave; + break; + default: + break; + } +} + +/** + * @brief select dac mask amplitude + * @param dac_select + * this parameter can be one of the following values: + * - DAC1_SELECT + * - DAC2_SELECT + * @param dac_mask_amplitude + * this parameter can be one of the following values: + * - DAC_LSFR_BIT0_AMPLITUDE_1 + * - DAC_LSFR_BIT10_AMPLITUDE_3 + * - DAC_LSFR_BIT20_AMPLITUDE_7 + * - DAC_LSFR_BIT30_AMPLITUDE_15 + * - DAC_LSFR_BIT40_AMPLITUDE_31 + * - DAC_LSFR_BIT50_AMPLITUDE_63 + * - DAC_LSFR_BIT60_AMPLITUDE_127 + * - DAC_LSFR_BIT70_AMPLITUDE_255 + * - DAC_LSFR_BIT80_AMPLITUDE_511 + * - DAC_LSFR_BIT90_AMPLITUDE_1023 + * - DAC_LSFR_BITA0_AMPLITUDE_2047 + * - DAC_LSFR_BITB0_AMPLITUDE_4095 + * @retval none + */ +void dac_mask_amplitude_select(dac_select_type dac_select, dac_mask_amplitude_type dac_mask_amplitude) +{ + switch(dac_select) + { + case DAC1_SELECT: + DAC->ctrl_bit.d1nbsel = dac_mask_amplitude; + break; + case DAC2_SELECT: + DAC->ctrl_bit.d2nbsel = dac_mask_amplitude; + break; + default: + break; + } +} + +/** + * @brief enable or disable dac dma + * @param dac_select + * this parameter can be one of the following values: + * - DAC1_SELECT + * - DAC2_SELECT + * @param new_state (TRUE or FALSE) + * @retval none + */ +void dac_dma_enable(dac_select_type dac_select, confirm_state new_state) +{ + switch(dac_select) + { + case DAC1_SELECT: + DAC->ctrl_bit.d1dmaen = new_state; + break; + case DAC2_SELECT: + DAC->ctrl_bit.d2dmaen = new_state; + break; + default: + break; + } +} + +/** + * @brief get dac data output + * @param dac_select + * this parameter can be one of the following values: + * - DAC1_SELECT + * - DAC2_SELECT + * @retval dac channel data output + */ +uint16_t dac_data_output_get(dac_select_type dac_select) +{ + uint16_t data_output =0; + switch(dac_select) + { + case DAC1_SELECT: + data_output = DAC->d1odt_bit.d1odt; + break; + case DAC2_SELECT: + data_output = DAC->d2odt_bit.d2odt; + break; + default: + break; + } + return data_output; +} + +/** + * @brief set dac1 data + * @param dac1_aligned + * this parameter can be one of the following values: + * DAC1_12BIT_RIGHT + * DAC1_12BIT_LEFT + * DAC1_8BIT_RIGHT + * @param dac1_data :indecate from selected data holding register + * @retval none + */ +void dac_1_data_set(dac1_aligned_data_type dac1_aligned, uint16_t dac1_data) +{ + *(__IO uint32_t *) dac1_aligned = dac1_data; +} + +/** + * @brief set dac2 data + * @param dac2_aligned + * this parameter can be one of the following values: + * DAC2_12BIT_RIGHT + * DAC2_12BIT_LEFT + * DAC2_8BIT_RIGHT + * @param dac2_data :indecate from selected data holding register + * @retval none + */ +void dac_2_data_set(dac2_aligned_data_type dac2_aligned, uint16_t dac2_data) +{ + *(__IO uint32_t *) dac2_aligned = dac2_data; +} + +/** + * @brief set dac dual data + * @param dac_dual + * this parameter can be one of the following values: + * DAC_DUAL_12BIT_RIGHT + * DAC_DUAL_12BIT_LEFT + * DAC_DUAL_8BIT_RIGHT + * @param data1 :dac1 channel indecate from selected data holding register + * @param data2 :dac1 channel indecate from selected data holding register + * @retval none + */ +void dac_dual_data_set(dac_dual_data_type dac_dual, uint16_t data1, uint16_t data2) +{ + switch(dac_dual) + { + case DAC_DUAL_12BIT_RIGHT: + *(__IO uint32_t *) dac_dual = (uint32_t)(data1 | (data2 << 16)); + break; + case DAC_DUAL_12BIT_LEFT: + *(__IO uint32_t *) dac_dual = (uint32_t)(data1 | (data2 << 16)); + break; + case DAC_DUAL_8BIT_RIGHT: + *(__IO uint32_t *) dac_dual = (uint32_t)(data1 | (data2 << 8)); + break; + default: + break; + } +} + +/** + * @brief enable/disable dac dma udr interrupt + * @param dac_select + * this parameter can be one of the following values: + * - DAC1_SELECT + * - DAC2_SELECT + * @param new_state (TRUE or FALSE) + * @retval none + */ +void dac_udr_enable(dac_select_type dac_select, confirm_state new_state) +{ + switch(dac_select) + { + case DAC1_SELECT: + DAC->ctrl_bit.d1dmaudrien = new_state; + break; + case DAC2_SELECT: + DAC->ctrl_bit.d2dmaudrien = new_state; + break; + default: + break; + } +} + +/** + * @brief get flag of the dac udr flag. + * @param dac_select + * this parameter can be one of the following values: + * - DAC1_SELECT + * - DAC2_SELECT + * @retval the new state of dac udr flag status(SET or RESET). + */ +flag_status dac_udr_flag_get(dac_select_type dac_select) +{ + flag_status status = RESET; + + switch(dac_select) + { + case DAC1_SELECT: + if(DAC->sts_bit.d1dmaudrf != 0) + status = SET; + break; + case DAC2_SELECT: + if(DAC->sts_bit.d2dmaudrf != 0) + status = SET; + break; + default: + break; + } + return status; +} + +/** + * @brief clear the dac udr flag. + * @param dac_select + * this parameter can be one of the following values: + * - DAC1_SELECT + * - DAC2_SELECT + * @retval none + */ +void dac_udr_flag_clear(dac_select_type dac_select) +{ + switch(dac_select) + { + case DAC1_SELECT: + DAC->sts = DAC1_D1DMAUDRF; + break; + case DAC2_SELECT: + DAC->sts = DAC2_D2DMAUDRF; + break; + default: + break; + } +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_debug.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_debug.c new file mode 100644 index 0000000000..bb451a7c23 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_debug.c @@ -0,0 +1,135 @@ +/** + ************************************************************************** + * @file at32f435_437_mcudbg.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the mcudbg firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup DEBUG + * @brief DEBUG driver modules + * @{ + */ + +#ifdef DEBUG_MODULE_ENABLED + +/** @defgroup DEBUG_private_functions + * @{ + */ + +/** + * @brief get debug device id + * @param none + * @retval the debug device id + */ +uint32_t debug_device_id_get(void) +{ + return DEBUGMCU->pid; +} +/** + * @brief set periph debug mode + * @param periph_debug_mode + * this parameter can be one of the following values: + * - DEBUG_SLEEP + * - DEBUG_DEEPSLEEP + * - DEBUG_STANDBY + * @param new_state (TRUE or FALSE) + * @retval none + */ +void debug_low_power_mode_set(uint32_t low_power_mode, confirm_state new_state) +{ + if(new_state != FALSE) + { + DEBUGMCU->ctrl |= low_power_mode; + } + else + { + DEBUGMCU->ctrl &= ~low_power_mode; + } +} +/** + * @brief set apb1 periph debug mode + * @param periph_debug_mode + * this parameter can be any combination of the following values: + * - DEBUG_TMR2_PAUSE - DEBUG_TMR3_PAUSE + * - DEBUG_TMR4_PAUSE - DEBUG_TMR5_PAUSE + * - DEBUG_TMR6_PAUSE - DEBUG_TMR7_PAUSE + * - DEBUG_TMR12_PAUSE - DEBUG_TMR13_PAUSE + * - DEBUG_TMR14_PAUSE - DEBUG_ERTC_PAUSE + * - DEBUG_WWDT_PAUSE - DEBUG_WDT_PAUSE + * - DEBUG_ERTC_512_PAUSE - DEBUG_I2C1_SMBUS_TIMEOUT + * - DEBUG_I2C2_SMBUS_TIMEOUT - DEBUG_I2C3_SMBUS_TIMEOUT + * - DEBUG_CAN1_PAUSE - DEBUG_CAN2_PAUSE + * @param new_state (TRUE or FALSE) + * @retval none + */ +void debug_apb1_periph_mode_set(uint32_t apb1_periph, confirm_state new_state) +{ + if(new_state != FALSE) + { + DEBUGMCU->apb1_frz |= apb1_periph; + } + else + { + DEBUGMCU->apb1_frz &= ~apb1_periph; + } +} +/** + * @brief set apb2 periph debug mode + * @param periph_debug_mode + * this parameter can be any combination of the following values: + * - DEBUG_TMR1_PAUSE - DEBUG_TMR8_PAUSE + * - DEBUG_TMR20_PAUSE - DEBUG_TMR9_PAUSE + * - DEBUG_TMR10_PAUSE - DEBUG_TMR11_PAUSE + * @param new_state (TRUE or FALSE) + * @retval none + */ +void debug_apb2_periph_mode_set(uint32_t apb2_periph, confirm_state new_state) +{ + if(new_state != FALSE) + { + DEBUGMCU->apb2_frz |= apb2_periph; + } + else + { + DEBUGMCU->apb2_frz &= ~apb2_periph; + } +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_dma.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_dma.c new file mode 100644 index 0000000000..a7d0313d85 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_dma.c @@ -0,0 +1,683 @@ +/** + ************************************************************************** + * @file at32f435_437_dma.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the dma firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup DMA + * @brief DMA driver modules + * @{ + */ + +#ifdef DMA_MODULE_ENABLED + +/** @defgroup DMA_private_functions + * @{ + */ + +/** + * @brief reset dmax channely register. + * @param dmax_channely: + * this parameter can be one of the following values: + * - DMA1_CHANNEL1 + * - DMA1_CHANNEL2 + * - DMA1_CHANNEL3 + * - DMA1_CHANNEL4 + * - DMA1_CHANNEL5 + * - DMA1_CHANNEL6 + * - DMA1_CHANNEL7 + * - DMA2_CHANNEL1 + * - DMA2_CHANNEL2 + * - DMA2_CHANNEL3 + * - DMA2_CHANNEL4 + * - DMA2_CHANNEL5 + * - DMA2_CHANNEL6 + * - DMA2_CHANNEL7 + * @retval none. + */ +void dma_reset(dma_channel_type *dmax_channely) +{ + uint32_t temp = 0; + dmax_channely->ctrl_bit.chen = FALSE; + dmax_channely->ctrl = 0; + dmax_channely->dtcnt = 0; + dmax_channely->paddr = 0; + dmax_channely->maddr = 0; + + temp = (uint32_t)dmax_channely; + + if((temp & 0x6FF) < 0x608) + { + /* dma1 channel */ + DMA1->clr |= (uint32_t)(0x0F << ((((temp & 0xFF) - 0x08) / 0x14) * 4)); + } + else if((temp & 0x6FF) < 0x688) + { + /* dma2 channel */ + DMA2->clr |= (uint32_t)(0x0F << ((((temp & 0xFF) - 0x08) / 0x14) * 4)); + } +} + +/** + * @brief set the number of data to be transferred. + * @param dmax_channely: + * this parameter can be one of the following values: + * - DMA1_CHANNEL1 + * - DMA1_CHANNEL2 + * - DMA1_CHANNEL3 + * - DMA1_CHANNEL4 + * - DMA1_CHANNEL5 + * - DMA1_CHANNEL6 + * - DMA1_CHANNEL7 + * - DMA2_CHANNEL1 + * - DMA2_CHANNEL2 + * - DMA2_CHANNEL3 + * - DMA2_CHANNEL4 + * - DMA2_CHANNEL5 + * - DMA2_CHANNEL6 + * - DMA2_CHANNEL7 + * @param data_number: the number of data to be transferred (0x0000~0xFFFF). + * @retval none. + */ +void dma_data_number_set(dma_channel_type *dmax_channely, uint16_t data_number) +{ + dmax_channely->dtcnt = data_number; +} + +/** + * @brief get the number of data to be transferred. + * @param dmax_channely: + * this parameter can be one of the following values: + * - DMA1_CHANNEL1 + * - DMA1_CHANNEL2 + * - DMA1_CHANNEL3 + * - DMA1_CHANNEL4 + * - DMA1_CHANNEL5 + * - DMA1_CHANNEL6 + * - DMA1_CHANNEL7 + * - DMA2_CHANNEL1 + * - DMA2_CHANNEL2 + * - DMA2_CHANNEL3 + * - DMA2_CHANNEL4 + * - DMA2_CHANNEL5 + * - DMA2_CHANNEL6 + * - DMA2_CHANNEL7 + * @retval the number value. + */ +uint16_t dma_data_number_get(dma_channel_type *dmax_channely) +{ + return (uint16_t)dmax_channely->dtcnt; +} + +/** + * @brief enable or disable dma interrupt. + * @param dmax_channely: + * this parameter can be one of the following values: + * - DMA1_CHANNEL1 + * - DMA1_CHANNEL2 + * - DMA1_CHANNEL3 + * - DMA1_CHANNEL4 + * - DMA1_CHANNEL5 + * - DMA1_CHANNEL6 + * - DMA1_CHANNEL7 + * - DMA2_CHANNEL1 + * - DMA2_CHANNEL2 + * - DMA2_CHANNEL3 + * - DMA2_CHANNEL4 + * - DMA2_CHANNEL5 + * - DMA2_CHANNEL6 + * - DMA2_CHANNEL7 + * @param dma_int: + * this parameter can be any combination of the following values: + * - DMA_FDT_INT + * - DMA_HDT_INT + * - DMA_DTERR_INT + * @param new_state (TRUE or FALSE) + * @retval none. + */ +void dma_interrupt_enable(dma_channel_type *dmax_channely, uint32_t dma_int, confirm_state new_state) +{ + if(new_state != FALSE) + { + dmax_channely->ctrl |= dma_int; + } + else + { + dmax_channely->ctrl &= ~dma_int; + } +} + +/** + * @brief enable or disable dma channel. + * @param dmax_channely: + * this parameter can be one of the following values: + * - DMA1_CHANNEL1 + * - DMA1_CHANNEL2 + * - DMA1_CHANNEL3 + * - DMA1_CHANNEL4 + * - DMA1_CHANNEL5 + * - DMA1_CHANNEL6 + * - DMA1_CHANNEL7 + * - DMA2_CHANNEL1 + * - DMA2_CHANNEL2 + * - DMA2_CHANNEL3 + * - DMA2_CHANNEL4 + * - DMA2_CHANNEL5 + * - DMA2_CHANNEL6 + * - DMA2_CHANNEL7 + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void dma_channel_enable(dma_channel_type *dmax_channely, confirm_state new_state) +{ + dmax_channely->ctrl_bit.chen = new_state; +} + +/** + * @brief dma flag get. + * @param dma_flag + * - DMA1_GL1_FLAG - DMA1_FDT1_FLAG - DMA1_HDT1_FLAG - DMA1_DTERR1_FLAG + * - DMA1_GL2_FLAG - DMA1_FDT2_FLAG - DMA1_HDT2_FLAG - DMA1_DTERR2_FLAG + * - DMA1_GL3_FLAG - DMA1_FDT3_FLAG - DMA1_HDT3_FLAG - DMA1_DTERR3_FLAG + * - DMA1_GL4_FLAG - DMA1_FDT4_FLAG - DMA1_HDT4_FLAG - DMA1_DTERR4_FLAG + * - DMA1_GL5_FLAG - DMA1_FDT5_FLAG - DMA1_HDT5_FLAG - DMA1_DTERR5_FLAG + * - DMA1_GL6_FLAG - DMA1_FDT6_FLAG - DMA1_HDT6_FLAG - DMA1_DTERR6_FLAG + * - DMA1_GL7_FLAG - DMA1_FDT7_FLAG - DMA1_HDT7_FLAG - DMA1_DTERR7_FLAG + * - DMA2_GL1_FLAG - DMA2_FDT1_FLAG - DMA2_HDT1_FLAG - DMA2_DTERR1_FLAG + * - DMA2_GL2_FLAG - DMA2_FDT2_FLAG - DMA2_HDT2_FLAG - DMA2_DTERR2_FLAG + * - DMA2_GL3_FLAG - DMA2_FDT3_FLAG - DMA2_HDT3_FLAG - DMA2_DTERR3_FLAG + * - DMA2_GL4_FLAG - DMA2_FDT4_FLAG - DMA2_HDT4_FLAG - DMA2_DTERR4_FLAG + * - DMA2_GL5_FLAG - DMA2_FDT5_FLAG - DMA2_HDT5_FLAG - DMA2_DTERR5_FLAG + * - DMA2_GL6_FLAG - DMA2_FDT6_FLAG - DMA2_HDT6_FLAG - DMA2_DTERR6_FLAG + * - DMA2_GL7_FLAG - DMA2_FDT7_FLAG - DMA2_HDT7_FLAG - DMA2_DTERR7_FLAG + * @retval state of dma flag. + */ +flag_status dma_flag_get(uint32_t dmax_flag) +{ + uint32_t temp = 0; + + if(dmax_flag > 0x10000000) + { + temp = DMA2->sts; + } + else + { + temp = DMA1->sts; + } + + if((temp & dmax_flag) != RESET) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief dma flag clear. + * @param dma_flag + * this parameter can be one of the following values: + * - DMA1_GL1_FLAG - DMA1_FDT1_FLAG - DMA1_HDT1_FLAG - DMA1_DTERR1_FLAG + * - DMA1_GL2_FLAG - DMA1_FDT2_FLAG - DMA1_HDT2_FLAG - DMA1_DTERR2_FLAG + * - DMA1_GL3_FLAG - DMA1_FDT3_FLAG - DMA1_HDT3_FLAG - DMA1_DTERR3_FLAG + * - DMA1_GL4_FLAG - DMA1_FDT4_FLAG - DMA1_HDT4_FLAG - DMA1_DTERR4_FLAG + * - DMA1_GL5_FLAG - DMA1_FDT5_FLAG - DMA1_HDT5_FLAG - DMA1_DTERR5_FLAG + * - DMA1_GL6_FLAG - DMA1_FDT6_FLAG - DMA1_HDT6_FLAG - DMA1_DTERR6_FLAG + * - DMA1_GL7_FLAG - DMA1_FDT7_FLAG - DMA1_HDT7_FLAG - DMA1_DTERR7_FLAG + * - DMA2_GL1_FLAG - DMA2_FDT1_FLAG - DMA2_HDT1_FLAG - DMA2_DTERR1_FLAG + * - DMA2_GL2_FLAG - DMA2_FDT2_FLAG - DMA2_HDT2_FLAG - DMA2_DTERR2_FLAG + * - DMA2_GL3_FLAG - DMA2_FDT3_FLAG - DMA2_HDT3_FLAG - DMA2_DTERR3_FLAG + * - DMA2_GL4_FLAG - DMA2_FDT4_FLAG - DMA2_HDT4_FLAG - DMA2_DTERR4_FLAG + * - DMA2_GL5_FLAG - DMA2_FDT5_FLAG - DMA2_HDT5_FLAG - DMA2_DTERR5_FLAG + * - DMA2_GL6_FLAG - DMA2_FDT6_FLAG - DMA2_HDT6_FLAG - DMA2_DTERR6_FLAG + * - DMA2_GL7_FLAG - DMA2_FDT7_FLAG - DMA2_HDT7_FLAG - DMA2_DTERR7_FLAG + * @retval none. + */ +void dma_flag_clear(uint32_t dmax_flag) +{ + if(dmax_flag > ((uint32_t)0x10000000)) + { + DMA2->clr = (uint32_t)(dmax_flag & 0x0FFFFFFF); + } + else + { + DMA1->clr = dmax_flag; + } +} + +/** + * @brief dma init config with its default value. + * @param dma_init_struct: pointer to a dma_init_type structure which will be initialized. + * @retval none. + */ +void dma_default_para_init(dma_init_type *dma_init_struct) +{ + dma_init_struct->peripheral_base_addr = 0; + dma_init_struct->memory_base_addr = 0; + dma_init_struct->direction = DMA_DIR_PERIPHERAL_TO_MEMORY; + dma_init_struct->buffer_size = 0; + dma_init_struct->peripheral_inc_enable = FALSE; + dma_init_struct->memory_inc_enable = FALSE; + dma_init_struct->peripheral_data_width = DMA_PERIPHERAL_DATA_WIDTH_BYTE; + dma_init_struct->memory_data_width = DMA_MEMORY_DATA_WIDTH_BYTE; + dma_init_struct->loop_mode_enable = FALSE; + dma_init_struct->priority = DMA_PRIORITY_LOW; +} + +/** + * @brief dma init. + * @param dmax_channely: + * this parameter can be one of the following values: + * - DMA1_CHANNEL1 + * - DMA1_CHANNEL2 + * - DMA1_CHANNEL3 + * - DMA1_CHANNEL4 + * - DMA1_CHANNEL5 + * - DMA1_CHANNEL6 + * - DMA1_CHANNEL7 + * - DMA2_CHANNEL1 + * - DMA2_CHANNEL2 + * - DMA2_CHANNEL3 + * - DMA2_CHANNEL4 + * - DMA2_CHANNEL5 + * - DMA2_CHANNEL6 + * - DMA2_CHANNEL7 + * @param dma_init_struct: pointer to a dma_init_type structure. + * @retval none. + */ +void dma_init(dma_channel_type *dmax_channely, dma_init_type *dma_init_struct) +{ + /* clear ctrl register dtd bit and m2m bit */ + dmax_channely->ctrl &= 0xbfef; + dmax_channely->ctrl |= dma_init_struct->direction; + + dmax_channely->ctrl_bit.chpl = dma_init_struct->priority; + dmax_channely->ctrl_bit.mwidth = dma_init_struct->memory_data_width; + dmax_channely->ctrl_bit.pwidth = dma_init_struct->peripheral_data_width; + dmax_channely->ctrl_bit.mincm = dma_init_struct->memory_inc_enable; + dmax_channely->ctrl_bit.pincm = dma_init_struct->peripheral_inc_enable; + dmax_channely->ctrl_bit.lm = dma_init_struct->loop_mode_enable; + dmax_channely->dtcnt_bit.cnt = dma_init_struct->buffer_size; + dmax_channely->paddr = dma_init_struct->peripheral_base_addr; + dmax_channely->maddr = dma_init_struct->memory_base_addr; +} +/** + * @brief dmamux init. + * @param dma_x: pointer to a dma_type structure, can be DMA1 or DMA2. + * @param dmamux_channelx: + * this parameter can be one of the following values: + * - DMA1MUX_CHANNEL1 + * - DMA1MUX_CHANNEL2 + * - DMA1MUX_CHANNEL3 + * - DMA1MUX_CHANNEL4 + * - DMA1MUX_CHANNEL5 + * - DMA1MUX_CHANNEL6 + * - DMA1MUX_CHANNEL7 + * - DMA2MUX_CHANNEL1 + * - DMA2MUX_CHANNEL2 + * - DMA2MUX_CHANNEL3 + * - DMA2MUX_CHANNEL4 + * - DMA2MUX_CHANNEL5 + * - DMA2MUX_CHANNEL6 + * - DMA2MUX_CHANNEL7 + * @param dmamux_req_sel: + * this parameter can be one of the following values: + * - DMAMUX_DMAREQ_ID_REQ_G1 - DMAMUX_DMAREQ_ID_REQ_G2 - DMAMUX_DMAREQ_ID_REQ_G3 - DMAMUX_DMAREQ_ID_REQ_G4 + * - DMAMUX_DMAREQ_ID_ADC1 - DMAMUX_DMAREQ_ID_ADC2 - DMAMUX_DMAREQ_ID_ADC3 - DMAMUX_DMAREQ_ID_DAC1 + * - DMAMUX_DMAREQ_ID_DAC2 - DMAMUX_DMAREQ_ID_TMR6_OVERFLOW- DMAMUX_DMAREQ_ID_TMR7_OVERFLOW- DMAMUX_DMAREQ_ID_SPI1_RX + * - DMAMUX_DMAREQ_ID_SPI1_TX - DMAMUX_DMAREQ_ID_SPI2_RX - DMAMUX_DMAREQ_ID_SPI2_TX - DMAMUX_DMAREQ_ID_SPI3_RX + * - DMAMUX_DMAREQ_ID_SPI3_TX - DMAMUX_DMAREQ_ID_SPI4_RX - DMAMUX_DMAREQ_ID_SPI4_TX - DMAMUX_DMAREQ_ID_I2S2_EXT_RX + * - DMAMUX_DMAREQ_ID_I2S2_EXT_TX - DMAMUX_DMAREQ_ID_I2S3_EXT_RX - DMAMUX_DMAREQ_ID_I2S3_EXT_TX - DMAMUX_DMAREQ_ID_I2C1_RX + * - DMAMUX_DMAREQ_ID_I2C1_TX - DMAMUX_DMAREQ_ID_I2C2_RX - DMAMUX_DMAREQ_ID_I2C2_TX - DMAMUX_DMAREQ_ID_I2C3_RX + * - DMAMUX_DMAREQ_ID_I2C3_TX - DMAMUX_DMAREQ_ID_USART1_RX - DMAMUX_DMAREQ_ID_USART1_TX - DMAMUX_DMAREQ_ID_USART2_RX + * - DMAMUX_DMAREQ_ID_USART2_TX - DMAMUX_DMAREQ_ID_USART3_RX - DMAMUX_DMAREQ_ID_USART3_TX - DMAMUX_DMAREQ_ID_UART4_RX + * - DMAMUX_DMAREQ_ID_UART4_TX - DMAMUX_DMAREQ_ID_UART5_RX - DMAMUX_DMAREQ_ID_UART5_TX - DMAMUX_DMAREQ_ID_USART6_RX + * - DMAMUX_DMAREQ_ID_USART6_TX - DMAMUX_DMAREQ_ID_UART7_RX - DMAMUX_DMAREQ_ID_UART7_TX - DMAMUX_DMAREQ_ID_UART8_RX + * - DMAMUX_DMAREQ_ID_UART8_TX - DMAMUX_DMAREQ_ID_SDIO1 - DMAMUX_DMAREQ_ID_SDIO2 - DMAMUX_DMAREQ_ID_QSPI1 + * - DMAMUX_DMAREQ_ID_QSPI2 - DMAMUX_DMAREQ_ID_TMR1_CH1 - DMAMUX_DMAREQ_ID_TMR1_CH2 - DMAMUX_DMAREQ_ID_TMR1_CH3 + * - DMAMUX_DMAREQ_ID_TMR1_CH4 - DMAMUX_DMAREQ_ID_TMR1_OVERFLOW- DMAMUX_DMAREQ_ID_TMR1_TRIG - DMAMUX_DMAREQ_ID_TMR1_COM + * - DMAMUX_DMAREQ_ID_TMR8_CH1 - DMAMUX_DMAREQ_ID_TMR8_CH2 - DMAMUX_DMAREQ_ID_TMR8_CH3 - DMAMUX_DMAREQ_ID_TMR8_CH4 + * - DMAMUX_DMAREQ_ID_TMR8_UP - DMAMUX_DMAREQ_ID_TMR8_TRIG - DMAMUX_DMAREQ_ID_TMR8_COM - DMAMUX_DMAREQ_ID_TMR2_CH1 + * - DMAMUX_DMAREQ_ID_TMR2_CH2 - DMAMUX_DMAREQ_ID_TMR2_CH3 - DMAMUX_DMAREQ_ID_TMR2_CH4 - DMAMUX_DMAREQ_ID_TMR2_OVERFLOW + * - DMAMUX_DMAREQ_ID_TMR2_TRIG - DMAMUX_DMAREQ_ID_TMR3_CH1 - DMAMUX_DMAREQ_ID_TMR3_CH2 - DMAMUX_DMAREQ_ID_TMR3_CH3 + * - DMAMUX_DMAREQ_ID_TMR3_CH4 - DMAMUX_DMAREQ_ID_TMR3_OVERFLOW- DMAMUX_DMAREQ_ID_TMR3_TRIG - DMAMUX_DMAREQ_ID_TMR4_CH1 + * - DMAMUX_DMAREQ_ID_TMR4_CH2 - DMAMUX_DMAREQ_ID_TMR4_CH3 - DMAMUX_DMAREQ_ID_TMR4_CH4 - DMAMUX_DMAREQ_ID_TMR4_OVERFLOW + * - DMAMUX_DMAREQ_ID_TMR4_TRIG - DMAMUX_DMAREQ_ID_TMR5_CH1 - DMAMUX_DMAREQ_ID_TMR5_CH2 - DMAMUX_DMAREQ_ID_TMR5_CH3 + * - DMAMUX_DMAREQ_ID_TMR5_CH4 - DMAMUX_DMAREQ_ID_TMR5_OVERFLOW- DMAMUX_DMAREQ_ID_TMR5_TRIG - DMAMUX_DMAREQ_ID_TMR20_CH1 + * - DMAMUX_DMAREQ_ID_TMR20_CH2 - DMAMUX_DMAREQ_ID_TMR20_CH3 - DMAMUX_DMAREQ_ID_TMR20_CH4 - DMAMUX_DMAREQ_ID_TMR20_OVERFLOW + * - DMAMUX_DMAREQ_ID_TMR20_TRIG - DMAMUX_DMAREQ_ID_TMR20_HALL - DMAMUX_DMAREQ_ID_DVP + * @retval none. + */ +void dma_flexible_config(dma_type* dma_x, dmamux_channel_type *dmamux_channelx, dmamux_requst_id_sel_type dmamux_req_sel) +{ + dma_x->muxsel_bit.tblsel = TRUE; + dmamux_channelx->muxctrl_bit.reqsel = dmamux_req_sel; +} + +/** + * @brief enable or disable the dmamux. + * @param dma_x: pointer to a dma_type structure, can be DMA1 or DMA2. + * @param new_state (TRUE or FALSE) . + * @retval none. + */ +void dmamux_enable(dma_type *dma_x, confirm_state new_state) +{ + dma_x->muxsel_bit.tblsel = new_state; +} + +/** + * @brief dmamux init. + * @param dmamux_channelx: + * this parameter can be one of the following values: + * - DMA1MUX_CHANNEL1 + * - DMA1MUX_CHANNEL2 + * - DMA1MUX_CHANNEL3 + * - DMA1MUX_CHANNEL4 + * - DMA1MUX_CHANNEL5 + * - DMA1MUX_CHANNEL6 + * - DMA1MUX_CHANNEL7 + * - DMA2MUX_CHANNEL1 + * - DMA2MUX_CHANNEL2 + * - DMA2MUX_CHANNEL3 + * - DMA2MUX_CHANNEL4 + * - DMA2MUX_CHANNEL5 + * - DMA2MUX_CHANNEL6 + * - DMA2MUX_CHANNEL7 + * @param dmamux_req_sel: + * this parameter can be one of the following values: + * - DMAMUX_DMAREQ_ID_REQ_G1 - DMAMUX_DMAREQ_ID_REQ_G2 - DMAMUX_DMAREQ_ID_REQ_G3 - DMAMUX_DMAREQ_ID_REQ_G4 + * - DMAMUX_DMAREQ_ID_ADC1 - DMAMUX_DMAREQ_ID_ADC2 - DMAMUX_DMAREQ_ID_ADC3 - DMAMUX_DMAREQ_ID_DAC1 + * - DMAMUX_DMAREQ_ID_DAC2 - DMAMUX_DMAREQ_ID_TMR6_OVERFLOW- DMAMUX_DMAREQ_ID_TMR7_OVERFLOW- DMAMUX_DMAREQ_ID_SPI1_RX + * - DMAMUX_DMAREQ_ID_SPI1_TX - DMAMUX_DMAREQ_ID_SPI2_RX - DMAMUX_DMAREQ_ID_SPI2_TX - DMAMUX_DMAREQ_ID_SPI3_RX + * - DMAMUX_DMAREQ_ID_SPI3_TX - DMAMUX_DMAREQ_ID_SPI4_RX - DMAMUX_DMAREQ_ID_SPI4_TX - DMAMUX_DMAREQ_ID_I2S2_EXT_RX + * - DMAMUX_DMAREQ_ID_I2S2_EXT_TX - DMAMUX_DMAREQ_ID_I2S3_EXT_RX - DMAMUX_DMAREQ_ID_I2S3_EXT_TX - DMAMUX_DMAREQ_ID_I2C1_RX + * - DMAMUX_DMAREQ_ID_I2C1_TX - DMAMUX_DMAREQ_ID_I2C2_RX - DMAMUX_DMAREQ_ID_I2C2_TX - DMAMUX_DMAREQ_ID_I2C3_RX + * - DMAMUX_DMAREQ_ID_I2C3_TX - DMAMUX_DMAREQ_ID_USART1_RX - DMAMUX_DMAREQ_ID_USART1_TX - DMAMUX_DMAREQ_ID_USART2_RX + * - DMAMUX_DMAREQ_ID_USART2_TX - DMAMUX_DMAREQ_ID_USART3_RX - DMAMUX_DMAREQ_ID_USART3_TX - DMAMUX_DMAREQ_ID_UART4_RX + * - DMAMUX_DMAREQ_ID_UART4_TX - DMAMUX_DMAREQ_ID_UART5_RX - DMAMUX_DMAREQ_ID_UART5_TX - DMAMUX_DMAREQ_ID_USART6_RX + * - DMAMUX_DMAREQ_ID_USART6_TX - DMAMUX_DMAREQ_ID_UART7_RX - DMAMUX_DMAREQ_ID_UART7_TX - DMAMUX_DMAREQ_ID_UART8_RX + * - DMAMUX_DMAREQ_ID_UART8_TX - DMAMUX_DMAREQ_ID_SDIO1 - DMAMUX_DMAREQ_ID_SDIO2 - DMAMUX_DMAREQ_ID_QSPI1 + * - DMAMUX_DMAREQ_ID_QSPI2 - DMAMUX_DMAREQ_ID_TMR1_CH1 - DMAMUX_DMAREQ_ID_TMR1_CH2 - DMAMUX_DMAREQ_ID_TMR1_CH3 + * - DMAMUX_DMAREQ_ID_TMR1_CH4 - DMAMUX_DMAREQ_ID_TMR1_OVERFLOW- DMAMUX_DMAREQ_ID_TMR1_TRIG - DMAMUX_DMAREQ_ID_TMR1_COM + * - DMAMUX_DMAREQ_ID_TMR8_CH1 - DMAMUX_DMAREQ_ID_TMR8_CH2 - DMAMUX_DMAREQ_ID_TMR8_CH3 - DMAMUX_DMAREQ_ID_TMR8_CH4 + * - DMAMUX_DMAREQ_ID_TMR8_UP - DMAMUX_DMAREQ_ID_TMR8_TRIG - DMAMUX_DMAREQ_ID_TMR8_COM - DMAMUX_DMAREQ_ID_TMR2_CH1 + * - DMAMUX_DMAREQ_ID_TMR2_CH2 - DMAMUX_DMAREQ_ID_TMR2_CH3 - DMAMUX_DMAREQ_ID_TMR2_CH4 - DMAMUX_DMAREQ_ID_TMR2_OVERFLOW + * - DMAMUX_DMAREQ_ID_TMR2_TRIG - DMAMUX_DMAREQ_ID_TMR3_CH1 - DMAMUX_DMAREQ_ID_TMR3_CH2 - DMAMUX_DMAREQ_ID_TMR3_CH3 + * - DMAMUX_DMAREQ_ID_TMR3_CH4 - DMAMUX_DMAREQ_ID_TMR3_OVERFLOW- DMAMUX_DMAREQ_ID_TMR3_TRIG - DMAMUX_DMAREQ_ID_TMR4_CH1 + * - DMAMUX_DMAREQ_ID_TMR4_CH2 - DMAMUX_DMAREQ_ID_TMR4_CH3 - DMAMUX_DMAREQ_ID_TMR4_CH4 - DMAMUX_DMAREQ_ID_TMR4_OVERFLOW + * - DMAMUX_DMAREQ_ID_TMR4_TRIG - DMAMUX_DMAREQ_ID_TMR5_CH1 - DMAMUX_DMAREQ_ID_TMR5_CH2 - DMAMUX_DMAREQ_ID_TMR5_CH3 + * - DMAMUX_DMAREQ_ID_TMR5_CH4 - DMAMUX_DMAREQ_ID_TMR5_OVERFLOW- DMAMUX_DMAREQ_ID_TMR5_TRIG - DMAMUX_DMAREQ_ID_TMR20_CH1 + * - DMAMUX_DMAREQ_ID_TMR20_CH2 - DMAMUX_DMAREQ_ID_TMR20_CH3 - DMAMUX_DMAREQ_ID_TMR20_CH4 - DMAMUX_DMAREQ_ID_TMR20_OVERFLOW + * - DMAMUX_DMAREQ_ID_TMR20_TRIG - DMAMUX_DMAREQ_ID_TMR20_HALL - DMAMUX_DMAREQ_ID_DVP + * @retval none. + */ +void dmamux_init(dmamux_channel_type *dmamux_channelx, dmamux_requst_id_sel_type dmamux_req_sel) +{ + dmamux_channelx->muxctrl_bit.reqsel = dmamux_req_sel; +} + +/** + * @brief dmamux sync init struct config with its default value. + * @param dmamux_sync_init_struct: pointer to a dmamux_sync_init_type structure which will be initialized. + * @retval none. + */ +void dmamux_sync_default_para_init(dmamux_sync_init_type *dmamux_sync_init_struct) +{ + dmamux_sync_init_struct->sync_enable = FALSE; + dmamux_sync_init_struct->sync_event_enable = FALSE; + dmamux_sync_init_struct->sync_polarity = DMAMUX_SYNC_POLARITY_DISABLE; + dmamux_sync_init_struct->sync_request_number = 0x0; + dmamux_sync_init_struct->sync_signal_sel = (dmamux_sync_id_sel_type)0; +} + +/** + * @brief dmamux synchronization config. + * @param dmamux_channelx: + * this parameter can be one of the following values: + * - DMA1MUX_CHANNEL1 + * - DMA1MUX_CHANNEL2 + * - DMA1MUX_CHANNEL3 + * - DMA1MUX_CHANNEL4 + * - DMA1MUX_CHANNEL5 + * - DMA1MUX_CHANNEL6 + * - DMA1MUX_CHANNEL7 + * - DMA2MUX_CHANNEL1 + * - DMA2MUX_CHANNEL2 + * - DMA2MUX_CHANNEL3 + * - DMA2MUX_CHANNEL4 + * - DMA2MUX_CHANNEL5 + * - DMA2MUX_CHANNEL6 + * - DMA2MUX_CHANNEL7 + * @param dmamux_sync_init_struct: ointer to a dmamux_sync_init_type structure. + * @retval none. + */ +void dmamux_sync_config(dmamux_channel_type *dmamux_channelx, dmamux_sync_init_type *dmamux_sync_init_struct) +{ + dmamux_channelx->muxctrl_bit.syncsel = dmamux_sync_init_struct->sync_signal_sel; + dmamux_channelx->muxctrl_bit.syncpol = dmamux_sync_init_struct->sync_polarity; + dmamux_channelx->muxctrl_bit.reqcnt = dmamux_sync_init_struct->sync_request_number; + dmamux_channelx->muxctrl_bit.evtgen = dmamux_sync_init_struct->sync_event_enable; + dmamux_channelx->muxctrl_bit.syncen = dmamux_sync_init_struct->sync_enable; +} + +/** + * @brief dmamux request generator init struct config with its default value. + * @param dmamux_gen_init_struct: pointer to a dmamux_gen_init_type structure which will be initialized. + * @retval none. + */ +void dmamux_generator_default_para_init(dmamux_gen_init_type *dmamux_gen_init_struct) +{ + dmamux_gen_init_struct->gen_enable = FALSE; + dmamux_gen_init_struct->gen_polarity = DMAMUX_GEN_POLARITY_DISABLE; + dmamux_gen_init_struct->gen_request_number = 0x0; + dmamux_gen_init_struct->gen_signal_sel = (dmamux_gen_id_sel_type)0x0; +} + +/** + * @brief dmamux request generator init. + * @param dmamux_gen_x : + * this parameter can be one of the following values: + * - DMA1MUX_GENERATOR1 + * - DMA1MUX_GENERATOR2 + * - DMA1MUX_GENERATOR3 + * - DMA1MUX_GENERATOR4 + * - DMA2MUX_GENERATOR1 + * - DMA2MUX_GENERATOR2 + * - DMA2MUX_GENERATOR3 + * - DMA2MUX_GENERATOR4 + * @param dmamux_gen_init_struct: pointer to a dmamux_gen_init_type structure which will be initialized. + * @retval none. + */ +void dmamux_generator_config(dmamux_generator_type *dmamux_gen_x, dmamux_gen_init_type *dmamux_gen_init_struct) +{ + dmamux_gen_x->gctrl_bit.sigsel = dmamux_gen_init_struct->gen_signal_sel; + dmamux_gen_x->gctrl_bit.gpol = dmamux_gen_init_struct->gen_polarity; + dmamux_gen_x->gctrl_bit.greqcnt = dmamux_gen_init_struct->gen_request_number; + dmamux_gen_x->gctrl_bit.gen = dmamux_gen_init_struct->gen_enable; +} + +/** + * @brief enable or disable the dmamux sync interrupts. + * @param dmamux_channelx: + * this parameter can be one of the following values: + * - DMA1MUX_CHANNEL1 + * - DMA1MUX_CHANNEL2 + * - DMA1MUX_CHANNEL3 + * - DMA1MUX_CHANNEL4 + * - DMA1MUX_CHANNEL5 + * - DMA1MUX_CHANNEL6 + * - DMA1MUX_CHANNEL7 + * - DMA2MUX_CHANNEL1 + * - DMA2MUX_CHANNEL2 + * - DMA2MUX_CHANNEL3 + * - DMA2MUX_CHANNEL4 + * - DMA2MUX_CHANNEL5 + * - DMA2MUX_CHANNEL6 + * - DMA2MUX_CHANNEL7 + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void dmamux_sync_interrupt_enable(dmamux_channel_type *dmamux_channelx, confirm_state new_state) +{ + if(new_state != FALSE) + { + dmamux_channelx->muxctrl_bit.syncovien = TRUE; + } + else + { + dmamux_channelx->muxctrl_bit.syncovien = FALSE; + } +} + +/** + * @brief enable or disable the dmamux request generator interrupts. + * @param dmamux_gen_x : pointer to a dmamux_generator_type structure. + * this parameter can be one of the following values: + * - DMA1MUX_GENERATOR1 + * - DMA1MUX_GENERATOR2 + * - DMA1MUX_GENERATOR3 + * - DMA1MUX_GENERATOR4 + * - DMA2MUX_GENERATOR1 + * - DMA2MUX_GENERATOR2 + * - DMA2MUX_GENERATOR3 + * - DMA2MUX_GENERATOR4 + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void dmamux_generator_interrupt_enable(dmamux_generator_type *dmamux_gen_x, confirm_state new_state) +{ + if(new_state != FALSE) + { + dmamux_gen_x->gctrl_bit.trgovien = TRUE; + } + else + { + dmamux_gen_x->gctrl_bit.trgovien = FALSE; + } +} + +/** + * @brief dmamux sync flag get. + * @param dma_x : pointer to a dma_type structure, can be DMA1 or DMA2. + * @param flag + * this parameter can be any combination of the following values: + * - DMAMUX_SYNC_OV1_FLAG + * - DMAMUX_SYNC_OV2_FLAG + * - DMAMUX_SYNC_OV3_FLAG + * - DMAMUX_SYNC_OV4_FLAG + * - DMAMUX_SYNC_OV5_FLAG + * - DMAMUX_SYNC_OV6_FLAG + * - DMAMUX_SYNC_OV7_FLAG + * @retval state of dmamux sync flag. + */ +flag_status dmamux_sync_flag_get(dma_type *dma_x, uint32_t flag) +{ + if((dma_x->muxsyncsts & flag) != RESET) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief dmamux sync flag clear. + * @param dma_x : pointer to a dma_type structure, can be DMA1 or DMA2. + * @param flag + * this parameter can be any combination of the following values: + * - DMAMUX_SYNC_OV1_FLAG + * - DMAMUX_SYNC_OV2_FLAG + * - DMAMUX_SYNC_OV3_FLAG + * - DMAMUX_SYNC_OV4_FLAG + * - DMAMUX_SYNC_OV5_FLAG + * - DMAMUX_SYNC_OV6_FLAG + * - DMAMUX_SYNC_OV7_FLAG + * @retval none. + */ +void dmamux_sync_flag_clear(dma_type *dma_x, uint32_t flag) +{ + dma_x->muxsyncclr = flag; +} + +/** + * @brief dmamux request generator flag get. + * @param dma_x : pointer to a dma_type structure, can be DMA1 or DMA2. + * @param flag + * this parameter can be any combination of the following values: + * - DMAMUX_GEN_TRIG_OV1_FLAG + * - DMAMUX_GEN_TRIG_OV2_FLAG + * - DMAMUX_GEN_TRIG_OV3_FLAG + * - DMAMUX_GEN_TRIG_OV4_FLAG + * @retval state of dmamux sync flag. + */ +flag_status dmamux_generator_flag_get(dma_type *dma_x, uint32_t flag) +{ + if((dma_x->muxgsts & flag) != RESET) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief dmamux request generator flag clear. + * @param dma_x : pointer to a dma_type structure, can be DMA1 or DMA2. + * @param flag + * this parameter can be any combination of the following values: + * - DMAMUX_GEN_TRIG_OV1_FLAG + * - DMAMUX_GEN_TRIG_OV2_FLAG + * - DMAMUX_GEN_TRIG_OV3_FLAG + * - DMAMUX_GEN_TRIG_OV4_FLAG + * @retval none. + */ +void dmamux_generator_flag_clear(dma_type *dma_x, uint32_t flag) +{ + dma_x->muxgclr = flag; +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_dvp.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_dvp.c new file mode 100644 index 0000000000..53bc9b345a --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_dvp.c @@ -0,0 +1,528 @@ +/** + ************************************************************************** + * @file at32f435_437_dvp.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the dvp firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup DVP + * @brief DVP driver modules + * @{ + */ + +#ifdef DVP_MODULE_ENABLED + +/** @defgroup DVP_private_functions + * @{ + */ + +/** + * @brief reset the dvp register + * @param none + * @retval none + */ +void dvp_reset(void) +{ + crm_periph_reset(CRM_DVP_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_DVP_PERIPH_RESET, FALSE); +} + +/** + * @brief enable or disable dvp capture + * @param new_state (TRUE or FALSE) + * @retval none + */ +void dvp_capture_enable(confirm_state new_state) +{ + DVP->ctrl_bit.cap = new_state; +} + +/** + * @brief set dvp capture mode + * @param cap_mode + * this parameter can be one of the following values: + * - DVP_CAP_FUNC_MODE_CONTINUOUS + * - DVP_CAP_FUNC_MODE_SINGLE + * @retval none + */ +void dvp_capture_mode_set(dvp_cfm_type cap_mode) +{ + DVP->ctrl_bit.cfm = cap_mode; +} + +/** + * @brief set dvp cropping window enable + * @param new_state (TRUE or FALSE) + * @retval none + */ +void dvp_window_crop_enable(confirm_state new_state) +{ + DVP->ctrl_bit.crp = new_state; +} + +/** + * @brief set dvp cropping window configuration + * @param crop_x: cropping window horizontal start pixel + * @param crop_y: cropping window vertical start line + * @param crop_w: cropping window horizontal pixel number + * @param crop_h: cropping window vertical line number + * @param bytes: the number of bytes corresponding to one pixel + * eg. y8:bytes = 1, rgb565:bytes = 2 + * @retval none + */ +void dvp_window_crop_set(uint16_t crop_x, uint16_t crop_y, uint16_t crop_w, uint16_t crop_h, uint8_t bytes) +{ + DVP->cwst = ((crop_x * bytes) | (crop_y << 16)); + DVP->cwsz = ((crop_w * bytes - 1) | ((crop_h - 1) << 16)); +} + +/** + * @brief enable or disable dvp jpeg + * @param new_state (TRUE or FALSE) + * @retval none + */ +void dvp_jpeg_enable(confirm_state new_state) +{ + DVP->ctrl_bit.jpeg = new_state; +} + +/** + * @brief set dvp synchronization mode + * @param sync_mode + * this parameter can be one of the following values: + * - DVP_SYNC_MODE_HARDWARE + * - DVP_SYNC_MODE_EMBEDDED + * @retval none + */ +void dvp_sync_mode_set(dvp_sm_type sync_mode) +{ + DVP->ctrl_bit.sm = sync_mode; +} + +/** + * @brief set dvp synchronization code configuration + * @param fmsc(0x00~0xFF): frame start code + * @param fmec(0x00~0xFF): frame end code + * @param lnsc(0x00~0xFF): line start code + * @param lnec(0x00~0xFF): line end code + * @retval none + */ +void dvp_sync_code_set(uint8_t fmsc, uint8_t fmec, uint8_t lnsc, uint8_t lnec) +{ + DVP->scr = (fmsc | (lnsc << 8) | (lnec << 16) | (fmec << 24)); +} + +/** + * @brief set dvp synchronization unmask configuration + * @param fmsu(0x00~0xFF): frame start unmask + * @param fmeu(0x00~0xFF): frame end unmask + * @param lnsu(0x00~0xFF): line start unmask + * @param lneu(0x00~0xFF): line end unmask + * @retval none + */ +void dvp_sync_unmask_set(uint8_t fmsu, uint8_t fmeu, uint8_t lnsu, uint8_t lneu) +{ + DVP->sur = (fmsu | (lnsu << 8) | (lneu << 16) | (fmeu << 24)); +} + +/** + * @brief set dvp pixel clock polarity + * @param edge + * this parameter can be one of the following values: + * - DVP_CLK_POLARITY_RISING + * - DVP_CLK_POLARITY_FALLING + * @retval none + */ +void dvp_pclk_polarity_set(dvp_ckp_type edge) +{ + DVP->ctrl_bit.ckp = edge; +} + +/** + * @brief set dvp horizontal synchronization polarity + * @param hsync_pol + * this parameter can be one of the following values: + * - DVP_HSYNC_POLARITY_HIGH + * - DVP_HSYNC_POLARITY_LOW + * @retval none + */ +void dvp_hsync_polarity_set(dvp_hsp_type hsync_pol) +{ + DVP->ctrl_bit.hsp = hsync_pol; +} + +/** + * @brief set dvp vertical synchronization polarity + * @param vsync_pol + * this parameter can be one of the following values: + * - DVP_VSYNC_POLARITY_LOW + * - DVP_VSYNC_POLARITY_HIGH + * @retval none + */ +void dvp_vsync_polarity_set(dvp_vsp_type vsync_pol) +{ + DVP->ctrl_bit.vsp = vsync_pol; +} + +/** + * @brief config dvp basic frame rate control + * @note this function only work in continuous fire mode(ctrl_bit.cfm = 0) + * @param dvp_bfrc + * this parameter can be one of the following values: + * - DVP_BFRC_ALL + * - DVP_BFRC_HALF + * - DVP_BFRC_QUARTER + * @retval none + */ +void dvp_basic_frame_rate_control_set(dvp_bfrc_type dvp_bfrc) +{ + DVP->ctrl_bit.bfrc = dvp_bfrc; +} + +/** + * @brief config dvp pixel data length + * @param dvp_pdl + * this parameter can be one of the following values: + * - DVP_PIXEL_DATA_LENGTH_8 + * - DVP_PIXEL_DATA_LENGTH_10 + * - DVP_PIXEL_DATA_LENGTH_12 + * - DVP_PIXEL_DATA_LENGTH_14 + * @retval none + */ +void dvp_pixel_data_length_set(dvp_pdl_type dvp_pdl) +{ + DVP->ctrl_bit.pdl = dvp_pdl; +} + +/** + * @brief enable or disable dvp function + * @param new_state (TRUE or FALSE) + * @retval none + */ +void dvp_enable(confirm_state new_state) +{ + DVP->ctrl_bit.ena = new_state; +} + +/** + * @brief set dvp zoomout select + * @param dvp_pcdes: pixel capture/drop selection extension (Only work when pcdc = 2) + * this parameter can be one of the following values: + * - DVP_PCDES_CAP_FIRST + * - DVP_PCDES_DROP_FIRST + * @retval none + */ +void dvp_zoomout_select(dvp_pcdes_type dvp_pcdes) +{ + DVP->actrl_bit.pcdes = dvp_pcdes; +} + +/** + * @brief set dvp zoomout configuration + * @param dvp_pcdc: basic pixel capture/drop control + * this parameter can be one of the following values: + * - DVP_PCDC_ALL + * - DVP_PCDC_ONE_IN_TWO + * - DVP_PCDC_ONE_IN_FOUR + * - DVP_PCDC_TWO_IN_FOUR + * @param dvp_pcds: pixel capture/drop selection + * this parameter can be one of the following values: + * - DVP_PCDS_CAP_FIRST + * - DVP_PCDS_DROP_FIRST + * @param dvp_lcdc: line capture/drop control + * this parameter can be one of the following values: + * - DVP_LCDC_ALL + * - DVP_LCDC_ONE_IN_TWO + * @param dvp_lcds: line capture/drop selection + * this parameter can be one of the following values: + * - DVP_LCDS_CAP_FIRST + * - DVP_LCDS_DROP_FIRST + * @retval none + */ +void dvp_zoomout_set(dvp_pcdc_type dvp_pcdc, dvp_pcds_type dvp_pcds, dvp_lcdc_type dvp_lcdc, dvp_lcds_type dvp_lcds) +{ + DVP->ctrl_bit.pcdc = dvp_pcdc; + DVP->ctrl_bit.pcds = dvp_pcds; + DVP->ctrl_bit.lcdc = dvp_lcdc; + DVP->ctrl_bit.lcds = dvp_lcds; +} + +/** + * @brief get dvp basic status + * @param dvp_status_basic_type: + * this parameter can be one of the following values: + * - DVP_STATUS_HSYN + * - DVP_STATUS_VSYN + * - DVP_STATUS_OFNE + * @retval flag_status (SET or RESET) + */ +flag_status dvp_basic_status_get(dvp_status_basic_type dvp_status_basic) +{ + flag_status status = RESET; + + if ((DVP->sts & (0x1 << dvp_status_basic)) != (uint16_t)RESET) + { + status = SET; + } + else + { + status = RESET; + } + + return status; +} + +/** + * @brief enable or disable dvp interrupt + * @param dvp_int: + * this parameter can be any combination of the following values: + * - DVP_CFD_INT + * - DVP_OVR_INT + * - DVP_ESE_INT + * - DVP_VS_INT + * - DVP_HS_INT + * @param new_state (TRUE or FALSE) + * @retval none + */ +void dvp_interrupt_enable(uint32_t dvp_int, confirm_state new_state) +{ + if(new_state == TRUE) + { + DVP->ier |= dvp_int; + } + else + { + DVP->ier &= ~dvp_int; + } +} + +/** + * @brief get dvp event/interrupt flag status + * @param flag + * this parameter can be one of the following values: + * event flag: + * - DVP_CFD_EVT_FLAG + * - DVP_OVR_EVT_FLAG + * - DVP_ESE_EVT_FLAG + * - DVP_VS_EVT_FLAG + * - DVP_HS_EVT_FLAG + * interrupt flag: + * - DVP_CFD_INT_FLAG + * - DVP_OVR_INT_FLAG + * - DVP_ESE_INT_FLAG + * - DVP_VS_INT_FLAG + * - DVP_HS_INT_FLAG + * @retval flag_status (SET or RESET) + */ +flag_status dvp_flag_get(uint32_t flag) +{ + flag_status status = RESET; + if(flag & 0x80000000) + { + if((DVP->ists & flag) != RESET) + { + status = SET; + } + else + { + status = RESET; + } + } + else + { + if((DVP->ests & flag) != RESET) + { + status = SET; + } + else + { + status = RESET; + } + } + return status; +} + +/** + * @brief clear dvp's pending flags + * @param flag + * this parameter can be one of the following values: + * event flag: + * - DVP_CFD_EVT_FLAG + * - DVP_OVR_EVT_FLAG + * - DVP_ESE_EVT_FLAG + * - DVP_VS_EVT_FLAG + * - DVP_HS_EVT_FLAG + * interrupt flag: + * - DVP_CFD_INT_FLAG + * - DVP_OVR_INT_FLAG + * - DVP_ESE_INT_FLAG + * - DVP_VS_INT_FLAG + * - DVP_HS_INT_FLAG + * @retval none + */ +void dvp_flag_clear(uint32_t flag) +{ + flag &= ~0x80000000; + DVP->iclr = flag; +} + +/** + * @brief set dvp enhanced image scaling resize enable + * @param new_state (TRUE or FALSE) + * @retval none + */ +void dvp_enhanced_scaling_resize_enable(confirm_state new_state) +{ + DVP->actrl_bit.eisre = new_state; +} +/** + * @brief set dvp enhanced image scaling resize configuration + * @param src_w(0x0001~0x1FFF): horizontal scaling resize source size (source image width) + * @param des_w(0x0001~0x1FFF): horizontal scaling resize target size (target image width) + * @param src_h(0x0001~0x1FFF): vertical scaling resize source size (source image height) + * @param des_h(0x0001~0x1FFF): vertical scaling resize target size (target image height) + * @retval none + */ +void dvp_enhanced_scaling_resize_set(uint16_t src_w, uint16_t des_w, uint16_t src_h, uint16_t des_h) +{ + if((!DVP->ctrl_bit.pcdc) && (!DVP->ctrl_bit.lcdc) && DVP->actrl_bit.efdf) + { + DVP->hscf = (src_w | (des_w << 16)); + DVP->vscf = (src_h | (des_h << 16)); + } +} + +/** + * @brief set enhanced frame rate control configuration + * @param efrcsf(0x00~0x1F): original frame rate contorl factor + * @param efrctf(0x00~0x1F): enhanced frame rate contorl factor + * @param new_state (TRUE or FALSE) + * @retval none + */ +void dvp_enhanced_framerate_set(uint16_t efrcsf, uint16_t efrctf, confirm_state new_state) +{ + if((!DVP->ctrl_bit.cfm) && (!DVP->ctrl_bit.bfrc) && (efrctf <= efrcsf)) + { + DVP->frf = (efrcsf | (efrctf << 8)); + } + + DVP->actrl_bit.efrce = new_state; +} + +/** + * @brief set dvp monochrome image binarization configuration + * @param mibthd(0x00~0xFF): monochrome image binarization threshold + * @param new_state: (TRUE or FALSE) + * @retval none + */ +void dvp_monochrome_image_binarization_set(uint8_t mibthd, confirm_state new_state) +{ + DVP->bth_bit.mibthd = mibthd; + DVP->actrl_bit.mibe = new_state; +} + +/** + * @brief set dvp enhanced function data format configuration + * @param dvp_efdf: enhanced function data format + * this parameter can be one of the following values: + * - DVP_EFDF_BYPASS + * - DVP_EFDF_YUV422_UYVY + * - DVP_EFDF_YUV422_YUYV + * - DVP_EFDF_RGB565_555 + * - DVP_EFDF_Y8 + * @retval none + */ +void dvp_enhanced_data_format_set(dvp_efdf_type dvp_efdf) +{ + DVP->actrl_bit.efdf = dvp_efdf; +} + +/** + * @brief set dvp input data un-used condition/number configuration + * @param dvp_idus: input data un-used condition + * this parameter can be one of the following values: + * - DVP_IDUS_MSB + * - DVP_IDUS_LSB + * @param dvp_idun: input data un-used number + * this parameter can be one of the following values: + * - DVP_IDUN_0 + * - DVP_IDUN_2 + * - DVP_IDUN_4 + * - DVP_IDUN_6 + * @retval none + */ +void dvp_input_data_unused_set(dvp_idus_type dvp_idus, dvp_idun_type dvp_idun) +{ + DVP->actrl_bit.idus = dvp_idus; + DVP->actrl_bit.idun = dvp_idun; +} + +/** + * @brief set dvp dma burst transfer configuration + * @param dvp_dmabt: dma burst transfer configuration + * this parameter can be one of the following values: + * - DVP_DMABT_SINGLE + * - DVP_DMABT_BURST + * @retval none + */ +void dvp_dma_burst_set(dvp_dmabt_type dvp_dmabt) +{ + DVP->actrl_bit.dmabt = dvp_dmabt; +} + +/** + * @brief set dvp hsync/vsync event interrupt strategy configuration + * @param dvp_hseid: hsync event interrupt strategy + * this parameter can be one of the following values: + * - DVP_HSEID_LINE_END + * - DVP_HSEID_LINE_START + * @param dvp_vseid: vsync event interrupt strategy + * this parameter can be one of the following values: + * - DVP_VSEID_FRAME_END + * - DVP_VSEID_FRMAE_START + * @retval none + */ +void dvp_sync_event_interrupt_set(dvp_hseid_type dvp_hseid, dvp_vseid_type dvp_vseid) +{ + DVP->actrl_bit.hseid = dvp_hseid; + DVP->actrl_bit.vseid = dvp_vseid; +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_edma.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_edma.c new file mode 100644 index 0000000000..88eb5c03e7 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_edma.c @@ -0,0 +1,931 @@ +/** + ************************************************************************** + * @file at32f435_437_edma.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the edma firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup EDMA + * @brief EDMA driver modules + * @{ + */ + +#ifdef EDMA_MODULE_ENABLED + +/** @defgroup EDMA_private_functions + * @{ + */ + +/** + * @brief reset edma_streamx channely register. + * @param edma_streamx: + * this parameter can be one of the following values: + * - EDMA_STREAM1 + * - EDMA_STREAM2 + * - EDMA_STREAM3 + * - EDMA_STREAM4 + * - EDMA_STREAM5 + * - EDMA_STREAM6 + * - EDMA_STREAM7 + * - EDMA_STREAM8 + * @retval none. + */ +void edma_reset(edma_stream_type *edma_streamx) +{ + /* reset registers for the selected stream */ + edma_streamx->ctrl_bit.sen = FALSE; + edma_streamx->ctrl = 0x0; + edma_streamx->dtcnt = 0x0; + edma_streamx->paddr = 0x0; + edma_streamx->m0addr = 0x0; + edma_streamx->m1addr = 0x0; + edma_streamx->fctrl = (uint32_t)0x00000021; + + /* reset interrupt pending bits for the selected stream */ + switch((uint32_t)edma_streamx) + { + case EDMA_STREAM1_BASE: + EDMA->clr1 = EDMA_STREAM1_INT_MASK; + break; + case EDMA_STREAM2_BASE: + EDMA->clr1 = EDMA_STREAM2_INT_MASK; + break; + case EDMA_STREAM3_BASE: + EDMA->clr1 = EDMA_STREAM3_INT_MASK; + break; + case EDMA_STREAM4_BASE: + EDMA->clr1 = EDMA_STREAM4_INT_MASK; + break; + case EDMA_STREAM5_BASE: + EDMA->clr2 = EDMA_STREAM5_INT_MASK; + break; + case EDMA_STREAM6_BASE: + EDMA->clr2 = EDMA_STREAM6_INT_MASK; + break; + case EDMA_STREAM7_BASE: + EDMA->clr2 = EDMA_STREAM7_INT_MASK; + break; + case EDMA_STREAM8_BASE: + EDMA->clr2 = EDMA_STREAM8_INT_MASK; + break; + default: break; + } +} + +/** + * @brief edma init. + * @param edma_streamx: + * this parameter can be one of the following values: + * - EDMA_STREAM1 + * - EDMA_STREAM2 + * - EDMA_STREAM3 + * - EDMA_STREAM4 + * - EDMA_STREAM5 + * - EDMA_STREAM6 + * - EDMA_STREAM7 + * - EDMA_STREAM8 + * @param edma_init_struct: pointer to a edma_init_type structure. + * @retval none. + */ +void edma_init(edma_stream_type *edma_streamx, edma_init_type *edma_init_struct) +{ + /* config dtd bits */ + edma_streamx->ctrl_bit.dtd = edma_init_struct->direction; + + /* config pincm bit */ + edma_streamx->ctrl_bit.pincm = edma_init_struct->peripheral_inc_enable; + + /* config mincm bit*/ + edma_streamx->ctrl_bit.mincm = edma_init_struct->memory_inc_enable; + + /* config pwidth bits */ + edma_streamx->ctrl_bit.pwidth = edma_init_struct->peripheral_data_width; + + /* config mwidth bits */ + edma_streamx->ctrl_bit.mwidth = edma_init_struct->memory_data_width; + + /* config lm bit */ + edma_streamx->ctrl_bit.lm = edma_init_struct->loop_mode_enable; + + /* config spl bits */ + edma_streamx->ctrl_bit.spl = edma_init_struct->priority; + + /* config mct bits */ + edma_streamx->ctrl_bit.mct = edma_init_struct->memory_burst_mode; + + /* config pct bits */ + edma_streamx->ctrl_bit.pct = edma_init_struct->peripheral_burst_mode; + + /* config fen bits */ + edma_streamx->fctrl_bit.fen = edma_init_struct->fifo_mode_enable; + + /* config fthsel bits*/ + edma_streamx->fctrl_bit.fthsel = edma_init_struct->fifo_threshold; + + /* config dtcnt */ + edma_streamx->dtcnt = edma_init_struct->buffer_size; + + /* config paddr */ + edma_streamx->paddr = edma_init_struct->peripheral_base_addr; + + /* config m0addr */ + edma_streamx->m0addr = edma_init_struct->memory0_base_addr; +} + +/** + * @brief edma init struct config with its default value. + * @param edma_init_struct: pointer to a edma_init_type structure which will be initialized. + * @retval none. + */ +void edma_default_para_init(edma_init_type *edma_init_struct) +{ + edma_init_struct->buffer_size = 0; + edma_init_struct->loop_mode_enable = FALSE; + edma_init_struct->direction = EDMA_DIR_PERIPHERAL_TO_MEMORY; + edma_init_struct->fifo_threshold = EDMA_FIFO_THRESHOLD_1QUARTER; + edma_init_struct->fifo_mode_enable = FALSE; + edma_init_struct->memory0_base_addr = 0; + edma_init_struct->memory_burst_mode = EDMA_MEMORY_SINGLE; + edma_init_struct->memory_data_width = EDMA_MEMORY_DATA_WIDTH_BYTE; + edma_init_struct->memory_inc_enable = FALSE; + edma_init_struct->peripheral_base_addr = 0; + edma_init_struct->peripheral_burst_mode = EDMA_PERIPHERAL_SINGLE; + edma_init_struct->peripheral_data_width = EDMA_PERIPHERAL_DATA_WIDTH_BYTE; + edma_init_struct->peripheral_inc_enable = FALSE; + edma_init_struct->priority = EDMA_PRIORITY_LOW; +} + +/** + * @brief enable or disable the edma streamx. + * @param edma_streamx: + * this parameter can be one of the following values: + * - EDMA_STREAM1 + * - EDMA_STREAM2 + * - EDMA_STREAM3 + * - EDMA_STREAM4 + * - EDMA_STREAM5 + * - EDMA_STREAM6 + * - EDMA_STREAM7 + * - EDMA_STREAM8 + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void edma_stream_enable(edma_stream_type *edma_streamx, confirm_state new_state) +{ + edma_streamx->ctrl_bit.sen = new_state; +} + +/** + * @brief enable or disable the edma streamx interrupts. + * @param edma_streamx: + * this parameter can be one of the following values: + * - EDMA_STREAM1 + * - EDMA_STREAM2 + * - EDMA_STREAM3 + * - EDMA_STREAM4 + * - EDMA_STREAM5 + * - EDMA_STREAM6 + * - EDMA_STREAM7 + * - EDMA_STREAM8 + * @param edma_int: + * this parameter can be one of the following values: + * - EDMA_FDT_INT + * - EDMA_HDT_INT + * - EDMA_DTERR_INT + * - EDMA_DMERR_INT + * - EDMA_FERR_INT + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void edma_interrupt_enable(edma_stream_type *edma_streamx, uint32_t edma_int, confirm_state new_state) +{ + if((edma_int & EDMA_FERR_INT) != 0) + { + if(new_state != FALSE) + { + edma_streamx->fctrl |= (uint32_t)EDMA_FERR_INT; + } + else + { + edma_streamx->fctrl &= ~(uint32_t)EDMA_FERR_INT; + } + } + + if(edma_int != EDMA_FERR_INT) + { + if(new_state != FALSE) + { + edma_streamx->ctrl |= (uint32_t)edma_int; + } + else + { + edma_streamx->ctrl &= ~(uint32_t)edma_int; + } + } +} + +/** + * @brief config the edma peripheral increment offset size mode. + * @param edma_streamx: + * this parameter can be one of the following values: + * - EDMA_STREAM1 + * - EDMA_STREAM2 + * - EDMA_STREAM3 + * - EDMA_STREAM4 + * - EDMA_STREAM5 + * - EDMA_STREAM6 + * - EDMA_STREAM7 + * - EDMA_STREAM8 + * @param offset: peripheral increment offset size. + * this parameter can be one of the following values: + * - EDMA_PERIPHERAL_INC_PSIZE + * - EDMA_PERIPHERAL_INC_4_BYTE + * @retval none. + */ +void edma_peripheral_inc_offset_set(edma_stream_type *edma_streamx, edma_peripheral_inc_offset_type offset) +{ + edma_streamx->ctrl_bit.pincos = offset; +} + +/** + * @brief enable or disable the edma streamx flow controller. + * @param edma_streamx: + * this parameter can be one of the following values: + * - EDMA_STREAM1 + * - EDMA_STREAM2 + * - EDMA_STREAM3 + * - EDMA_STREAM4 + * - EDMA_STREAM5 + * - EDMA_STREAM6 + * - EDMA_STREAM7 + * - EDMA_STREAM8 + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void edma_flow_controller_enable(edma_stream_type *edma_streamx, confirm_state new_state) +{ + edma_streamx->ctrl_bit.pfctrl = new_state; +} + +/** + * @brief set the number of data to be transferred. + * @param edma_streamx: + * this parameter can be one of the following values: + * - EDMA_STREAM1 + * - EDMA_STREAM2 + * - EDMA_STREAM3 + * - EDMA_STREAM4 + * - EDMA_STREAM5 + * - EDMA_STREAM6 + * - EDMA_STREAM7 + * - EDMA_STREAM8 + * @param data_number: the number of data to be transferred (0x0000~0xFFFF). + * @retval none. + */ +void edma_data_number_set(edma_stream_type *edma_streamx, uint16_t data_number) +{ + /* write the number of data units to be transferred */ + edma_streamx->dtcnt = data_number; +} + +/** + * @brief get the number of data to be transferred. + * @param edma_streamx: + * this parameter can be one of the following values: + * - EDMA_STREAM1 + * - EDMA_STREAM2 + * - EDMA_STREAM3 + * - EDMA_STREAM4 + * - EDMA_STREAM5 + * - EDMA_STREAM6 + * - EDMA_STREAM7 + * - EDMA_STREAM8 + * @retval the number value. + */ +uint16_t edma_data_number_get(edma_stream_type *edma_streamx) +{ + return ((uint16_t)(edma_streamx->dtcnt)); +} + +/** + * @brief config the the double buffer mode. + * @param edma_streamx: + * this parameter can be one of the following values: + * - EDMA_STREAM1 + * - EDMA_STREAM2 + * - EDMA_STREAM3 + * - EDMA_STREAM4 + * - EDMA_STREAM5 + * - EDMA_STREAM6 + * - EDMA_STREAM7 + * - EDMA_STREAM8 + * @param memory1_addr: the address of the second buffer. + * @param current_memory: specifies the target area of the first transfer. + * this parameter can be one of the following values: + * - EDMA_MEMORY_0 + * - EDMA_MEMORY_1 + * @retval none. + */ +void edma_double_buffer_mode_init(edma_stream_type *edma_streamx, uint32_t memory1_addr, edma_memory_type current_memory) +{ + if(current_memory != EDMA_MEMORY_0) + { + edma_streamx->ctrl_bit.cm = 1; + } + else + { + edma_streamx->ctrl_bit.cm = 0; + } + + edma_streamx->m1addr = memory1_addr; +} + +/** + * @brief enable or disable the double memory mode. + * @param edma_streamx: + * this parameter can be one of the following values: + * - EDMA_STREAM1 + * - EDMA_STREAM2 + * - EDMA_STREAM3 + * - EDMA_STREAM4 + * - EDMA_STREAM5 + * - EDMA_STREAM6 + * - EDMA_STREAM7 + * - EDMA_STREAM8 + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void edma_double_buffer_mode_enable(edma_stream_type *edma_streamx, confirm_state new_state) +{ + if(new_state != FALSE) + { + edma_streamx->ctrl_bit.dmm = 1; + } + else + { + edma_streamx->ctrl_bit.dmm = 0; + } +} + +/** + * @brief config the memory address in double buffer mode. + * @param edma_streamx: + * this parameter can be one of the following values: + * - EDMA_STREAM1 + * - EDMA_STREAM2 + * - EDMA_STREAM3 + * - EDMA_STREAM4 + * - EDMA_STREAM5 + * - EDMA_STREAM6 + * - EDMA_STREAM7 + * - EDMA_STREAM8 + * @param memory_addr: the address of the buffer. + * @param memory_target: indicates the which memory addr register will be config. + * this parameter can be one of the following values: + * - EDMA_MEMORY_0 + * - EDMA_MEMORY_1 + * @retval none. + */ +void edma_memory_addr_set(edma_stream_type *edma_streamx, uint32_t memory_addr, uint32_t memory_target) +{ + if(memory_target != EDMA_MEMORY_0) + { + edma_streamx->m1addr = memory_addr; + } + else + { + edma_streamx->m0addr = memory_addr; + } +} + +/** + * @brief get the current memory target. + * @param edma_streamx: + * this parameter can be one of the following values: + * - EDMA_STREAM1 + * - EDMA_STREAM2 + * - EDMA_STREAM3 + * - EDMA_STREAM4 + * - EDMA_STREAM5 + * - EDMA_STREAM6 + * - EDMA_STREAM7 + * - EDMA_STREAM8 + * @retval the memory target + * - EDMA_MEMORY_0 + * - EDMA_MEMORY_1 + */ +edma_memory_type edma_memory_target_get(edma_stream_type *edma_streamx) +{ + return (edma_memory_type)(edma_streamx->ctrl_bit.cm); +} + +/** + * @brief get the enable status of edma streamx. + * @param edma_streamx: + * this parameter can be one of the following values: + * - EDMA_STREAM1 + * - EDMA_STREAM2 + * - EDMA_STREAM3 + * - EDMA_STREAM4 + * - EDMA_STREAM5 + * - EDMA_STREAM6 + * - EDMA_STREAM7 + * - EDMA_STREAM8 + * @retval current state of the edma streamx (SET or RESET). + */ +flag_status edma_stream_status_get(edma_stream_type *edma_streamx) +{ + if((edma_streamx->ctrl_bit.sen) != RESET) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief get the fifo level status. + * @param edma_streamx: + * this parameter can be one of the following values: + * - EDMA_STREAM1 + * - EDMA_STREAM2 + * - EDMA_STREAM3 + * - EDMA_STREAM4 + * - EDMA_STREAM5 + * - EDMA_STREAM6 + * - EDMA_STREAM7 + * - EDMA_STREAM8 + * @retval the fifo filling state. + * - EDMA_FIFO_STATUS_LESS_1QUARTER: (0) < fifo level < (1/4). + * - EDMA_FIFO_STATUS_1QUARTER: (1/4) <= fifo level < (1/2) . + * - EDMA_FIFO_STATUS_HALF: (1/2) <= fifo level < (3/4). + * - EDMA_FIFO_STATUS_3QUARTER: (3/4) <= fifo level < (1). + * - EDMA_FIFO_STATUS_EMPTY: fifo is empty. + * - EDMA_FIFO_STATUS_FULL: fifo is full. + */ +uint8_t edma_fifo_status_get(edma_stream_type *edma_streamx) +{ + return (uint8_t)(edma_streamx->fctrl_bit.fsts); +} + +/** + * @brief get the edma flag. + * @param edma_flag: + * this parameter can be one of the following values: + * - EDMA_FERR1_FLAG - EDMA_DMERR1_FLAG - EDMA_DTERR1_FLAG - EDMA_HDT1_FLAG - EDMA_FDT1_FLAG + * - EDMA_FERR2_FLAG - EDMA_DMERR2_FLAG - EDMA_DTERR2_FLAG - EDMA_HDT2_FLAG - EDMA_FDT2_FLAG + * - EDMA_FERR3_FLAG - EDMA_DMERR3_FLAG - EDMA_DTERR3_FLAG - EDMA_HDT3_FLAG - EDMA_FDT3_FLAG + * - EDMA_FERR4_FLAG - EDMA_DMERR4_FLAG - EDMA_DTERR4_FLAG - EDMA_HDT4_FLAG - EDMA_FDT4_FLAG + * - EDMA_FERR5_FLAG - EDMA_DMERR5_FLAG - EDMA_DTERR5_FLAG - EDMA_HDT5_FLAG - EDMA_FDT5_FLAG + * - EDMA_FERR6_FLAG - EDMA_DMERR6_FLAG - EDMA_DTERR6_FLAG - EDMA_HDT6_FLAG - EDMA_FDT6_FLAG + * - EDMA_FERR7_FLAG - EDMA_DMERR7_FLAG - EDMA_DTERR7_FLAG - EDMA_HDT7_FLAG - EDMA_FDT7_FLAG + * - EDMA_FERR8_FLAG - EDMA_DMERR8_FLAG - EDMA_DTERR8_FLAG - EDMA_HDT8_FLAG - EDMA_FDT8_FLAG + * @retval the new state of edma flag (SET or RESET). + */ +flag_status edma_flag_get(uint32_t edma_flag) +{ + uint32_t status; + + if(edma_flag > ((uint32_t)0x20000000)) + { + status = EDMA->sts2; + } + else + { + status = EDMA->sts1; + } + + if((status & edma_flag) != ((uint32_t)RESET)) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief clear the edma flag. + * @param edma_flag: + * this parameter can be one of the following values: + * - EDMA_FERR1_FLAG - EDMA_DMERR1_FLAG - EDMA_DTERR1_FLAG - EDMA_HDT1_FLAG - EDMA_FDT1_FLAG + * - EDMA_FERR2_FLAG - EDMA_DMERR2_FLAG - EDMA_DTERR2_FLAG - EDMA_HDT2_FLAG - EDMA_FDT2_FLAG + * - EDMA_FERR3_FLAG - EDMA_DMERR3_FLAG - EDMA_DTERR3_FLAG - EDMA_HDT3_FLAG - EDMA_FDT3_FLAG + * - EDMA_FERR4_FLAG - EDMA_DMERR4_FLAG - EDMA_DTERR4_FLAG - EDMA_HDT4_FLAG - EDMA_FDT4_FLAG + * - EDMA_FERR5_FLAG - EDMA_DMERR5_FLAG - EDMA_DTERR5_FLAG - EDMA_HDT5_FLAG - EDMA_FDT5_FLAG + * - EDMA_FERR6_FLAG - EDMA_DMERR6_FLAG - EDMA_DTERR6_FLAG - EDMA_HDT6_FLAG - EDMA_FDT6_FLAG + * - EDMA_FERR7_FLAG - EDMA_DMERR7_FLAG - EDMA_DTERR7_FLAG - EDMA_HDT7_FLAG - EDMA_FDT7_FLAG + * - EDMA_FERR8_FLAG - EDMA_DMERR8_FLAG - EDMA_DTERR8_FLAG - EDMA_HDT8_FLAG - EDMA_FDT8_FLAG + * @retval none. + */ +void edma_flag_clear(uint32_t edma_flag) +{ + if(edma_flag > ((uint32_t)0x20000000)) + { + EDMA->clr2 = (uint32_t)(edma_flag & 0x0FFFFFFF); + } + else + { + EDMA->clr1 = edma_flag; + } +} + +/** + * @brief initialize the edma 2d mode. + * @param edma_streamx_2d: + * this parameter can be one of the following values: + * - EDMA_STREAM1_2D + * - EDMA_STREAM2_2D + * - EDMA_STREAM3_2D + * - EDMA_STREAM4_2D + * - EDMA_STREAM5_2D + * - EDMA_STREAM6_2D + * - EDMA_STREAM7_2D + * - EDMA_STREAM8_2D + * @param src_stride: source stride(-32768 ~ 32767). + * @param dst_stride: destination stride(-32768 ~ 32767). + * @param xcnt: x dimension transfer count(0x0000~ 0xFFFF). + * @param ycnt: y dimension transfer count(0x0000~ 0xFFFF). + * @retval none. + */ +void edma_2d_init(edma_stream_2d_type *edma_streamx_2d, int16_t src_stride, int16_t dst_stride, uint16_t xcnt, uint16_t ycnt) +{ + edma_streamx_2d->s2dcnt = (uint32_t)((ycnt << 16) | (xcnt)); + + edma_streamx_2d->stride = (uint32_t)((dst_stride << 16) | (src_stride)); +} + +/** + * @brief enable or disable the edma 2d mode. + * @param edma_streamx_2d: + * this parameter can be one of the following values: + * - EDMA_STREAM1_2D + * - EDMA_STREAM2_2D + * - EDMA_STREAM3_2D + * - EDMA_STREAM4_2D + * - EDMA_STREAM5_2D + * - EDMA_STREAM6_2D + * - EDMA_STREAM7_2D + * - EDMA_STREAM8_2D + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void edma_2d_enable(edma_stream_2d_type *edma_streamx_2d, confirm_state new_state) +{ + uint32_t offset; + + offset = ((uint32_t)edma_streamx_2d - EDMA_STREAM1_2D_BASE) / 4; + + if(new_state != FALSE) + { + EDMA->s2dctrl |= (uint16_t)0x0001 << offset; + } + else + { + EDMA->s2dctrl &= ~((uint16_t)0x0001 << offset); + } +} + +/** + * @brief initialize the edma link list. + * @param edma_streamx_ll: + * this parameter can be one of the following values: + * - EDMA_STREAM1_LL + * - EDMA_STREAM2_LL + * - EDMA_STREAM3_LL + * - EDMA_STREAM4_LL + * - EDMA_STREAM5_LL + * - EDMA_STREAM6_LL + * - EDMA_STREAM7_LL + * - EDMA_STREAM8_LL + * @param pointer: link list pointer. + * @retval none. + */ +void edma_link_list_init(edma_stream_link_list_type *edma_streamx_ll, uint32_t pointer) +{ + edma_streamx_ll->llp = pointer; +} + +/** + * @brief enable or disable the edma stream link list mode. + * @param edma_streamx_ll: + * this parameter can be any combination of the following values: + * - EDMA_STREAM1_LL + * - EDMA_STREAM2_LL + * - EDMA_STREAM3_LL + * - EDMA_STREAM4_LL + * - EDMA_STREAM5_LL + * - EDMA_STREAM6_LL + * - EDMA_STREAM7_LL + * - EDMA_STREAM8_LL + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void edma_link_list_enable(edma_stream_link_list_type *edma_streamx_ll, confirm_state new_state) +{ + uint32_t offset; + + offset = ((uint32_t)edma_streamx_ll - EDMA_STREAM1_LL_BASE) / 4; + + if(new_state != FALSE) + { + EDMA->llctrl |= (uint16_t)0x0001 << offset; + } + else + { + EDMA->llctrl &= ~((uint16_t)0x0001 << offset); + } +} + +/** + * @brief enable or disable the edma edmamux. + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void edmamux_enable(confirm_state new_state) +{ + EDMA->muxsel_bit.tblsel = new_state; +} + +/** + * @brief edmamux init. + * @param edmamux_channelx: + * this parameter can be one of the following values: + * - EDMAMUX_CHANNEL1 + * - EDMAMUX_CHANNEL2 + * - EDMAMUX_CHANNEL3 + * - EDMAMUX_CHANNEL4 + * - EDMAMUX_CHANNEL5 + * - EDMAMUX_CHANNEL6 + * - EDMAMUX_CHANNEL7 + * - EDMAMUX_CHANNEL8 + * @param edmamux_req_id: + * this parameter can be one of the following values: + * - EDMAMUX_DMAREQ_ID_REQ_G1 - EDMAMUX_DMAREQ_ID_REQ_G2 - EDMAMUX_DMAREQ_ID_REQ_G3 - EDMAMUX_DMAREQ_ID_REQ_G4 + * - EDMAMUX_DMAREQ_ID_ADC1 - EDMAMUX_DMAREQ_ID_ADC2 - EDMAMUX_DMAREQ_ID_ADC3 - EDMAMUX_DMAREQ_ID_DAC1 + * - EDMAMUX_DMAREQ_ID_DAC2 - EDMAMUX_DMAREQ_ID_TMR6_OVERFLOW- EDMAMUX_DMAREQ_ID_TMR7_OVERFLOW- EDMAMUX_DMAREQ_ID_SPI1_RX + * - EDMAMUX_DMAREQ_ID_SPI1_TX - EDMAMUX_DMAREQ_ID_SPI2_RX - EDMAMUX_DMAREQ_ID_SPI2_TX - EDMAMUX_DMAREQ_ID_SPI3_RX + * - EDMAMUX_DMAREQ_ID_SPI3_TX - EDMAMUX_DMAREQ_ID_SPI4_RX - EDMAMUX_DMAREQ_ID_SPI4_TX - EDMAMUX_DMAREQ_ID_I2S2_EXT_RX + * - EDMAMUX_DMAREQ_ID_I2S2_EXT_TX - EDMAMUX_DMAREQ_ID_I2S3_EXT_RX - EDMAMUX_DMAREQ_ID_I2S3_EXT_TX - EDMAMUX_DMAREQ_ID_I2C1_RX + * - EDMAMUX_DMAREQ_ID_I2C1_TX - EDMAMUX_DMAREQ_ID_I2C2_RX - EDMAMUX_DMAREQ_ID_I2C2_TX - EDMAMUX_DMAREQ_ID_I2C3_RX + * - EDMAMUX_DMAREQ_ID_I2C3_TX - EDMAMUX_DMAREQ_ID_USART1_RX - EDMAMUX_DMAREQ_ID_USART1_TX - EDMAMUX_DMAREQ_ID_USART2_RX + * - EDMAMUX_DMAREQ_ID_USART2_TX - EDMAMUX_DMAREQ_ID_USART3_RX - EDMAMUX_DMAREQ_ID_USART3_TX - EDMAMUX_DMAREQ_ID_UART4_RX + * - EDMAMUX_DMAREQ_ID_UART4_TX - EDMAMUX_DMAREQ_ID_UART5_RX - EDMAMUX_DMAREQ_ID_UART5_TX - EDMAMUX_DMAREQ_ID_USART6_RX + * - EDMAMUX_DMAREQ_ID_USART6_TX - EDMAMUX_DMAREQ_ID_UART7_RX - EDMAMUX_DMAREQ_ID_UART7_TX - EDMAMUX_DMAREQ_ID_UART8_RX + * - EDMAMUX_DMAREQ_ID_UART8_TX - EDMAMUX_DMAREQ_ID_SDIO1 - EDMAMUX_DMAREQ_ID_SDIO2 - EDMAMUX_DMAREQ_ID_QSPI1 + * - EDMAMUX_DMAREQ_ID_QSPI2 - EDMAMUX_DMAREQ_ID_TMR1_CH1 - EDMAMUX_DMAREQ_ID_TMR1_CH2 - EDMAMUX_DMAREQ_ID_TMR1_CH3 + * - EDMAMUX_DMAREQ_ID_TMR1_CH4 - EDMAMUX_DMAREQ_ID_TMR1_OVERFLOW- EDMAMUX_DMAREQ_ID_TMR1_TRIG - EDMAMUX_DMAREQ_ID_TMR1_COM + * - EDMAMUX_DMAREQ_ID_TMR8_CH1 - EDMAMUX_DMAREQ_ID_TMR8_CH2 - EDMAMUX_DMAREQ_ID_TMR8_CH3 - EDMAMUX_DMAREQ_ID_TMR8_CH4 + * - EDMAMUX_DMAREQ_ID_TMR8_UP - EDMAMUX_DMAREQ_ID_TMR8_TRIG - EDMAMUX_DMAREQ_ID_TMR8_COM - EDMAMUX_DMAREQ_ID_TMR2_CH1 + * - EDMAMUX_DMAREQ_ID_TMR2_CH2 - EDMAMUX_DMAREQ_ID_TMR2_CH3 - EDMAMUX_DMAREQ_ID_TMR2_CH4 - EDMAMUX_DMAREQ_ID_TMR2_OVERFLOW + * - EDMAMUX_DMAREQ_ID_TMR2_TRIG - EDMAMUX_DMAREQ_ID_TMR3_CH1 - EDMAMUX_DMAREQ_ID_TMR3_CH2 - EDMAMUX_DMAREQ_ID_TMR3_CH3 + * - EDMAMUX_DMAREQ_ID_TMR3_CH4 - EDMAMUX_DMAREQ_ID_TMR3_OVERFLOW- EDMAMUX_DMAREQ_ID_TMR3_TRIG - EDMAMUX_DMAREQ_ID_TMR4_CH1 + * - EDMAMUX_DMAREQ_ID_TMR4_CH2 - EDMAMUX_DMAREQ_ID_TMR4_CH3 - EDMAMUX_DMAREQ_ID_TMR4_CH4 - EDMAMUX_DMAREQ_ID_TMR4_OVERFLOW + * - EDMAMUX_DMAREQ_ID_TMR4_TRIG - EDMAMUX_DMAREQ_ID_TMR5_CH1 - EDMAMUX_DMAREQ_ID_TMR5_CH2 - EDMAMUX_DMAREQ_ID_TMR5_CH3 + * - EDMAMUX_DMAREQ_ID_TMR5_CH4 - EDMAMUX_DMAREQ_ID_TMR5_OVERFLOW- EDMAMUX_DMAREQ_ID_TMR5_TRIG - EDMAMUX_DMAREQ_ID_TMR20_CH1 + * - EDMAMUX_DMAREQ_ID_TMR20_CH2 - EDMAMUX_DMAREQ_ID_TMR20_CH3 - EDMAMUX_DMAREQ_ID_TMR20_CH4 - EDMAMUX_DMAREQ_ID_TMR20_OVERFLOW + * - EDMAMUX_DMAREQ_ID_TMR20_TRIG - EDMAMUX_DMAREQ_ID_TMR20_HALL - EDMAMUX_DMAREQ_ID_DVP + * @retval none. + */ +void edmamux_init(edmamux_channel_type *edmamux_channelx, edmamux_requst_id_sel_type edmamux_req_id) +{ + edmamux_channelx->muxctrl_bit.reqsel = edmamux_req_id; +} + +/** + * @brief edmamux sync init struct config with its default value. + * @param edmamux_sync_init_struct: pointer to a edmamux_sync_init_type structure which will be initialized. + * @retval none. + */ +void edmamux_sync_default_para_init(edmamux_sync_init_type *edmamux_sync_init_struct) +{ + edmamux_sync_init_struct->sync_enable = FALSE; + edmamux_sync_init_struct->sync_event_enable = FALSE; + edmamux_sync_init_struct->sync_polarity = EDMAMUX_SYNC_POLARITY_DISABLE; + edmamux_sync_init_struct->sync_request_number = 0x0; + edmamux_sync_init_struct->sync_signal_sel = EDMAMUX_SYNC_ID_EXINT0; +} + +/** + * @brief edmamux synchronization config. + * @param edmamux_channelx: + * this parameter can be one of the following values: + * - EDMAMUX_CHANNEL1 + * - EDMAMUX_CHANNEL2 + * - EDMAMUX_CHANNEL3 + * - EDMAMUX_CHANNEL4 + * - EDMAMUX_CHANNEL5 + * - EDMAMUX_CHANNEL6 + * - EDMAMUX_CHANNEL7 + * - EDMAMUX_CHANNEL8 + * @param edmamux_sync_init_struct: ointer to a edmamux_sync_init_type structure. + * @retval none. + */ +void edmamux_sync_config(edmamux_channel_type *edmamux_channelx, edmamux_sync_init_type *edmamux_sync_init_struct) +{ + edmamux_channelx->muxctrl_bit.syncsel = edmamux_sync_init_struct->sync_signal_sel; + edmamux_channelx->muxctrl_bit.syncpol = edmamux_sync_init_struct->sync_polarity; + edmamux_channelx->muxctrl_bit.reqcnt = edmamux_sync_init_struct->sync_request_number; + edmamux_channelx->muxctrl_bit.evtgen = edmamux_sync_init_struct->sync_event_enable; + edmamux_channelx->muxctrl_bit.syncen = edmamux_sync_init_struct->sync_enable; +} + +/** + * @brief edmamux request generator init struct config with its default value. + * @param edmamux_gen_init_struct: pointer to a edmamux_gen_init_type structure which will be initialized. + * @retval none. + */ +void edmamux_generator_default_para_init(edmamux_gen_init_type *edmamux_gen_init_struct) +{ + edmamux_gen_init_struct->gen_enable = FALSE; + edmamux_gen_init_struct->gen_polarity = EDMAMUX_GEN_POLARITY_DISABLE; + edmamux_gen_init_struct->gen_request_number = 0x0; + edmamux_gen_init_struct->gen_signal_sel = EDMAMUX_GEN_ID_EXINT0; +} + +/** + * @brief edmamux request generator init. + * @param edmamux_gen_init_struct: pointer to a edmamux_gen_init_type structure which will be initialized. + * @retval none. + */ +void edmamux_generator_config(edmamux_generator_type *edmamux_gen_x, edmamux_gen_init_type *edmamux_gen_init_struct) +{ + edmamux_gen_x->gctrl_bit.sigsel = edmamux_gen_init_struct->gen_signal_sel; + edmamux_gen_x->gctrl_bit.gpol = edmamux_gen_init_struct->gen_polarity; + edmamux_gen_x->gctrl_bit.greqcnt = edmamux_gen_init_struct->gen_request_number; + edmamux_gen_x->gctrl_bit.gen = edmamux_gen_init_struct->gen_enable; +} + +/** + * @brief enable or disable the edmamux sync interrupts. + * @param edmamux_channelx: + * this parameter can be one of the following values: + * - EDMAMUX_CHANNEL1 + * - EDMAMUX_CHANNEL2 + * - EDMAMUX_CHANNEL3 + * - EDMAMUX_CHANNEL4 + * - EDMAMUX_CHANNEL5 + * - EDMAMUX_CHANNEL6 + * - EDMAMUX_CHANNEL7 + * - EDMAMUX_CHANNEL8 + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void edmamux_sync_interrupt_enable(edmamux_channel_type *edmamux_channelx, confirm_state new_state) +{ + if(new_state != FALSE) + { + edmamux_channelx->muxctrl_bit.syncovien = TRUE; + } + else + { + edmamux_channelx->muxctrl_bit.syncovien = FALSE; + } +} + +/** + * @brief enable or disable the edmamux request generator interrupts. + * @param edmamux_gen_x: pointer to a edmamux_generator_type structure. + * this parameter can be one of the following values: + * - EDMAMUX_GENERATOR1 + * - EDMAMUX_GENERATOR2 + * - EDMAMUX_GENERATOR3 + * - EDMAMUX_GENERATOR4 + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void edmamux_generator_interrupt_enable(edmamux_generator_type *edmamux_gen_x, confirm_state new_state) +{ + if(new_state != FALSE) + { + edmamux_gen_x->gctrl_bit.trgovien = TRUE; + } + else + { + edmamux_gen_x->gctrl_bit.trgovien = FALSE; + } +} + +/** + * @brief edmamux sync flag get. + * @param flag + * this parameter can be any combination of the following values: + * - EDMAMUX_SYNC_OV1_FLAG + * - EDMAMUX_SYNC_OV2_FLAG + * - EDMAMUX_SYNC_OV3_FLAG + * - EDMAMUX_SYNC_OV4_FLAG + * - EDMAMUX_SYNC_OV5_FLAG + * - EDMAMUX_SYNC_OV6_FLAG + * - EDMAMUX_SYNC_OV7_FLAG + * - EDMAMUX_SYNC_OV8_FLAG + * @retval state of edmamux sync flag. + */ +flag_status edmamux_sync_flag_get(uint32_t flag) +{ + if((EDMA->muxsyncsts & flag) != RESET) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief edmamux sync flag clear. + * @param flag + * this parameter can be any combination of the following values: + * - EDMAMUX_SYNC_OV1_FLAG + * - EDMAMUX_SYNC_OV2_FLAG + * - EDMAMUX_SYNC_OV3_FLAG + * - EDMAMUX_SYNC_OV4_FLAG + * - EDMAMUX_SYNC_OV5_FLAG + * - EDMAMUX_SYNC_OV6_FLAG + * - EDMAMUX_SYNC_OV7_FLAG + * - EDMAMUX_SYNC_OV8_FLAG + * @retval none. + */ +void edmamux_sync_flag_clear(uint32_t flag) +{ + EDMA->muxsyncclr = flag; +} + +/** + * @brief edmamux request generator flag get. + * @param flag + * this parameter can be any combination of the following values: + * - EDMAMUX_GEN_TRIG_OV1_FLAG + * - EDMAMUX_GEN_TRIG_OV2_FLAG + * - EDMAMUX_GEN_TRIG_OV3_FLAG + * - EDMAMUX_GEN_TRIG_OV4_FLAG + * @retval state of edmamux sync flag. + */ +flag_status edmamux_generator_flag_get(uint32_t flag) +{ + if((EDMA->muxgsts & flag) != RESET) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief edmamux request generator flag clear. + * @param flag + * this parameter can be any combination of the following values: + * - EDMAMUX_GEN_TRIG_OV1_FLAG + * - EDMAMUX_GEN_TRIG_OV2_FLAG + * - EDMAMUX_GEN_TRIG_OV3_FLAG + * - EDMAMUX_GEN_TRIG_OV4_FLAG + * @retval none. + */ +void edmamux_generator_flag_clear(uint32_t flag) +{ + EDMA->muxgclr = flag; +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_emac.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_emac.c new file mode 100644 index 0000000000..c1dbe1ef5e --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_emac.c @@ -0,0 +1,2309 @@ +/** + ************************************************************************** + * @file at32f435_437_emac.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the emac firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup EMAC + * @brief EMAC driver modules + * @{ + */ + +#ifdef EMAC_MODULE_ENABLED + +/** @defgroup EMAC_private_functions + * @{ + */ + +#if defined (EMAC_BASE) +/** + * @brief global pointers on tx and rx descriptor used to track transmit and receive descriptors + */ +emac_dma_desc_type *dma_tx_desc_to_set; +emac_dma_desc_type *dma_rx_desc_to_get; + +/* emac private function */ +static void emac_delay(uint32_t delay); + +/** + * @brief deinitialize the emac peripheral registers to their default reset values. + * @param none + * @retval none + */ +void emac_reset(void) +{ + crm_periph_reset(CRM_EMAC_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_EMAC_PERIPH_RESET, FALSE); +} + +/** + * @brief initialize emac control structure + * @param emac_control_config_type + * @retval none + */ +void emac_control_para_init(emac_control_config_type *control_para) +{ + control_para->auto_nego = EMAC_AUTO_NEGOTIATION_OFF; + control_para->auto_pad_crc_strip = FALSE; + control_para->back_off_limit = EMAC_BACKOFF_LIMIT_0; + control_para->carrier_sense_disable = FALSE; + control_para->deferral_check = FALSE; + control_para->duplex_mode = EMAC_HALF_DUPLEX; + control_para->fast_ethernet_speed = EMAC_SPEED_10MBPS; + control_para->interframe_gap = EMAC_INTERFRAME_GAP_96BIT; + control_para->ipv4_checksum_offload = FALSE; + control_para->jabber_disable = FALSE; + control_para->loopback_mode = FALSE; + control_para->receive_own_disable = FALSE; + control_para->retry_disable = FALSE; + control_para->watchdog_disable = FALSE; +} + +/** + * @brief according to hclk to set mdc clock frequency. + * @param none + * @retval none + */ +void emac_clock_range_set(void) +{ + uint8_t bits_value = 0; + crm_clocks_freq_type clocks_freq = {0}; + + /* clear clock range bits */ + EMAC->miiaddr_bit.cr = bits_value; + + crm_clocks_freq_get(&clocks_freq); + + if((clocks_freq.ahb_freq >= EMAC_HCLK_BORDER_20MHZ) && (clocks_freq.ahb_freq < EMAC_HCLK_BORDER_35MHZ)) + { + bits_value = EMAC_CLOCK_RANGE_20_TO_35; + } + else if((clocks_freq.ahb_freq >= EMAC_HCLK_BORDER_35MHZ) && (clocks_freq.ahb_freq < EMAC_HCLK_BORDER_60MHZ)) + { + bits_value = EMAC_CLOCK_RANGE_35_TO_60; + } + else if((clocks_freq.ahb_freq >= EMAC_HCLK_BORDER_60MHZ) && (clocks_freq.ahb_freq < EMAC_HCLK_BORDER_100MHZ)) + { + bits_value = EMAC_CLOCK_RANGE_60_TO_100; + } + else if((clocks_freq.ahb_freq >= EMAC_HCLK_BORDER_100MHZ) && (clocks_freq.ahb_freq < EMAC_HCLK_BORDER_150MHZ)) + { + bits_value = EMAC_CLOCK_RANGE_100_TO_150; + } + else if((clocks_freq.ahb_freq >= EMAC_HCLK_BORDER_150MHZ) && (clocks_freq.ahb_freq < EMAC_HCLK_BORDER_250MHZ)) + { + bits_value = EMAC_CLOCK_RANGE_150_TO_250; + } + else if((clocks_freq.ahb_freq >= EMAC_HCLK_BORDER_250MHZ) && (clocks_freq.ahb_freq <= EMAC_HCLK_BORDER_288MHZ)) + { + bits_value = EMAC_CLOCK_RANGE_250_TO_288; + } + + EMAC->miiaddr_bit.cr = bits_value; +} + +/** + * @brief configure emac control setting. + * @param control_struct: control setting of mac control register. + * @retval none + */ +void emac_control_config(emac_control_config_type *control_struct) +{ + emac_deferral_check_set(control_struct->deferral_check); + emac_backoff_limit_set(control_struct->back_off_limit); + emac_auto_pad_crc_stripping_set(control_struct->auto_pad_crc_strip); + emac_retry_disable(control_struct->retry_disable); + emac_ipv4_checksum_offload_set(control_struct->ipv4_checksum_offload); + emac_loopback_mode_enable(control_struct->loopback_mode); + emac_receive_own_disable(control_struct->receive_own_disable); + emac_carrier_sense_disable(control_struct->carrier_sense_disable); + emac_interframe_gap_set(control_struct->interframe_gap); + emac_jabber_disable(control_struct->jabber_disable); + emac_watchdog_disable(control_struct->watchdog_disable); +} + +/** + * @brief reset emac dma + * @param none + * @retval none + */ +void emac_dma_software_reset_set(void) +{ + EMAC_DMA->bm_bit.swr = 1; +} + +/** + * @brief get emac dma reset status + * @param none + * @retval TRUE of FALSE + */ +flag_status emac_dma_software_reset_get(void) +{ + if(EMAC_DMA->bm_bit.swr) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief enable emac and dma reception/transmission + * @param none + * @retval none + */ +void emac_start(void) +{ + /* enable transmit state machine of the mac for transmission on the mii */ + emac_trasmitter_enable(TRUE); + + /* flush transmit fifo */ + emac_dma_operations_set(EMAC_DMA_OPS_FLUSH_TRANSMIT_FIFO, TRUE); + + /* enable receive state machine of the mac for reception from the mii */ + emac_receiver_enable(TRUE); + + /* start dma transmission */ + emac_dma_operations_set(EMAC_DMA_OPS_START_STOP_TRANSMIT, TRUE); + + /* start dma reception */ + emac_dma_operations_set(EMAC_DMA_OPS_START_STOP_RECEIVE, TRUE); +} + +/** + * @brief stop emac and dma reception/transmission + * @param none + * @retval none + */ +void emac_stop(void) +{ + /* stop dma transmission */ + emac_dma_operations_set(EMAC_DMA_OPS_START_STOP_TRANSMIT, FALSE); + + /* stop dma reception */ + emac_dma_operations_set(EMAC_DMA_OPS_START_STOP_RECEIVE, FALSE); + + /* stop receive state machine of the mac for reception from the mii */ + emac_receiver_enable(FALSE); + + /* flush transmit fifo */ + emac_dma_operations_set(EMAC_DMA_OPS_FLUSH_TRANSMIT_FIFO, TRUE); + + /* stop transmit state machine of the mac for transmission on the mii */ + emac_trasmitter_enable(FALSE); +} + + +/** + * @brief write phy data. + * @param address: phy address. + * @param reg: register of phy. + * @param data: value that wants to write to phy. + * @retval SUCCESS or ERROR + */ +error_status emac_phy_register_write(uint8_t address, uint8_t reg, uint16_t data) +{ + uint32_t timeout = 0; + + EMAC->miidt_bit.md = data; + + EMAC->miiaddr_bit.pa = address; + EMAC->miiaddr_bit.mii = reg; + EMAC->miiaddr_bit.mw = 1; + EMAC->miiaddr_bit.mb = 1; + + do + { + timeout++; + } while((EMAC->miiaddr_bit.mb) && (timeout < PHY_TIMEOUT)); + + if(timeout == PHY_TIMEOUT) + { + return ERROR; + } + return SUCCESS; +} + +/** + * @brief read phy data + * @param address: phy address. + * @param reg: register of phy. + * @param data: value that is read from phy. + * @retval SUCCESS or ERROR + */ +error_status emac_phy_register_read(uint8_t address, uint8_t reg, uint16_t *data) +{ + uint32_t timeout = 0; + + EMAC->miiaddr_bit.pa = address; + EMAC->miiaddr_bit.mii = reg; + EMAC->miiaddr_bit.mw = 0; + EMAC->miiaddr_bit.mb = 1; + + do + { + timeout++; + *data = EMAC->miidt_bit.md; + } while((EMAC->miiaddr_bit.mb) && (timeout < PHY_TIMEOUT)); + + if(timeout == PHY_TIMEOUT) + { + return ERROR; + } + + *data = EMAC->miidt_bit.md; + return SUCCESS; +} + +/** + * @brief emac receiver enable. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_receiver_enable(confirm_state new_state) +{ + __IO uint32_t temp = 0; + + EMAC->ctrl_bit.re = new_state; + + temp = EMAC->ctrl; + emac_delay(1); + EMAC->ctrl = temp; +} + +/** + * @brief emac transmitter enable. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_trasmitter_enable(confirm_state new_state) +{ + __IO uint32_t temp = 0; + + EMAC->ctrl_bit.te = new_state; + + temp = EMAC->ctrl; + emac_delay(1); + EMAC->ctrl = temp; +} + +/** + * @brief emac defferal check enable, only avalible in half-duplex mode. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_deferral_check_set(confirm_state new_state) +{ + EMAC->ctrl_bit.dc = new_state; +} + +/** + * @brief emac back-off limit, only avalible in half-duplex mode. + * @param slot_time: waiting time of retransmission after collision + * this parameter can be one of the following values: + * - EMAC_BACKOFF_LIMIT_0 + * - EMAC_BACKOFF_LIMIT_1 + * - EMAC_BACKOFF_LIMIT_2 + * - EMAC_BACKOFF_LIMIT_3 + * @retval none + */ +void emac_backoff_limit_set(emac_bol_type slot_time) +{ + EMAC->ctrl_bit.bl = slot_time; +} + +/** + * @brief set mac automatic pad/CRC stripping. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_auto_pad_crc_stripping_set(confirm_state new_state) +{ + EMAC->ctrl_bit.acs = new_state; +} + +/** + * @brief transmittion retry disable. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_retry_disable(confirm_state new_state) +{ + EMAC->ctrl_bit.dr = new_state; +} + +/** + * @brief set ipv4 checksum offload. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_ipv4_checksum_offload_set(confirm_state new_state) +{ + EMAC->ctrl_bit.ipc = new_state; +} + +/** + * @brief enable loopback mode. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_loopback_mode_enable(confirm_state new_state) +{ + EMAC->ctrl_bit.lm = new_state; +} + +/** + * @brief receive own disable. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_receive_own_disable(confirm_state new_state) +{ + EMAC->ctrl_bit.dro = new_state; +} + +/** + * @brief carrier sense disbale. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_carrier_sense_disable(confirm_state new_state) +{ + EMAC->ctrl_bit.dcs = new_state; +} + +/** + * @brief set minimum interframe gap between frames during transmission. + * @param number: interframe gap number. + * this parameter can be one of the following values: + * - EMAC_FRAME_GAP_96BIT + * - EMAC_FRAME_GAP_88BIT + * - EMAC_FRAME_GAP_80BIT + * - EMAC_FRAME_GAP_72BIT + * - EMAC_FRAME_GAP_64BIT + * - EMAC_FRAME_GAP_56BIT + * - EMAC_FRAME_GAP_48BIT + * - EMAC_FRAME_GAP_40BIT + * @retval none + */ +void emac_interframe_gap_set(emac_intergrame_gap_type number) +{ + EMAC->ctrl_bit.ifg = number; +} + +/** + * @brief jabber disable. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_jabber_disable(confirm_state new_state) +{ + EMAC->ctrl_bit.jd = new_state; +} + +/** + * @brief watchdog disable. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_watchdog_disable(confirm_state new_state) +{ + EMAC->ctrl_bit.wd = new_state; +} + +/** + * @brief set mac fast emac speed. + * @param speed: mac bandwidth + * this parameter can be one of the following values: + * - EMAC_SPEED_10MBPS + * - EMAC_SPEED_100MBPS + * @retval none + */ +void emac_fast_speed_set(emac_speed_type speed) +{ + EMAC->ctrl_bit.fes = speed; +} + +/** + * @brief set duplex mode. + * @param duplex_mode: communication mode + * this parameter can be one of the following values: + * - EMAC_HALF_DUPLEX + * - EMAC_FULL_DUPLEX + * @retval none + */ +void emac_duplex_mode_set(emac_duplex_type duplex_mode) +{ + EMAC->ctrl_bit.dm = duplex_mode; +} + +/** + * @brief set mac promiscuous mode. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_promiscuous_mode_set(confirm_state new_state) +{ + EMAC->frmf_bit.pr = new_state; +} + +/** + * @brief hash unicast. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_hash_unicast_set(confirm_state new_state) +{ + EMAC->frmf_bit.huc = new_state; +} + +/** + * @brief hash multicast. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_hash_multicast_set(confirm_state new_state) +{ + EMAC->frmf_bit.hmc = new_state; +} + +/** + * @brief destination address inverse filtering. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_dstaddr_inverse_filter_set(confirm_state new_state) +{ + EMAC->frmf_bit.daif = new_state; +} + +/** + * @brief pass all multicasting frames. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_pass_all_multicasting_set(confirm_state new_state) +{ + EMAC->frmf_bit.pmc = new_state; +} + +/** + * @brief broadcast frames disable. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_broadcast_frames_disable(confirm_state new_state) +{ + EMAC->frmf_bit.dbf = new_state; +} + +/** + * @brief set mac how to pass control frames. + * @param condition: set what control frame can pass filter. + * this parameter can be one of the following values: + * - EMAC_CONTROL_FRAME_PASSING_NO + * - EMAC_CONTROL_FRAME_PASSING_ALL + * - EMAC_CONTROL_FRAME_PASSING_MATCH + * @retval none + */ +void emac_pass_control_frames_set(emac_control_frames_filter_type condition) +{ + EMAC->frmf_bit.pcf = condition; +} + +/** + * @brief source address inverse filtering. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_srcaddr_inverse_filter_set(confirm_state new_state) +{ + EMAC->frmf_bit.saif = new_state; +} + +/** + * @brief source address filtering. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_srcaddr_filter_set(confirm_state new_state) +{ + EMAC->frmf_bit.saf = new_state; +} + +/** + * @brief mac uses hash or perfect filter. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_hash_perfect_filter_set(confirm_state new_state) +{ + EMAC->frmf_bit.hpf = new_state; +} + +/** + * @brief mac receives all frames. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_receive_all_set(confirm_state new_state) +{ + EMAC->frmf_bit.ra = new_state; +} + +/** + * @brief hash table high 32-bit. + * @param high32bits: the highest 32-bit of hash table. + * @retval none + */ +void emac_hash_table_high32bits_set(uint32_t high32bits) +{ + EMAC->hth_bit.hth = high32bits; +} + +/** + * @brief hash table low 32-bit. + * @param low32bits: the lowest 32-bit of hash table. + * @retval none + */ +void emac_hash_table_low32bits_set(uint32_t low32bits) +{ + EMAC->htl_bit.htl = low32bits; +} + +/** + * @brief mii busy status. + * @param none + * @retval SET or RESET + */ +flag_status emac_mii_busy_get(void) +{ + if(EMAC->miiaddr_bit.mb) { + return SET; + } + else { + return RESET; + } +} + +/** + * @brief tell phy that will be written. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_mii_write(confirm_state new_state) +{ + EMAC->miiaddr_bit.mw = new_state; +} + +/** + * @brief set flow control busy in full-duplex mode, back pressure activate in half-duplex mode. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_fcb_bpa_set(confirm_state new_state) +{ + EMAC->fctrl_bit.fcbbpa = new_state; +} + +/** + * @brief set transmit flow control. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_transmit_flow_control_enable(confirm_state new_state) +{ + EMAC->fctrl_bit.etf = new_state; +} + +/** + * @brief set receive flow control. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_receive_flow_control_enable(confirm_state new_state) +{ + EMAC->fctrl_bit.erf = new_state; +} + +/** + * @brief set unicast pause frame detect. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_unicast_pause_frame_detect(confirm_state new_state) +{ + EMAC->fctrl_bit.dup = new_state; +} + +/** + * @brief set pause low threshold. + * @param pasue_threshold: pause slot time. + * this parameter can be one of the following values: + * - EMAC_PAUSE_4_SLOT_TIME + * - EMAC_PAUSE_28_SLOT_TIME + * - EMAC_PAUSE_144_SLOT_TIME + * - EMAC_PAUSE_256_SLOT_TIME + * @retval none + */ +void emac_pause_low_threshold_set(emac_pause_slot_threshold_type pasue_threshold) +{ + EMAC->fctrl_bit.plt = pasue_threshold; +} + +/** + * @brief set zero-quanta pause disable. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_zero_quanta_pause_disable(confirm_state new_state) +{ + EMAC->fctrl_bit.dzqp = new_state; +} + +/** + * @brief set pause time. + * @param pause_time: time slots to pause transmit frame. + * @retval none + */ +void emac_pause_time_set(uint16_t pause_time) +{ + EMAC->fctrl_bit.pt = pause_time; +} + +/** + * @brief identify coming vlan frame field with setting value. + * @param identifier: it will be compared with coming frame. + * @retval none + */ +void emac_vlan_tag_identifier_set(uint16_t identifier) +{ + EMAC->vlt_bit.vti = identifier; +} + +/** + * @brief set 12-bit vlan identifier. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_vlan_tag_comparison_set(confirm_state new_state) +{ + EMAC->vlt_bit.etv = new_state; +} + +/** + * @brief set wakeup frame. + * @param value: it will be written to eight non transparent registers. + * @retval none + */ +void emac_wakeup_frame_set(uint32_t value) +{ + EMAC->rwff = value; +} + +/** + * @brief get wakeup frame. + * @param none + * @retval get value from eight non transparent registers. + */ +uint32_t emac_wakeup_frame_get(void) +{ + return (EMAC->rwff); +} + +/** + * @brief all frame will be droppped except wakeup frame or magic packet. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_power_down_set(confirm_state new_state) +{ + EMAC->pmtctrlsts_bit.pd = new_state; +} + +/** + * @brief magic packet enable + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_magic_packet_enable(confirm_state new_state) +{ + EMAC->pmtctrlsts_bit.emp = new_state; +} + +/** + * @brief wakeup frame enable + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_wakeup_frame_enable(confirm_state new_state) +{ + EMAC->pmtctrlsts_bit.erwf = new_state; +} + +/** + * @brief received magic packet + * @param none + * @retval the new state of usart_flag (SET or RESET). + */ +flag_status emac_received_magic_packet_get(void) +{ + if(EMAC->pmtctrlsts_bit.rmp) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief received wakeup frame. + * @param none + * @retval the new state of usart_flag (SET or RESET). + */ +flag_status emac_received_wakeup_frame_get(void) +{ + if(EMAC->pmtctrlsts_bit.rrwf) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief set unicast frame that passes DAF as wakeup frame. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_global_unicast_set(confirm_state new_state) +{ + EMAC->pmtctrlsts_bit.guc = new_state; +} + +/** + * @brief reset wakeup frame filter resgister + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_wakeup_frame_filter_reset(confirm_state new_state) +{ + EMAC->pmtctrlsts_bit.rwffpr = new_state; +} + +/** + * @brief read interrupt status + * @param flag: specifies the flag to check. + * this parameter can be one of the following values: + * - EMAC_PMT_FLAG + * - EMAC_MMC_FLAG + * - EMAC_MMCR_FLAG + * - EMAC_MMCT_FLAG + * - EMAC_TST_FLAG + * @retval the new state of usart_flag (SET or RESET). + */ +flag_status emac_interrupt_status_read(uint32_t flag) +{ + if(EMAC->ists & flag) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief set interrupt mask + * @param mask_type: mask the interrupt signal + * this parameter can be one of the following values: + * - EMAC_INTERRUPT_PMT_MASK + * - EMAC_INTERRUPT_TST_MASK + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_interrupt_mask_set(emac_interrupt_mask_type mask_type, confirm_state new_state) +{ + switch(mask_type) + { + case EMAC_INTERRUPT_PMT_MASK: + { + EMAC->imr_bit.pim = new_state; + break; + } + case EMAC_INTERRUPT_TST_MASK: + { + EMAC->imr_bit.tim = new_state; + break; + } + } +} + +/** + * @brief set local mac address + * @param address: local address for mac0 + * @retval none + */ +void emac_local_address_set(uint8_t *address) +{ + EMAC->a0h_bit.ma0h = (uint32_t)(address[5] << 8 | address[4]); + EMAC->a0l_bit.ma0l = (uint32_t)(address[3] << 24 | address[2] << 16 | address[1] << 8 | address[0]); +} + +/** + * @brief set mac filter address + * @param mac: select which mac you want to set + * this parameter can be one of the following values: + * - EMAC_ADDRESS_FILTER_1 + * - EMAC_ADDRESS_FILTER_2 + * - EMAC_ADDRESS_FILTER_3 + * @retval none + */ +void emac_address_filter_set(emac_address_type mac, emac_address_filter_type filter, emac_address_mask_type mask_bit, confirm_state new_state) +{ + switch(mac) + { + case EMAC_ADDRESS_FILTER_1: + { + EMAC->a1h_bit.sa = filter; + EMAC->a1h_bit.mbc = mask_bit; + EMAC->a1h_bit.ae = new_state; + break; + } + case EMAC_ADDRESS_FILTER_2: + { + EMAC->a2h_bit.sa = filter; + EMAC->a2h_bit.mbc = mask_bit; + EMAC->a2h_bit.ae = new_state; + break; + } + case EMAC_ADDRESS_FILTER_3: + { + EMAC->a3h_bit.sa = filter; + EMAC->a3h_bit.mbc = mask_bit; + EMAC->a3h_bit.ae = new_state; + break; + } + } +} + +/** + * @brief set transmit/receive descriptor list address + * @param transfer_type: it will be transmit or receive + * this parameter can be one of the following values: + * - EMAC_DMA_TRANSMIT + * - EMAC_DMA_RECEIVE + * @param dma_desc_tab: pointer on the first tx desc list + * @param buff: pointer on the first tx/rx buffer list + * @param buffer_count: number of the used Tx desc in the list + * @retval none + */ +void emac_dma_descriptor_list_address_set(emac_dma_tx_rx_type transfer_type, emac_dma_desc_type *dma_desc_tab, uint8_t *buff, uint32_t buffer_count) +{ + uint32_t i = 0; + emac_dma_desc_type *dma_descriptor; + + switch(transfer_type) + { + case EMAC_DMA_TRANSMIT: + { + dma_tx_desc_to_set = dma_desc_tab; + for(i = 0; i < buffer_count; i++) + { + dma_descriptor = dma_desc_tab + i; + + dma_descriptor->status = EMAC_DMATXDESC_TCH; + + dma_descriptor->buf1addr = (uint32_t)(&buff[i * EMAC_MAX_PACKET_LENGTH]); + + if(i < (buffer_count - 1)) + { + dma_descriptor->buf2nextdescaddr = (uint32_t)(dma_desc_tab + i + 1); + } + else + { + dma_descriptor->buf2nextdescaddr = (uint32_t) dma_desc_tab; + } + } + EMAC_DMA->tdladdr_bit.stl = (uint32_t) dma_desc_tab; + break; + } + case EMAC_DMA_RECEIVE: + { + dma_rx_desc_to_get = dma_desc_tab; + for(i = 0; i < buffer_count; i++) + { + dma_descriptor = dma_desc_tab + i; + + dma_descriptor->status = EMAC_DMARXDESC_OWN; + + dma_descriptor->controlsize = EMAC_DMARXDESC_RCH | (uint32_t)EMAC_MAX_PACKET_LENGTH; + + dma_descriptor->buf1addr = (uint32_t)(&buff[i * EMAC_MAX_PACKET_LENGTH]); + + if(i < (buffer_count - 1)) + { + dma_descriptor->buf2nextdescaddr = (uint32_t)(dma_desc_tab + i + 1); + } + else + { + dma_descriptor->buf2nextdescaddr = (uint32_t) dma_desc_tab; + } + } + EMAC_DMA->rdladdr_bit.srl = (uint32_t) dma_desc_tab; + break; + } + } +} + +/** + * @brief enable or disable the specified dma rx descriptor receive interrupt + * @param dma_rx_desc: pointer on a rx desc. + * @param new_state: new state of the specified dma rx descriptor interrupt. + * this parameter can be one of the following values: + * - TRUE + * - FALSE. + * @retval none + */ +void emac_dma_rx_desc_interrupt_config(emac_dma_desc_type *dma_rx_desc, confirm_state new_state) +{ + if (new_state != FALSE) + { + /* enable the dma rx desc receive interrupt */ + dma_rx_desc->controlsize &= (~(uint32_t)EMAC_DMARXDESC_DIC); + } + else + { + /* disable the dma rx desc receive interrupt */ + dma_rx_desc->controlsize |= EMAC_DMARXDESC_DIC; + } +} + +/** + * @brief get transmit/receive descriptor list address + * @param transfer_type: it will be transmit or receive + * this parameter can be one of the following values: + * - EMAC_DMA_TRANSMIT + * - EMAC_DMA_RECEIVE + * @retval transmit/receive descriptor list address + */ +uint32_t emac_dma_descriptor_list_address_get(emac_dma_tx_rx_type transfer_type) +{ + switch(transfer_type) + { + case EMAC_DMA_TRANSMIT: + { + return (EMAC_DMA->tdladdr_bit.stl); + } + case EMAC_DMA_RECEIVE: + { + return (EMAC_DMA->rdladdr_bit.srl); + } + } + return 0; +} + +/** + * @brief get the size of received the received packet. + * @param none + * @retval received packet size + */ +uint32_t emac_received_packet_size_get(void) +{ + uint32_t frame_length = 0; + if(((dma_rx_desc_to_get->status & EMAC_DMARXDESC_OWN) == (uint32_t)RESET) && + ((dma_rx_desc_to_get->status & EMAC_DMATXDESC_ES) == (uint32_t)RESET) && + ((dma_rx_desc_to_get->status & EMAC_DMARXDESC_LS) != (uint32_t)RESET) && + ((dma_rx_desc_to_get->status & EMAC_DMARXDESC_FS) != (uint32_t)RESET)) + { + frame_length = emac_dmarxdesc_frame_length_get(dma_rx_desc_to_get); + } + + return frame_length; +} + +/** + * @brief get the specified dma rx descsriptor frame length. + * @param dma_rx_desc: pointer on a dma rx descriptor + * @retval the rx descriptor received frame length. + */ +uint32_t emac_dmarxdesc_frame_length_get(emac_dma_desc_type *dma_rx_desc) +{ + return ((dma_rx_desc->status & EMAC_DMARXDESC_FL) >> EMAC_DMARXDESC_FRAME_LENGTHSHIFT); +} + +/** + * @brief init emac dma parameters + * @param emac_dma_config_type + * @retval none + */ +void emac_dma_para_init(emac_dma_config_type *control_para) +{ + control_para->aab_enable = FALSE; + control_para->da_enable = FALSE; + control_para->desc_skip_length = 0; + control_para->dt_disable = FALSE; + control_para->fb_enable = FALSE; + control_para->fef_enable = FALSE; + control_para->flush_rx_disable = FALSE; + control_para->fugf_enable = FALSE; + control_para->osf_enable = FALSE; + control_para->priority_ratio = EMAC_DMA_1_RX_1_TX; + control_para->rsf_enable = FALSE; + control_para->rx_dma_pal = EMAC_DMA_PBL_1; + control_para->rx_threshold = EMAC_DMA_RX_THRESHOLD_64_BYTES; + control_para->tsf_enable = FALSE; + control_para->tx_dma_pal = EMAC_DMA_PBL_1; + control_para->tx_threshold = EMAC_DMA_TX_THRESHOLD_64_BYTES; + control_para->usp_enable = FALSE; +} + +/** + * @brief configure emac dma + * @param emac_dma_config_type + * @retval none + */ +void emac_dma_config(emac_dma_config_type *control_para) +{ + EMAC_DMA->bm_bit.aab = control_para->aab_enable; + EMAC_DMA->bm_bit.dsl = control_para->desc_skip_length; + EMAC_DMA->bm_bit.rdp = control_para->rx_dma_pal; + EMAC_DMA->bm_bit.pbl = control_para->tx_dma_pal; + EMAC_DMA->bm_bit.fb = control_para->fb_enable; + EMAC_DMA->bm_bit.usp = control_para->usp_enable; + EMAC_DMA->bm_bit.da = control_para->da_enable; + EMAC_DMA->bm_bit.pr = control_para->priority_ratio; + + EMAC_DMA->opm_bit.dt = control_para->dt_disable; + EMAC_DMA->opm_bit.rsf = control_para->rsf_enable; + EMAC_DMA->opm_bit.dfrf = control_para->flush_rx_disable; + EMAC_DMA->opm_bit.tsf = control_para->tsf_enable; + EMAC_DMA->opm_bit.ttc = control_para->tx_threshold; + EMAC_DMA->opm_bit.fef = control_para->fef_enable; + EMAC_DMA->opm_bit.fugf = control_para->fugf_enable; + EMAC_DMA->opm_bit.rtc = control_para->rx_threshold; + EMAC_DMA->opm_bit.osf = control_para->osf_enable; +} + +/** + * @brief set rx tx priority + * @param ratio: rx tx priority ratio + * this parameter can be one of the following values: + * - EMAC_DMA_1_RX_1_TX + * - EMAC_DMA_2_RX_1_TX + * - EMAC_DMA_3_RX_1_TX + * - EMAC_DMA_4_RX_1_TX + * @param new_state: TRUE or FALSE + * @retval none + */ +void emac_dma_arbitation_set(emac_dma_rx_tx_ratio_type ratio, confirm_state new_state) +{ + EMAC_DMA->bm_bit.da = new_state; + + if(new_state) + { + EMAC_DMA->bm_bit.pr = ratio; + } +} + +/** + * @brief set descriptor skip mength + * @param length: descriptor skip length + * @retval none + */ +void emac_dma_descriptor_skip_length_set(uint8_t length) +{ + EMAC_DMA->bm_bit.dsl = length; +} + +/** + * @brief set programmable burst length + * @param tx_length: tx programmable burst length + * this parameter can be one of the following values: + * - EMAC_DMA_PBL_1 + * - EMAC_DMA_PBL_2 + * - EMAC_DMA_PBL_4 + * - EMAC_DMA_PBL_8 + * - EMAC_DMA_PBL_16 + * - EMAC_DMA_PBL_32 + * @param rx_length: rx programmable burst length + * this parameter can be one of the following values: + * - EMAC_DMA_PBL_1 + * - EMAC_DMA_PBL_2 + * - EMAC_DMA_PBL_4 + * - EMAC_DMA_PBL_8 + * - EMAC_DMA_PBL_16 + * - EMAC_DMA_PBL_32 + * @param new_state: TRUE or FALSE + * @retval none + */ +void emac_dma_separate_pbl_set(emac_dma_pbl_type tx_length, emac_dma_pbl_type rx_length, confirm_state new_state) +{ + EMAC_DMA->bm_bit.usp = new_state; + EMAC_DMA->bm_bit.pbl = tx_length; + + if(new_state) + { + EMAC_DMA->bm_bit.pbl = rx_length; + } +} + +/** + * @brief set 8 times programmable burst length + * @param new_state: TRUE or FALSE + * @retval none + */ +void emac_dma_eight_pbl_mode_set(confirm_state new_state) +{ + EMAC_DMA->bm_bit.pblx8 = new_state; +} + +/** + * @brief set address-aligned beats + * @param new_state: TRUE or FALSE + * @retval none + */ +void emac_dma_address_aligned_beats_set(confirm_state new_state) +{ + EMAC_DMA->bm_bit.aab = new_state; +} + +/** + * @brief set transmit/receive poll demand + * @param transfer_type: it will be transmit or receive + * this parameter can be one of the following values: + * - EMAC_DMA_TRANSMIT + * - EMAC_DMA_RECEIVE + * @param value: it can be any number + * @retval none + */ +void emac_dma_poll_demand_set(emac_dma_tx_rx_type transfer_type, uint32_t value) +{ + switch(transfer_type) + { + case EMAC_DMA_TRANSMIT: + { + EMAC_DMA->tpd_bit.tpd = value; + break; + } + case EMAC_DMA_RECEIVE: + { + EMAC_DMA->rpd_bit.rpd = value; + break; + } + } +} + +/** + * @brief get transmit poll demand + * @param transfer_type: it will be transmit or receive + * this parameter can be one of the following values: + * - EMAC_DMA_TRANSMIT + * - EMAC_DMA_RECEIVE + * @retval current transmit descriptor + */ +uint32_t emac_dma_poll_demand_get(emac_dma_tx_rx_type transfer_type) +{ + switch(transfer_type) + { + case EMAC_DMA_TRANSMIT: + { + return (EMAC_DMA->tpd_bit.tpd); + } + case EMAC_DMA_RECEIVE: + { + return (EMAC_DMA->rpd_bit.rpd); + } + } + return 0; +} + +/** + * @brief get receive dma process status + * @param none + * @retval every situation it describe in RM + * this parameter can be one of the following values: + * - EMAC_DMA_RX_RESET_STOP_COMMAND + * - EMAC_DMA_RX_FETCH_DESCRIPTOR + * - EMAC_DMA_RX_WAITING_PACKET + * - EMAC_DMA_RX_DESCRIPTOR_UNAVAILABLE + * - EMAC_DMA_RX_CLOSE_DESCRIPTOR + * - EMAC_DMA_RX_FIFO_TO_HOST + */ +emac_dma_receive_process_status_type emac_dma_receive_status_get(void) +{ + switch(EMAC_DMA->sts_bit.rs) + { + case EMAC_DMA_RX_RESET_STOP_COMMAND: + { + return EMAC_DMA_RX_RESET_STOP_COMMAND; + } + + case EMAC_DMA_RX_FETCH_DESCRIPTOR: + { + return EMAC_DMA_RX_FETCH_DESCRIPTOR; + } + + case EMAC_DMA_RX_WAITING_PACKET: + { + return EMAC_DMA_RX_WAITING_PACKET; + } + + case EMAC_DMA_RX_DESCRIPTOR_UNAVAILABLE: + { + return EMAC_DMA_RX_DESCRIPTOR_UNAVAILABLE; + } + + case EMAC_DMA_RX_CLOSE_DESCRIPTOR: + { + return EMAC_DMA_RX_CLOSE_DESCRIPTOR; + } + + case EMAC_DMA_RX_FIFO_TO_HOST: + { + return EMAC_DMA_RX_FIFO_TO_HOST; + } + } + + return EMAC_DMA_RX_RESET_STOP_COMMAND; +} + +/** + * @brief get transmit dma process status + * @param none + * @retval every situation it describe in RM + * this parameter can be one of the following values: + * - EMAC_DMA_TX_RESET_STOP_COMMAND + * - EMAC_DMA_TX_FETCH_DESCRIPTOR + * - EMAC_DMA_TX_WAITING_FOR_STATUS + * - EMAC_DMA_TX_HOST_TO_FIFO + * - EMAC_DMA_TX_DESCRIPTOR_UNAVAILABLE + * - EMAC_DMA_TX_CLOSE_DESCRIPTOR + */ +emac_dma_transmit_process_status_type emac_dma_transmit_status_get(void) +{ + switch(EMAC_DMA->sts_bit.ts) + { + case EMAC_DMA_TX_RESET_STOP_COMMAND: + { + return EMAC_DMA_TX_RESET_STOP_COMMAND; + } + + case EMAC_DMA_TX_FETCH_DESCRIPTOR: + { + return EMAC_DMA_TX_FETCH_DESCRIPTOR; + } + + case EMAC_DMA_TX_WAITING_FOR_STATUS: + { + return EMAC_DMA_TX_WAITING_FOR_STATUS; + } + + case EMAC_DMA_TX_HOST_TO_FIFO: + { + return EMAC_DMA_TX_HOST_TO_FIFO; + } + + case EMAC_DMA_TX_DESCRIPTOR_UNAVAILABLE: + { + return EMAC_DMA_TX_DESCRIPTOR_UNAVAILABLE; + } + + case EMAC_DMA_TX_CLOSE_DESCRIPTOR: + { + return EMAC_DMA_TX_CLOSE_DESCRIPTOR; + } + } + + return EMAC_DMA_TX_RESET_STOP_COMMAND; +} + +/** + * @brief set dma operations + * @param ops: operations of dma + * this parameter can be one of the following values: + * - EMAC_DMA_OPS_START_STOP_RECEIVE + * - EMAC_DMA_OPS_SECOND_FRAME + * - EMAC_DMA_OPS_FORWARD_UNDERSIZED + * - EMAC_DMA_OPS_FORWARD_ERROR + * - EMAC_DMA_OPS_START_STOP_TRANSMIT + * - EMAC_DMA_OPS_FLUSH_TRANSMIT_FIFO + * - EMAC_DMA_OPS_TRANSMIT_STORE_FORWARD + * - EMAC_DMA_OPS_RECEIVE_FLUSH_DISABLE + * - EMAC_DMA_OPS_RECEIVE_STORE_FORWARD + * - EMAC_DMA_OPS_DROP_ERROR_DISABLE + * @param new_state: TRUE or FALSE + * @retval none + */ +void emac_dma_operations_set(emac_dma_operations_type ops, confirm_state new_state) +{ + __IO uint32_t temp = 0; + switch(ops) + { + case EMAC_DMA_OPS_START_STOP_RECEIVE: + { + EMAC_DMA->opm_bit.ssr = new_state; + break; + } + + case EMAC_DMA_OPS_SECOND_FRAME: + { + EMAC_DMA->opm_bit.osf = new_state; + break; + } + + case EMAC_DMA_OPS_FORWARD_UNDERSIZED: + { + EMAC_DMA->opm_bit.fugf = new_state; + break; + } + + case EMAC_DMA_OPS_FORWARD_ERROR: + { + EMAC_DMA->opm_bit.fef = new_state; + break; + } + + case EMAC_DMA_OPS_START_STOP_TRANSMIT: + { + EMAC_DMA->opm_bit.sstc = new_state; + break; + } + + case EMAC_DMA_OPS_FLUSH_TRANSMIT_FIFO: + { + EMAC_DMA->opm_bit.ftf = new_state; + temp = EMAC_DMA->opm; + emac_delay(1); + EMAC_DMA->opm = temp; + break; + } + + case EMAC_DMA_OPS_TRANSMIT_STORE_FORWARD: + { + EMAC_DMA->opm_bit.tsf = new_state; + break; + } + + case EMAC_DMA_OPS_RECEIVE_FLUSH_DISABLE: + { + EMAC_DMA->opm_bit.dfrf = new_state; + break; + } + + case EMAC_DMA_OPS_RECEIVE_STORE_FORWARD: + { + EMAC_DMA->opm_bit.rsf = new_state; + break; + } + + case EMAC_DMA_OPS_DROP_ERROR_DISABLE: + { + EMAC_DMA->opm_bit.dt = new_state; + break; + } + } +} + +/** + * @brief set receive dma threshold + * @param value: receive threshold + * this parameter can be one of the following values: + * - EMAC_DMA_RX_THRESHOLD_64_BYTES + * - EMAC_DMA_RX_THRESHOLD_32_BYTES + * - EMAC_DMA_RX_THRESHOLD_96_BYTES + * - EMAC_DMA_RX_THRESHOLD_128_BYTES + * @retval none + */ +void emac_dma_receive_threshold_set(emac_dma_receive_threshold_type value) +{ + EMAC_DMA->opm_bit.rtc = value; +} + +/** + * @brief set transmit dma threshold + * @param value: transmit threshold + * this parameter can be one of the following values: + * - EMAC_DMA_TX_THRESHOLD_64_BYTES + * - EMAC_DMA_TX_THRESHOLD_128_BYTES + * - EMAC_DMA_TX_THRESHOLD_192_BYTES + * - EMAC_DMA_TX_THRESHOLD_256_BYTES + * - EMAC_DMA_TX_THRESHOLD_40_BYTES + * - EMAC_DMA_TX_THRESHOLD_32_BYTES + * - EMAC_DMA_TX_THRESHOLD_24_BYTES + * - EMAC_DMA_TX_THRESHOLD_16_BYTES + * @retval none + */ +void emac_dma_transmit_threshold_set(emac_dma_transmit_threshold_type value) +{ + EMAC_DMA->opm_bit.ttc = value; +} + +/** + * @brief enable dma interrupt + * @param it: interrupt type + * this parameter can be one of the following values: + * - EMAC_DMA_INTERRUPT_TX + * - EMAC_DMA_INTERRUPT_TX_STOP + * - EMAC_DMA_INTERRUPT_TX_UNAVAILABLE + * - EMAC_DMA_INTERRUPT_TX_JABBER + * - EMAC_DMA_INTERRUPT_RX_OVERFLOW + * - EMAC_DMA_INTERRUPT_TX_UNDERFLOW + * - EMAC_DMA_INTERRUPT_RX + * - EMAC_DMA_INTERRUPT_RX_UNAVAILABLE + * - EMAC_DMA_INTERRUPT_RX_STOP + * - EMAC_DMA_INTERRUPT_RX_TIMEOUT + * - EMAC_DMA_INTERRUPT_TX_EARLY + * - EMAC_DMA_INTERRUPT_FATAL_BUS_ERROR + * - EMAC_DMA_INTERRUPT_RX_EARLY + * - EMAC_DMA_INTERRUPT_ABNORMAL_SUMMARY + * - EMAC_DMA_INTERRUPT_NORMAL_SUMMARY + * @param new_state: TRUE or FALSE + * @retval none + */ +void emac_dma_interrupt_enable(emac_dma_interrupt_type it, confirm_state new_state) +{ + switch(it) + { + case EMAC_DMA_INTERRUPT_TX: + { + EMAC_DMA->ie_bit.tie = new_state; + break; + } + case EMAC_DMA_INTERRUPT_TX_STOP: + { + EMAC_DMA->ie_bit.tse = new_state; + break; + } + case EMAC_DMA_INTERRUPT_TX_UNAVAILABLE: + { + EMAC_DMA->ie_bit.tue = new_state; + break; + } + case EMAC_DMA_INTERRUPT_TX_JABBER: + { + EMAC_DMA->ie_bit.tje = new_state; + break; + } + case EMAC_DMA_INTERRUPT_RX_OVERFLOW: + { + EMAC_DMA->ie_bit.ove = new_state; + break; + } + case EMAC_DMA_INTERRUPT_TX_UNDERFLOW: + { + EMAC_DMA->ie_bit.une = new_state; + break; + } + case EMAC_DMA_INTERRUPT_RX: + { + EMAC_DMA->ie_bit.rie = new_state; + break; + } + case EMAC_DMA_INTERRUPT_RX_UNAVAILABLE: + { + EMAC_DMA->ie_bit.rbue = new_state; + break; + } + case EMAC_DMA_INTERRUPT_RX_STOP: + { + EMAC_DMA->ie_bit.rse = new_state; + break; + } + case EMAC_DMA_INTERRUPT_RX_TIMEOUT: + { + EMAC_DMA->ie_bit.rwte = new_state; + break; + } + case EMAC_DMA_INTERRUPT_TX_EARLY: + { + EMAC_DMA->ie_bit.eie = new_state; + break; + } + case EMAC_DMA_INTERRUPT_FATAL_BUS_ERROR: + { + EMAC_DMA->ie_bit.fbee = new_state; + break; + } + case EMAC_DMA_INTERRUPT_RX_EARLY: + { + EMAC_DMA->ie_bit.ere = new_state; + break; + } + case EMAC_DMA_INTERRUPT_ABNORMAL_SUMMARY: + { + EMAC_DMA->ie_bit.aie = new_state; + break; + } + case EMAC_DMA_INTERRUPT_NORMAL_SUMMARY: + { + EMAC_DMA->ie_bit.nie = new_state; + break; + } + } +} + +/** + * @brief get missed frames by the controller + * @param none + * @retval missed frames by the controller + */ +uint16_t emac_dma_controller_missing_frame_get(void) +{ + uint16_t number = EMAC_DMA->mfbocnt_bit.mfc; + return number; +} + +/** + * @brief get overflow bit for missed frame counter + * @param none + * @retval overflow bit for missed frame counter + */ +uint8_t emac_dma_missing_overflow_bit_get(void) +{ + uint8_t number = EMAC_DMA->mfbocnt_bit.obmfc; + return number; +} + +/** + * @brief get missed frames by the application + * @param none + * @retval missed frames by the application + */ +uint16_t emac_dma_application_missing_frame_get(void) +{ + uint16_t number = EMAC_DMA->mfbocnt_bit.ofc; + return number; +} + +/** + * @brief get overflow bit for FIFO overflow counter + * @param none + * @retval overflow bit for FIFO overflow counter + */ +uint8_t emac_dma_fifo_overflow_bit_get(void) +{ + uint8_t number = EMAC_DMA->mfbocnt_bit.obfoc; + return number; +} + +/** + * @brief get overflow bit for FIFO overflow counter + * @param transfer type: receive/transmit type + * this parameter can be one of the following values: + * - EMAC_DMA_TX_DESCRIPTOR + * - EMAC_DMA_RX_DESCRIPTOR + * - EMAC_DMA_TX_BUFFER + * - EMAC_DMA_RX_BUFFER + * @retval memory address + */ +uint32_t emac_dma_tansfer_address_get(emac_dma_transfer_address_type transfer_type) +{ + uint32_t address = 0; + + switch(transfer_type) + { + case EMAC_DMA_TX_DESCRIPTOR: + { + address = EMAC_DMA->ctd_bit.htdap; + break; + } + case EMAC_DMA_RX_DESCRIPTOR: + { + address = EMAC_DMA->crd_bit.hrdap; + break; + } + case EMAC_DMA_TX_BUFFER: + { + address = EMAC_DMA->ctbaddr_bit.htbap; + break; + } + case EMAC_DMA_RX_BUFFER: + { + address = EMAC_DMA->crbaddr_bit.hrbap; + break; + } + } + return address; +} + +/** + * @brief reset all counter + * @param none + * @retval none + */ +void emac_mmc_counter_reset(void) +{ + EMAC_MMC->ctrl_bit.rc = TRUE; +} + +/** + * @brief counter stop counting from zero when it reaches maximum + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_mmc_rollover_stop(confirm_state new_state) +{ + EMAC_MMC->ctrl_bit.scr = new_state; +} + +/** + * @brief enable reset on read + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_mmc_reset_on_read_enable(confirm_state new_state) +{ + EMAC_MMC->ctrl_bit.rr = new_state; +} + +/** + * @brief freeze mmc counter + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_mmc_counter_freeze(confirm_state new_state) +{ + EMAC_MMC->ctrl_bit.fmc = new_state; +} + +/** + * @brief interupt status of received frames + * @param flag: specifies the flag to check. + * this parameter can be one of the following values: + * - MMC_RX_CRC_ERROR + * - MMC_RX_ALIGN_ERROR + * - MMC_RX_GOOD_UNICAST + * @retval the new state of usart_flag (SET or RESET). + */ +flag_status emac_mmc_received_status_get(uint32_t flag) +{ + if(EMAC_MMC->ri & flag) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief interupt status of transmit frames + * @param transmit_type: transmit type. + * this parameter can be one of the following values: + * - MMC_TX_SINGLE_COL + * - MMC_TX_MULTIPLE_COL + * - MMC_TX_GOOD_FRAMES + * @retval the new state of usart_flag (SET or RESET). + */ +flag_status emac_mmc_transmit_status_get(uint32_t flag) +{ + if(EMAC_MMC->ti & flag) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief mask received mmc interrupt + * @param flag: specifies the flag to check. + * this parameter can be one of the following values: + * - MMC_RX_CRC_ERROR + * - MMC_RX_ALIGN_ERROR + * - MMC_RX_GOOD_UNICAST + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_mmc_received_interrupt_mask_set(uint32_t flag, confirm_state new_state) +{ + switch(flag) + { + case MMC_RX_CRC_ERROR: + { + EMAC_MMC->rim_bit.rcefcim = new_state; + break; + } + case MMC_RX_ALIGN_ERROR: + { + EMAC_MMC->rim_bit.raefacim = new_state; + break; + } + case MMC_RX_GOOD_UNICAST: + { + EMAC_MMC->rim_bit.rugfcim = new_state; + break; + } + } +} + +/** + * @brief mask transmit mmc interrupt + * @param transmit_type: transmit type. + * this parameter can be one of the following values: + * - MMC_TX_SINGLE_COL + * - MMC_TX_MULTIPLE_COL + * - MMC_TX_GOOD_FRAMES + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_mmc_transmit_interrupt_mask_set(uint32_t flag, confirm_state new_state) +{ + switch(flag) + { + case MMC_TX_SINGLE_COL: + { + EMAC_MMC->tim_bit.tscgfcim = new_state; + break; + } + case MMC_TX_MULTIPLE_COL: + { + EMAC_MMC->tim_bit.tmcgfcim = new_state; + break; + } + case MMC_TX_GOOD_FRAMES: + { + EMAC_MMC->tim_bit.tgfcim = new_state; + break; + } + } +} + +/** + * @brief get good frame numbers as single collision occurs. + * @param flag: specifies the flag to check. + * this parameter can be one of the following values: + * - MMC_TX_SINGLE_COL + * - MMC_TX_MULTIPLE_COL + * - MMC_TX_GOOD_FRAMES + * @retval good frames + */ +uint32_t emac_mmc_transmit_good_frames_get(uint32_t flag) +{ + uint32_t good_frames = MMC_TX_GOOD_FRAMES; + + switch(flag) + { + case MMC_TX_SINGLE_COL: + { + good_frames = EMAC_MMC->tfscc_bit.tgfscc; + break; + } + case MMC_TX_MULTIPLE_COL: + { + good_frames = EMAC_MMC->tfmscc_bit.tgfmscc; + break; + } + case MMC_TX_GOOD_FRAMES: + { + good_frames = EMAC_MMC->tfcnt_bit.tgfc; + break; + } + } + return good_frames; +} + +/** + * @brief get good frame numbers as single collision occurs. + * @param flag: specifies the flag to check. + * this parameter can be one of the following values: + * - MMC_RX_CRC_ERROR + * - MMC_RX_ALIGN_ERROR + * - MMC_RX_GOOD_UNICAST + * @retval good frames + */ +uint32_t emac_mmc_received_error_frames_get(uint32_t flag) +{ + uint32_t error_frames = MMC_RX_GOOD_UNICAST; + + switch(flag) + { + case MMC_RX_CRC_ERROR: + { + error_frames = EMAC_MMC->rfcecnt_bit.rfcec; + break; + } + case MMC_RX_ALIGN_ERROR: + { + error_frames = EMAC_MMC->rfaecnt_bit.rfaec; + break; + } + case MMC_RX_GOOD_UNICAST: + { + error_frames = EMAC_MMC->rgufcnt_bit.rgufc; + break; + } + } + return error_frames; +} + +/** + * @brief enable timestamp. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_ptp_timestamp_enable(confirm_state new_state) +{ + EMAC_PTP->tsctrl_bit.te = new_state; +} + +/** + * @brief enable timestamp fine update. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_ptp_timestamp_fine_update_enable(confirm_state new_state) +{ + EMAC_PTP->tsctrl_bit.tfcu = new_state; +} + +/** + * @brief initialize timestamp time system. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_ptp_timestamp_system_time_init(confirm_state new_state) +{ + EMAC_PTP->tsctrl_bit.ti = new_state; +} + +/** + * @brief update timestamp time system. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_ptp_timestamp_system_time_update(confirm_state new_state) +{ + EMAC_PTP->tsctrl_bit.tu = new_state; +} + +/** + * @brief enable timestamp interrupt trigger. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_ptp_interrupt_trigger_enable(confirm_state new_state) +{ + EMAC_PTP->tsctrl_bit.tite = new_state; +} + +/** + * @brief update timestamp addend register. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_ptp_addend_register_update(confirm_state new_state) +{ + EMAC_PTP->tsctrl_bit.aru = new_state; +} + +/** + * @brief enable timestamp snapshot for all received frames. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_ptp_snapshot_received_frames_enable(confirm_state new_state) +{ + EMAC_PTP->tsctrl_bit.etaf = new_state; +} + +/** + * @brief enable digital rollover. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_ptp_subsecond_rollover_enable(confirm_state new_state) +{ + EMAC_PTP->tsctrl_bit.tdbrc = new_state; +} + +/** + * @brief enable packet snooping for version 2. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_ptp_psv2_enable(confirm_state new_state) +{ + EMAC_PTP->tsctrl_bit.eppv2f = new_state; +} + +/** + * @brief enable snapshot over emac. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_ptp_snapshot_emac_frames_enable(confirm_state new_state) +{ + EMAC_PTP->tsctrl_bit.eppef = new_state; +} + +/** + * @brief enable snapshot for ipv6 frames. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_ptp_snapshot_ipv6_frames_enable(confirm_state new_state) +{ + EMAC_PTP->tsctrl_bit.eppfsip6u = new_state; +} + +/** + * @brief enable snapshot for ipv4 frames. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_ptp_snapshot_ipv4_frames_enable(confirm_state new_state) +{ + EMAC_PTP->tsctrl_bit.eppfsip4u = new_state; +} + +/** + * @brief enable snapshot for event message. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_ptp_snapshot_event_message_enable(confirm_state new_state) +{ + EMAC_PTP->tsctrl_bit.etsfem = new_state; +} + +/** + * @brief enable snapshot for message relevant to master + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_ptp_snapshot_master_event_enable(confirm_state new_state) +{ + EMAC_PTP->tsctrl_bit.esfmrtm = new_state; +} + +/** + * @brief set clock node type + * @param node: select ptp packets for taking snapshot + * this parameter can be one of the following values: + * - EMAC_PTP_NORMAL_CLOCK + * - EMAC_PTP_BOUNDARY_CLOCK + * - EMAC_PTP_END_TO_END_CLOCK + * - EMAC_PTP_PEER_TO_PEER_CLOCK + * @retval none + */ +void emac_ptp_clock_node_set(emac_ptp_clock_node_type node) +{ + EMAC_PTP->tsctrl_bit.sppfts = node; +} + +/** + * @brief enable ptp frame filtering mac address + * @param new_state: TRUE or FALSE. + * @retval none + */ +void emac_ptp_mac_address_filter_enable(confirm_state new_state) +{ + EMAC_PTP->tsctrl_bit.emafpff = new_state; +} + +/** + * @brief set subsecond increment value + * @param value: add to subsecond value for every update + * @retval none + */ +void emac_ptp_subsecond_increment_set(uint8_t value) +{ + EMAC_PTP->ssinc_bit.ssiv = value; +} + +/** + * @brief get system time second + * @param none + * @retval system time second + */ +uint32_t emac_ptp_system_second_get(void) +{ + uint32_t second = EMAC_PTP->tsh_bit.ts; + return second; +} + +/** + * @brief get system time subsecond + * @param none + * @retval system time subsecond + */ +uint32_t emac_ptp_system_subsecond_get(void) +{ + uint32_t subsecond = EMAC_PTP->tsl_bit.tss; + return subsecond; +} + +/** + * @brief get system time sign + * @param none + * @retval TRUE or FALSE + */ +confirm_state emac_ptp_system_time_sign_get(void) +{ + if(EMAC_PTP->tsl_bit.ast) + { + return TRUE; + } + else + { + return FALSE; + } +} + +/** + * @brief set system time second + * @param second: system time second + * @retval none + */ +void emac_ptp_system_second_set(uint32_t second) +{ + EMAC_PTP->tshud_bit.ts = second; +} + +/** + * @brief set system time subsecond + * @param subsecond: system time subsecond + * @retval none + */ +void emac_ptp_system_subsecond_set(uint32_t subsecond) +{ + EMAC_PTP->tslud_bit.tss = subsecond; +} + +/** + * @brief set system time sign + * @param sign: TRUE or FALSE. + * @retval none + */ +void emac_ptp_system_time_sign_set(confirm_state sign) +{ + if(sign) + { + EMAC_PTP->tslud_bit.ast = 1; + } + else + { + EMAC_PTP->tslud_bit.ast = 0; + } +} + +/** + * @brief set time stamp addend + * @param value: to achieve time synchronization + * @retval none + */ +void emac_ptp_timestamp_addend_set(uint32_t value) +{ + EMAC_PTP->tsad_bit.tar = value; +} + +/** + * @brief set target time stamp high + * @param value: to set target time second + * @retval none + */ +void emac_ptp_target_second_set(uint32_t value) +{ + EMAC_PTP->tth_bit.ttsr = value; +} + +/** + * @brief set target time stamp low + * @param value: to set target time nanosecond + * @retval none + */ +void emac_ptp_target_nanosecond_set(uint32_t value) +{ + EMAC_PTP->ttl_bit.ttlr = value; +} + +/** + * @brief set target time stamp low + * @param status: type of status + * this parameter can be one of the following values: + * - EMAC_PTP_SECOND_OVERFLOW + * - EMAC_PTP_TARGET_TIME_REACH + * @retval TRUE or FALSE + */ +confirm_state emac_ptp_timestamp_status_get(emac_ptp_timestamp_status_type status) +{ + switch(status) + { + case EMAC_PTP_SECOND_OVERFLOW: + { + if(EMAC_PTP->tssr_bit.tso) + { + return TRUE; + } + else + { + return FALSE; + } + } + case EMAC_PTP_TARGET_TIME_REACH: + { + if(EMAC_PTP->tssr_bit.tttr) + { + return TRUE; + } + else + { + return FALSE; + } + } + } + return FALSE; +} + +/** + * @brief set pps frequency + * @param freq: pps frequency + * this parameter can be one of the following values: + * - EMAC_PTP_PPS_1HZ + * - EMAC_PTP_PPS_2HZ + * - EMAC_PTP_PPS_4HZ + * - EMAC_PTP_PPS_8HZ + * - EMAC_PTP_PPS_16HZ + * - EMAC_PTP_PPS_32HZ + * - EMAC_PTP_PPS_64HZ + * - EMAC_PTP_PPS_128HZ + * - EMAC_PTP_PPS_256HZ + * - EMAC_PTP_PPS_512HZ + * - EMAC_PTP_PPS_1024HZ + * - EMAC_PTP_PPS_2048HZ + * - EMAC_PTP_PPS_4096HZ + * - EMAC_PTP_PPS_8192HZ + * - EMAC_PTP_PPS_16384HZ + * - EMAC_PTP_PPS_32768HZ + * @retval none + */ +void emac_ptp_pps_frequency_set(emac_ptp_pps_control_type freq) +{ + EMAC_PTP->ppscr_bit.pofc = freq; +} + +/** + * @brief this is delay function base on system clock. + * @param delay: delay time + * @retval none + */ +static void emac_delay(uint32_t delay) +{ + __IO uint32_t delay_time = delay * (system_core_clock / 8 / 1000); + do + { + __NOP(); + } + while(delay_time --); +} + +/** + * @brief check whether the specified emac dma flag is set or not. + * @param dma_flag: specifies the emac dma flag to check. + * this parameter can be one of emac dma flag status: + * - EMAC_DMA_TI_FLAG + * - EMAC_DMA_TPS_FLAG + * - EMAC_DMA_TBU_FLAG + * - EMAC_DMA_TJT_FLAG + * - EMAC_DMA_OVF_FLAG + * - EMAC_DMA_UNF_FLAG + * - EMAC_DMA_RI_FLAG + * - EMAC_DMA_RBU_FLAG + * - EMAC_DMA_RPS_FLAG + * - EMAC_DMA_RWT_FLAG + * - EMAC_DMA_ETI_FLAG + * - EMAC_DMA_FBEI_FLAG + * - EMAC_DMA_ERI_FLAG + * - EMAC_DMA_AIS_FLAG + * - EMAC_DMA_NIS_FLAG + * @retval the new state of dma_flag (SET or RESET). + */ +flag_status emac_dma_flag_get(uint32_t dma_flag) +{ + flag_status status = RESET; + + if(EMAC_DMA->sts & dma_flag) + status = SET; + /* return the new state (SET or RESET) */ + return status; +} + +/** + * @brief clear the emac dma flag. + * @param dma_flag: specifies the emac dma flags to clear. + * this parameter can be any combination of the following values: + * - EMAC_DMA_TI_FLAG + * - EMAC_DMA_TPS_FLAG + * - EMAC_DMA_TBU_FLAG + * - EMAC_DMA_TJT_FLAG + * - EMAC_DMA_OVF_FLAG + * - EMAC_DMA_UNF_FLAG + * - EMAC_DMA_RI_FLAG + * - EMAC_DMA_RBU_FLAG + * - EMAC_DMA_RPS_FLAG + * - EMAC_DMA_RWT_FLAG + * - EMAC_DMA_ETI_FLAG + * - EMAC_DMA_FBEI_FLAG + * - EMAC_DMA_ERI_FLAG + * - EMAC_DMA_AIS_FLAG + * - EMAC_DMA_NIS_FLAG + * @retval none + */ +void emac_dma_flag_clear(uint32_t dma_flag) +{ + EMAC_DMA->sts = dma_flag; +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +#endif + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_ertc.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_ertc.c new file mode 100644 index 0000000000..d09528481d --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_ertc.c @@ -0,0 +1,1571 @@ +/** + ************************************************************************** + * @file at32f435_437_ertc.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the ertc firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup ERTC + * @brief ERTC driver modules + * @{ + */ + +#ifdef ERTC_MODULE_ENABLED + +/** @defgroup ERTC_private_functions + * @{ + */ + +#define ERTC_TIMEOUT ((uint32_t) 0x00360000) + +/** + * @brief number conversion to bcd code. + * @param num: number(0~99) + * @retval bcd code. + */ +uint8_t ertc_num_to_bcd(uint8_t num) +{ + uint8_t bcd_h = 0, bcd_l = 0; + + bcd_h = num / 10; + bcd_l = num % 10; + + return ((uint8_t)(bcd_h << 4) | bcd_l); +} + +/** + * @brief bcd code conversion to number. + * @param bcd: bcd code(0~99). + * @retval number. + */ +uint8_t ertc_bcd_to_num(uint8_t bcd) +{ + return ((((uint8_t)(bcd & (uint8_t)0xF0) >> 4) * 10) + (bcd & (uint8_t)0x0F)); +} + +/** + * @brief enable write protection. + * @param none. + * @retval none + */ +void ertc_write_protect_enable(void) +{ + ERTC->wp = 0xFF; +} + +/** + * @brief disable write protection. + * @param none. + * @retval none + */ +void ertc_write_protect_disable(void) +{ + ERTC->wp = 0xCA; + ERTC->wp = 0x53; +} + +/** + * @brief ertc wait register update finish. + * @param none. + * @retval error_status (ERROR or SUCCESS). + */ +error_status ertc_wait_update(void) +{ + uint32_t timeout = ERTC_TIMEOUT * 2; + + /* disable write protection */ + ertc_write_protect_disable(); + + /* clear updf flag */ + ERTC->sts = ~(ERTC_UPDF_FLAG | 0x00000080) | (ERTC->sts_bit.imen << 7); + + /* enable write protection */ + ertc_write_protect_enable(); + + while(ERTC->sts_bit.updf == 0) + { + if(timeout == 0) + { + return ERROR; + } + + timeout--; + } + + return SUCCESS; +} + +/** + * @brief ertc wait flag status. + * @param flag: flag to wait. + * this parameter can be one of the following values: + * - ERTC_ALAWF_FLAG: alarm a register allows write flag. + * - ERTC_ALBWF_FLAG: alarm b register allows write flag. + * - ERTC_WATWF_FLAG: wakeup timer register allows write flag. + * - ERTC_TADJF_FLAG: time adjustment flag. + * - ERTC_CALUPDF_FLAG: calibration value update completed flag. + * @param status: status to wait. + * this parameter can be one of the following values: + * - SET. + * - RESET. + * @retval error_status (ERROR or SUCCESS). + */ +error_status ertc_wait_flag(uint32_t flag, flag_status status) +{ + uint32_t timeout = ERTC_TIMEOUT; + + while(ertc_flag_get(flag) == status) + { + if(timeout == 0) + { + /* enable write protection */ + ertc_write_protect_enable(); + + return ERROR; + } + + timeout--; + } + + return SUCCESS; +} + +/** + * @brief ertc enter init mode. + * @param none. + * @retval error_status (ERROR or SUCCESS). + */ +error_status ertc_init_mode_enter(void) +{ + uint32_t timeout = ERTC_TIMEOUT * 2; + + /* disable write protection */ + ertc_write_protect_disable(); + + if(ERTC->sts_bit.imf == 0) + { + /* enter init mode */ + ERTC->sts = 0xFFFFFFFF; + + while(ERTC->sts_bit.imf == 0) + { + if(timeout == 0) + { + /* enable write protection */ + ertc_write_protect_enable(); + + return ERROR; + } + + timeout--; + } + } + + return SUCCESS; +} + +/** + * @brief ertc exit init mode. + * @param none. + * @retval none. + */ +void ertc_init_mode_exit(void) +{ + ERTC->sts = 0xFFFFFF7F; +} + +/** + * @brief ertc reset all register. + * @param none. + * @retval error_status (ERROR or SUCCESS). + */ +error_status ertc_reset(void) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + ERTC->ctrl = (uint32_t)0x00000000; + + /* enter init mode */ + if(ertc_init_mode_enter() != SUCCESS) + { + return ERROR; + } + + /* reset register */ + ERTC->time = (uint32_t)0x00000000; + ERTC->date = (uint32_t)0x00002101; + ERTC->ctrl = (uint32_t)0x00000000; + ERTC->div = (uint32_t)0x007F00FF; + ERTC->wat = (uint32_t)0x0000FFFF; + ERTC->ccal = (uint32_t)0x00000000; + ERTC->ala = (uint32_t)0x00000000; + ERTC->alb = (uint32_t)0x00000000; + ERTC->tadj = (uint32_t)0x00000000; + ERTC->scal = (uint32_t)0x00000000; + ERTC->tamp = (uint32_t)0x00000000; + ERTC->alasbs = (uint32_t)0x00000000; + ERTC->albsbs = (uint32_t)0x00000000; + ERTC->sts = (uint32_t)0x00000000; + + /* wait calendar update */ + ertc_wait_update(); + + /* enable write protection */ + ertc_write_protect_enable(); + + return SUCCESS; +} + +/** + * @brief ertc division set. + * @param div_a: division a (0~0x7F). + * @param div_b: division b (0~0x7FFF). + * @retval error_status (ERROR or SUCCESS). + */ +error_status ertc_divider_set(uint16_t div_a, uint16_t div_b) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + /* enter init mode */ + if(ertc_init_mode_enter() != SUCCESS) + { + return ERROR; + } + + /* config the ertc divider */ + ERTC->div_bit.diva = div_a; + ERTC->div_bit.divb = div_b; + + /* exit init mode */ + ertc_init_mode_exit(); + + /* enable write protection */ + ertc_write_protect_enable(); + + return SUCCESS; +} + +/** + * @brief ertc hour mode set. + * @param mode: hour mode. + * this parameter can be one of the following values: + * - ERTC_HOUR_MODE_24: 24-hour format. + * - ERTC_HOUR_MODE_12: 12-hour format. + * @retval error_status (ERROR or SUCCESS). + */ +error_status ertc_hour_mode_set(ertc_hour_mode_set_type mode) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + /* enter init mode */ + if(ertc_init_mode_enter() != SUCCESS) + { + return ERROR; + } + + /* write register */ + ERTC->ctrl_bit.hm = mode; + + /* exit init mode */ + ertc_init_mode_exit(); + + /* enable write protection */ + ertc_write_protect_enable(); + + return SUCCESS; +} + +/** + * @brief set date. + * @param year: year (0~99). + * @param month: month (1~12). + * @param date: date (1~31). + * @param week: week (1~7). + * @retval error_status (ERROR or SUCCESS). + */ +error_status ertc_date_set(uint8_t year, uint8_t month, uint8_t date, uint8_t week) +{ + ertc_reg_date_type reg; + + reg.date = 0; + + reg.date_bit.y = ertc_num_to_bcd(year); + reg.date_bit.m = ertc_num_to_bcd(month); + reg.date_bit.d = ertc_num_to_bcd(date); + reg.date_bit.wk = week; + + /* disable write protection */ + ertc_write_protect_disable(); + + /* enter init mode */ + if(ertc_init_mode_enter() != SUCCESS) + { + return ERROR; + } + + /* Set the ertc_DR register */ + ERTC->date = reg.date; + + /* exit init mode */ + ertc_init_mode_exit(); + + if(ERTC->ctrl_bit.dren == 0) + { + ertc_wait_update(); + } + + /* enable write protection */ + ertc_write_protect_enable(); + + return SUCCESS; +} + +/** + * @brief set time. + * @param hour: hour (0~23). + * @param min: minute (0~59). + * @param sec: second (0~59). + * @param ampm: hour mode. + * this parameter can be one of the following values: + * - ERTC_24H: 24-hour format. + * - ERTC_AM: 12-hour format, ante meridiem. + * - ERTC_PM: 12-hour format, post meridiem. + * @retval error_status (ERROR or SUCCESS). + */ +error_status ertc_time_set(uint8_t hour, uint8_t min, uint8_t sec, ertc_am_pm_type ampm) +{ + ertc_reg_time_type reg; + + reg.time = 0; + + reg.time_bit.h = ertc_num_to_bcd(hour); + reg.time_bit.m = ertc_num_to_bcd(min); + reg.time_bit.s = ertc_num_to_bcd(sec); + reg.time_bit.ampm = ampm; + + /* disable write protection */ + ertc_write_protect_disable(); + + /* enter init mode */ + if(ertc_init_mode_enter() != SUCCESS) + { + return ERROR; + } + + ERTC->time = reg.time; + + /* exit init mode */ + ertc_init_mode_exit(); + + if(ERTC->ctrl_bit.dren == 0) + { + ertc_wait_update(); + } + + /* enable write protection */ + ertc_write_protect_enable(); + + return SUCCESS; +} + +/** + * @brief get calendar + * @param time: ertc time. + * @retval none. + */ +void ertc_calendar_get(ertc_time_type* time) +{ + ertc_reg_time_type reg_tm; + ertc_reg_date_type reg_dt; + + UNUSED(ERTC->sts); + + reg_tm.time = ERTC->time; + reg_dt.date = ERTC->date; + + time->hour = ertc_bcd_to_num(reg_tm.time_bit.h); + time->min = ertc_bcd_to_num(reg_tm.time_bit.m); + time->sec = ertc_bcd_to_num(reg_tm.time_bit.s); + time->ampm = (ertc_am_pm_type)reg_tm.time_bit.ampm; + + time->year = ertc_bcd_to_num(reg_dt.date_bit.y); + time->month = ertc_bcd_to_num(reg_dt.date_bit.m); + time->day = ertc_bcd_to_num(reg_dt.date_bit.d); + time->week = reg_dt.date_bit.wk; +} + +/** + * @brief get current sub second. + * @param none. + * @retval sub second. + */ +uint32_t ertc_sub_second_get(void) +{ + uint32_t reg = 0; + + reg = ERTC->sbs; + + (void) (ERTC->date); + + return (reg); +} + +/** + * @brief set which bits are irrelevant to the alarm match. + * @param alarm_x: select the alarm. + * this parameter can be one of the following values: + * - ERTC_ALA: alarm a. + * - ERTC_ALB: alarm b. + * @param mask: select which bits are irrelevant to the alarm match. + * this parameter can be one of the following values: + * - ERTC_ALARM_MASK_NONE: match all. + * - ERTC_ALARM_MASK_SEC: don't match seconds. + * - ERTC_ALARM_MASK_MIN: don't match minute. + * - ERTC_ALARM_MASK_HOUR: don't match hour. + * - ERTC_ALARM_MASK_DATE_WEEK: don't match date or week. + * - ERTC_ALARM_MASK_ALL: don't match all. + * @param alarm: alarm para. + * @retval none. + */ +void ertc_alarm_mask_set(ertc_alarm_type alarm_x, uint32_t mask) +{ + uint32_t reg; + + /* disable write protection */ + ertc_write_protect_disable(); + + if(alarm_x == ERTC_ALA) + { + reg = ERTC->ala; + + reg &= ~ERTC_ALARM_MASK_ALL; + reg |= mask; + + ERTC->ala= reg; + } + else + { + reg = ERTC->alb; + + reg &= ~ERTC_ALARM_MASK_ALL; + reg |= mask; + + ERTC->alb= reg; + } + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief alarm week or date mode select. + * @param alarm_x: select the alarm. + * this parameter can be one of the following values: + * - ERTC_ALA: alarm a. + * - ERTC_ALB: alarm b. + * @param wk: week or date mode select. + * this parameter can be one of the following values: + * - ERTC_SLECT_DATE: slect date mode. + * - ERTC_SLECT_WEEK: slect week mode. + * @retval none. + */ +void ertc_alarm_week_date_select(ertc_alarm_type alarm_x, ertc_week_date_select_type wk) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + if(alarm_x == ERTC_ALA) + { + ERTC->ala_bit.wksel = wk; + } + else + { + ERTC->alb_bit.wksel = wk; + } + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief set alarm. + * @param alarm_x: select the alarm. + * this parameter can be one of the following values: + * - ERTC_ALA: alarm a. + * - ERTC_ALB: alarm b. + * @param week_day: week or date. + * - week: 1~7. + * - date: 1~31. + * @param hour: hour (0~23). + * @param min: minute (0~59). + * @param sec: second (0~59). + * @param ampm: hour mode. + * this parameter can be one of the following values: + * - ERTC_24H: 24-hour format. + * - ERTC_AM: 12-hour format, ante meridiem. + * - ERTC_PM: 12-hour format, post meridiem. + * @param alarm: alarm para. + * @retval none. + */ +void ertc_alarm_set(ertc_alarm_type alarm_x, uint8_t week_date, uint8_t hour, uint8_t min, uint8_t sec, ertc_am_pm_type ampm) +{ + ertc_reg_alarm_type reg; + + if(alarm_x == ERTC_ALA) + { + reg.ala = ERTC->ala; + } + else + { + reg.ala = ERTC->alb; + } + + reg.ala_bit.d = ertc_num_to_bcd(week_date); + reg.ala_bit.h = ertc_num_to_bcd(hour); + reg.ala_bit.m = ertc_num_to_bcd(min); + reg.ala_bit.s = ertc_num_to_bcd(sec); + reg.ala_bit.ampm = ampm; + + /* disable write protection */ + ertc_write_protect_disable(); + + if(alarm_x == ERTC_ALA) + { + ERTC->ala= reg.ala; + } + else + { + ERTC->alb = reg.ala; + } + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief set alarm sub second. + * @param alarm_x: select the alarm. + * this parameter can be one of the following values: + * - ERTC_ALA: alarm a. + * - ERTC_ALB: alarm b. + * @param value: sub second value. + * @param mask: sub second mask. + * this parameter can be one of the following values: + * - ERTC_ALARM_SBS_MASK_ALL: do not match the sub-second. + * - ERTC_ALARM_SBS_MASK_14_1: only compare bit [0]. + * - ERTC_ALARM_SBS_MASK_14_2: only compare bit [1:0]. + * - ERTC_ALARM_SBS_MASK_14_3: only compare bit [2:0]. + * - ERTC_ALARM_SBS_MASK_14_4: only compare bit [3:0]. + * - ERTC_ALARM_SBS_MASK_14_5: only compare bit [4:0]. + * - ERTC_ALARM_SBS_MASK_14_6: only compare bit [5:0]. + * - ERTC_ALARM_SBS_MASK_14_7: only compare bit [6:0]. + * - ERTC_ALARM_SBS_MASK_14_8: only compare bit [7:0]. + * - ERTC_ALARM_SBS_MASK_14_9: only compare bit [8:0]. + * - ERTC_ALARM_SBS_MASK_14_10: only compare bit [9:0]. + * - ERTC_ALARM_SBS_MASK_14_11: only compare bit [10:0]. + * - ERTC_ALARM_SBS_MASK_14_12: only compare bit [11:0]. + * - ERTC_ALARM_SBS_MASK_14_13: only compare bit [12:0]. + * - ERTC_ALARM_SBS_MASK_14: only compare bit [13:0]. + * - ERTC_ALARM_SBS_MASK_NONE: compare bit [14:0]. + * @retval none. + */ +void ertc_alarm_sub_second_set(ertc_alarm_type alarm_x, uint32_t value, ertc_alarm_sbs_mask_type mask) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + if(alarm_x == ERTC_ALA) + { + ERTC->alasbs_bit.sbsmsk = mask; + ERTC->alasbs_bit.sbs = value; + } + else + { + ERTC->albsbs_bit.sbsmsk = mask; + ERTC->albsbs_bit.sbs = value; + } + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief enable or disable alarm clock. + * @param alarm_x: select the alarm. + * this parameter can be one of the following values: + * - ERTC_ALA: alarm a. + * - ERTC_ALB: alarm b. + * @param new_state (TRUE or FALSE). + * @retval error_status (ERROR or SUCCESS). + */ +error_status ertc_alarm_enable(ertc_alarm_type alarm_x, confirm_state new_state) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + if(alarm_x == ERTC_ALA) + { + ERTC->ctrl_bit.alaen = new_state; + + if(new_state == FALSE) + { + if(ertc_wait_flag(ERTC_ALAWF_FLAG, RESET) != SUCCESS) + { + return ERROR; + } + } + } + else + { + ERTC->ctrl_bit.alben = new_state; + + if(new_state == FALSE) + { + if(ertc_wait_flag(ERTC_ALBWF_FLAG, RESET) != SUCCESS) + { + return ERROR; + } + } + } + + /* enable write protection */ + ertc_write_protect_enable(); + + return SUCCESS; +} + +/** + * @brief get alarm value. + * @param alarm_x: select the alarm. + * this parameter can be one of the following values: + * - ERTC_ALA: alarm a. + * - ERTC_ALB: alarm b. + * @param alarm: alarm para. + * @retval none. + */ +void ertc_alarm_get(ertc_alarm_type alarm_x, ertc_alarm_value_type* alarm) +{ + ertc_reg_alarm_type reg; + + reg.ala = 0; + + if(alarm_x == ERTC_ALA) + { + reg.ala = ERTC->ala; + } + else + { + reg.ala = ERTC->alb; + } + + alarm->day = ertc_bcd_to_num(reg.ala_bit.d); + alarm->week = ertc_bcd_to_num(reg.ala_bit.d); + alarm->hour = ertc_bcd_to_num(reg.ala_bit.h); + alarm->min = ertc_bcd_to_num(reg.ala_bit.m); + alarm->sec = ertc_bcd_to_num(reg.ala_bit.s); + alarm->ampm = (ertc_am_pm_type)reg.ala_bit.ampm; + alarm->week_date_sel = reg.ala_bit.wksel; + alarm->mask = reg.ala & ERTC_ALARM_MASK_ALL; +} + +/** + * @brief get alarm sub second. + * @param alarm_x: select the alarm. + * this parameter can be one of the following values: + * - ERTC_ALA: alarm a. + * - ERTC_ALB: alarm b. + * @retval sub second. + */ +uint32_t ertc_alarm_sub_second_get(ertc_alarm_type alarm_x) +{ + if(alarm_x == ERTC_ALA) + { + return (ERTC->alasbs_bit.sbs); + } + else + { + return (ERTC->albsbs_bit.sbs); + } +} + +/** + * @brief set wakeup timer clock. + * @param clock: wakeup timer clock source. + * this parameter can be one of the following values: + * - ERTC_WAT_CLK_ERTCCLK_DIV16: ERTC_CLK / 16. + * - ERTC_WAT_CLK_ERTCCLK_DIV8: ERTC_CLK / 8. + * - ERTC_WAT_CLK_ERTCCLK_DIV4: ERTC_CLK / 4. + * - ERTC_WAT_CLK_ERTCCLK_DIV2: ERTC_CLK / 2. + * - ERTC_WAT_CLK_CK_B_16BITS: CK_B, wakeup counter = ERTC_WAT + * - ERTC_WAT_CLK_CK_B_17BITS: CK_B, wakeup counter = ERTC_WAT + 65535. + * @retval none. + */ +void ertc_wakeup_clock_set(ertc_wakeup_clock_type clock) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + ERTC->ctrl_bit.watclk = clock; + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief set wakeup counter. + * @param counter: wakeup counter(0~65535). + * @retval none. + */ +void ertc_wakeup_counter_set(uint32_t counter) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + ERTC->wat_bit.val = counter; + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief get wakeup counter. + * @param none. + * @retval wakeup counter. + */ +uint16_t ertc_wakeup_counter_get(void) +{ + return ERTC->wat_bit.val; +} + +/** + * @brief enable or disable wakeup timer. + * @param new_state (TRUE or FALSE). + * @retval error_status (ERROR or SUCCESS). + */ +error_status ertc_wakeup_enable(confirm_state new_state) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + ERTC->ctrl_bit.waten = new_state; + + if(new_state == FALSE) + { + if(ertc_wait_flag(ERTC_WATWF_FLAG, RESET) != SUCCESS) + { + return ERROR; + } + } + + /* enable write protection */ + ertc_write_protect_enable(); + + return SUCCESS; +} + +/** + * @brief config the smooth calibration. + * @param period: calibration period. + * this parameter can be one of the following values: + * - ERTC_SMOOTH_CAL_PERIOD_32: 32 second calibration period. + * - ERTC_SMOOTH_CAL_PERIOD_16: 16 second calibration period. + * - ERTC_SMOOTH_CAL_PERIOD_8: 8 second calibration period. + * @param clk_add: add clock. + * this parameter can be one of the following values: + * - ERTC_SMOOTH_CAL_CLK_ADD_0: do not increase clock. + * - ERTC_SMOOTH_CAL_CLK_ADD_512: add 512 clocks. + * @param clk_dec: decrease clock(0~511). + * @retval error_status (ERROR or SUCCESS). + */ +error_status ertc_smooth_calibration_config(ertc_smooth_cal_period_type period, ertc_smooth_cal_clk_add_type clk_add, uint32_t clk_dec) +{ + ertc_reg_scal_type reg; + + /* disable write protection */ + ertc_write_protect_disable(); + + if(ertc_wait_flag(ERTC_CALUPDF_FLAG, SET) != SUCCESS) + { + return ERROR; + } + + reg.scal = 0; + + switch (period) + { + case ERTC_SMOOTH_CAL_PERIOD_32: + break; + case ERTC_SMOOTH_CAL_PERIOD_16: + reg.scal_bit.cal16 = 1; + break; + case ERTC_SMOOTH_CAL_PERIOD_8: + reg.scal_bit.cal8 = 1; + break; + default: + break; + } + + reg.scal_bit.add = clk_add; + reg.scal_bit.dec = clk_dec; + + ERTC->scal = reg.scal; + + /* enable write protection */ + ertc_write_protect_enable(); + + return SUCCESS; +} + +/** + * @brief set the coarse digital calibration. + * @param dir: calibration direction. + * this parameter can be one of the following values: + * - ERTC_CAL_DIR_POSITIVE: positive calibration. + * - ERTC_CAL_DIR_NEGATIVE: negative calibration. + * @param value: calibration value(0~31). + * @retval error_status (ERROR or SUCCESS). + */ +error_status ertc_coarse_calibration_set(ertc_cal_direction_type dir, uint32_t value) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + /* enter init mode */ + if(ertc_init_mode_enter() == ERROR) + { + return ERROR; + } + + ERTC->ccal_bit.caldir = dir; + + ERTC->ccal_bit.calval = value; + + /* exit init mode */ + ertc_init_mode_exit(); + + /* enable write protection */ + ertc_write_protect_enable(); + + return SUCCESS; +} + +/** + * @brief enable or disable coarse calibration. + * @param new_state (TRUE or FALSE). + * @retval error_status (ERROR or SUCCESS). + */ +error_status ertc_coarse_calibration_enable(confirm_state new_state) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + /* enter init mode */ + if(ertc_init_mode_enter() == ERROR) + { + return ERROR; + } + + ERTC->ctrl_bit.ccalen = new_state; + + /* exit init mode */ + ertc_init_mode_exit(); + + /* enable write protection */ + ertc_write_protect_enable(); + + return SUCCESS; +} + +/** + * @brief calibration output source select. + * @param output: output source. + * this parameter can be one of the following values: + * - ERTC_CAL_OUTPUT_512HZ: output 512 hz. + * - ERTC_CAL_OUTPUT_1HZ: output 1 hz. + * @retval none. + */ +void ertc_cal_output_select(ertc_cal_output_select_type output) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + ERTC->ctrl_bit.calosel = output; + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief enable or disable calibration output. + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void ertc_cal_output_enable(confirm_state new_state) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + ERTC->ctrl_bit.caloen = new_state; + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief adjust the time. + * @param add1s: second operation. + * this parameter can be one of the following values: + * - ERTC_TIME_ADD_NONE: none operation. + * - ERTC_TIME_ADD_1S: add 1 second. + * @param decsbs: decrease sub second(0~0x7FFF). + * @retval error_status (ERROR or SUCCESS). + */ +error_status ertc_time_adjust(ertc_time_adjust_type add1s, uint32_t decsbs) +{ + ertc_reg_tadj_type reg; + + reg.tadj = 0; + + /* disable write protection */ + ertc_write_protect_disable(); + + if(ertc_wait_flag(ERTC_TADJF_FLAG, SET) != SUCCESS) + { + return ERROR; + } + + /* check if the reference clock detection is disabled */ + if(ERTC->ctrl_bit.rcden == 0) + { + reg.tadj_bit.add1s = add1s; + reg.tadj_bit.decsbs = decsbs; + + ERTC->tadj = reg.tadj; + + if(ertc_wait_update() == ERROR) + { + return ERROR; + } + } + else + { + return ERROR; + } + + /* enable write protection */ + ertc_write_protect_enable(); + + return SUCCESS; +} + +/** + * @brief config the daylight saving time. + * @param operation: time adjust. + * this parameter can be one of the following values: + * - ERTC_DST_ADD_1H: add 1 hour. + * - ERTC_DST_DEC_1H: dec 1 hour. + * @param save: operation save. + * this parameter can be one of the following values: + * - ERTC_DST_SAVE_0: set the bpr register value to 0. + * - ERTC_DST_SAVE_1: set the bpr register value to 1. + * @retval none. + */ +void ertc_daylight_set(ertc_dst_operation_type operation, ertc_dst_save_type save) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + if(operation == ERTC_DST_ADD_1H) + { + ERTC->ctrl_bit.add1h = 1; + } + else + { + ERTC->ctrl_bit.dec1h = 1; + } + + ERTC->ctrl_bit.bpr = save; + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief get the bpr value. + * @param none. + * @retval bpr value. + */ +uint8_t ertc_daylight_bpr_get(void) +{ + return ERTC->ctrl_bit.bpr; +} + +/** + * @brief enable or disable refer clock detect. + * @param new_state (TRUE or FALSE). + * @retval error_status (ERROR or SUCCESS). + */ +error_status ertc_refer_clock_detect_enable(confirm_state new_state) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + /* enter init mode */ + if(ertc_init_mode_enter() != SUCCESS) + { + return ERROR; + } + + /* write register */ + ERTC->ctrl_bit.rcden = new_state; + + /* exit init mode */ + ertc_init_mode_exit(); + + /* enable write protection */ + ertc_write_protect_enable(); + + return SUCCESS; +} + +/** + * @brief enable or disable direct read mode. + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void ertc_direct_read_enable(confirm_state new_state) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + ERTC->ctrl_bit.dren = new_state; + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief set the output mode. + * @param source: output source. + * this parameter can be one of the following values: + * - ERTC_OUTPUT_DISABLE: diable output. + * - ERTC_OUTPUT_ALARM_A: output alarm a event. + * - ERTC_OUTPUT_ALARM_B: output alarm b event. + * - ERTC_OUTPUT_WAKEUP: output wakeup event. + * @param polarity: output polarity. + * this parameter can be one of the following values: + * - ERTC_OUTPUT_POLARITY_HIGH: when the event occurs, the output is high. + * - ERTC_OUTPUT_POLARITY_LOW: when the event occurs, the output is low. + * @param type: output type. + * this parameter can be one of the following values: + * - ERTC_OUTPUT_TYPE_OPEN_DRAIN: open drain output. + * - ERTC_OUTPUT_TYPE_PUSH_PULL: push pull output. + * @retval none. + */ +void ertc_output_set(ertc_output_source_type source, ertc_output_polarity_type polarity, ertc_output_type type) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + ERTC->ctrl_bit.outp = polarity; + + ERTC->tamp_bit.outtype = type; + + ERTC->ctrl_bit.outsel = source; + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief timestamp detection pin selection. + * @param pin: data register + * this parameter can be one of the following values: + * - ERTC_PIN_PC13: pc13 is used as timestamp detection pin. + * - ERTC_PIN_PA0: pa0 is used as timestamp detection pin. + * @retval data value. + */ +void ertc_timestamp_pin_select(ertc_pin_select_type pin) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + ERTC->tamp_bit.tspin = pin; + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief set the timestamp valid edge. + * @param edge: calibration period. + * this parameter can be one of the following values: + * - ERTC_TIMESTAMP_EDGE_RISING : rising edge trigger. + * - ERTC_TIMESTAMP_EDGE_FALLING: falling edge trigger. + * @retval none. + */ +void ertc_timestamp_valid_edge_set(ertc_timestamp_valid_edge_type edge) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + ERTC->ctrl_bit.tsedg = edge; + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief enable or disable timestamp. + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void ertc_timestamp_enable(confirm_state new_state) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + ERTC->ctrl_bit.tsen = new_state; + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief get the timestamp. + * @param time: time. + * @param date: date. + * @retval none. + */ +void ertc_timestamp_get(ertc_time_type* time) +{ + ertc_reg_tstm_type tmtime; + ertc_reg_tsdt_type tmdate; + + tmtime.tstm = ERTC->tstm; + tmdate.tsdt = ERTC->tsdt; + + time->year = 0; + time->month = ertc_bcd_to_num(tmdate.tsdt_bit.m); + time->day = ertc_bcd_to_num(tmdate.tsdt_bit.d); + time->week = ertc_bcd_to_num(tmdate.tsdt_bit.wk); + time->hour = ertc_bcd_to_num(tmtime.tstm_bit.h); + time->min = ertc_bcd_to_num(tmtime.tstm_bit.m); + time->sec = ertc_bcd_to_num(tmtime.tstm_bit.s); + time->ampm = (ertc_am_pm_type)tmtime.tstm_bit.ampm; +} + +/** + * @brief get the timestamp sub second. + * @param none. + * @retval timestamp sub second. + */ +uint32_t ertc_timestamp_sub_second_get(void) +{ + return ERTC->tssbs_bit.sbs; +} + +/** + * @brief tamper 1 detection pin selection. + * @param pin: data register + * this parameter can be one of the following values: + * - ERTC_PIN_PC13: pc13 is used as tamper 1 detection pin. + * - ERTC_PIN_PA0: pa0 is used as tamper 1 detection pin. + * @retval data value. + */ +void ertc_tamper_1_pin_select(ertc_pin_select_type pin) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + ERTC->tamp_bit.tp1pin = pin; + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief enable or disable tamper pin pull up. + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void ertc_tamper_pull_up_enable(confirm_state new_state) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + ERTC->tamp_bit.tppu = !new_state; + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief set the tamper pin pre-charge time. + * @param precharge: tamper detection pre-charge time + * this parameter can be one of the following values: + * - ERTC_TAMPER_PR_1_ERTCCLK: pre-charge time is 1 ERTC_CLK. + * - ERTC_TAMPER_PR_2_ERTCCLK: pre-charge time is 2 ERTC_CLK. + * - ERTC_TAMPER_PR_4_ERTCCLK: pre-charge time is 4 ERTC_CLK. + * - ERTC_TAMPER_PR_8_ERTCCLK: pre-charge time is 8 ERTC_CLK. + * @retval none. + */ +void ertc_tamper_precharge_set(ertc_tamper_precharge_type precharge) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + ERTC->tamp_bit.tppr = precharge; + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief set the tamper filter time. + * @param filter: tamper filter. + * this parameter can be one of the following values: + * - ERTC_TAMPER_FILTER_DISABLE: disable filter function. + * - ERTC_TAMPER_FILTER_2: 2 consecutive samples arw valid, effective tamper event. + * - ERTC_TAMPER_FILTER_4: 4 consecutive samples arw valid, effective tamper event. + * - ERTC_TAMPER_FILTER_8: 8 consecutive samples arw valid, effective tamper event. + * @retval none. + */ +void ertc_tamper_filter_set(ertc_tamper_filter_type filter) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + ERTC->tamp_bit.tpflt = filter; + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief set the tamper detection frequency. + * @param freq: tamper detection frequency. + * this parameter can be one of the following values: + * - ERTC_TAMPER_FREQ_DIV_32768: ERTC_CLK / 32768. + * - ERTC_TAMPER_FREQ_DIV_16384: ERTC_CLK / 16384. + * - ERTC_TAMPER_FREQ_DIV_8192: ERTC_CLK / 8192. + * - ERTC_TAMPER_FREQ_DIV_4096: ERTC_CLK / 4096. + * - ERTC_TAMPER_FREQ_DIV_2048: ERTC_CLK / 2048. + * - ERTC_TAMPER_FREQ_DIV_1024: ERTC_CLK / 1024. + * - ERTC_TAMPER_FREQ_DIV_512: ERTC_CLK / 512. + * - ERTC_TAMPER_FREQ_DIV_256: ERTC_CLK / 256. + * @retval none. + */ +void ertc_tamper_detect_freq_set(ertc_tamper_detect_freq_type freq) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + ERTC->tamp_bit.tpfreq = freq; + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief set the tamper trigger. + * @param tamper_x: select the tamper. + * this parameter can be one of the following values: + * - ERTC_TAMPER_1: tamper 1. + * - ERTC_TAMPER_2: tamper 2. + * @param trigger: tamper valid edge. + * this parameter can be one of the following values: + * - ERTC_TAMPER_EDGE_RISING: rising gedge. + * - ERTC_TAMPER_EDGE_FALLING: falling gedge. + * - ERTC_TAMPER_EDGE_LOW: low level. + * - ERTC_TAMPER_EDGE_HIGH: high level. + * @param alarm: alarm para. + * @retval none. + */ +void ertc_tamper_valid_edge_set(ertc_tamper_select_type tamper_x, ertc_tamper_valid_edge_type trigger) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + if(tamper_x == ERTC_TAMPER_1) + { + ERTC->tamp_bit.tp1edg = trigger; + } + else + { + ERTC->tamp_bit.tp2edg = trigger; + } + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief enable or disable trigger timestamp when tamper event occurs. + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void ertc_tamper_timestamp_enable(confirm_state new_state) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + ERTC->tamp_bit.tptsen = new_state; + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief enable or disable tamper. + * @param tamper_x: select the tamper. + * this parameter can be one of the following values: + * - ERTC_TAMPER_1: tamper 1. + * - ERTC_TAMPER_2: tamper 2. + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void ertc_tamper_enable(ertc_tamper_select_type tamper_x, confirm_state new_state) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + if(tamper_x == ERTC_TAMPER_1) + { + ERTC->tamp_bit.tp1en = new_state; + } + else + { + ERTC->tamp_bit.tp2en = new_state; + } + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief enable or disable interrupt. + * @param source: interrupts sources + * this parameter can be any combination of the following values: + * - ERTC_TP_INT: tamper interrupt. + * - ERTC_ALA_INT: alarm a interrupt. + * - ERTC_ALB_INT: alarm b interrupt. + * - ERTC_WAT_INT: wakeup timer interrupt. + * - ERTC_TS_INT: timestamp interrupt. + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void ertc_interrupt_enable(uint32_t source, confirm_state new_state) +{ + /* disable write protection */ + ertc_write_protect_disable(); + + if(source & ERTC_TP_INT) + { + if(new_state != FALSE) + { + ERTC->tamp |= ERTC_TP_INT; + } + else + { + ERTC->tamp &= ~ERTC_TP_INT; + } + + source &= ~ERTC_TP_INT; + } + + if(new_state != FALSE) + { + ERTC->ctrl |= source; + } + else + { + ERTC->ctrl &= ~source; + } + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief get interrupt status + * @param source + * this parameter can be one of the following values: + * - ERTC_TP_INT: tamper interrupt. + * - ERTC_ALA_INT: alarm a interrupt. + * - ERTC_ALB_INT: alarm b interrupt. + * - ERTC_WAT_INT: wakeup timer interrupt. + * - ERTC_TS_INT: timestamp interrupt. + * @retval flag_status (SET or RESET) + */ +flag_status ertc_interrupt_get(uint32_t source) +{ + if(source & ERTC_TP_INT) + { + if((ERTC->tamp & ERTC_TP_INT) != RESET) + { + return SET; + } + else + { + return RESET; + } + } + + if((ERTC->ctrl & source) != RESET) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief get flag status. + * @param flag: specifies the flag to check. + * this parameter can be one of the following values: + * - ERTC_ALAWF_FLAG: alarm a register allows write flag. + * - ERTC_ALBWF_FLAG: alarm b register allows write flag. + * - ERTC_WATWF_FLAG: wakeup timer register allows write flag. + * - ERTC_TADJF_FLAG: time adjustment flag. + * - ERTC_INITF_FLAG: calendar initialization flag. + * - ERTC_UPDF_FLAG: calendar update flag. + * - ERTC_IMF_FLAG: enter initialization mode flag. + * - ERTC_ALAF_FLAG: alarm clock a flag. + * - ERTC_ALBF_FLAG: alarm clock b flag. + * - ERTC_WATF_FLAG: wakeup timer flag. + * - ERTC_TSF_FLAG: timestamp flag. + * - ERTC_TSOF_FLAG: timestamp overflow flag. + * - ERTC_TP1F_FLAG: tamper detection 1 flag. + * - ERTC_TP2F_FLAG: tamper detection 2 flag. + * - ERTC_CALUPDF_FLAG: calibration value update completed flag. + * @retval the new state of flag (SET or RESET). + */ +flag_status ertc_flag_get(uint32_t flag) +{ + if((ERTC->sts & flag) != (uint32_t)RESET) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief clear flag status + * @param flag: specifies the flag to clear. + * this parameter can be any combination of the following values: + * - ERTC_ALAWF_FLAG: alarm a register allows write flag. + * - ERTC_ALBWF_FLAG: alarm b register allows write flag. + * - ERTC_WATWF_FLAG: wakeup timer register allows write flag. + * - ERTC_TADJF_FLAG: time adjustment flag. + * - ERTC_INITF_FLAG: calendar initialization flag. + * - ERTC_UPDF_FLAG: calendar update flag. + * - ERTC_IMF_FLAG: enter initialization mode flag. + * - ERTC_ALAF_FLAG: alarm clock a flag. + * - ERTC_ALBF_FLAG: alarm clock b flag. + * - ERTC_WATF_FLAG: wakeup timer flag. + * - ERTC_TSF_FLAG: timestamp flag. + * - ERTC_TSOF_FLAG: timestamp overflow flag. + * - ERTC_TP1F_FLAG: tamper detection 1 flag. + * - ERTC_TP2F_FLAG: tamper detection 2 flag. + * - ERTC_CALUPDF_FLAG: calibration value update completed flag. + * @retval none + */ +void ertc_flag_clear(uint32_t flag) +{ + ERTC->sts = ~(flag | 0x00000080) | (ERTC->sts_bit.imen << 7); +} + +/** + * @brief write data to the bpr register. + * @param dt: data register + * this parameter can be one of the following values: + * - ERTC_DT1 + * - ERTC_DT2 + * - ... + * - ERTC_DT19 + * - ERTC_DT20 + * @param data: data to be write. + * @retval none. + */ +void ertc_bpr_data_write(ertc_dt_type dt, uint32_t data) +{ + __IO uint32_t reg = 0; + + reg = ERTC_BASE + 0x50 + (dt * 4); + + /* disable write protection */ + ertc_write_protect_disable(); + + *(__IO uint32_t *)reg = data; + + /* enable write protection */ + ertc_write_protect_enable(); +} + +/** + * @brief read data from bpr register. + * @param dt: data register + * this parameter can be one of the following values: + * - ERTC_DT1 + * - ERTC_DT2 + * - ... + * - ERTC_DT19 + * - ERTC_DT20 + * @retval data value. + */ +uint32_t ertc_bpr_data_read(ertc_dt_type dt) +{ + __IO uint32_t reg = 0; + + reg = ERTC_BASE + 0x50 + (dt * 4); + + return (*(__IO uint32_t *)reg); +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_exint.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_exint.c new file mode 100644 index 0000000000..31d55c0aff --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_exint.c @@ -0,0 +1,236 @@ +/** + ************************************************************************** + * @file at32f435_437_exint.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the exint firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup EXINT + * @brief EXINT driver modules + * @{ + */ + +#ifdef EXINT_MODULE_ENABLED + +/** @defgroup EXINT_private_functions + * @{ + */ + +/** + * @brief exint reset + * @param none + * @retval none + */ +void exint_reset(void) +{ + EXINT->inten = 0x00000000; + EXINT->polcfg1 = 0x00000000; + EXINT->polcfg2 = 0x00000000; + EXINT->evten = 0x00000000; + EXINT->intsts = 0x007FFFFF; +} + +/** + * @brief exint default para init + * @param exint_struct + * - to the structure of exint_init_type + * @retval none + */ +void exint_default_para_init(exint_init_type *exint_struct) +{ + exint_struct->line_enable = FALSE; + exint_struct->line_select = EXINT_LINE_NONE; + exint_struct->line_polarity = EXINT_TRIGGER_FALLING_EDGE; + exint_struct->line_mode = EXINT_LINE_EVENT; +} + +/** + * @brief exint init + * @param exint_struct + * - to the structure of exint_init_type + * @retval none + */ +void exint_init(exint_init_type *exint_struct) +{ + uint32_t line_index = 0; + line_index = exint_struct->line_select; + + EXINT->inten &= ~line_index; + EXINT->evten &= ~line_index; + + if(exint_struct->line_enable != FALSE) + { + if(exint_struct->line_mode == EXINT_LINE_INTERRUPUT) + { + EXINT->inten |= line_index; + } + else + { + EXINT->evten |= line_index; + } + + EXINT->polcfg1 &= ~line_index; + EXINT->polcfg2 &= ~line_index; + if(exint_struct->line_polarity == EXINT_TRIGGER_RISING_EDGE) + { + EXINT->polcfg1 |= line_index; + } + else if(exint_struct->line_polarity == EXINT_TRIGGER_FALLING_EDGE) + { + EXINT->polcfg2 |= line_index; + } + else + { + EXINT->polcfg1 |= line_index; + EXINT->polcfg2 |= line_index; + } + } +} + +/** + * @brief clear exint flag + * @param exint_line + * this parameter can be any combination of the following values: + * - EXINT_LINE_0 + * - EXINT_LINE_1 + * ... + * - EXINT_LINE_21 + * - EXINT_LINE_22 + * @retval none + */ +void exint_flag_clear(uint32_t exint_line) +{ + EXINT->intsts = exint_line; +} + +/** + * @brief get exint flag + * @param exint_line + * this parameter can be one of the following values: + * - EXINT_LINE_0 + * - EXINT_LINE_1 + * ... + * - EXINT_LINE_21 + * - EXINT_LINE_22 + * @retval the new state of exint flag(SET or RESET). + */ +flag_status exint_flag_get(uint32_t exint_line) +{ + flag_status status = RESET; + uint32_t exint_flag =0; + exint_flag = EXINT->intsts & exint_line; + if((exint_flag != (uint16_t)RESET)) + { + status = SET; + } + else + { + status = RESET; + } + return status; +} + +/** + * @brief generate exint software interrupt event + * @param exint_line + * this parameter can be one of the following values: + * - EXINT_LINE_0 + * - EXINT_LINE_1 + * ... + * - EXINT_LINE_21 + * - EXINT_LINE_22 + * @retval none + */ +void exint_software_interrupt_event_generate(uint32_t exint_line) +{ + EXINT->swtrg |= exint_line; +} + +/** + * @brief enable or disable exint interrupt + * @param exint_line + * this parameter can be any combination of the following values: + * - EXINT_LINE_0 + * - EXINT_LINE_1 + * ... + * - EXINT_LINE_21 + * - EXINT_LINE_22 + * @param new_state: new state of exint interrupt. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void exint_interrupt_enable(uint32_t exint_line, confirm_state new_state) +{ + if(new_state == TRUE) + { + EXINT->inten |= exint_line; + } + else + { + EXINT->inten &= ~exint_line; + } +} + +/** + * @brief enable or disable exint event + * @param exint_line + * this parameter can be any combination of the following values: + * - EXINT_LINE_0 + * - EXINT_LINE_1 + * ... + * - EXINT_LINE_21 + * - EXINT_LINE_22 + * @param new_state: new state of exint event. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void exint_event_enable(uint32_t exint_line, confirm_state new_state) +{ + if(new_state == TRUE) + { + EXINT->evten |= exint_line; + } + else + { + EXINT->evten &= ~exint_line; + } +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_flash.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_flash.c new file mode 100644 index 0000000000..6aa059555d --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_flash.c @@ -0,0 +1,1158 @@ +/** + ************************************************************************** + * @file at32f435_437_flash.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the flash firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup FLASH + * @brief FLASH driver modules + * @{ + */ + +#ifdef FLASH_MODULE_ENABLED + +/** @defgroup FLASH_private_functions + * @{ + */ + +/** + * @brief check whether the specified flash flag is set or not. + * @param flash_flag: specifies the flash flag to check. + * this parameter can be one of flash flag status: + * - FLASH_OBF_FLAG + * - FLASH_ODF_FLAG + * - FLASH_PRGMERR_FLAG + * - FLASH_EPPERR_FLAG + * - FLASH_BANK1_OBF_FLAG + * - FLASH_BANK1_ODF_FLAG + * - FLASH_BANK1_PRGMERR_FLAG + * - FLASH_BANK1_EPPERR_FLAG + * - FLASH_BANK2_OBF_FLAG + * - FLASH_BANK2_ODF_FLAG + * - FLASH_BANK2_PRGMERR_FLAG + * - FLASH_BANK2_EPPERR_FLAG + * - FLASH_USDERR_FLAG + * @retval the new state of flash_flag (SET or RESET). + */ +flag_status flash_flag_get(uint32_t flash_flag) +{ + flag_status status = RESET; + uint32_t flag_position; + flag_position = flash_flag & 0x70000000; + flash_flag &= 0x8FFFFFFF; + switch(flag_position) + { + case 0x00000000: + if(FLASH->sts & flash_flag) + status = SET; + break; + case 0x10000000: + if(FLASH->sts2 & flash_flag) + status = SET; + break; + case 0x40000000: + if(FLASH->usd & flash_flag) + status = SET; + break; + default: + break; + } + /* return the new state of flash_flag (SET or RESET) */ + return status; +} + +/** + * @brief clear the flash flag. + * @param flash_flag: specifies the flash flags to clear. + * this parameter can be any combination of the following values: + * - FLASH_ODF_FLAG + * - FLASH_PRGMERR_FLAG + * - FLASH_EPPERR_FLAG + * - FLASH_BANK1_ODF_FLAG + * - FLASH_BANK1_PRGMERR_FLAG + * - FLASH_BANK1_EPPERR_FLAG + * - FLASH_BANK2_ODF_FLAG + * - FLASH_BANK2_PRGMERR_FLAG + * - FLASH_BANK2_EPPERR_FLAG + * @retval none + */ +void flash_flag_clear(uint32_t flash_flag) +{ + uint32_t flag_position; + flag_position = flash_flag & 0x70000000; + flash_flag &= 0x8FFFFFFF; + switch(flag_position) + { + case 0x00000000: + FLASH->sts = flash_flag; + break; + case 0x10000000: + FLASH->sts2 = flash_flag; + break; + default: + break; + } +} + +/** + * @brief return the flash operation status. + * @param none + * @retval status: the returned value can be: FLASH_OPERATE_BUSY, + * FLASH_PROGRAM_ERROR, FLASH_EPP_ERROR or FLASH_OPERATE_DONE. + */ +flash_status_type flash_operation_status_get(void) +{ + flash_status_type flash_status = FLASH_OPERATE_DONE; + if(FLASH->sts_bit.obf != RESET) + { + flash_status = FLASH_OPERATE_BUSY; + } + else if(FLASH->sts_bit.prgmerr != RESET) + { + flash_status = FLASH_PROGRAM_ERROR; + } + else if(FLASH->sts_bit.epperr != RESET) + { + flash_status = FLASH_EPP_ERROR; + } + else + { + flash_status = FLASH_OPERATE_DONE; + } + /* return the flash status */ + return flash_status; +} + +/** + * @brief return the flash bank1 operation status. + * @param none + * @retval status: the returned value can be: FLASH_OPERATE_BUSY, + * FLASH_PROGRAM_ERROR, FLASH_EPP_ERROR or FLASH_OPERATE_DONE. + */ +flash_status_type flash_bank1_operation_status_get(void) +{ + flash_status_type flash_status = FLASH_OPERATE_DONE; + if(FLASH->sts_bit.obf != RESET) + { + flash_status = FLASH_OPERATE_BUSY; + } + else if(FLASH->sts_bit.prgmerr != RESET) + { + flash_status = FLASH_PROGRAM_ERROR; + } + else if(FLASH->sts_bit.epperr != RESET) + { + flash_status = FLASH_EPP_ERROR; + } + else + { + flash_status = FLASH_OPERATE_DONE; + } + /* return the flash status */ + return flash_status; +} + +/** + * @brief return the flash bank2 operation status. + * @param none + * @retval status: the returned value can be: FLASH_OPERATE_BUSY, + * FLASH_PROGRAM_ERROR, FLASH_EPP_ERROR or FLASH_OPERATE_DONE. + */ +flash_status_type flash_bank2_operation_status_get(void) +{ + flash_status_type flash_status = FLASH_OPERATE_DONE; + if(FLASH->sts2_bit.obf != RESET) + { + flash_status = FLASH_OPERATE_BUSY; + } + else if(FLASH->sts2_bit.prgmerr != RESET) + { + flash_status = FLASH_PROGRAM_ERROR; + } + else if(FLASH->sts2_bit.epperr != RESET) + { + flash_status = FLASH_EPP_ERROR; + } + else + { + flash_status = FLASH_OPERATE_DONE; + } + /* return the flash status */ + return flash_status; +} + +/** + * @brief wait for flash operation complete or timeout. + * @param time_out: flash operation timeout + * @retval status: the returned value can be: FLASH_PROGRAM_ERROR, + * FLASH_EPP_ERROR, FLASH_OPERATE_DONE or FLASH_OPERATE_TIMEOUT. + */ +flash_status_type flash_operation_wait_for(uint32_t time_out) +{ + flash_status_type status = FLASH_OPERATE_DONE; + /* check for the flash status */ + status = flash_operation_status_get(); + + while((status == FLASH_OPERATE_BUSY) && (time_out != 0x00)) + { + status = flash_operation_status_get(); + time_out--; + } + if(time_out == 0x00) + { + status = FLASH_OPERATE_TIMEOUT; + } + /* return the status */ + return status; +} + +/** + * @brief wait for flash bank1 operation complete or timeout. + * @param time_out: flash operation timeout + * @retval status: the returned value can be: FLASH_PROGRAM_ERROR, + * FLASH_EPP_ERROR, FLASH_OPERATE_DONE or FLASH_OPERATE_TIMEOUT. + */ +flash_status_type flash_bank1_operation_wait_for(uint32_t time_out) +{ + flash_status_type status = FLASH_OPERATE_DONE; + /* check for the flash status */ + status = flash_bank1_operation_status_get(); + + while((status == FLASH_OPERATE_BUSY) && (time_out != 0x00)) + { + status = flash_bank1_operation_status_get(); + time_out--; + } + if(time_out == 0x00) + { + status = FLASH_OPERATE_TIMEOUT; + } + /* return the operation status */ + return status; +} + +/** + * @brief wait for flash bank2 operation complete or timeout. + * @param time_out: flash operation timeout + * @retval status: the returned value can be: FLASH_PROGRAM_ERROR, + * FLASH_EPP_ERROR, FLASH_OPERATE_DONE or FLASH_OPERATE_TIMEOUT. + */ +flash_status_type flash_bank2_operation_wait_for(uint32_t time_out) +{ + flash_status_type status = FLASH_OPERATE_DONE; + /* check for the flash status */ + status = flash_bank2_operation_status_get(); + + while((status == FLASH_OPERATE_BUSY) && (time_out != 0x00)) + { + status = flash_bank2_operation_status_get(); + time_out--; + } + if(time_out == 0x00) + { + status = FLASH_OPERATE_TIMEOUT; + } + /* return the operation status */ + return status; +} + +/** + * @brief unlock the flash controller. + * @param none + * @retval none + */ +void flash_unlock(void) +{ + FLASH->unlock = FLASH_UNLOCK_KEY1; + FLASH->unlock = FLASH_UNLOCK_KEY2; + FLASH->unlock2 = FLASH_UNLOCK_KEY1; + FLASH->unlock2 = FLASH_UNLOCK_KEY2; +} + +/** + * @brief unlock the flash bank1 controller. + * @param none + * @retval none + */ +void flash_bank1_unlock(void) +{ + FLASH->unlock = FLASH_UNLOCK_KEY1; + FLASH->unlock = FLASH_UNLOCK_KEY2; +} + +/** + * @brief unlock the flash bank2 controller. + * @param none + * @retval none + */ +void flash_bank2_unlock(void) +{ + FLASH->unlock2 = FLASH_UNLOCK_KEY1; + FLASH->unlock2 = FLASH_UNLOCK_KEY2; +} + +/** + * @brief lock the flash controller. + * @param none + * @retval none + */ +void flash_lock(void) +{ + FLASH->ctrl_bit.oplk = TRUE; + FLASH->ctrl2_bit.oplk = TRUE; +} + +/** + * @brief lock the flash bank1 controller. + * @param none + * @retval none + */ +void flash_bank1_lock(void) +{ + FLASH->ctrl_bit.oplk = TRUE; +} + +/** + * @brief lock the flash bank2 controller. + * @param none + * @retval none + */ +void flash_bank2_lock(void) +{ + FLASH->ctrl2_bit.oplk = TRUE; +} + +/** + * @brief erase a specified flash sector. + * @param sector_address: the sector address to be erased. + * @retval status: the returned value can be: FLASH_PROGRAM_ERROR, + * FLASH_EPP_ERROR, FLASH_OPERATE_DONE or FLASH_OPERATE_TIMEOUT. + */ +flash_status_type flash_sector_erase(uint32_t sector_address) +{ + flash_status_type status = FLASH_OPERATE_DONE; + if((sector_address >= FLASH_BANK1_START_ADDR) && (sector_address <= FLASH_BANK1_END_ADDR)) + { + FLASH->ctrl_bit.secers = TRUE; + FLASH->addr = sector_address; + FLASH->ctrl_bit.erstr = TRUE; + + /* wait for operation to be completed */ + status = flash_bank1_operation_wait_for(AT_ERASE_TIMEOUT); + + /* disable the secers bit */ + FLASH->ctrl_bit.secers = FALSE; + } + else if((sector_address >= FLASH_BANK2_START_ADDR) && (sector_address <= FLASH_BANK2_END_ADDR)) + { + FLASH->ctrl2_bit.secers = TRUE; + FLASH->addr2 = sector_address; + FLASH->ctrl2_bit.erstr = TRUE; + + /* wait for operation to be completed */ + status = flash_bank2_operation_wait_for(AT_ERASE_TIMEOUT); + + /* disable the secers bit */ + FLASH->ctrl2_bit.secers = FALSE; + } + + /* return the erase status */ + return status; +} + +/** + * @brief erase a specified flash block. + * @param block_address: the block address to be erased. + * @retval status: the returned value can be: FLASH_PROGRAM_ERROR, + * FLASH_EPP_ERROR, FLASH_OPERATE_DONE or FLASH_OPERATE_TIMEOUT. + */ +flash_status_type flash_block_erase(uint32_t block_address) +{ + flash_status_type status = FLASH_OPERATE_DONE; + if((block_address >= FLASH_BANK1_START_ADDR) && (block_address <= FLASH_BANK1_END_ADDR)) + { + FLASH->ctrl_bit.blkers = TRUE; + FLASH->addr = block_address; + FLASH->ctrl_bit.erstr = TRUE; + + /* wait for operation to be completed */ + status = flash_bank1_operation_wait_for(AT_ERASE_TIMEOUT); + + /* disable the blkers bit */ + FLASH->ctrl_bit.blkers = FALSE; + } + else if((block_address >= FLASH_BANK2_START_ADDR) && (block_address <= FLASH_BANK2_END_ADDR)) + { + FLASH->ctrl2_bit.blkers = TRUE; + FLASH->addr2 = block_address; + FLASH->ctrl2_bit.erstr = TRUE; + + /* wait for operation to be completed */ + status = flash_bank2_operation_wait_for(AT_ERASE_TIMEOUT); + + /* disable the blkers bit */ + FLASH->ctrl2_bit.blkers = FALSE; + } + + /* return the erase status */ + return status; +} + +/** + * @brief erase flash all internal sectors. + * @param none + * @retval status: the returned value can be: FLASH_PROGRAM_ERROR, + * FLASH_EPP_ERROR, FLASH_OPERATE_DONE or FLASH_OPERATE_TIMEOUT. + */ +flash_status_type flash_internal_all_erase(void) +{ + flash_status_type status = FLASH_OPERATE_DONE; + + FLASH->ctrl_bit.bankers = TRUE; + FLASH->ctrl_bit.erstr = TRUE; + + /* wait for operation to be completed */ + status = flash_bank1_operation_wait_for(AT_ERASE_TIMEOUT); + + /* disable the bankers bit */ + FLASH->ctrl_bit.bankers = FALSE; + + if(status == FLASH_OPERATE_DONE) + { + /* if the previous operation is completed, continue to erase bank2 */ + FLASH->ctrl2_bit.bankers = TRUE; + FLASH->ctrl2_bit.erstr = TRUE; + + /* wait for operation to be completed */ + status = flash_bank2_operation_wait_for(AT_ERASE_TIMEOUT); + + /* disable the bankers bit */ + FLASH->ctrl2_bit.bankers = FALSE; + } + /* return the erase status */ + return status; +} + +/** + * @brief erase flash bank1 sectors. + * @param none + * @retval status: the returned value can be: FLASH_PROGRAM_ERROR, + * FLASH_EPP_ERROR, FLASH_OPERATE_DONE or FLASH_OPERATE_TIMEOUT. + */ +flash_status_type flash_bank1_erase(void) +{ + flash_status_type status = FLASH_OPERATE_DONE; + + FLASH->ctrl_bit.bankers = TRUE; + FLASH->ctrl_bit.erstr = TRUE; + + /* wait for operation to be completed */ + status = flash_bank1_operation_wait_for(AT_ERASE_TIMEOUT); + + /* disable the bankers bit */ + FLASH->ctrl_bit.bankers = FALSE; + + /* return the erase status */ + return status; +} + +/** + * @brief erase flash bank2 sectors. + * @param none + * @retval status: the returned value can be: FLASH_PROGRAM_ERROR, + * FLASH_EPP_ERROR, FLASH_OPERATE_DONE or FLASH_OPERATE_TIMEOUT. + */ +flash_status_type flash_bank2_erase(void) +{ + flash_status_type status = FLASH_OPERATE_DONE; + + FLASH->ctrl2_bit.bankers = TRUE; + FLASH->ctrl2_bit.erstr = TRUE; + + /* wait for operation to be completed */ + status = flash_bank2_operation_wait_for(AT_ERASE_TIMEOUT); + + /* disable the bankers bit */ + FLASH->ctrl2_bit.bankers = FALSE; + + /* return the erase status */ + return status; +} + +/** + * @brief erase the flash user system data. + * @note this functions erase all user system data except the fap byte. + * the eopb0 byte value change to 0xFF, sram size maybe change too. + * @param none + * @retval status: the returned value can be: FLASH_PROGRAM_ERROR, + * FLASH_EPP_ERROR, FLASH_OPERATE_DONE or FLASH_OPERATE_TIMEOUT. + */ +flash_status_type flash_user_system_data_erase(void) +{ + flash_status_type status = FLASH_OPERATE_DONE; + uint16_t fap_val = FAP_RELIEVE_KEY; + /* get the flash access protection status */ + if(flash_fap_status_get() != RESET) + { + fap_val = 0x0000; + } + + /* unlock the user system data */ + FLASH->usd_unlock = FLASH_UNLOCK_KEY1; + FLASH->usd_unlock = FLASH_UNLOCK_KEY2; + while(FLASH->ctrl_bit.usdulks==RESET); + + /* erase the user system data */ + FLASH->ctrl_bit.usders = TRUE; + FLASH->ctrl_bit.erstr = TRUE; + + /* wait for operation to be completed */ + status = flash_operation_wait_for(AT_ERASE_TIMEOUT); + + /* disable the usders bit */ + FLASH->ctrl_bit.usders = FALSE; + + if((status == FLASH_OPERATE_DONE) && (fap_val == FAP_RELIEVE_KEY)) + { + /* enable the user system data programming operation */ + FLASH->ctrl_bit.usdprgm = TRUE; + + /* restore the last flash access protection value */ + USD->fap = (uint16_t)fap_val; + + /* wait for operation to be completed */ + status = flash_operation_wait_for(PROGRAMMING_TIMEOUT); + + /*disable the usdprgm bit */ + FLASH->ctrl_bit.usdprgm = FALSE; + } + + /* return the status */ + return status; +} + +/** + * @brief config the extend sram byte eopb0 in user system data. + * @note the 256kb and below capacity mcu only support FLASH_EOPB0_SRAM_384K, + * FLASH_EOPB0_SRAM_448K or FLASH_EOPB0_SRAM_512K. + * @param data: the eopb0 value. + * this parameter can be one of the following values: + * - FLASH_EOPB0_SRAM_512K + * - FLASH_EOPB0_SRAM_448K + * - FLASH_EOPB0_SRAM_384K + * - FLASH_EOPB0_SRAM_320K + * - FLASH_EOPB0_SRAM_256K + * - FLASH_EOPB0_SRAM_192K + * - FLASH_EOPB0_SRAM_128K + * @retval status: the returned value can be: FLASH_PROGRAM_ERROR, + * FLASH_EPP_ERROR, FLASH_OPERATE_DONE or FLASH_OPERATE_TIMEOUT. + */ +flash_status_type flash_eopb0_config(flash_usd_eopb0_type data) +{ + flash_status_type status = FLASH_OPERATE_DONE; + + /* unlock the user system data */ + FLASH->usd_unlock = FLASH_UNLOCK_KEY1; + FLASH->usd_unlock = FLASH_UNLOCK_KEY2; + while(FLASH->ctrl_bit.usdulks==RESET); + + /* enable the user system data programming operation */ + FLASH->ctrl_bit.usdprgm = TRUE; + + /* restore the default eopb0 value */ + USD->eopb0 = (uint16_t)data; + + /* wait for operation to be completed */ + status = flash_operation_wait_for(PROGRAMMING_TIMEOUT); + + /*disable the usdprgm bit */ + FLASH->ctrl_bit.usdprgm = FALSE; + + /* return the status */ + return status; +} + +/** + * @brief program a word at a specified address. + * @param address: specifies the address to be programmed, word alignment is recommended. + * @param data: specifies the data to be programmed. + * @retval status: the returned value can be: FLASH_PROGRAM_ERROR, + * FLASH_EPP_ERROR, FLASH_OPERATE_DONE or FLASH_OPERATE_TIMEOUT. + */ +flash_status_type flash_word_program(uint32_t address, uint32_t data) +{ + flash_status_type status = FLASH_OPERATE_DONE; + if((address >= FLASH_BANK1_START_ADDR) && (address <= FLASH_BANK1_END_ADDR)) + { + FLASH->ctrl_bit.fprgm = TRUE; + *(__IO uint32_t*)address = data; + /* wait for operation to be completed */ + status = flash_bank1_operation_wait_for(PROGRAMMING_TIMEOUT); + + /* disable the fprgm bit */ + FLASH->ctrl_bit.fprgm = FALSE; + } + else if((address >= FLASH_BANK2_START_ADDR) && (address <= FLASH_BANK2_END_ADDR)) + { + FLASH->ctrl2_bit.fprgm = TRUE; + *(__IO uint32_t*)address = data; + /* wait for operation to be completed */ + status = flash_bank2_operation_wait_for(PROGRAMMING_TIMEOUT); + + /* disable the fprgm bit */ + FLASH->ctrl2_bit.fprgm = FALSE; + } + + /* return the program status */ + return status; +} + +/** + * @brief program a halfword at a specified address. + * @param address: specifies the address to be programmed, halfword alignment is recommended. + * @param data: specifies the data to be programmed. + * @retval status: the returned value can be: FLASH_PROGRAM_ERROR, + * FLASH_EPP_ERROR, FLASH_OPERATE_DONE or FLASH_OPERATE_TIMEOUT. + */ +flash_status_type flash_halfword_program(uint32_t address, uint16_t data) +{ + flash_status_type status = FLASH_OPERATE_DONE; + if((address >= FLASH_BANK1_START_ADDR) && (address <= FLASH_BANK1_END_ADDR)) + { + FLASH->ctrl_bit.fprgm = TRUE; + *(__IO uint16_t*)address = data; + /* wait for operation to be completed */ + status = flash_bank1_operation_wait_for(PROGRAMMING_TIMEOUT); + + /* disable the fprgm bit */ + FLASH->ctrl_bit.fprgm = FALSE; + } + else if((address >= FLASH_BANK2_START_ADDR) && (address <= FLASH_BANK2_END_ADDR)) + { + FLASH->ctrl2_bit.fprgm = TRUE; + *(__IO uint16_t*)address = data; + /* wait for operation to be completed */ + status = flash_bank2_operation_wait_for(PROGRAMMING_TIMEOUT); + + /* disable the fprgm bit */ + FLASH->ctrl2_bit.fprgm = FALSE; + } + + /* return the program status */ + return status; +} + +/** + * @brief program a byte at a specified address. + * @note this function cannot be used to program spim. + * @param address: specifies the address to be programmed. + * @param data: specifies the data to be programmed. + * @retval status: the returned value can be: FLASH_PROGRAM_ERROR, + * FLASH_EPP_ERROR, FLASH_OPERATE_DONE or FLASH_OPERATE_TIMEOUT. + */ +flash_status_type flash_byte_program(uint32_t address, uint8_t data) +{ + flash_status_type status = FLASH_OPERATE_DONE; + if((address >= FLASH_BANK1_START_ADDR) && (address <= FLASH_BANK1_END_ADDR)) + { + FLASH->ctrl_bit.fprgm = TRUE; + *(__IO uint8_t*)address = data; + /* wait for operation to be completed */ + status = flash_bank1_operation_wait_for(PROGRAMMING_TIMEOUT); + + /* disable the fprgm bit */ + FLASH->ctrl_bit.fprgm = FALSE; + } + else if((address >= FLASH_BANK2_START_ADDR) && (address <= FLASH_BANK2_END_ADDR)) + { + FLASH->ctrl2_bit.fprgm = TRUE; + *(__IO uint8_t*)address = data; + /* wait for operation to be completed */ + status = flash_bank2_operation_wait_for(PROGRAMMING_TIMEOUT); + + /* disable the fprgm bit */ + FLASH->ctrl2_bit.fprgm = FALSE; + } + /* return the program status */ + return status; +} + +/** + * @brief program a halfword at a specified user system data address. + * @param address: specifies the address to be programmed. + * @param data: specifies the data to be programmed. + * @retval status: the returned value can be: FLASH_PROGRAM_ERROR, + * FLASH_EPP_ERROR, FLASH_OPERATE_DONE or FLASH_OPERATE_TIMEOUT. + */ +flash_status_type flash_user_system_data_program(uint32_t address, uint8_t data) +{ + flash_status_type status = FLASH_OPERATE_DONE; + + if(address == USD_BASE) + { + if(data != 0xA5) + return FLASH_OPERATE_DONE; + } + + /* unlock the user system data */ + FLASH->usd_unlock = FLASH_UNLOCK_KEY1; + FLASH->usd_unlock = FLASH_UNLOCK_KEY2; + while(FLASH->ctrl_bit.usdulks==RESET); + + /* enable the user system data programming operation */ + FLASH->ctrl_bit.usdprgm = TRUE; + *(__IO uint16_t*)address = data; + + /* wait for operation to be completed */ + status = flash_operation_wait_for(PROGRAMMING_TIMEOUT); + + /* disable the usdprgm bit */ + FLASH->ctrl_bit.usdprgm = FALSE; + + /* return the user system data program status */ + return status; +} + +/** + * @brief config erase/program protection for the desired sectors. + * @param sector_bits: + * the pointer of the address of the sectors to be erase/program protected. + * general bit 0~31 every bit is used to protect the 4KB bytes, bit 62~32 + * every bit is used to protect the 128KB bytes + * @retval status: the returned value can be: FLASH_PROGRAM_ERROR, + * FLASH_EPP_ERROR, FLASH_OPERATE_DONE or FLASH_OPERATE_TIMEOUT. + */ +flash_status_type flash_epp_set(uint32_t *sector_bits) +{ + uint16_t epp_data[4] = {0xFFFF,0xFFFF,0xFFFF,0xFFFF}; + flash_status_type status = FLASH_OPERATE_DONE; + sector_bits[0] = (uint32_t)(~sector_bits[0]); + epp_data[0] = (uint16_t)((sector_bits[0] >> 0) & 0xFF); + epp_data[1] = (uint16_t)((sector_bits[0] >> 8) & 0xFF); + epp_data[2] = (uint16_t)((sector_bits[0] >> 16) & 0xFF); + epp_data[3] = (uint16_t)((sector_bits[0] >> 24) & 0xFF); + + /* unlock the user system data */ + FLASH->usd_unlock = FLASH_UNLOCK_KEY1; + FLASH->usd_unlock = FLASH_UNLOCK_KEY2; + while(FLASH->ctrl_bit.usdulks==RESET); + + FLASH->ctrl_bit.usdprgm = TRUE; + USD->epp0 = epp_data[0]; + /* wait for operation to be completed */ + status = flash_operation_wait_for(PROGRAMMING_TIMEOUT); + + if(status == FLASH_OPERATE_DONE) + { + USD->epp1 = epp_data[1]; + /* wait for operation to be completed */ + status = flash_operation_wait_for(PROGRAMMING_TIMEOUT); + } + if(status == FLASH_OPERATE_DONE) + { + USD->epp2 = epp_data[2]; + /* wait for operation to be completed */ + status = flash_operation_wait_for(PROGRAMMING_TIMEOUT); + } + if(status == FLASH_OPERATE_DONE) + { + USD->epp3 = epp_data[3]; + /* wait for operation to be completed */ + status = flash_operation_wait_for(PROGRAMMING_TIMEOUT); + } + + sector_bits[1] = (uint32_t)(~sector_bits[1]); + epp_data[0] = (uint16_t)((sector_bits[1] >> 0) & 0xFF); + epp_data[1] = (uint16_t)((sector_bits[1] >> 8) & 0xFF); + epp_data[2] = (uint16_t)((sector_bits[1] >> 16) & 0xFF); + epp_data[3] = (uint16_t)((sector_bits[1] >> 24) & 0xFF); + if(status == FLASH_OPERATE_DONE) + { + USD->epp4 = epp_data[0]; + /* wait for operation to be completed */ + status = flash_operation_wait_for(PROGRAMMING_TIMEOUT); + } + if(status == FLASH_OPERATE_DONE) + { + USD->epp5 = epp_data[1]; + /* wait for operation to be completed */ + status = flash_operation_wait_for(PROGRAMMING_TIMEOUT); + } + if(status == FLASH_OPERATE_DONE) + { + USD->epp6 = epp_data[2]; + /* wait for operation to be completed */ + status = flash_operation_wait_for(PROGRAMMING_TIMEOUT); + } + if(status == FLASH_OPERATE_DONE) + { + USD->epp7 = epp_data[3]; + /* wait for operation to be completed */ + status = flash_operation_wait_for(PROGRAMMING_TIMEOUT); + } + + /* disable the usdprgm bit */ + FLASH->ctrl_bit.usdprgm = FALSE; + + /* return the erase/program protection operation status */ + return status; +} + +/** + * @brief return the flash erase/program protection status. + * @param sector_bits: pointer to get the epps register. + * @retval none + */ +void flash_epp_status_get(uint32_t *sector_bits) +{ + /* return the flash erase/program protection register value */ + sector_bits[0] = (uint32_t)(FLASH->epps0); + sector_bits[1] = (uint32_t)(FLASH->epps1); +} + +/** + * @brief enable or disable the flash access protection. + * @note if the user has already programmed the other user system data before calling + * this function, must re-program them since this function erase all user system data. + * @param new_state: new state of the flash access protection. + * this parameter can be: TRUE or FALSE. + * @retval status: the returned value can be: FLASH_PROGRAM_ERROR, + * FLASH_EPP_ERROR, FLASH_OPERATE_DONE or FLASH_OPERATE_TIMEOUT. + */ +flash_status_type flash_fap_enable(confirm_state new_state) +{ + flash_status_type status = FLASH_OPERATE_DONE; + + /* unlock the user system data */ + FLASH->usd_unlock = FLASH_UNLOCK_KEY1; + FLASH->usd_unlock = FLASH_UNLOCK_KEY2; + while(FLASH->ctrl_bit.usdulks==RESET); + + FLASH->ctrl_bit.usders = TRUE; + FLASH->ctrl_bit.erstr = TRUE; + /* wait for operation to be completed */ + status = flash_operation_wait_for(AT_ERASE_TIMEOUT); + + /* disable the usders bit */ + FLASH->ctrl_bit.usders = FALSE; + + if(status == FLASH_OPERATE_DONE) + { + /* enable the user system data programming operation */ + FLASH->ctrl_bit.usdprgm = TRUE; + + /* restore the default eopb0 value */ + USD->eopb0 = (uint16_t)0x0002; + + /* Wait for operation to be completed */ + status = flash_operation_wait_for(AT_ERASE_TIMEOUT); + + if(new_state == FALSE) + { + USD->fap = FAP_RELIEVE_KEY; + /* Wait for operation to be completed */ + status = flash_operation_wait_for(AT_ERASE_TIMEOUT); + } + /* disable the usdprgm bit */ + FLASH->ctrl_bit.usdprgm = FALSE; + } + + /* return the flash access protection operation status */ + return status; +} + +/** + * @brief check the flash access protection status. + * @param none + * @retval flash access protection status(SET or RESET) + */ +flag_status flash_fap_status_get(void) +{ + return (flag_status)FLASH->usd_bit.fap; +} + +/** + * @brief program the flash system setting byte in usd: wdt_ato_en / depslp_rst / stdby_rst / btopt. + * @param usd_ssb: the system setting byte + * @note this parameter usd_ssb must contain a combination of all the following 6 types of data + * type 1: wdt_ato_en, select the wdt auto start + * this data can be one of the following values: + * - USD_WDT_ATO_DISABLE: disable wdt auto start + * - USD_WDT_ATO_ENABLE: enable wdt auto start + * type 2: depslp_rst, reset event when entering deepsleep mode. + * this data can be one of the following values: + * - USD_DEPSLP_NO_RST: no reset generated when entering in deepsleep + * - USD_DEPSLP_RST: reset generated when entering in deepsleep + * type 3: stdby_rst, reset event when entering standby mode. + * this data can be one of the following values: + * - USD_STDBY_NO_RST: no reset generated when entering in standby + * - USD_STDBY_RST: reset generated when entering in standby + * type 4: btopt, at startup,if boot pins are set in boot from user flash position,selected the device boot from bank1/bank2. + * this data can be one of the following values: + * - FLASH_BOOT_FROM_BANK1:boot from bank1 + * - FLASH_BOOT_FROM_BANK2:boot from bank 2 or bank 1 + * type 5: wdt_depslp, wdt stop/continue count when entering in deepsleep. + * this data can be one of the following values: + * - USD_WDT_DEPSLP_CONTINUE: wdt continue count + * - USD_WDT_DEPSLP_STOP: wdt stop count + * type 6: wdt_stdby, wdt stop/continue count when entering in standby. + * this data can be one of the following values: + * - USD_WDT_STDBY_CONTINUE: wdt continue count + * - USD_WDT_STDBY_STOP: wdt stop count + * @retval status: the returned value can be: FLASH_PROGRAM_ERROR, + * FLASH_EPP_ERROR, FLASH_OPERATE_DONE or FLASH_OPERATE_TIMEOUT. + */ +flash_status_type flash_ssb_set(uint8_t usd_ssb) +{ + flash_status_type status = FLASH_OPERATE_DONE; + + /* unlock the user system data */ + FLASH->usd_unlock = FLASH_UNLOCK_KEY1; + FLASH->usd_unlock = FLASH_UNLOCK_KEY2; + while(FLASH->ctrl_bit.usdulks==RESET); + + /* enable the user system data programming operation */ + FLASH->ctrl_bit.usdprgm = TRUE; + + USD->ssb = usd_ssb; + /* wait for operation to be completed */ + status = flash_operation_wait_for(PROGRAMMING_TIMEOUT); + + /* disable the usdprgm bit */ + FLASH->ctrl_bit.usdprgm = FALSE; + + /* return the user system data program status */ + return status; +} + +/** + * @brief return the flash system setting byte status. + * @param none + * @retval values from flash_usd register: wdt_ato_en(bit0), depslp_rst(bit1), + * stdby_rst(bit2) and btopt(bit3). + */ +uint8_t flash_ssb_status_get(void) +{ + /* return the system setting byte status */ + return (uint8_t)(FLASH->usd >> 2); +} + +/** + * @brief enable or disable the specified flash interrupts. + * @param flash_int: specifies the flash interrupt sources to be enabled or disabled. + * this parameter can be any combination of the following values: + * - FLASH_ERR_INT + * - FLASH_ODF_INT + * - FLASH_BANK1_ERR_INT + * - FLASH_BANK1_ODF_INT + * - FLASH_BANK2_ERR_INT + * - FLASH_BANK2_ODF_INT + * @param new_state: new state of the specified flash interrupts. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void flash_interrupt_enable(uint32_t flash_int, confirm_state new_state) +{ + if(flash_int & FLASH_BANK1_ERR_INT) + FLASH->ctrl_bit.errie = new_state; + if(flash_int & FLASH_BANK1_ODF_INT) + FLASH->ctrl_bit.odfie = new_state; + if(flash_int & FLASH_BANK2_ERR_INT) + FLASH->ctrl2_bit.errie = new_state; + if(flash_int & FLASH_BANK2_ODF_INT) + FLASH->ctrl2_bit.odfie = new_state; +} + +/** + * @brief enable security library function. + * @param pwd: slib password + * start_sector: security library start sector + * inst_start_sector: security library i-bus area start sector + * end_sector: security library end sector + * @retval status: the returned value can be: FLASH_PROGRAM_ERROR, + * FLASH_EPP_ERROR, FLASH_OPERATE_DONE or FLASH_OPERATE_TIMEOUT. + */ +flash_status_type flash_slib_enable(uint32_t pwd, uint16_t start_sector, uint16_t inst_start_sector, uint16_t end_sector) +{ + uint32_t slib_range; + flash_status_type status = FLASH_OPERATE_DONE; + + /*check range param limits*/ + if((start_sector>=inst_start_sector) || ((inst_start_sector > end_sector) && \ + (inst_start_sector != 0xFFFF)) || (start_sector > end_sector)) + return FLASH_PROGRAM_ERROR; + + /* unlock slib cfg register */ + FLASH->slib_unlock = SLIB_UNLOCK_KEY; + while(FLASH->slib_misc_sts_bit.slib_ulkf==RESET); + + /* configure slib, set pwd and range */ + FLASH->slib_set_pwd = pwd; + status = flash_operation_wait_for(PROGRAMMING_TIMEOUT); + if(status == FLASH_OPERATE_DONE) + { + slib_range = ((uint32_t)(end_sector << 16) & FLASH_SLIB_END_SECTOR) | (start_sector & FLASH_SLIB_START_SECTOR); + FLASH->slib_set_range0 = slib_range; + status = flash_operation_wait_for(PROGRAMMING_TIMEOUT); + if(status == FLASH_OPERATE_DONE) + { + slib_range = (inst_start_sector & FLASH_SLIB_INST_START_SECTOR) | 0x80000000; + FLASH->slib_set_range1 = slib_range; + status = flash_operation_wait_for(PROGRAMMING_TIMEOUT); + } + } + + return status; +} + +/** + * @brief disable slib when slib enabled. + * @param pwd: slib password + * @retval success or error + */ +error_status flash_slib_disable(uint32_t pwd) +{ + flash_status_type status = FLASH_OPERATE_DONE; + /* write password to disable slib */ + FLASH->slib_pwd_clr = pwd; + + status = flash_operation_wait_for(AT_ERASE_TIMEOUT); + if(status == FLASH_OPERATE_DONE) + { + if(FLASH->slib_misc_sts_bit.slib_pwd_ok) + return SUCCESS; + else + return ERROR; + } + return ERROR; +} + +/** + * @brief get remaining count of slib(range: 256~0). + * @param none + * @retval uint32_t + */ +uint32_t flash_slib_remaining_count_get(void) +{ + return (uint32_t)FLASH->slib_misc_sts_bit.slib_rcnt; +} + +/** + * @brief get the slib state. + * @param none + * @retval SET or RESET + */ +flag_status flash_slib_state_get(void) +{ + if(FLASH->slib_sts0_bit.slib_enf) + return SET; + else + return RESET; +} + +/** + * @brief get the start sector of slib. + * @param none + * @retval uint16_t + */ +uint16_t flash_slib_start_sector_get(void) +{ + return (uint16_t)FLASH->slib_sts1_bit.slib_ss; +} + +/** + * @brief get the instruction start sector of slib. + * @param none + * @retval uint16_t + */ +uint16_t flash_slib_inststart_sector_get(void) +{ + return (uint16_t)FLASH->slib_sts2_bit.slib_inst_ss; +} + +/** + * @brief get the end sector of slib. + * @param none + * @retval uint16_t + */ +uint16_t flash_slib_end_sector_get(void) +{ + return (uint16_t)FLASH->slib_sts1_bit.slib_es; +} + +/** + * @brief flash crc calibration in main block. + * @param start_sector: crc calibration start sector number + * sector_cnt: crc calibration sector count + * @retval uint32: crc calibration result + */ +uint32_t flash_crc_calibrate(uint32_t start_sector, uint32_t sector_cnt) +{ + FLASH->crc_ctrl_bit.crc_ss = start_sector; + FLASH->crc_ctrl_bit.crc_sn = sector_cnt; + FLASH->crc_ctrl_bit.crc_strt = TRUE; + flash_operation_wait_for(OPERATION_TIMEOUT); + return FLASH->crc_chkr; +} + +/** + * @brief flash non-zero wait area boost enable. + * @param new_state: new state of the flash non-zero wait area boost operation. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void flash_nzw_boost_enable(confirm_state new_state) +{ + FLASH->psr_bit.nzw_bst = new_state; +} + +/** + * @brief flash continue read enable. + * @param new_state: new state of the flash continue read enable operation. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void flash_continue_read_enable(confirm_state new_state) +{ + FLASH->contr_bit.fcontr_en = new_state; +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_gpio.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_gpio.c new file mode 100644 index 0000000000..cb62c5eb73 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_gpio.c @@ -0,0 +1,523 @@ +/** + ************************************************************************** + * @file at32f435_437_gpio.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the gpio firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup GPIO + * @brief GPIO driver modules + * @{ + */ + +#ifdef GPIO_MODULE_ENABLED + +/** @defgroup GPIO_private_functions + * @{ + */ + +/** + * @brief reset the gpio register + * @param gpio_x: to select the gpio peripheral. + * this parameter can be one of the following values: + * GPIOA, GPIOB, GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH. + * @retval none + */ +void gpio_reset(gpio_type *gpio_x) +{ + if(gpio_x == GPIOA) + { + crm_periph_reset(CRM_GPIOA_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_GPIOA_PERIPH_RESET, FALSE); + } + else if(gpio_x == GPIOB) + { + crm_periph_reset(CRM_GPIOB_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_GPIOB_PERIPH_RESET, FALSE); + } + else if(gpio_x == GPIOC) + { + crm_periph_reset(CRM_GPIOC_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_GPIOC_PERIPH_RESET, FALSE); + } + else if(gpio_x == GPIOD) + { + crm_periph_reset(CRM_GPIOD_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_GPIOD_PERIPH_RESET, FALSE); + } + else if(gpio_x == GPIOE) + { + crm_periph_reset(CRM_GPIOE_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_GPIOE_PERIPH_RESET, FALSE); + } + else if(gpio_x == GPIOF) + { + crm_periph_reset(CRM_GPIOF_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_GPIOF_PERIPH_RESET, FALSE); + } + else if(gpio_x == GPIOG) + { + crm_periph_reset(CRM_GPIOG_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_GPIOG_PERIPH_RESET, FALSE); + } + else if(gpio_x == GPIOH) + { + crm_periph_reset(CRM_GPIOH_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_GPIOH_PERIPH_RESET, FALSE); + } +} + +/** + * @brief initialize the gpio peripheral. + * @param gpio_x: to select the gpio peripheral. + * this parameter can be one of the following values: + * GPIOA, GPIOB, GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH. + * @param gpio_init_struct: pointer to gpio init structure. + * @retval none + */ +void gpio_init(gpio_type *gpio_x, gpio_init_type *gpio_init_struct) +{ + uint16_t pinx_value, pin_index = 0; + + pinx_value = (uint16_t)gpio_init_struct->gpio_pins; + + while(pinx_value > 0) + { + if(pinx_value & 0x01) + { + gpio_x->cfgr &= (uint32_t)~(0x03 << (pin_index * 2)); + gpio_x->cfgr |= (uint32_t)(gpio_init_struct->gpio_mode << (pin_index * 2)); + + gpio_x->omode &= (uint32_t)~(0x01 << (pin_index)); + gpio_x->omode |= (uint32_t)(gpio_init_struct->gpio_out_type << (pin_index)); + + gpio_x->odrvr &= (uint32_t)~(0x03 << (pin_index * 2)); + gpio_x->odrvr |= (uint32_t)(gpio_init_struct->gpio_drive_strength << (pin_index * 2)); + + gpio_x->pull &= (uint32_t)~(0x03 << (pin_index * 2)); + gpio_x->pull |= (uint32_t)(gpio_init_struct->gpio_pull << (pin_index * 2)); + } + pinx_value >>= 1; + pin_index++; + } +} + +/** + * @brief fill each gpio_init_type member with its default value. + * @param gpio_init_struct : pointer to a gpio_init_type structure which will be initialized. + * @retval none + */ +void gpio_default_para_init(gpio_init_type *gpio_init_struct) +{ + /* reset gpio init structure parameters values */ + gpio_init_struct->gpio_pins = GPIO_PINS_ALL; + gpio_init_struct->gpio_mode = GPIO_MODE_INPUT; + gpio_init_struct->gpio_out_type = GPIO_OUTPUT_PUSH_PULL; + gpio_init_struct->gpio_pull = GPIO_PULL_NONE; + gpio_init_struct->gpio_drive_strength = GPIO_DRIVE_STRENGTH_STRONGER; +} + +/** + * @brief read the specified input port pin. + * @param gpio_x: to select the gpio peripheral. + * this parameter can be one of the following values: + * GPIOA, GPIOB, GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH. + * @param pins: gpio pin number + * this parameter can be one of the following values: + * - GPIO_PINS_0 + * - GPIO_PINS_1 + * - GPIO_PINS_2 + * - GPIO_PINS_3 + * - GPIO_PINS_4 + * - GPIO_PINS_5 + * - GPIO_PINS_6 + * - GPIO_PINS_7 + * - GPIO_PINS_8 + * - GPIO_PINS_9 + * - GPIO_PINS_10 + * - GPIO_PINS_11 + * - GPIO_PINS_12 + * - GPIO_PINS_13 + * - GPIO_PINS_14 + * - GPIO_PINS_15 + * @retval flag_status (SET or RESET) + */ +flag_status gpio_input_data_bit_read(gpio_type *gpio_x, uint16_t pins) +{ + flag_status status = RESET; + + if(pins != (pins & gpio_x->idt)) + { + status = RESET; + } + else + { + status = SET; + } + + return status; +} + +/** + * @brief read the specified gpio input data port. + * @param gpio_x: to select the gpio peripheral. + * this parameter can be one of the following values: + * GPIOA, GPIOB, GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH. + * @retval gpio input data port value. + */ +uint16_t gpio_input_data_read(gpio_type *gpio_x) +{ + return ((uint16_t)(gpio_x->idt)); +} + +/** + * @brief read the specified output port pin. + * @param gpio_x: to select the gpio peripheral. + * this parameter can be one of the following values: + * GPIOA, GPIOB, GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH. + * @param pins: gpio pin number + * this parameter can be one of the following values: + * - GPIO_PINS_0 + * - GPIO_PINS_1 + * - GPIO_PINS_2 + * - GPIO_PINS_3 + * - GPIO_PINS_4 + * - GPIO_PINS_5 + * - GPIO_PINS_6 + * - GPIO_PINS_7 + * - GPIO_PINS_8 + * - GPIO_PINS_9 + * - GPIO_PINS_10 + * - GPIO_PINS_11 + * - GPIO_PINS_12 + * - GPIO_PINS_13 + * - GPIO_PINS_14 + * - GPIO_PINS_15 + * @retval flag_status (SET or RESET) + */ +flag_status gpio_output_data_bit_read(gpio_type *gpio_x, uint16_t pins) +{ + flag_status status = RESET; + + if((gpio_x->odt & pins) != RESET) + { + status = SET; + } + else + { + status = RESET; + } + + return status; +} + +/** + * @brief read the specified gpio ouput data port. + * @param gpio_x: to select the gpio peripheral. + * this parameter can be one of the following values: + * GPIOA, GPIOB, GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH. + * @retval gpio input data port value. + */ +uint16_t gpio_output_data_read(gpio_type *gpio_x) +{ + return ((uint16_t)(gpio_x->odt)); +} + +/** + * @brief set the selected data port bits. + * @param gpio_x: to select the gpio peripheral. + * this parameter can be one of the following values: + * GPIOA, GPIOB, GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH. + * @param pins: gpio pin number + * parameter can be any combination of gpio_pin_x, gpio_pin_x as following values: + * - GPIO_PINS_0 + * - GPIO_PINS_1 + * - GPIO_PINS_2 + * - GPIO_PINS_3 + * - GPIO_PINS_4 + * - GPIO_PINS_5 + * - GPIO_PINS_6 + * - GPIO_PINS_7 + * - GPIO_PINS_8 + * - GPIO_PINS_9 + * - GPIO_PINS_10 + * - GPIO_PINS_11 + * - GPIO_PINS_12 + * - GPIO_PINS_13 + * - GPIO_PINS_14 + * - GPIO_PINS_15 + * - GPIO_PINS_ALL + * @retval none + */ +void gpio_bits_set(gpio_type *gpio_x, uint16_t pins) +{ + gpio_x->scr = pins; +} + +/** + * @brief clear the selected data port bits. + * @param gpio_x: to select the gpio peripheral. + * this parameter can be one of the following values: + * GPIOA, GPIOB, GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH. + * @param pins: gpio pin number + * parameter can be any combination of gpio_pin_x, gpio_pin_x as following values: + * - GPIO_PINS_0 + * - GPIO_PINS_1 + * - GPIO_PINS_2 + * - GPIO_PINS_3 + * - GPIO_PINS_4 + * - GPIO_PINS_5 + * - GPIO_PINS_6 + * - GPIO_PINS_7 + * - GPIO_PINS_8 + * - GPIO_PINS_9 + * - GPIO_PINS_10 + * - GPIO_PINS_11 + * - GPIO_PINS_12 + * - GPIO_PINS_13 + * - GPIO_PINS_14 + * - GPIO_PINS_15 + * - GPIO_PINS_ALL + * @retval none + */ +void gpio_bits_reset(gpio_type *gpio_x, uint16_t pins) +{ + gpio_x->clr = pins; +} + +/** + * @brief set or clear the selected data port bit. + * @param gpio_x: to select the gpio peripheral. + * this parameter can be one of the following values: + * GPIOA, GPIOB, GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH. + * @param pins: gpio pin number + * parameter can be any combination of gpio_pin_x, gpio_pin_x as following values: + * - GPIO_PINS_0 + * - GPIO_PINS_1 + * - GPIO_PINS_2 + * - GPIO_PINS_3 + * - GPIO_PINS_4 + * - GPIO_PINS_5 + * - GPIO_PINS_6 + * - GPIO_PINS_7 + * - GPIO_PINS_8 + * - GPIO_PINS_9 + * - GPIO_PINS_10 + * - GPIO_PINS_11 + * - GPIO_PINS_12 + * - GPIO_PINS_13 + * - GPIO_PINS_14 + * - GPIO_PINS_15 + * - GPIO_PINS_ALL + * @param bit_state: specifies the value to be written to the selected bit (TRUE or FALSE). + * @retval none + */ +void gpio_bits_write(gpio_type *gpio_x, uint16_t pins, confirm_state bit_state) +{ + if(bit_state != FALSE) + { + gpio_x->scr = pins; + } + else + { + gpio_x->clr = pins; + } +} + +/** + * @brief write data to the specified gpio data port. + * @param gpio_x: to select the gpio peripheral. + * this parameter can be one of the following values: + * GPIOA, GPIOB, GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH. + * @param port_value: specifies the value to be written to the port output data register. + * @retval none + */ +void gpio_port_write(gpio_type *gpio_x, uint16_t port_value) +{ + gpio_x->odt = port_value; +} + +/** + * @brief write protect gpio pins configuration registers. + * @param gpio_x: to select the gpio peripheral. + * this parameter can be one of the following values: + * GPIOA, GPIOB, GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH. + * @param pins: gpio pin number + * this parameter can be any combination of the following: + * - GPIO_PINS_0 + * - GPIO_PINS_1 + * - GPIO_PINS_2 + * - GPIO_PINS_3 + * - GPIO_PINS_4 + * - GPIO_PINS_5 + * - GPIO_PINS_6 + * - GPIO_PINS_7 + * - GPIO_PINS_8 + * - GPIO_PINS_9 + * - GPIO_PINS_10 + * - GPIO_PINS_11 + * - GPIO_PINS_12 + * - GPIO_PINS_13 + * - GPIO_PINS_14 + * - GPIO_PINS_15 + * - GPIO_PINS_ALL + * @retval none + */ +void gpio_pin_wp_config(gpio_type *gpio_x, uint16_t pins) +{ + uint32_t temp = 0x00010000; + + temp |= pins; + /* set wpen bit */ + gpio_x->wpr = temp; + /* reset wpen bit */ + gpio_x->wpr = pins; + /* set wpen bit */ + gpio_x->wpr = temp; + /* read wpen bit*/ + temp = gpio_x->wpr; + /* read wpen bit*/ + temp = gpio_x->wpr; +} + +/** + * @brief enable or disable gpio pins huge driven. + * @param gpio_x: to select the gpio peripheral. + * this parameter can be one of the following values: + * GPIOA, GPIOB, GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH. + * @param pins: gpio pin number + * parameter can be any combination of gpio_pin_x, gpio_pin_x as following values: + * - GPIO_PINS_0 + * - GPIO_PINS_1 + * - GPIO_PINS_2 + * - GPIO_PINS_3 + * - GPIO_PINS_4 + * - GPIO_PINS_5 + * - GPIO_PINS_6 + * - GPIO_PINS_7 + * - GPIO_PINS_8 + * - GPIO_PINS_9 + * - GPIO_PINS_10 + * - GPIO_PINS_11 + * - GPIO_PINS_12 + * - GPIO_PINS_13 + * - GPIO_PINS_14 + * - GPIO_PINS_15 + * - GPIO_PINS_ALL + * @param new_state: new state of the slew rate. + * this parameter can be: true or false. + * @retval none + */ +void gpio_pins_huge_driven_config(gpio_type *gpio_x, uint16_t pins, confirm_state new_state) +{ + if(new_state != FALSE) + { + gpio_x->hdrv |= pins; + } + else + { + gpio_x->hdrv &= ~pins; + } +} + +/** + * @brief configure the pin's muxing function. + * @param gpio_x: to select the gpio peripheral. + * this parameter can be one of the following values: + * GPIOA, GPIOB, GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH. + * @param gpio_pin_source: specifies the pin for the muxing function. + * this parameter can be one of the following values: + * - GPIO_PINS_SOURCE0 + * - GPIO_PINS_SOURCE1 + * - GPIO_PINS_SOURCE2 + * - GPIO_PINS_SOURCE3 + * - GPIO_PINS_SOURCE4 + * - GPIO_PINS_SOURCE5 + * - GPIO_PINS_SOURCE6 + * - GPIO_PINS_SOURCE7 + * - GPIO_PINS_SOURCE8 + * - GPIO_PINS_SOURCE9 + * - GPIO_PINS_SOURCE10 + * - GPIO_PINS_SOURCE11 + * - GPIO_PINS_SOURCE12 + * - GPIO_PINS_SOURCE13 + * - GPIO_PINS_SOURCE14 + * - GPIO_PINS_SOURCE15 + * @param gpio_mux: select the pin to used as muxing function. + * this parameter can be one of the following values: + * - GPIO_MUX_0 + * - GPIO_MUX_1 + * - GPIO_MUX_2 + * - GPIO_MUX_3 + * - GPIO_MUX_4 + * - GPIO_MUX_5 + * - GPIO_MUX_6 + * - GPIO_MUX_7 + * - GPIO_MUX_8 + * - GPIO_MUX_9 + * - GPIO_MUX_10 + * - GPIO_MUX_11 + * - GPIO_MUX_12 + * - GPIO_MUX_13 + * - GPIO_MUX_14 + * - GPIO_MUX_15 + * @retval none + */ +void gpio_pin_mux_config(gpio_type *gpio_x, gpio_pins_source_type gpio_pin_source, gpio_mux_sel_type gpio_mux) +{ + uint32_t temp = 0x00; + uint32_t temp_2 = 0x00; + + temp = ((uint32_t)(gpio_mux) << ((uint32_t)((uint32_t)gpio_pin_source & (uint32_t)0x07) * 4)); + if(gpio_pin_source >> 0x03) + { + gpio_x->muxh &= ~((uint32_t)0xF << ((uint32_t)((uint32_t)gpio_pin_source & (uint32_t)0x07) * 4)); + temp_2 = gpio_x->muxh | temp; + gpio_x->muxh = temp_2; + } + else + { + gpio_x->muxl &= ~((uint32_t)0xF << ((uint32_t)((uint32_t)gpio_pin_source & (uint32_t)0x07) * 4)); + temp_2 = gpio_x->muxl | temp; + gpio_x->muxl = temp_2; + } +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_i2c.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_i2c.c new file mode 100644 index 0000000000..d91f033ce6 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_i2c.c @@ -0,0 +1,748 @@ +/** + ************************************************************************** + * @file at32f435_437_i2c.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the i2c firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup I2C + * @brief I2C driver modules + * @{ + */ + +#ifdef I2C_MODULE_ENABLED + +/** @defgroup I2C_private_functions + * @{ + */ + +/** + * @brief reset the i2c register + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @retval none + */ +void i2c_reset(i2c_type *i2c_x) +{ + if(i2c_x == I2C1) + { + crm_periph_reset(CRM_I2C1_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_I2C1_PERIPH_RESET, FALSE); + } + else if(i2c_x == I2C2) + { + crm_periph_reset(CRM_I2C2_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_I2C2_PERIPH_RESET, FALSE); + } + else if(i2c_x == I2C3) + { + crm_periph_reset(CRM_I2C3_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_I2C3_PERIPH_RESET, FALSE); + } +} + +/** + * @brief init i2c digit filters and clock control register. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param dfilters: number of digit filters (0x00~0x0F). + * @param clk: i2c clock control register (0x00000000~0xFFFFFFFF). + * @retval none + */ +void i2c_init(i2c_type *i2c_x, uint8_t dfilters, uint32_t clk) +{ + /* disable i2c peripheral */ + i2c_x->ctrl1_bit.i2cen = FALSE; + + /* write clkctrl register*/ + i2c_x->clkctrl = clk; + + /* write digital filter register*/ + i2c_x->ctrl1_bit.dflt = dfilters; +} + +/** + * @brief config i2c own address 1. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param mode: i2c address mode. + * this parameter can be one of the following values: + * - I2C_ADDRESS_MODE_7BIT: 7bit address. + * - I2C_ADDRESS_MODE_10BIT: 10bit address. + * @param address: own address 1, such as 0xB0. + * @retval none + */ +void i2c_own_address1_set(i2c_type *i2c_x, i2c_address_mode_type mode, uint16_t address) +{ + /* config address mode */ + i2c_x->oaddr1_bit.addr1mode = mode; + + /* config address */ + i2c_x->oaddr1_bit.addr1 = address & 0x03FF; + + /* enable address */ + i2c_x->oaddr1_bit.addr1en = TRUE; +} + +/** + * @brief config i2c own address 2 and mask. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param address: own address 1, such as 0xC0. + * @param mask: own address 2 mask. + * this parameter can be one of the following values: + * - I2C_ADDR2_NOMASK: compare bit [7:1]. + * - I2C_ADDR2_MASK01: only compare bit [7:2]. + * - I2C_ADDR2_MASK02: only compare bit [7:2]. + * - I2C_ADDR2_MASK03: only compare bit [7:3]. + * - I2C_ADDR2_MASK04: only compare bit [7:4]. + * - I2C_ADDR2_MASK05: only compare bit [7:5]. + * - I2C_ADDR2_MASK06: only compare bit [7:6]. + * - I2C_ADDR2_MASK07: only compare bit [7]. + * @retval none + */ +void i2c_own_address2_set(i2c_type *i2c_x, uint8_t address, i2c_addr2_mask_type mask) +{ + i2c_x->oaddr2_bit.addr2mask = mask; + + i2c_x->oaddr2_bit.addr2 = (address >> 1) & 0x7F; +} + +/** + * @brief enable or disable own address 2. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param new_state (TRUE or FALSE). + * @retval none + */ +void i2c_own_address2_enable(i2c_type *i2c_x, confirm_state new_state) +{ + i2c_x->oaddr2_bit.addr2en = new_state; +} + +/** + * @brief enable or disable smbus mode. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param mode: smbus device mode. + * this parameter can be one of the following values: + * - I2C_SMBUS_MODE_DEVICE: smbus device. + * - I2C_SMBUS_MODE_HOST: smbus host. + * @param new_state (TRUE or FALSE). + * @retval none + */ +void i2c_smbus_enable(i2c_type *i2c_x, i2c_smbus_mode_type mode, confirm_state new_state) +{ + switch (mode) + { + case I2C_SMBUS_MODE_DEVICE: + i2c_x->ctrl1_bit.devaddren = new_state; + break; + case I2C_SMBUS_MODE_HOST: + i2c_x->ctrl1_bit.haddren = new_state; + break; + default: + break; + } +} + +/** + * @brief enable or disable peripheral. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param new_state (TRUE or FALSE). + * @retval none + */ +void i2c_enable(i2c_type *i2c_x, confirm_state new_state) +{ + i2c_x->ctrl1_bit.i2cen = new_state; +} + +/** + * @brief enable or disable clock stretch. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param new_state (TRUE or FALSE). + * @retval none + */ +void i2c_clock_stretch_enable(i2c_type *i2c_x, confirm_state new_state) +{ + i2c_x->ctrl1_bit.stretch = (!new_state); +} + +/** + * @brief enable or disable ack. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param new_state (TRUE or FALSE). + * @retval none. + */ +void i2c_ack_enable(i2c_type *i2c_x, confirm_state new_state) +{ + i2c_x->ctrl2_bit.nacken = (!new_state); +} + +/** + * @brief enable or disable 10-bit address mode (master transfer). + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param new_state (TRUE or FALSE). + * @retval none + */ +void i2c_addr10_mode_enable(i2c_type *i2c_x, confirm_state new_state) +{ + i2c_x->ctrl2_bit.addr10 = new_state; +} + +/** + * @brief config the slave address to be transmitted. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param address: slave address. + * @retval none + */ +void i2c_transfer_addr_set(i2c_type *i2c_x, uint16_t address) +{ + i2c_x->ctrl2_bit.saddr = address & 0x03FF; +} + +/** + * @brief get the slave address to be transmitted. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @retval slave address + */ +uint16_t i2c_transfer_addr_get(i2c_type *i2c_x) +{ + return i2c_x->ctrl2_bit.saddr; +} + +/** + * @brief config the master transfer direction. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param i2c_direction: transfer request direction. + * this parameter can be one of the following values: + * - I2C_DIR_TRANSMIT: master request a write transfer. + * - I2C_DIR_RECEIVE: master request a read transfer. + * @retval none + */ +void i2c_transfer_dir_set(i2c_type *i2c_x, i2c_transfer_dir_type i2c_direction) +{ + i2c_x->ctrl2_bit.dir = i2c_direction; +} + +/** + * @brief slave get the i2c transfer direction. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @retval the value of the slave direction + * - I2C_DIR_TRANSMIT: master request a write transfer, slave enters receiver mode. + * - I2C_DIR_RECEIVE: master request a read transfer, slave enters transmitter mode. + */ +i2c_transfer_dir_type i2c_transfer_dir_get(i2c_type *i2c_x) +{ + if (i2c_x->sts_bit.sdir == 0) + { + return I2C_DIR_TRANSMIT; + } + else + { + return I2C_DIR_RECEIVE; + } +} + +/** + * @brief get the i2c slave matched address. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @retval slave matched address. + */ +uint8_t i2c_matched_addr_get(i2c_type *i2c_x) +{ + return (i2c_x->sts_bit.addr << 1); +} + +/** + * @brief enable or disable auto send stop mode. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param new_state (TRUE or FALSE). + * @retval none + */ +void i2c_auto_stop_enable(i2c_type *i2c_x, confirm_state new_state) +{ + i2c_x->ctrl2_bit.astopen = new_state; +} + +/** + * @brief enable or disable cnt reload mode. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param new_state (TRUE or FALSE). + * @retval none + */ +void i2c_reload_enable(i2c_type *i2c_x, confirm_state new_state) +{ + i2c_x->ctrl2_bit.rlden = new_state; +} + +/** + * @brief config the transfer cnt . + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param cnt: transfer cnt. + * @retval none + */ +void i2c_cnt_set(i2c_type *i2c_x, uint8_t cnt) +{ + i2c_x->ctrl2_bit.cnt = cnt; +} + +/** + * @brief enable or disable read 10-bit header, this mode + * only used in 10-bit address mode read. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param new_state (TRUE or FALSE). + * @retval none + */ +void i2c_addr10_header_enable(i2c_type *i2c_x, confirm_state new_state) +{ + i2c_x->ctrl2_bit.readh10 = new_state; +} + +/** + * @brief enable or disable general call mode. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param new_state (TRUE or FALSE). + * @retval none + */ +void i2c_general_call_enable(i2c_type *i2c_x, confirm_state new_state) +{ + i2c_x->ctrl1_bit.gcaen = new_state; +} + +/** + * @brief drives the smbus alert pin high or low. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param level + * this parameter can be one of the following values: + * - I2C_SMBUS_ALERT_LOW: smbus alert set low. + * - I2C_SMBUS_ALERT_HIGH: smbus alert set high. + * @retval none + */ +void i2c_smbus_alert_set(i2c_type *i2c_x, i2c_smbus_alert_set_type level) +{ + i2c_x->ctrl1_bit.smbalert = level; +} + +/** + * @brief enable or disable slave data control. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param new_state (TRUE or FALSE). + * @retval none + */ +void i2c_slave_data_ctrl_enable(i2c_type *i2c_x, confirm_state new_state) +{ + i2c_x->ctrl1_bit.sctrl = new_state; +} + +/** + * @brief enable or disable pec calculate. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param new_state (TRUE or FALSE). + * @retval none + */ +void i2c_pec_calculate_enable(i2c_type *i2c_x, confirm_state new_state) +{ + i2c_x->ctrl1_bit.pecen = new_state; +} + +/** + * @brief enable or disable pec transfer. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param new_state (TRUE or FALSE). + * @retval none + */ +void i2c_pec_transmit_enable(i2c_type *i2c_x, confirm_state new_state) +{ + i2c_x->ctrl2_bit.pecten = new_state; +} + +/** + * @brief get the i2c pec value. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @retval the value of the pec. + */ +uint8_t i2c_pec_value_get(i2c_type *i2c_x) +{ + return (uint8_t)(i2c_x->pec_bit.pecval); +} + +/** + * @brief config the i2c bus timeout. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param timeout: timeout (0x0000~0x0FFF). + * @retval none + */ +void i2c_timeout_set(i2c_type *i2c_x, uint16_t timeout) +{ + i2c_x->timeout_bit.totime = timeout; +} + +/** + * @brief config the bus timeout detcet level. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param level + * this parameter can be one of the following values: + * - I2C_TIMEOUT_DETCET_HIGH: detect high level timeout. + * - I2C_TIMEOUT_DETCET_LOW: detect low level timeout. + * @retval none + */ +void i2c_timeout_detcet_set(i2c_type *i2c_x, i2c_timeout_detcet_type mode) +{ + i2c_x->timeout_bit.tomode = mode; +} + +/** + * @brief enable or disable bus timeout. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param new_state (TRUE or FALSE). + * @retval none + */ +void i2c_timeout_enable(i2c_type *i2c_x, confirm_state new_state) +{ + i2c_x->timeout_bit.toen = new_state; +} + +/** + * @brief config the i2c extend bus timeout. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param timeout: extend timeout (0x0000~0x0FFF). + * @retval none + */ +void i2c_ext_timeout_set(i2c_type *i2c_x, uint16_t timeout) +{ + i2c_x->timeout_bit.exttime = timeout; +} + +/** + * @brief enable or disable extend bus timeout. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param new_state (TRUE or FALSE). + * @retval none + */ +void i2c_ext_timeout_enable(i2c_type *i2c_x, confirm_state new_state) +{ + i2c_x->timeout_bit.exten = new_state; +} + +/** + * @brief enable or disable interrupts. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param i2c_int: interrupts sources. + * this parameter can be one of the following values: + * - I2C_TD_INT: transmit data interrupt. + * - I2C_RD_INT: receive data interrupt. + * - I2C_ADDR_INT: address match interrupt. + * - I2C_ACKFIAL_INT: ack fail interrupt. + * - I2C_STOP_INT: stop detect interrupt. + * - I2C_TDC_INT: transmit data complete interrupt. + * - I2C_ERR_INT: bus error interrupt. + * @param new_state (TRUE or FALSE). + * @retval none + */ +void i2c_interrupt_enable(i2c_type *i2c_x, uint32_t source, confirm_state new_state) +{ + if (new_state != FALSE) + { + i2c_x->ctrl1 |= source; + } + else + { + i2c_x->ctrl1 &= (uint32_t)~source; + } +} + +/** + * @brief get interrupt status + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param source + * this parameter can be one of the following values: + * - I2C_TD_INT: transmit data interrupt. + * - I2C_RD_INT: receive data interrupt. + * - I2C_ADDR_INT: address match interrupt. + * - I2C_ACKFIAL_INT: ack fail interrupt. + * - I2C_STOP_INT: stop detect interrupt. + * - I2C_TDC_INT: transmit data complete interrupt. + * - I2C_ERR_INT: bus error interrupt. + * @retval flag_status (SET or RESET) + */ +flag_status i2c_interrupt_get(i2c_type *i2c_x, uint16_t source) +{ + if((i2c_x->ctrl1 & source) != RESET) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief enable or disable dma requests. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param dma_req: dma transfer request. + * this parameter can be one of the following values: + * - I2C_DMA_REQUEST_TX: dma transmit request. + * - I2C_DMA_REQUEST_RX: dma receive request. + * @param new_state (TRUE or FALSE). + * @retval none + */ +void i2c_dma_enable(i2c_type *i2c_x, i2c_dma_request_type dma_req, confirm_state new_state) +{ + if(dma_req == I2C_DMA_REQUEST_TX) + { + i2c_x->ctrl1_bit.dmaten = new_state; + } + else + { + i2c_x->ctrl1_bit.dmaren = new_state; + } +} + +/** + * @brief config data transfer. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param address: slave address. + * @param cnt: transfer conuter(0~255) + * @param rld_stop: config reload and gen stop condition mode. + * this parameter can be one of the following values: + * - I2C_AUTO_STOP_MODE: auto generate stop mode. + * - I2C_SOFT_STOP_MODE: soft generate stop mode. + * - I2C_RELOAD_MODE: reload mode. + * @param start: config gen start condition mode. + * this parameter can be one of the following values: + * - I2C_WITHOUT_START: transfer data without start condition. + * - I2C_GEN_START_READ: read data and generate start. + * - I2C_GEN_START_WRITE: send data and generate start. + * @retval none + */ +void i2c_transmit_set(i2c_type *i2c_x, uint16_t address, uint8_t cnt, i2c_reload_stop_mode_type rld_stop, i2c_start_mode_type start) +{ + uint32_t temp; + + /* copy ctrl2 value to temp */ + temp = i2c_x->ctrl2; + + /* clear ctrl2_bit specific bits */ + temp &= ~0x03FF67FF; + + /* transfer mode and address set */ + temp |= address | rld_stop | start; + + /* transfer counter set */ + temp |= (uint32_t)cnt << 16; + + /* update ctrl2 value */ + i2c_x->ctrl2 = temp; +} + +/** + * @brief generate start condition. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @retval none + */ +void i2c_start_generate(i2c_type *i2c_x) +{ + i2c_x->ctrl2_bit.genstart = TRUE; +} + +/** + * @brief generate stop condition. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @retval none + */ +void i2c_stop_generate(i2c_type *i2c_x) +{ + i2c_x->ctrl2_bit.genstop = TRUE; +} + +/** + * @brief send a byte through the i2c periph. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param data: byte to be transmitted. + * @retval none + */ +void i2c_data_send(i2c_type *i2c_x, uint8_t data) +{ + i2c_x->txdt = data; +} + +/** + * @brief receive a byte through the i2c periph. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @retval the value of the received data. + */ +uint8_t i2c_data_receive(i2c_type *i2c_x) +{ + return (uint8_t)i2c_x->rxdt; +} + +/** + * @brief get flag status. + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param flag: specifies the flag to check. + * this parameter can be one of the following values: + * - I2C_TDBE_FLAG: transmit data buffer empty flag. + * - I2C_TDIS_FLAG: send interrupt status. + * - I2C_RDBF_FLAG: receive data buffer full flag. + * - I2C_ADDRF_FLAG: 0~7 bit address match flag. + * - I2C_ACKFAIL_FLAG: acknowledge failure flag. + * - I2C_STOPF_FLAG: stop condition generation complete flag. + * - I2C_TDC_FLAG: transmit data complete flag. + * - I2C_TCRLD_FLAG: transmission is complete, waiting to load data. + * - I2C_BUSERR_FLAG: bus error flag. + * - I2C_ARLOST_FLAG: arbitration lost flag. + * - I2C_OUF_FLAG: overflow or underflow flag. + * - I2C_PECERR_FLAG: pec receive error flag. + * - I2C_TMOUT_FLAG: smbus timeout flag. + * - I2C_ALERTF_FLAG: smbus alert flag. + * - I2C_BUSYF_FLAG: bus busy flag transmission mode. + * - I2C_SDIR_FLAG: slave data transmit direction. + * @retval the new state of flag (SET or RESET). + */ +flag_status i2c_flag_get(i2c_type *i2c_x, uint32_t flag) +{ + if((i2c_x->sts & flag) != RESET) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief clear flag status + * @param i2c_x: to select the i2c peripheral. + * this parameter can be one of the following values: + * I2C1, I2C2, I2C3. + * @param flag: specifies the flag to clear. + * this parameter can be any combination of the following values: + * - I2C_ADDRF_FLAG: 0~7 bit address match flag. + * - I2C_ACKFAIL_FLAG: acknowledge failure flag. + * - I2C_STOPF_FLAG: stop condition generation complete flag. + * - I2C_BUSERR_FLAG: bus error flag. + * - I2C_ARLOST_FLAG: arbitration lost flag. + * - I2C_OUF_FLAG: overflow or underflow flag. + * - I2C_PECERR_FLAG: pec receive error flag. + * - I2C_TMOUT_FLAG: smbus timeout flag. + * - I2C_ALERTF_FLAG: smbus alert flag. + * @retval none + */ +void i2c_flag_clear(i2c_type *i2c_x, uint32_t flag) +{ + i2c_x->clr = flag; +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_misc.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_misc.c new file mode 100644 index 0000000000..9fa3ab1110 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_misc.c @@ -0,0 +1,173 @@ +/** + ************************************************************************** + * @file at32f435_437_misc.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the misc firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* includes ------------------------------------------------------------------*/ +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup MISC + * @brief MISC driver modules + * @{ + */ + +#ifdef MISC_MODULE_ENABLED + +/** @defgroup MISC_private_functions + * @{ + */ + +#define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000) + +/** + * @brief system reset + * @param none + * @retval none + */ +void nvic_system_reset(void) +{ + NVIC_SystemReset(); +} + +/** + * @brief enable nvic irq + * @param irqn (IRQn_Type number) + * @param preempt_priority: preemptive priority value (starting from 0) + * @param sub_priority: subpriority value (starting from 0) + * @retval none + */ +void nvic_irq_enable(IRQn_Type irqn, uint32_t preempt_priority, uint32_t sub_priority) +{ + uint32_t temp_priority = 0; + + /* encode priority */ + temp_priority = NVIC_EncodePriority(NVIC_GetPriorityGrouping(), preempt_priority, sub_priority); + /* set priority */ + NVIC_SetPriority(irqn, temp_priority); + /* enable irqn */ + NVIC_EnableIRQ(irqn); +} + +/** + * @brief disable nvic irq number + * @param irqn (IRQn_Type number) + * @retval none + */ +void nvic_irq_disable(IRQn_Type irqn) +{ + NVIC_DisableIRQ(irqn); +} + +/** + * @brief config nvic priority group + * @param priority_group + * this parameter can be one of the following values: + * - NVIC_PRIORITY_GROUP_0 + * - NVIC_PRIORITY_GROUP_1 + * - NVIC_PRIORITY_GROUP_2 + * - NVIC_PRIORITY_GROUP_3 + * - NVIC_PRIORITY_GROUP_4 + * @retval none + */ +void nvic_priority_group_config(nvic_priority_group_type priority_group) +{ + /* set the prigroup[10:8] bits according to nvic_prioritygroup value */ + NVIC_SetPriorityGrouping(priority_group); +} + +/** + * @brief set the vector table location and offset. + * @param base + * this parameter can be one of the following values: + * - NVIC_VECTTAB_RAM + * - NVIC_VECTTAB_FLASH + * @param offset (vector table base offset field. this value must be a multiple of 0x200) + * @retval none + */ +void nvic_vector_table_set(uint32_t base, uint32_t offset) +{ + SCB->VTOR = base | (offset & (uint32_t)0x1FFFFF80); +} + +/** + * @brief config nvic lowpower mode + * @param lp_mode + * this parameter can be one of the following values: + * - NVIC_LP_SEVONPEND + * - NVIC_LP_SLEEPDEEP + * - NVIC_LP_SLEEPONEXIT + * @param new_state (new state of lp condition. ENABLE or DISABLE) + * @retval none + */ +void nvic_lowpower_mode_config(nvic_lowpower_mode_type lp_mode, confirm_state new_state) +{ + if(new_state != FALSE) + { + SCB->SCR |= lp_mode; + } + else + { + SCB->SCR &= (uint32_t)(~(uint32_t)lp_mode); + } +} + +/** + * @brief config systick clock source + * @param source + * this parameter can be one of the following values: + * - SYSTICK_CLOCK_SOURCE_AHBCLK_DIV8 + * - SYSTICK_CLOCK_SOURCE_AHBCLK_NODIV + * @retval none + */ +void systick_clock_source_config(systick_clock_source_type source) +{ + if(source == SYSTICK_CLOCK_SOURCE_AHBCLK_NODIV) + { + SysTick->CTRL |= SYSTICK_CLOCK_SOURCE_AHBCLK_NODIV; + } + else + { + SysTick->CTRL &= ~(uint32_t)SYSTICK_CLOCK_SOURCE_AHBCLK_NODIV; + } +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ + + diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_pwc.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_pwc.c new file mode 100644 index 0000000000..b952928ff8 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_pwc.c @@ -0,0 +1,250 @@ +/** + ************************************************************************** + * @file at32f435_437_pwc.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the pwc firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup PWC + * @brief PWC driver modules + * @{ + */ + +#ifdef PWC_MODULE_ENABLED + +/** @defgroup PWC_private_functions + * @{ + */ + +/** + * @brief deinitialize the pwc peripheral registers to their default reset values. + * @param none + * @retval none + */ +void pwc_reset(void) +{ + crm_periph_reset(CRM_PWC_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_PWC_PERIPH_RESET, FALSE); +} + +/** + * @brief enable or disable access to the battery powered domain. + * @param new_state: new state of battery powered domain access. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void pwc_battery_powered_domain_access(confirm_state new_state) +{ + PWC->ctrl_bit.bpwen= new_state; +} + +/** + * @brief select the voltage threshold detected by the power voltage detector. + * @param pvm_voltage: select pwc pvm voltage + * this parameter can be one of the following values: + * - PWC_PVM_VOLTAGE_2V3 + * - PWC_PVM_VOLTAGE_2V4 + * - PWC_PVM_VOLTAGE_2V5 + * - PWC_PVM_VOLTAGE_2V6 + * - PWC_PVM_VOLTAGE_2V7 + * - PWC_PVM_VOLTAGE_2V8 + * - PWC_PVM_VOLTAGE_2V9 + * @retval none + */ +void pwc_pvm_level_select(pwc_pvm_voltage_type pvm_voltage) +{ + PWC->ctrl_bit.pvmsel= pvm_voltage; +} + +/** + * @brief enable or disable pwc power voltage monitor (pvm) + * @param new_state: new state of pvm. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void pwc_power_voltage_monitor_enable(confirm_state new_state) +{ + PWC->ctrl_bit.pvmen= new_state; +} + +/** + * @brief enable or disable pwc standby wakeup pin + * @param pin_num: choose the wakeup pin. + * this parameter can be be any combination of the following values: + * - PWC_WAKEUP_PIN_1 + * - PWC_WAKEUP_PIN_2 + * @param new_state: new state of the standby wakeup pin. + * this parameter can be one of the following values: + * - TRUE + * - FALSE + * @retval none + */ +void pwc_wakeup_pin_enable(uint32_t pin_num, confirm_state new_state) +{ + if(new_state == TRUE) + { + PWC->ctrlsts |= pin_num; + } + else + { + PWC->ctrlsts &= ~pin_num; + } +} + +/** + * @brief clear flag of pwc + * @param pwc_flag: select the pwc flag. + * this parameter can be any combination of the following values: + * - PWC_WAKEUP_FLAG + * - PWC_STANDBY_FLAG + * - note:"PWC_PVM_OUTPUT_FLAG" cannot be choose!this bit is readonly bit,it means the voltage monitoring output state + * @retval none + */ +void pwc_flag_clear(uint32_t pwc_flag) +{ + if(pwc_flag & PWC_STANDBY_FLAG) + PWC->ctrl_bit.clsef = TRUE; + if(pwc_flag & PWC_WAKEUP_FLAG) + PWC->ctrl_bit.clswef = TRUE; +} + +/** + * @brief get flag of pwc + * @param pwc_flag: select the pwc flag. + * this parameter can be one of the following values: + * - PWC_WAKEUP_FLAG + * - PWC_STANDBY_FLAG + * - PWC_PVM_OUTPUT_FLAG + * @retval state of select flag(SET or RESET). + */ +flag_status pwc_flag_get(uint32_t pwc_flag) +{ + flag_status status = RESET; + if ((PWC->ctrlsts & pwc_flag) == RESET) + { + status = RESET; + } + else + { + status = SET; + } + return status; +} + +/** + * @brief enter pwc sleep mode + * @param sleep_mode_enter: choose the instruction to enter sleep mode. + * this parameter can be one of the following values: + * - PWC_SLEEP_ENTER_WFI + * - PWC_SLEEP_ENTER_WFE + * @retval none + */ +void pwc_sleep_mode_enter(pwc_sleep_enter_type pwc_sleep_enter) +{ + SCB->SCR &= (uint32_t)~0x4; + if(pwc_sleep_enter == PWC_SLEEP_ENTER_WFE) + { + __SEV(); + __WFE(); + __WFE(); + } + else if(pwc_sleep_enter == PWC_SLEEP_ENTER_WFI) + { + __WFI(); + } +} + +/** + * @brief enter pwc deep-sleep mode + * @param pwc_deep_sleep_enter: choose the instruction to enter deep sleep mode. + * this parameter can be one of the following values: + * - PWC_DEEP_SLEEP_ENTER_WFI + * - PWC_DEEP_SLEEP_ENTER_WFE + * @retval none + */ +void pwc_deep_sleep_mode_enter(pwc_deep_sleep_enter_type pwc_deep_sleep_enter) +{ + SCB->SCR |= 0x04; + if(pwc_deep_sleep_enter == PWC_DEEP_SLEEP_ENTER_WFE) + { + __SEV(); + __WFE(); + __WFE(); + } + else if(pwc_deep_sleep_enter == PWC_DEEP_SLEEP_ENTER_WFI) + { + __WFI(); + } + SCB->SCR &= (uint32_t)~0x4; +} + +/** + * @brief regulate low power consumption in the deep sleep mode + * @param pwc_regulator: set the regulator state. + * this parameter can be one of the following values: + * - PWC_REGULATOR_ON + * - PWC_REGULATOR_LOW_POWER + * @retval none + */ +void pwc_voltage_regulate_set(pwc_regulator_type pwc_regulator) +{ + PWC->ctrl_bit.vrsel = pwc_regulator; +} + +/** + * @brief enter pwc standby mode + * @param none + * @retval none + */ +void pwc_standby_mode_enter(void) +{ + PWC->ctrl_bit.clswef = TRUE; + PWC->ctrl_bit.lpsel = TRUE; + SCB->SCR |= 0x04; +#if defined (__CC_ARM) + __force_stores(); +#endif + while(1) + { + __WFI(); + } +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_qspi.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_qspi.c new file mode 100644 index 0000000000..04facef797 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_qspi.c @@ -0,0 +1,430 @@ +/** + ************************************************************************** + * @file at32f435_437_qspi.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contain all the functions for qspi firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup QSPI + * @brief QSPI driver modules + * @{ + */ + +#ifdef QSPI_MODULE_ENABLED + +/** @defgroup QSPI_private_functions + * @{ + */ + +/** + * @brief enable/disable encryption for qspi. + * @note the function must be configured only when qspi in command-port mode!!! + * @param qspi_x: select the qspi peripheral. + * this parameter can be one of the following values: + * QSPI1,QSPI2. + * @param new_state (TRUE or FALSE) + * @retval none + */ +void qspi_encryption_enable(qspi_type* qspi_x, confirm_state new_state) +{ + qspi_x->ctrl_bit.keyen = new_state; +} + +/** + * @brief set qspi sck mode. + * @note the function must be configured only when qspi in command-port mode!!! + * @param qspi_x: select the qspi peripheral. + * this parameter can be one of the following values: + * QSPI1,QSPI2. + * @param new_mode: new state to be set + * this parameter can be one of the following values: + * - QSPI_SCK_MODE_0 + * - QSPI_SCK_MODE_3 + * @retval none + */ +void qspi_sck_mode_set(qspi_type* qspi_x, qspi_clk_mode_type new_mode) +{ + qspi_x->ctrl_bit.sckmode = new_mode; +} + +/** + * @brief set qspi clock division + * @note the function must be configured only when qspi in command-port mode!!! + * @param qspi_x: select the qspi peripheral. + * this parameter can be one of the following values: + * QSPI1,QSPI2. + * @param new_clkdiv: new division value + * this parameter can be one of the following values: + * - QSPI_CLK_DIV_2 + * - QSPI_CLK_DIV_4 + * - QSPI_CLK_DIV_6 + * - QSPI_CLK_DIV_8 + * - QSPI_CLK_DIV_3 + * - QSPI_CLK_DIV_5 + * - QSPI_CLK_DIV_10 + * - QSPI_CLK_DIV_12 + * @retval none + */ +void qspi_clk_division_set(qspi_type* qspi_x, qspi_clk_div_type new_clkdiv) +{ + qspi_x->ctrl_bit.clkdiv = new_clkdiv; +} + +/** + * @brief enable/disable cache in xip mode + * @note the function must be configured only when qspi in command-port mode!!! + * @param qspi_x: select the qspi peripheral. + * this parameter can be one of the following values: + * QSPI1,QSPI2. + * @param new_state (TRUE or FALSE) + * @retval none + */ +void qspi_xip_cache_bypass_set(qspi_type* qspi_x, confirm_state new_state) +{ + qspi_x->xip_cmd_w3_bit.bypassc = new_state; +} + +/** + * @brief enable/disable interrupt when command is completed + * @note the function must be configured only when qspi in command-port mode!!! + * @param qspi_x: select the qspi peripheral. + * this parameter can be one of the following values: + * QSPI1,QSPI2. + * @param new_state (TRUE or FALSE) + * @retval none + */ +void qspi_interrupt_enable(qspi_type* qspi_x, confirm_state new_state) +{ + qspi_x->ctrl2_bit.cmdie = new_state; +} + +/** + * @brief get status flags. + * @param qspi_x: select the qspi peripheral. + * this parameter can be one of the following values: + * QSPI1,QSPI2. + * @param flag: specifies the flag to check. + * this parameter can be one of the following values: + * - QSPI_RXFIFORDY_FLAG + * - QSPI_TXFIFORDY_FLAG + * - QSPI_CMDSTS_FLAG + * @retval the new state of usart_flag (SET or RESET). + */ +flag_status qspi_flag_get(qspi_type* qspi_x, uint32_t flag) +{ + flag_status bit_status = RESET; + switch(flag) + { + case QSPI_RXFIFORDY_FLAG: + bit_status = (flag_status)qspi_x->fifosts_bit.rxfifordy; + break; + case QSPI_TXFIFORDY_FLAG: + bit_status = (flag_status)qspi_x->fifosts_bit.txfifordy; + break; + case QSPI_CMDSTS_FLAG: + bit_status = (flag_status)qspi_x->cmdsts_bit.cmdsts; + break; + default: + break; + } + return bit_status; +} + +/** + * @brief clear flags + * @param qspi_x: select the qspi peripheral. + * this parameter can be one of the following values: + * QSPI1,QSPI2. + * @param flag: flags to be clear + * this parameter can be one of the following values: + * - QSPI_CMDSTS_FLAG + * @retval none + */ +void qspi_flag_clear(qspi_type* qspi_x, uint32_t flag) +{ + UNUSED(flag); + qspi_x->cmdsts = QSPI_CMDSTS_FLAG; +} + +/** + * @brief set dma threshold for dma rx + * @note the function must be configured only when qspi in command-port mode!!! + * @param qspi_x: select the qspi peripheral. + * this parameter can be one of the following values: + * QSPI1,QSPI2. + * @param new_threshold: value to set + * this parameter can be one of the following values: + * - QSPI_DMA_FIFO_THOD_WORD08 + * - QSPI_DMA_FIFO_THOD_WORD16 + * - QSPI_DMA_FIFO_THOD_WORD32 + * @retval none + */ +void qspi_dma_rx_threshold_set(qspi_type* qspi_x, qspi_dma_fifo_thod_type new_threshold) +{ + qspi_x->ctrl2_bit.rxfifo_thod = new_threshold; +} + +/** + * @brief set dma threshold for dma tx + * @note the function must be configured only when qspi in command-port mode!!! + * @param qspi_x: select the qspi peripheral. + * this parameter can be one of the following values: + * QSPI1,QSPI2. + * @param new_threshold: value to set + * this parameter can be one of the following values: + * - QSPI_DMA_FIFO_THOD_WORD08 + * - QSPI_DMA_FIFO_THOD_WORD16 + * - QSPI_DMA_FIFO_THOD_WORD32 + * @retval none + */ +void qspi_dma_tx_threshold_set(qspi_type* qspi_x, qspi_dma_fifo_thod_type new_threshold) +{ + qspi_x->ctrl2_bit.txfifo_thod = new_threshold; +} + +/** + * @brief enable/disable dma transfer + * @note the function must be configured only when qspi in command-port mode!!! + * @param qspi_x: select the qspi peripheral. + * this parameter can be one of the following values: + * QSPI1,QSPI2. + * @param new_state (TRUE or FALSE) + * @retval none + */ +void qspi_dma_enable(qspi_type* qspi_x, confirm_state new_state) +{ + qspi_x->ctrl2_bit.dmaen = new_state; +} + +/** + * @brief set wip position in status register of flash + * @note the function must be configured only when qspi in command-port mode!!! + * @param qspi_x: select the qspi peripheral. + * this parameter can be one of the following values: + * QSPI1,QSPI2. + * @param busy_pos: value to set + * this parameter can be one of the following values: + * - QSPI_BUSY_OFFSET_0 + * - QSPI_BUSY_OFFSET_1 + * - QSPI_BUSY_OFFSET_2 + * - QSPI_BUSY_OFFSET_3 + * - QSPI_BUSY_OFFSET_4 + * - QSPI_BUSY_OFFSET_5 + * - QSPI_BUSY_OFFSET_6 + * - QSPI_BUSY_OFFSET_7 + * @retval none + */ +void qspi_busy_config(qspi_type* qspi_x, qspi_busy_pos_type busy_pos) +{ + qspi_x->ctrl_bit.busy = busy_pos; +} + +/** + * @brief enable xip mode or command-port mode. + * @param qspi_x: select the qspi peripheral. + * this parameter can be one of the following values: + * QSPI1,QSPI2. + * @param new_state (TRUE or FALSE) + * @retval none + */ +void qspi_xip_enable(qspi_type* qspi_x, confirm_state new_state) +{ + /* skip if state is no change */ + if(new_state == (confirm_state)(qspi_x->ctrl_bit.xipsel)) + { + return; + } + + /* wait until tx fifo emoty*/ + while(qspi_x->fifosts_bit.txfifordy == 0); + + /* flush and reset qspi state */ + qspi_x->ctrl_bit.xiprcmdf = 1; + + /* wait until action is finished */ + while(qspi_x->ctrl_bit.abort); + + /* set xip mode to new state */ + qspi_x->ctrl_bit.xipsel = new_state; + + /* wait until abort is not set */ + while(qspi_x->ctrl_bit.abort); + + /* wait until cache status valid*/ + if(new_state == TRUE) + { + while( qspi_x->xip_cmd_w3_bit.csts ); + } +} + +/** + * @brief set command-port and qspi_x will start to work + * @param qspi_x: select the qspi peripheral. + * this parameter can be one of the following values: + * QSPI1,QSPI2. + * @param qspi_cmd_struct: pointer to qspi cmd structure + * @retval none + */ +void qspi_cmd_operation_kick(qspi_type* qspi_x, qspi_cmd_type* qspi_cmd_struct) +{ + uint32_t w1_val = 0, w3_val = 0; + + /* config analyse cmd_w0 register */ + qspi_x->cmd_w0 = (uint32_t)qspi_cmd_struct->address_code; + + /* config analyse cmd_w1 register */ + w1_val = (uint32_t)qspi_cmd_struct->address_length; + w1_val |= (uint32_t)(qspi_cmd_struct->second_dummy_cycle_num << 16); + w1_val |= (uint32_t)(qspi_cmd_struct->instruction_length << 24); + w1_val |= (uint32_t)(qspi_cmd_struct->pe_mode_enable << 28); + qspi_x->cmd_w1 = w1_val; + + /* config analyse cmd_w2 register */ + qspi_x->cmd_w2 = (uint32_t)qspi_cmd_struct->data_counter; + + /* config analyse cmd_w3 register */ + w3_val = (uint32_t)(qspi_cmd_struct->write_data_enable << 1); + w3_val |= (uint32_t)(qspi_cmd_struct->read_status_enable << 2); + w3_val |= (uint32_t)(qspi_cmd_struct->read_status_config << 3); + w3_val |= (uint32_t)(qspi_cmd_struct->operation_mode << 5); + w3_val |= (uint32_t)(qspi_cmd_struct->pe_mode_operate_code << 16); + w3_val |= (uint32_t)(qspi_cmd_struct->instruction_code << 24); + qspi_x->cmd_w3 = w3_val; +} + +/** + * @brief initial xip mode for qspi_x + * @param qspi_x: select the qspi peripheral. + * this parameter can be one of the following values: + * QSPI1,QSPI2. + * @param xip_init_struct: pointer to xip init structure. + * @retval none. + */ +void qspi_xip_init(qspi_type* qspi_x, qspi_xip_type* xip_init_struct) +{ + uint32_t xc0_val = 0, xc1_val = 0, xc2_val = 0; + /* config analyse xip_cmd_w0 register */ + xc0_val = (uint32_t)xip_init_struct->read_second_dummy_cycle_num; + xc0_val |= (uint32_t)(xip_init_struct->read_operation_mode << 8); + xc0_val |= (uint32_t)(xip_init_struct->read_address_length << 11); + xc0_val |= (uint32_t)(xip_init_struct->read_instruction_code << 12); + qspi_x->xip_cmd_w0 = xc0_val; + + /* config analyse xip_cmd_w1 register */ + xc1_val = (uint32_t)xip_init_struct->write_second_dummy_cycle_num; + xc1_val |= (uint32_t)(xip_init_struct->write_operation_mode << 8); + xc1_val |= (uint32_t)(xip_init_struct->write_address_length << 11); + xc1_val |= (uint32_t)(xip_init_struct->write_instruction_code << 12); + qspi_x->xip_cmd_w1 = xc1_val; + + /* config analyse xip_cmd_w2 register */ + xc2_val = (uint32_t)xip_init_struct->read_data_counter; + xc2_val |= (uint32_t)(xip_init_struct->read_time_counter << 8); + xc2_val |= (uint32_t)(xip_init_struct->read_select_mode << 15); + xc2_val |= (uint32_t)(xip_init_struct->write_data_counter << 16); + xc2_val |= (uint32_t)(xip_init_struct->write_time_counter << 24); + xc2_val |= (uint32_t)(xip_init_struct->write_select_mode << 31); + qspi_x->xip_cmd_w2 = xc2_val; +} + +/** + * @brief read one byte from qspi device in command mode + * @param qspi_x: select the qspi peripheral. + * @retval 8-bit data. + */ +uint8_t qspi_byte_read(qspi_type* qspi_x) +{ + return qspi_x->dt_u8; +} + +/** + * @brief read one half-word from qspi device in command mode + * @param qspi_x: select the qspi peripheral. + * @retval 16-bit data. + */ +uint16_t qspi_half_word_read(qspi_type* qspi_x) +{ + return qspi_x->dt_u16; +} + +/** + * @brief read one word from qspi device in command mode + * @param qspi_x: select the qspi peripheral. + * @retval 32-bit data. + */ +uint32_t qspi_word_read(qspi_type* qspi_x) +{ + return qspi_x->dt; +} + +/** + * @brief write one byte to qspi device in command mode + * @param qspi_x: select the qspi peripheral. + * @param value: 8-bit data. + * @retval none. + */ +void qspi_byte_write(qspi_type* qspi_x, uint8_t value) +{ + qspi_x->dt_u8 = value; +} + +/** + * @brief write one half-word to qspi device in command mode + * @param qspi_x: select the qspi peripheral. + * @param value: 16-bit data. + * @retval none. + */ +void qspi_half_word_write(qspi_type* qspi_x, uint16_t value) +{ + qspi_x->dt_u16 = value; +} + +/** + * @brief write one word to qspi device in command mode + * @param qspi_x: select the qspi peripheral. + * @param value: 32-bit data. + * @retval none. + */ +void qspi_word_write(qspi_type* qspi_x, uint32_t value) +{ + qspi_x->dt = value; +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_scfg.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_scfg.c new file mode 100644 index 0000000000..3728c2dfb6 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_scfg.c @@ -0,0 +1,220 @@ +/** + ************************************************************************** + * @file at32f435_437_scfg.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the system config firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup SCFG + * @brief SCFG driver modules + * @{ + */ + +#ifdef SCFG_MODULE_ENABLED + +/** @defgroup SCFG_private_functions + * @{ + */ + +/** + * @brief scfg reset + * @param none + * @retval none + */ +void scfg_reset(void) +{ + crm_periph_reset(CRM_SCFG_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_SCFG_PERIPH_RESET, FALSE); +} + +/** + * @brief scfg xmc address mapping swap set + * @param xmc_swap + * this parameter can be one of the following values: + * - SCFG_XMC_SWAP_NONE + * - SCFG_XMC_SWAP_MODE1 + * - SCFG_XMC_SWAP_MODE2 + * - SCFG_XMC_SWAP_MODE3 + * @retval none + */ +void scfg_xmc_mapping_swap_set(scfg_xmc_swap_type xmc_swap) +{ + SCFG->cfg1_bit.swap_xmc = xmc_swap; +} + +/** + * @brief scfg infrared config + * @param source + * this parameter can be one of the following values: + * - SCFG_IR_SOURCE_TMR10 + * - SCFG_IR_SOURCE_USART1 + * - SCFG_IR_SOURCE_USART2 + * @param polarity + * this parameter can be one of the following values: + * - SCFG_IR_POLARITY_NO_AFFECTE + * - SCFG_IR_POLARITY_REVERSE + * @retval none + */ +void scfg_infrared_config(scfg_ir_source_type source, scfg_ir_polarity_type polarity) +{ + SCFG->cfg1_bit.ir_src_sel = source; + SCFG->cfg1_bit.ir_pol = polarity; +} + +/** + * @brief scfg memory address mapping set + * @param mem_map + * this parameter can be one of the following values: + * - SCFG_MEM_MAP_MAIN_MEMORY + * - SCFG_MEM_MAP_BOOT_MEMORY + * - SCFG_MEM_MAP_XMC_BANK1 + * - SCFG_MEM_MAP_INTERNAL_SRAM + * - SCFG_MEM_MAP_XMC_SDRAM_BANK1 + * @retval none + */ +void scfg_mem_map_set(scfg_mem_map_type mem_map) +{ + SCFG->cfg1_bit.mem_map_sel = mem_map; +} + +/** + * @brief scfg emac interface set + * @param mode + * this parameter can be one of the following values: + * - SCFG_EMAC_SELECT_MII + * - SCFG_EMAC_SELECT_RMII + * @retval none + */ +void scfg_emac_interface_set(scfg_emac_interface_type mode) +{ + SCFG->cfg2_bit.mii_rmii_sel = mode; +} + +/** + * @brief select the gpio pin used as exint line. + * @param port_source: + * select the gpio port to be used as source for exint lines. + * this parameter can be one of the following values: + * - SCFG_PORT_SOURCE_GPIOA + * - SCFG_PORT_SOURCE_GPIOB + * - SCFG_PORT_SOURCE_GPIOC + * - SCFG_PORT_SOURCE_GPIOD + * - SCFG_PORT_SOURCE_GPIOE + * - SCFG_PORT_SOURCE_GPIOF + * - SCFG_PORT_SOURCE_GPIOG + * - SCFG_PORT_SOURCE_GPIOH + * @param pin_source: + * specifies the exint line to be configured. + * this parameter can be one of the following values: + * - SCFG_PINS_SOURCE0 + * - SCFG_PINS_SOURCE1 + * - SCFG_PINS_SOURCE2 + * - SCFG_PINS_SOURCE3 + * - SCFG_PINS_SOURCE4 + * - SCFG_PINS_SOURCE5 + * - SCFG_PINS_SOURCE6 + * - SCFG_PINS_SOURCE7 + * - SCFG_PINS_SOURCE8 + * - SCFG_PINS_SOURCE9 + * - SCFG_PINS_SOURCE10 + * - SCFG_PINS_SOURCE11 + * - SCFG_PINS_SOURCE12 + * - SCFG_PINS_SOURCE13 + * - SCFG_PINS_SOURCE14 + * - SCFG_PINS_SOURCE15 + * @retval none + */ +void scfg_exint_line_config(scfg_port_source_type port_source, scfg_pins_source_type pin_source) +{ + uint32_t tmp = 0x00; + tmp = ((uint32_t)0x0F) << (0x04 * (pin_source & (uint8_t)0x03)); + + switch (pin_source >> 0x02) + { + case 0: + SCFG->exintc1 &= ~tmp; + SCFG->exintc1 |= (((uint32_t)port_source) << (0x04 * (pin_source & (uint8_t)0x03))); + break; + case 1: + SCFG->exintc2 &= ~tmp; + SCFG->exintc2 |= (((uint32_t)port_source) << (0x04 * (pin_source & (uint8_t)0x03))); + break; + case 2: + SCFG->exintc3 &= ~tmp; + SCFG->exintc3 |= (((uint32_t)port_source) << (0x04 * (pin_source & (uint8_t)0x03))); + break; + case 3: + SCFG->exintc4 &= ~tmp; + SCFG->exintc4 |= (((uint32_t)port_source) << (0x04 * (pin_source & (uint8_t)0x03))); + break; + default: + break; + } +} + +/** + * @brief enable or disable gpio pins ultra driven. + * @param value: + * this parameter can be one of the following values: + * - SCFG_ULTRA_DRIVEN_PB3 + * - SCFG_ULTRA_DRIVEN_PB9 + * - SCFG_ULTRA_DRIVEN_PB10 + * - SCFG_ULTRA_DRIVEN_PD12 + * - SCFG_ULTRA_DRIVEN_PD13 + * - SCFG_ULTRA_DRIVEN_PD14 + * - SCFG_ULTRA_DRIVEN_PD15 + * - SCFG_ULTRA_DRIVEN_PF14 + * - SCFG_ULTRA_DRIVEN_PF15 + * @param new_state (TRUE or FALSE) + * @retval none + */ +void scfg_pins_ultra_driven_enable(scfg_ultra_driven_pins_type value, confirm_state new_state) +{ + if(TRUE == new_state) + { + SCFG_REG(value) |= SCFG_REG_BIT(value); + } + else + { + SCFG_REG(value) &= ~(SCFG_REG_BIT(value)); + } +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_sdio.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_sdio.c new file mode 100644 index 0000000000..2cff6dc727 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_sdio.c @@ -0,0 +1,575 @@ +/** + ************************************************************************** + * @file at32f435_437_sdio.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the sdio firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup SDIO + * @brief SDIO driver modules + * @{ + */ + +#ifdef SDIO_MODULE_ENABLED + +/** @defgroup SDIO_private_functions + * @{ + */ + +/** + * @brief reset the sdio register + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @retval none + */ +void sdio_reset(sdio_type *sdio_x) +{ + sdio_x->pwrctrl = 0x0; + sdio_x->clkctrl = 0x0; + sdio_x->argu = 0x0; + sdio_x->cmdctrl = 0x0; + sdio_x->dttmr = 0x0; + sdio_x->dtlen = 0x0; + sdio_x->dtctrl = 0x0; + sdio_x->inten = 0x0; + sdio_x->intclr = 0x004007FF; +} + +/** + * @brief set the power status of the controller + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param power_state + * this parameter can be one of the following values: + * - SDIO_POWER_OFF + * - SDIO_POWER_ON + * @retval none + */ +void sdio_power_set(sdio_type *sdio_x, sdio_power_state_type power_state) +{ + sdio_x->pwrctrl_bit.ps = power_state; +} + +/** + * @brief get power status. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @retval sdio_power_state_type (SDIO_POWER_ON or SDIO_POWER_OFF) + */ +sdio_power_state_type sdio_power_status_get(sdio_type *sdio_x) +{ + return (sdio_power_state_type)(sdio_x->pwrctrl_bit.ps); +} + +/** + * @brief config sdio clock + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param clk_div: sdio clock divide factor(frequency = sdio_clk / [clk_psc + 2]). + * @param clk_edg + * this parameter can be one of the following values: + * - SDIO_CLOCK_EDGE_RISING + * - SDIO_CLOCK_EDGE_FALLING + * @retval none + */ +void sdio_clock_config(sdio_type *sdio_x, uint16_t clk_div, sdio_edge_phase_type clk_edg) +{ + /* config clock edge */ + sdio_x->clkctrl_bit.clkegs = clk_edg; + + /* config clock divide [7:0] */ + sdio_x->clkctrl_bit.clkdiv_l = (clk_div & 0xFF); + + /* config clock divide [9:8] */ + sdio_x->clkctrl_bit.clkdiv_h = ((clk_div & 0x300) >> 8); +} + +/** + * @brief config sdio bus width + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param width + * this parameter can be one of the following values: + * - SDIO_BUS_WIDTH_D1 + * - SDIO_BUS_WIDTH_D4 + * - SDIO_BUS_WIDTH_D8 + * @retval none + */ +void sdio_bus_width_config(sdio_type *sdio_x, sdio_bus_width_type width) +{ + sdio_x->clkctrl_bit.busws = width; +} + +/** + * @brief enable or disable clock divider bypss + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param new_state (TRUE or FALSE) + * @retval none + */ +void sdio_clock_bypass(sdio_type *sdio_x, confirm_state new_state) +{ + sdio_x->clkctrl_bit.bypsen = new_state; +} + +/** + * @brief enable or disable power saving mode, config sdio_ck clock output + * when the bus is idle. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param new_state (TRUE or FALSE) + * @retval none + */ +void sdio_power_saving_mode_enable(sdio_type *sdio_x, confirm_state new_state) +{ + sdio_x->clkctrl_bit.pwrsven = new_state; +} + +/** + * @brief enable or disable hardware flow control. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param new_state (TRUE or FALSE) + * @retval none + */ +void sdio_flow_control_enable(sdio_type *sdio_x, confirm_state new_state) +{ + sdio_x->clkctrl_bit.hfcen = new_state; +} + +/** + * @brief enable or disable sdio_ck output. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param new_state (TRUE or FALSE) + * @retval none + */ +void sdio_clock_enable(sdio_type *sdio_x, confirm_state new_state) +{ + sdio_x->clkctrl_bit.clkoen = new_state; +} + +/** + * @brief enable or disable dma. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param new_state (TRUE or FALSE) + * @retval none + */ +void sdio_dma_enable(sdio_type *sdio_x, confirm_state new_state) +{ + sdio_x->dtctrl_bit.dmaen = new_state; +} + +/** + * @brief config corresponding interrupt. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param int_opt + * this parameter can be one of the following values: + * - SDIO_CMDFAIL_INT + * - SDIO_DTFAIL_INT + * - SDIO_CMDTIMEOUT_INT + * - SDIO_DTTIMEOUT_INT + * - SDIO_TXERRU_INT + * - SDIO_RXERRO_INT + * - SDIO_CMDRSPCMPL_INT + * - SDIO_CMDCMPL_INT + * - SDIO_DTCMP_INT + * - SDIO_SBITERR_INT + * - SDIO_DTBLKCMPL_INT + * - SDIO_DOCMD_INT + * - SDIO_DOTX_INT + * - SDIO_DORX_INT + * - SDIO_TXBUFH_INT + * - SDIO_RXBUFH_INT + * - SDIO_TXBUFF_INT + * - SDIO_RXBUFF_INT + * - SDIO_TXBUFE_INT + * - SDIO_RXBUFE_INT + * - SDIO_TXBUF_INT + * - SDIO_RXBUF_INT + * - SDIO_SDIOIF_INT + * @param new_state (TRUE or FALSE) + * @retval none + */ +void sdio_interrupt_enable(sdio_type *sdio_x, uint32_t int_opt, confirm_state new_state) +{ + /* enable interrupt */ + if(TRUE == new_state) + { + sdio_x->inten |= int_opt; + } + /* disable interrupt */ + else + { + sdio_x->inten &= ~(int_opt); + } +} + +/** + * @brief get sdio flag. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param flag + * this parameter can be one of the following values: + * - SDIO_CMDFAIL_FLAG + * - SDIO_DTFAIL_FLAG + * - SDIO_CMDTIMEOUT_FLAG + * - SDIO_DTTIMEOUT_FLAG + * - SDIO_TXERRU_FLAG + * - SDIO_RXERRO_FLAG + * - SDIO_CMDRSPCMPL_FLAG + * - SDIO_CMDCMPL_FLAG + * - SDIO_DTCMPL_FLAG + * - SDIO_SBITERR_FLAG + * - SDIO_DTBLKCMPL_FLAG + * - SDIO_DOCMD_FLAG + * - SDIO_DOTX_FLAG + * - SDIO_DORX_FLAG + * - SDIO_TXBUFH_FLAG + * - SDIO_RXBUFH_FLAG + * - SDIO_TXBUFF_FLAG + * - SDIO_RXBUFF_FLAG + * - SDIO_TXBUFE_FLAG + * - SDIO_RXBUFE_FLAG + * - SDIO_TXBUF_FLAG + * - SDIO_RXBUF_FLAG + * - SDIO_SDIOIF_FLAG + * @retval flag_status (SET or RESET) + */ +flag_status sdio_flag_get(sdio_type *sdio_x, uint32_t flag) +{ + flag_status status = RESET; + + if((sdio_x->sts & flag) == flag) + { + status = SET; + } + else + { + status = RESET; + } + + return status; +} + +/** + * @brief clear sdio flag. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param int_opt + * this parameter can be any combination of the following values: + * - SDIO_CMDFAIL_FLAG + * - SDIO_DTFAIL_FLAG + * - SDIO_CMDTIMEOUT_FLAG + * - SDIO_DTTIMEOUT_FLAG + * - SDIO_TXERRU_FLAG + * - SDIO_RXERRO_FLAG + * - SDIO_CMDRSPCMPL_FLAG + * - SDIO_CMDCMPL_FLAG + * - SDIO_DTCMPL_FLAG + * - SDIO_SBITERR_FLAG + * - SDIO_DTBLKCMPL_FLAG + * - SDIO_SDIOIF_FLAG + * @retval none + */ +void sdio_flag_clear(sdio_type *sdio_x, uint32_t flag) +{ + sdio_x->intclr = flag; +} + +/** + * @brief config sdio command. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param command_struct : pointer to a sdio_command_struct_type structure + * that contains the configuration information for the sdio command. + * @retval none + */ +void sdio_command_config(sdio_type *sdio_x, sdio_command_struct_type *command_struct) +{ + /* disable command path state machine */ + sdio_x->cmdctrl_bit.ccsmen = FALSE; + + /* config command argument */ + sdio_x->argu = command_struct->argument; + + /* config command register */ + sdio_x->cmdctrl_bit.cmdidx = command_struct->cmd_index; + sdio_x->cmdctrl_bit.rspwt = command_struct->rsp_type; + sdio_x->cmdctrl_bit.intwt = (command_struct->wait_type & 0x1); /* [1:0] -> [0] */ + sdio_x->cmdctrl_bit.pndwt = (command_struct->wait_type & 0x2)>>1; /* [1:0] -> [1] */ +} + +/** + * @brief enable or disable command path state machine(CPSM). + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param new_state (TRUE or FALSE) + * @retval none + */ +void sdio_command_state_machine_enable(sdio_type *sdio_x, confirm_state new_state) +{ + sdio_x->cmdctrl_bit.ccsmen = new_state; +} + +/** + * @brief get command index of last command for which response received. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param new_state (TRUE or FALSE) + * @retval uint8_t: command index + */ +uint8_t sdio_command_response_get(sdio_type *sdio_x) +{ + return sdio_x->rspcmd_bit.rspcmd; +} + +/** + * @brief get response received from the card for the last command. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param reg_index + * this parameter can be one of the following values: + * - SDIO_RSP1_INDEX + * - SDIO_RSP2_INDEX + * - SDIO_RSP3_INDEX + * - SDIO_RSP4_INDEX + * @retval uint32_t: response register value + */ +uint32_t sdio_response_get(sdio_type *sdio_x, sdio_rsp_index_type reg_index) +{ + uint32_t response_value = 0; + + switch(reg_index) + { + case SDIO_RSP1_INDEX: + response_value = sdio_x->rsp1; + break; + case SDIO_RSP2_INDEX: + response_value = sdio_x->rsp2; + break; + case SDIO_RSP3_INDEX: + response_value = sdio_x->rsp3; + break; + case SDIO_RSP4_INDEX: + response_value = sdio_x->rsp4; + break; + default: break; + } + + return response_value; +} + +/** + * @brief config sdio data. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param data_struct : pointer to a sdio_data_struct_type structure + * that contains the configuration information for the sdio data. + * @retval none + */ +void sdio_data_config(sdio_type *sdio_x, sdio_data_struct_type *data_struct) +{ + /* disable data path state machine */ + sdio_x->dtctrl_bit.tfren = FALSE; + + /* config data block, transfer mode and transfer direction */ + sdio_x->dtctrl_bit.blksize = data_struct->block_size; + sdio_x->dtctrl_bit.tfrdir = data_struct->transfer_direction; + sdio_x->dtctrl_bit.tfrmode = data_struct->transfer_mode; + + /* config data length */ + sdio_x->dtlen_bit.dtlen = data_struct->data_length; + + /* config data transfer timeout */ + sdio_x->dttmr_bit.timeout = data_struct->timeout; +} + +/** + * @brief enable or disable data path state machine(DPSM). + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param new_state (TRUE or FALSE) + * @retval none + */ +void sdio_data_state_machine_enable(sdio_type *sdio_x, confirm_state new_state) +{ + sdio_x->dtctrl_bit.tfren = new_state; +} + +/** + * @brief get the number of remaining data bytes to be transferred. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @retval uint32_t: number of bytes + */ +uint32_t sdio_data_counter_get(sdio_type *sdio_x) +{ + return sdio_x->dtcnt; +} + +/** + * @brief read a word data from sdio fifo. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @retval uint32_t: data received + */ +uint32_t sdio_data_read(sdio_type *sdio_x) +{ + return sdio_x->buf; +} + +/** + * @brief get the number of words left to be written to or read from fifo.. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @retval uint32_t: number of words + */ +uint32_t sdio_buffer_counter_get(sdio_type *sdio_x) +{ + return sdio_x->bufcnt; +} + +/** + * @brief write one word data to fifo. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param data: data to be transferred. + * @retval none + */ +void sdio_data_write(sdio_type *sdio_x, uint32_t data) +{ + sdio_x->buf = data; +} + +/** + * @brief set the read wait mode. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param mode + * this parameter can be one of the following values: + * - SDIO_READ_WAIT_CONTROLLED_BY_D2 + * - SDIO_READ_WAIT_CONTROLLED_BY_CK + * @retval none + */ +void sdio_read_wait_mode_set(sdio_type *sdio_x, sdio_read_wait_mode_type mode) +{ + sdio_x->dtctrl_bit.rdwtmode = mode; +} + +/** + * @brief enable or disable to start sd i/o read wait operation. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param new_state (TRUE or FALSE) + * @retval none + */ +void sdio_read_wait_start(sdio_type *sdio_x, confirm_state new_state) +{ + sdio_x->dtctrl_bit.rdwtstart = new_state; +} + +/** + * @brief enable or disable to stop sd i/o read wait operation. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param new_state (TRUE or FALSE) + * @retval none + */ +void sdio_read_wait_stop(sdio_type *sdio_x, confirm_state new_state) +{ + sdio_x->dtctrl_bit.rdwtstop = new_state; +} + +/** + * @brief enable or disable the sd i/o function. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param new_state (TRUE or FALSE) + * @retval none + */ +void sdio_io_function_enable(sdio_type *sdio_x, confirm_state new_state) +{ + sdio_x->dtctrl_bit.ioen = new_state; +} + +/** + * @brief enable or disable sd i/o suspend command sending. + * @param sdio_x: to select the sdio peripheral. + * this parameter can be one of the following values: + * SDIO1, SDIO2. + * @param new_state (TRUE or FALSE) + * @retval none + */ +void sdio_io_suspend_command_set(sdio_type *sdio_x, confirm_state new_state) +{ + sdio_x->cmdctrl_bit.iosusp = new_state; +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_spi.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_spi.c new file mode 100644 index 0000000000..369c34fa23 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_spi.c @@ -0,0 +1,650 @@ +/** + ************************************************************************** + * @file at32f435_437_spi.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the spi firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup SPI + * @brief SPI driver modules + * @{ + */ + +#ifdef SPI_MODULE_ENABLED + +/** @defgroup SPI_private_functions + * @{ + */ + +/** + * @brief spi reset by crm reset register + * @param spi_x: select the spi peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 + * @retval none + */ +void spi_i2s_reset(spi_type *spi_x) +{ + if(spi_x == SPI1) + { + crm_periph_reset(CRM_SPI1_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_SPI1_PERIPH_RESET, FALSE); + } + else if(spi_x == SPI2) + { + crm_periph_reset(CRM_SPI2_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_SPI2_PERIPH_RESET, FALSE); + } + else if(spi_x == SPI3) + { + crm_periph_reset(CRM_SPI3_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_SPI3_PERIPH_RESET, FALSE); + } + else if(spi_x == SPI4) + { + crm_periph_reset(CRM_SPI4_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_SPI4_PERIPH_RESET, FALSE); + } +} + +/** + * @brief spi init config with its default value. + * @param spi_init_struct : pointer to a spi_init_type structure which will + * be initialized. + * @retval none + */ +void spi_default_para_init(spi_init_type* spi_init_struct) +{ + spi_init_struct->transmission_mode = SPI_TRANSMIT_FULL_DUPLEX; + spi_init_struct->master_slave_mode = SPI_MODE_SLAVE; + spi_init_struct->mclk_freq_division = SPI_MCLK_DIV_2; + spi_init_struct->first_bit_transmission = SPI_FIRST_BIT_MSB; + spi_init_struct->frame_bit_num = SPI_FRAME_8BIT; + spi_init_struct->clock_polarity = SPI_CLOCK_POLARITY_LOW; + spi_init_struct->clock_phase = SPI_CLOCK_PHASE_1EDGE; + spi_init_struct->cs_mode_selection = SPI_CS_SOFTWARE_MODE; +} + +/** + * @brief spi init config with its setting value. + * @param spi_x: select the spi peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 + * @param spi_init_struct : pointer to a spi_init_type structure which will be initialized. + * @retval none + */ +void spi_init(spi_type* spi_x, spi_init_type* spi_init_struct) +{ + spi_x->i2sctrl_bit.i2smsel = FALSE; + if(spi_init_struct->transmission_mode == SPI_TRANSMIT_FULL_DUPLEX) + { + spi_x->ctrl1_bit.slben = FALSE; + spi_x->ctrl1_bit.slbtd = FALSE; + spi_x->ctrl1_bit.ora = FALSE; + } + else if(spi_init_struct->transmission_mode == SPI_TRANSMIT_SIMPLEX_RX) + { + spi_x->ctrl1_bit.slben = FALSE; + spi_x->ctrl1_bit.slbtd = FALSE; + spi_x->ctrl1_bit.ora = TRUE; + } + else if(spi_init_struct->transmission_mode == SPI_TRANSMIT_HALF_DUPLEX_RX) + { + spi_x->ctrl1_bit.slben = TRUE; + spi_x->ctrl1_bit.slbtd = FALSE; + spi_x->ctrl1_bit.ora = FALSE; + } + else if(spi_init_struct->transmission_mode == SPI_TRANSMIT_HALF_DUPLEX_TX) + { + spi_x->ctrl1_bit.slben = TRUE; + spi_x->ctrl1_bit.slbtd = TRUE; + spi_x->ctrl1_bit.ora = FALSE; + } + + spi_x->ctrl1_bit.swcsen = spi_init_struct->cs_mode_selection; + if((spi_init_struct->master_slave_mode == SPI_MODE_MASTER) && (spi_init_struct->cs_mode_selection == SPI_CS_SOFTWARE_MODE)) + { + spi_x->ctrl1_bit.swcsil = TRUE; + } + else + { + spi_x->ctrl1_bit.swcsil = FALSE; + } + spi_x->ctrl1_bit.msten = spi_init_struct->master_slave_mode; + + if(spi_init_struct->mclk_freq_division <= SPI_MCLK_DIV_256) + { + spi_x->ctrl2_bit.mdiv3en = FALSE; + spi_x->ctrl2_bit.mdiv_h = FALSE; + spi_x->ctrl1_bit.mdiv_l = spi_init_struct->mclk_freq_division; + } + else if(spi_init_struct->mclk_freq_division == SPI_MCLK_DIV_3) + { + spi_x->ctrl2_bit.mdiv3en = TRUE; + spi_x->ctrl2_bit.mdiv_h = FALSE; + spi_x->ctrl1_bit.mdiv_l = 0; + } + else + { + spi_x->ctrl2_bit.mdiv3en = FALSE; + spi_x->ctrl2_bit.mdiv_h = TRUE; + spi_x->ctrl1_bit.mdiv_l = spi_init_struct->mclk_freq_division & 0x7; + } + + spi_x->ctrl1_bit.ltf = spi_init_struct->first_bit_transmission; + spi_x->ctrl1_bit.fbn = spi_init_struct->frame_bit_num; + spi_x->ctrl1_bit.clkpol = spi_init_struct->clock_polarity; + spi_x->ctrl1_bit.clkpha = spi_init_struct->clock_phase; +} + +/** + * @brief enable or disable the ti mode for the spi peripheral. + * @param spi_x: select the spi peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 + * @param new_state: new state of ti mode. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void spi_ti_mode_enable(spi_type* spi_x, confirm_state new_state) +{ + spi_x->ctrl2_bit.tien = new_state; +} + +/** + * @brief spi next transmit crc for the spi peripheral. + * @param spi_x: select the spi peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 + * @retval none + */ +void spi_crc_next_transmit(spi_type* spi_x) +{ + spi_x->ctrl1_bit.ntc = TRUE; +} + +/** + * @brief set the crc polynomial value for the spi peripheral. + * @param spi_x: select the spi peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 + * @param crc_poly: crc polynomial value. + * @retval none + */ +void spi_crc_polynomial_set(spi_type* spi_x, uint16_t crc_poly) +{ + spi_x->cpoly_bit.cpoly = crc_poly; +} + +/** + * @brief return the crc polynomial register value for the spi peripheral. + * @param spi_x: select the spi peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 + * @retval the select crc polynomial register value + */ +uint16_t spi_crc_polynomial_get(spi_type* spi_x) +{ + return spi_x->cpoly_bit.cpoly; +} + +/** + * @brief enable or disable the hardware crc calculation for the spi peripheral. + * @param spi_x: select the spi peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 + * @param new_state: new state of crc calculation. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void spi_crc_enable(spi_type* spi_x, confirm_state new_state) +{ + spi_x->ctrl1_bit.ccen = new_state; +} + +/** + * @brief return the transmit or the receive crc value for the spi peripheral. + * @param spi_x: select the spi peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 + * @param crc_direction: select transmit or receive crc value to be read + * - SPI_CRC_RX + * - SPI_CRC_TX + * @retval the select crc register value + */ +uint16_t spi_crc_value_get(spi_type* spi_x, spi_crc_direction_type crc_direction) +{ + if(crc_direction == SPI_CRC_RX) + return spi_x->rcrc_bit.rcrc; + else + return spi_x->tcrc_bit.tcrc; +} + +/** + * @brief enable or disable the hardware cs output for the spi peripheral. + * @param spi_x: select the spi peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 + * @param new_state: new state of spi master cs output. + * this parameter can be: TRUE or FALSE. + * note:the bit only use in spi master mode + * @retval none + */ +void spi_hardware_cs_output_enable(spi_type* spi_x, confirm_state new_state) +{ + spi_x->ctrl2_bit.hwcsoe = new_state; +} + +/** + * @brief set the software cs internal level for the spi peripheral. + * @param spi_x: select the spi peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 + * @param level: set the state of spi cs level. + * this parameter can be one of the following values: + * - SPI_SWCS_INTERNAL_LEVEL_LOW + * - SPI_SWCS_INTERNAL_LEVEL_HIGHT + * note:the bit only use when swcsen bit is set. + * note:when use this bit,io operation on the cs pin are invalid. + * @retval none + */ +void spi_software_cs_internal_level_set(spi_type* spi_x, spi_software_cs_level_type level) +{ + spi_x->ctrl1_bit.swcsil = level; +} + +/** + * @brief set the data frame bit num for the spi peripheral. + * @param spi_x: select the spi peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 + * @param bit_num: set the data frame size + * - SPI_FRAME_8BIT + * - SPI_FRAME_16BIT + * @retval none + */ +void spi_frame_bit_num_set(spi_type* spi_x, spi_frame_bit_num_type bit_num) +{ + spi_x->ctrl1_bit.fbn = bit_num; +} + +/** + * @brief set the data transmission direction in single line bidirectiona half duplex mode of the spi peripheral. + * @param spi_x: select the spi peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 + * @param direction: data transfer direction + * this parameter can be one of the following values: + * - SPI_HALF_DUPLEX_DIRECTION_RX + * - SPI_HALF_DUPLEX_DIRECTION_TX + * @retval none + */ +void spi_half_duplex_direction_set(spi_type* spi_x, spi_half_duplex_direction_type direction) +{ + spi_x->ctrl1_bit.slbtd = direction; +} + +/** + * @brief enable or disable spi. + * @param spi_x: select the spi peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 + * @param new_state: new state of spi. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void spi_enable(spi_type* spi_x, confirm_state new_state) +{ + spi_x->ctrl1_bit.spien = new_state; +} + +/** + * @brief i2s init config with its default value. + * @param i2s_init_struct : pointer to a i2s_init_type structure which will + * be initialized. + * @retval none + */ +void i2s_default_para_init(i2s_init_type* i2s_init_struct) +{ + i2s_init_struct->operation_mode = I2S_MODE_SLAVE_TX; + i2s_init_struct->audio_protocol = I2S_AUDIO_PROTOCOL_PHILLIPS; + i2s_init_struct->audio_sampling_freq = I2S_AUDIO_FREQUENCY_DEFAULT; + i2s_init_struct->data_channel_format = I2S_DATA_16BIT_CHANNEL_16BIT; + i2s_init_struct->clock_polarity = I2S_CLOCK_POLARITY_LOW; + i2s_init_struct->mclk_output_enable = FALSE; +} + +/** + * @brief i2s init config with its setting value. + * @param spi_x: select the spi peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 , I2S2EXT, I2S3EXT + * @param i2s_init_struct : pointer to a i2s_init_type structure which will be initialized. + * @retval none + */ +void i2s_init(spi_type* spi_x, i2s_init_type* i2s_init_struct) +{ + crm_clocks_freq_type clocks_freq; + uint32_t i2s_sclk_index = 0; + uint32_t i2sdiv_index = 2, i2sodd_index = 0, frequency_index = 0; + + /* i2s audio frequency config */ + if(i2s_init_struct->audio_sampling_freq == I2S_AUDIO_FREQUENCY_DEFAULT) + { + i2sodd_index = 0; + i2sdiv_index = 2; + } + else + { + crm_clocks_freq_get(&clocks_freq); + i2s_sclk_index = clocks_freq.sclk_freq; + if((i2s_init_struct->audio_protocol == I2S_AUDIO_PROTOCOL_PCM_SHORT) || (i2s_init_struct->audio_protocol == I2S_AUDIO_PROTOCOL_PCM_LONG)) + { + if(i2s_init_struct->mclk_output_enable == TRUE) + { + frequency_index = (((i2s_sclk_index / 128) * 10) / i2s_init_struct->audio_sampling_freq) + 5; + } + else + { + if(i2s_init_struct->data_channel_format == I2S_DATA_16BIT_CHANNEL_16BIT) + frequency_index = (((i2s_sclk_index / 16) * 10) / i2s_init_struct->audio_sampling_freq) + 5; + else + frequency_index = (((i2s_sclk_index / 32) * 10) / i2s_init_struct->audio_sampling_freq) + 5; + } + } + else + { + if(i2s_init_struct->mclk_output_enable == TRUE) + { + frequency_index = (((i2s_sclk_index / 256) * 10) / i2s_init_struct->audio_sampling_freq) + 5; + } + else + { + if(i2s_init_struct->data_channel_format == I2S_DATA_16BIT_CHANNEL_16BIT) + frequency_index = (((i2s_sclk_index / 32) * 10) / i2s_init_struct->audio_sampling_freq) + 5; + else + frequency_index = (((i2s_sclk_index / 64) * 10) / i2s_init_struct->audio_sampling_freq) + 5; + } + } + } + frequency_index = frequency_index / 10; + i2sodd_index = frequency_index & (uint16_t)0x0001; + i2sdiv_index = (frequency_index - i2sodd_index) / 2; + if((i2sdiv_index < 2) || (i2sdiv_index > 0x03FF)) + { + i2sodd_index = 0; + i2sdiv_index = 2; + } + spi_x->i2sclk_bit.i2sodd = i2sodd_index; + if(i2sdiv_index > 0x00FF) + { + spi_x->i2sclk_bit.i2sdiv_h = (i2sdiv_index >> 8) & 0x0003; + spi_x->i2sclk_bit.i2sdiv_l = i2sdiv_index & 0x00FF; + } + else + { + spi_x->i2sclk_bit.i2sdiv_h = 0; + spi_x->i2sclk_bit.i2sdiv_l = i2sdiv_index; + } + + /* i2s audio_protocol set*/ + if(i2s_init_struct->audio_protocol == I2S_AUDIO_PROTOCOL_PCM_LONG) + { + spi_x->i2sctrl_bit.pcmfssel = 1; + spi_x->i2sctrl_bit.stdsel = 3; + } + else if(i2s_init_struct->audio_protocol == I2S_AUDIO_PROTOCOL_PCM_SHORT) + { + spi_x->i2sctrl_bit.pcmfssel = 0; + spi_x->i2sctrl_bit.stdsel = 3; + } + else if(i2s_init_struct->audio_protocol == I2S_AUDIO_PROTOCOL_LSB) + { + spi_x->i2sctrl_bit.pcmfssel = 0; + spi_x->i2sctrl_bit.stdsel = 2; + } + else if(i2s_init_struct->audio_protocol == I2S_AUDIO_PROTOCOL_MSB) + { + spi_x->i2sctrl_bit.pcmfssel = 0; + spi_x->i2sctrl_bit.stdsel = 1; + } + else if(i2s_init_struct->audio_protocol == I2S_AUDIO_PROTOCOL_PHILLIPS) + { + spi_x->i2sctrl_bit.pcmfssel = 0; + spi_x->i2sctrl_bit.stdsel = 0; + } + + /* i2s data_channel_format set*/ + if(i2s_init_struct->data_channel_format == I2S_DATA_16BIT_CHANNEL_16BIT) + { + spi_x->i2sctrl_bit.i2scbn = 0; + spi_x->i2sctrl_bit.i2sdbn = 0; + } + else if(i2s_init_struct->data_channel_format == I2S_DATA_16BIT_CHANNEL_32BIT) + { + spi_x->i2sctrl_bit.i2scbn = 1; + spi_x->i2sctrl_bit.i2sdbn = 0; + } + else if(i2s_init_struct->data_channel_format == I2S_DATA_24BIT_CHANNEL_32BIT) + { + spi_x->i2sctrl_bit.i2scbn = 1; + spi_x->i2sctrl_bit.i2sdbn = 1; + } + else if(i2s_init_struct->data_channel_format == I2S_DATA_32BIT_CHANNEL_32BIT) + { + spi_x->i2sctrl_bit.i2scbn = 1; + spi_x->i2sctrl_bit.i2sdbn = 2; + } + + spi_x->i2sctrl_bit.i2sclkpol = i2s_init_struct->clock_polarity; + spi_x->i2sclk_bit.i2smclkoe = i2s_init_struct->mclk_output_enable; + spi_x->i2sctrl_bit.opersel = i2s_init_struct->operation_mode; + spi_x->i2sctrl_bit.i2smsel = TRUE; +} + +/** + * @brief enable or disable i2s. + * @param spi_x: select the i2s peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 , I2S2EXT, I2S3EXT + * @param new_state: new state of i2s. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void i2s_enable(spi_type* spi_x, confirm_state new_state) +{ + spi_x->i2sctrl_bit.i2sen = new_state; +} + +/** + * @brief enable or disable the specified spi/i2s interrupts. + * @param spi_x: select the spi/i2s peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 , I2S2EXT, I2S3EXT + * @param spi_i2s_int: specifies the spi/i2s interrupt sources to be enabled or disabled. + * this parameter can be one of the following values: + * - SPI_I2S_ERROR_INT + * - SPI_I2S_RDBF_INT + * - SPI_I2S_TDBE_INT + * @param new_state: new state of the specified spi/i2s interrupts. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void spi_i2s_interrupt_enable(spi_type* spi_x, uint32_t spi_i2s_int, confirm_state new_state) +{ + if(new_state != FALSE) + { + spi_x->ctrl2 |= spi_i2s_int; + } + else + { + spi_x->ctrl2 &= ~spi_i2s_int; + } +} + +/** + * @brief enable or disable the spi/i2s dma transmitter mode. + * @param spi_x: select the spi/i2s peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 , I2S2EXT, I2S3EXT + * @param new_state: new state of the dma request. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void spi_i2s_dma_transmitter_enable(spi_type* spi_x, confirm_state new_state) +{ + spi_x->ctrl2_bit.dmaten = new_state; +} + +/** + * @brief enable or disable the spi/i2s dma receiver mode. + * @param spi_x: select the spi/i2s peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 , I2S2EXT, I2S3EXT + * @param new_state: new state of the dma request. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void spi_i2s_dma_receiver_enable(spi_type* spi_x, confirm_state new_state) +{ + spi_x->ctrl2_bit.dmaren = new_state; +} + +/** + * @brief spi/i2s data transmit + * @param spi_x: select the spi/i2s peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 , I2S2EXT, I2S3EXT + * @param tx_data: the data to be transmit. + * this parameter can be: + * - (0x0000~0xFFFF) + * @retval none + */ +void spi_i2s_data_transmit(spi_type* spi_x, uint16_t tx_data) +{ + spi_x->dt = tx_data; +} + +/** + * @brief spi/i2s data receive + * @param spi_x: select the spi/i2s peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 , I2S2EXT, I2S3EXT + * @retval the received data value + */ +uint16_t spi_i2s_data_receive(spi_type* spi_x) +{ + return (uint16_t)spi_x->dt; +} + +/** + * @brief get flag of the specified spi/i2s peripheral. + * @param spi_x: select the spi/i2s peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 , I2S2EXT, I2S3EXT + * @param spi_i2s_flag: select the spi/i2s flag + * this parameter can be one of the following values: + * - SPI_I2S_RDBF_FLAG + * - SPI_I2S_TDBE_FLAG + * - I2S_ACS_FLAG (this flag only use in i2s mode) + * - I2S_TUERR_FLAG (this flag only use in i2s mode) + * - SPI_CCERR_FLAG (this flag only use in spi mode) + * - SPI_MMERR_FLAG (this flag only use in spi mode) + * - SPI_I2S_ROERR_FLAG + * - SPI_I2S_BF_FLAG + * - SPI_CSPAS_FLAG + * @retval the new state of spi/i2s flag + */ +flag_status spi_i2s_flag_get(spi_type* spi_x, uint32_t spi_i2s_flag) +{ + flag_status status = RESET; + if ((spi_x->sts & spi_i2s_flag) == RESET) + { + status = RESET; + } + else + { + status = SET; + } + return status; +} + +/** + * @brief clear flag of the specified spi/i2s peripheral. + * @param spi_x: select the spi/i2s peripheral. + * this parameter can be one of the following values: + * SPI1, SPI2, SPI3 ,SPI4 , I2S2EXT, I2S3EXT + * @param spi_i2s_flag: select the spi/i2s flag + * this parameter can be one of the following values: + * - SPI_CCERR_FLAG + * - SPI_I2S_RDBF_FLAG + * - I2S_TUERR_FLAG + * - SPI_MMERR_FLAG + * - SPI_I2S_ROERR_FLAG + * - SPI_CSPAS_FLAG + * @note + * SPI_I2S_TDBE_FLAG this flag is cleared when the tx buffer already contain data to be transmit. + * I2S_ACS_FLAG this flag cann't cleared by software,the flag indicate the channel side(not use in pcm standard mode). + * SPI_I2S_BF_FLAG this flag cann't cleared by software, it's set and cleared by hardware. + * @retval none + */ +void spi_i2s_flag_clear(spi_type* spi_x, uint32_t spi_i2s_flag) +{ + if(spi_i2s_flag == SPI_CCERR_FLAG) + spi_x->sts = ~SPI_CCERR_FLAG; + else if(spi_i2s_flag == SPI_I2S_RDBF_FLAG) + UNUSED(spi_x->dt); + else if(spi_i2s_flag == I2S_TUERR_FLAG) + UNUSED(spi_x->sts); + else if(spi_i2s_flag == SPI_CSPAS_FLAG) + UNUSED(spi_x->sts); + else if(spi_i2s_flag == SPI_MMERR_FLAG) + { + UNUSED(spi_x->sts); + spi_x->ctrl1 = spi_x->ctrl1; + } + else if(spi_i2s_flag == SPI_I2S_ROERR_FLAG) + { + UNUSED(spi_x->dt); + UNUSED(spi_x->sts); + } +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_tmr.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_tmr.c new file mode 100644 index 0000000000..660e207d5d --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_tmr.c @@ -0,0 +1,1848 @@ +/** + ************************************************************************** + * @file at32f435_437_tmr.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the tmr firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup TMR + * @brief TMR driver modules + * @{ + */ + +#ifdef TMR_MODULE_ENABLED + +/** @defgroup TMR_private_functions + * @{ + */ + +/** + * @brief tmr reset by crm reset register + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR6, TMR7, TMR8, + * TMR9, TMR10, TMR11, TMR12, TMR13, TMR14, TMR20 + * @retval none + */ +void tmr_reset(tmr_type *tmr_x) +{ + if(tmr_x == TMR1) + { + crm_periph_reset(CRM_TMR1_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_TMR1_PERIPH_RESET, FALSE); + } + else if(tmr_x == TMR2) + { + crm_periph_reset(CRM_TMR2_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_TMR2_PERIPH_RESET, FALSE); + } + else if(tmr_x == TMR3) + { + crm_periph_reset(CRM_TMR3_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_TMR3_PERIPH_RESET, FALSE); + } + else if(tmr_x == TMR4) + { + crm_periph_reset(CRM_TMR4_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_TMR4_PERIPH_RESET, FALSE); + } + else if(tmr_x == TMR5) + { + crm_periph_reset(CRM_TMR5_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_TMR5_PERIPH_RESET, FALSE); + } + else if(tmr_x == TMR6) + { + crm_periph_reset(CRM_TMR6_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_TMR6_PERIPH_RESET, FALSE); + } + else if(tmr_x == TMR7) + { + crm_periph_reset(CRM_TMR7_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_TMR7_PERIPH_RESET, FALSE); + } + else if(tmr_x == TMR8) + { + crm_periph_reset(CRM_TMR8_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_TMR8_PERIPH_RESET, FALSE); + } + else if(tmr_x == TMR9) + { + crm_periph_reset(CRM_TMR9_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_TMR9_PERIPH_RESET, FALSE); + } + else if(tmr_x == TMR10) + { + crm_periph_reset(CRM_TMR10_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_TMR10_PERIPH_RESET, FALSE); + } + else if(tmr_x == TMR11) + { + crm_periph_reset(CRM_TMR11_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_TMR11_PERIPH_RESET, FALSE); + } + else if(tmr_x == TMR12) + { + crm_periph_reset(CRM_TMR12_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_TMR12_PERIPH_RESET, FALSE); + } + else if(tmr_x == TMR13) + { + crm_periph_reset(CRM_TMR13_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_TMR13_PERIPH_RESET, FALSE); + } + else if(tmr_x == TMR14) + { + crm_periph_reset(CRM_TMR14_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_TMR14_PERIPH_RESET, FALSE); + } + else if(tmr_x == TMR20) + { + crm_periph_reset(CRM_TMR20_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_TMR20_PERIPH_RESET, FALSE); + } +} + +/** + * @brief enable or disable tmr counter + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR6, TMR7, TMR8, + * TMR9, TMR10, TMR11, TMR12, TMR13, TMR14, TMR20 + * @param new_state (TRUE or FALSE) + * @retval none + */ +void tmr_counter_enable(tmr_type *tmr_x, confirm_state new_state) +{ + /* tmr counter enable */ + tmr_x->ctrl1_bit.tmren = new_state; +} + +/** + * @brief init tmr output default para + * @param tmr_output_struct + * - to the structure of tmr_output_config_type + * @retval none + */ +void tmr_output_default_para_init(tmr_output_config_type *tmr_output_struct) +{ + tmr_output_struct->oc_mode = TMR_OUTPUT_CONTROL_OFF; + tmr_output_struct->oc_idle_state = FALSE; + tmr_output_struct->occ_idle_state = FALSE; + tmr_output_struct->oc_polarity = TMR_OUTPUT_ACTIVE_HIGH; + tmr_output_struct->occ_polarity = TMR_OUTPUT_ACTIVE_HIGH; + tmr_output_struct->oc_output_state = FALSE; + tmr_output_struct->occ_output_state = FALSE; +} + +/** + * @brief init tmr input default para + * @param tmr_input_struct + * - to the structure of tmr_input_config_type + * @retval none + */ +void tmr_input_default_para_init(tmr_input_config_type *tmr_input_struct) +{ + tmr_input_struct->input_channel_select = TMR_SELECT_CHANNEL_1; + tmr_input_struct->input_polarity_select = TMR_INPUT_RISING_EDGE; + tmr_input_struct->input_mapped_select = TMR_CC_CHANNEL_MAPPED_DIRECT; + tmr_input_struct->input_filter_value = 0x0; +} + +/** + * @brief init tmr brkdt default para + * @param tmr_brkdt_struct + * - to the structure of tmr_brkdt_config_type + * @retval none + */ +void tmr_brkdt_default_para_init(tmr_brkdt_config_type *tmr_brkdt_struct) +{ + tmr_brkdt_struct->deadtime = 0x0; + tmr_brkdt_struct->brk_polarity = TMR_BRK_INPUT_ACTIVE_LOW; + tmr_brkdt_struct->wp_level = TMR_WP_OFF; + tmr_brkdt_struct->auto_output_enable = FALSE ; + tmr_brkdt_struct->fcsoen_state = FALSE ; + tmr_brkdt_struct->fcsodis_state = FALSE ; + tmr_brkdt_struct->brk_enable = FALSE ; +} + +/** + * @brief init tmr base + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR6, TMR7, TMR8, + * TMR9, TMR10, TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_pr (for 16 bit tmr 0x0000~0xFFFF, + * for 32 bit tmr 0x0000_0000~0xFFFF_FFFF) + * @param tmr_div (timer div value:0x0000~0xFFFF) + * @retval none + */ +void tmr_base_init(tmr_type* tmr_x, uint32_t tmr_pr, uint32_t tmr_div) +{ + /* set the pr value */ + tmr_x->pr = tmr_pr; + + /* set the div value */ + tmr_x->div = tmr_div; + + /* trigger the overflow event to immediately reload pr value and div value */ + tmr_x->swevt_bit.ovfswtr = TRUE; +} + +/** + * @brief set tmr clock source division + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR10, + * TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_clock_div + * this parameter can be one of the following values: + * - TMR_CLOCK_DIV1 + * - TMR_CLOCK_DIV2 + * - TMR_CLOCK_DIV4 + * @retval none + */ +void tmr_clock_source_div_set(tmr_type *tmr_x, tmr_clock_division_type tmr_clock_div) +{ + /* set tmr clock source division */ + tmr_x->ctrl1_bit.clkdiv = tmr_clock_div; +} + +/** + * @brief set tmr counter count direction + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR10, + * TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_cnt_dir + * this parameter can be one of the following values: + * - TMR_COUNT_UP + * - TMR_COUNT_DOWN + * - TMR_COUNT_TWO_WAY_1 + * - TMR_COUNT_TWO_WAY_2 + * - TMR_COUNT_TWO_WAY_3 + * @retval none + */ +void tmr_cnt_dir_set(tmr_type *tmr_x, tmr_count_mode_type tmr_cnt_dir) +{ + /* set the cnt direct */ + tmr_x->ctrl1_bit.cnt_dir = tmr_cnt_dir; +} + +/** + * @brief set the repetition counter register(rpr) value + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR8, TMR20 + * @param tmr_rpr_value (0x0000~0xFFFF) + * @retval none + */ +void tmr_repetition_counter_set(tmr_type *tmr_x, uint8_t tmr_rpr_value) +{ + /* set the repetition counter value */ + tmr_x->rpr_bit.rpr = tmr_rpr_value; +} + +/** + * @brief set tmr counter value + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR6, TMR7, TMR8, + * TMR9, TMR10, TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_cnt_value (for 16 bit tmr 0x0000~0xFFFF, + * for 32 bit tmr 0x0000_0000~0xFFFF_FFFF) + * @retval none + */ +void tmr_counter_value_set(tmr_type *tmr_x, uint32_t tmr_cnt_value) +{ + /* set the tmr counter value */ + tmr_x->cval = tmr_cnt_value; +} + +/** + * @brief get tmr counter value + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR6, TMR7, TMR8, + * TMR9, TMR10, TMR11, TMR12, TMR13, TMR14, TMR20 + * @retval tmr counter value + */ +uint32_t tmr_counter_value_get(tmr_type *tmr_x) +{ + return tmr_x->cval; +} + +/** + * @brief set tmr div value + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR6, TMR7, TMR8, + * TMR9, TMR10, TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_div_value (for 16 bit tmr 0x0000~0xFFFF, + * for 32 bit tmr 0x0000_0000~0xFFFF_FFFF) + * @retval none + */ +void tmr_div_value_set(tmr_type *tmr_x, uint32_t tmr_div_value) +{ + /* set the tmr div value */ + tmr_x->div = tmr_div_value; +} + +/** + * @brief get tmr div value + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR6, TMR7, TMR8, + * TMR9, TMR10, TMR11, TMR12, TMR13, TMR14, TMR20 + * @retval tmr div value + */ +uint32_t tmr_div_value_get(tmr_type *tmr_x) +{ + return tmr_x->div; +} + +/** + * @brief config tmr output channel + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR10, + * TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_channel + * this parameter can be one of the following values: + * - TMR_SELECT_CHANNEL_1 + * - TMR_SELECT_CHANNEL_2 + * - TMR_SELECT_CHANNEL_3 + * - TMR_SELECT_CHANNEL_4 + * - TMR_SELECT_CHANNEL_5 + * @param tmr_output_struct + * - to the structure of tmr_output_config_type + * @retval none + */ +void tmr_output_channel_config(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + tmr_output_config_type *tmr_output_struct) +{ + uint16_t channel_index = 0, channel_c_index = 0, channel = 0, chx_offset, chcx_offset; + + chx_offset = (8 + tmr_channel); + chcx_offset = (9 + tmr_channel); + + /* get channel idle state bit position in ctrl2 register */ + channel_index = (uint16_t)(tmr_output_struct->oc_idle_state << chx_offset); + + /* get channel complementary idle state bit position in ctrl2 register */ + channel_c_index = (uint16_t)(tmr_output_struct->occ_idle_state << chcx_offset); + + /* set output channel complementary idle state */ + tmr_x->ctrl2 &= ~(1<ctrl2 |= channel_c_index; + + /* set output channel idle state */ + tmr_x->ctrl2 &= ~(1<ctrl2 |= channel_index; + + /* set channel output mode */ + channel = tmr_channel; + + switch(channel) + { + case TMR_SELECT_CHANNEL_1: + tmr_x->cm1_output_bit.c1octrl = tmr_output_struct->oc_mode; + break; + + case TMR_SELECT_CHANNEL_2: + tmr_x->cm1_output_bit.c2octrl = tmr_output_struct->oc_mode; + break; + + case TMR_SELECT_CHANNEL_3: + tmr_x->cm2_output_bit.c3octrl = tmr_output_struct->oc_mode; + break; + + case TMR_SELECT_CHANNEL_4: + tmr_x->cm2_output_bit.c4octrl = tmr_output_struct->oc_mode; + break; + + case TMR_SELECT_CHANNEL_5: + tmr_x->cm3_output_bit.c5octrl = tmr_output_struct->oc_mode; + break; + + default: + break; + } + + chx_offset = ((tmr_channel * 2) + 1); + chcx_offset = ((tmr_channel * 2) + 3); + + /* get channel polarity bit position in cctrl register */ + channel_index = (uint16_t)(tmr_output_struct->oc_polarity << chx_offset); + + /* get channel complementary polarity bit position in cctrl register */ + channel_c_index = (uint16_t)(tmr_output_struct->occ_polarity << chcx_offset); + + /* set output channel complementary polarity */ + tmr_x->cctrl &= ~(1<cctrl |= channel_c_index; + + /* set output channel polarity */ + tmr_x->cctrl &= ~(1<cctrl |= channel_index; + + chx_offset = (tmr_channel * 2); + chcx_offset = ((tmr_channel * 2) + 2); + + /* get channel enable bit position in cctrl register */ + channel_index = (uint16_t)(tmr_output_struct->oc_output_state << (tmr_channel * 2)); + + /* get channel complementary enable bit position in cctrl register */ + channel_c_index = (uint16_t)(tmr_output_struct->occ_output_state << ((tmr_channel * 2) + 2)); + + /* set output channel complementary enable bit */ + tmr_x->cctrl &= ~(1<cctrl |= channel_c_index; + + /* set output channel enable bit */ + tmr_x->cctrl &= ~(1<cctrl |= channel_index; +} + +/** + * @brief select tmr output channel mode + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR10, + * TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_channel + * this parameter can be one of the following values: + * - TMR_SELECT_CHANNEL_1 + * - TMR_SELECT_CHANNEL_2 + * - TMR_SELECT_CHANNEL_3 + * - TMR_SELECT_CHANNEL_4 + * - TMR_SELECT_CHANNEL_5 + * @param oc_mode + * this parameter can be one of the following values: + * - TMR_OUTPUT_CONTROL_OFF + * - TMR_OUTPUT_CONTROL_HIGH + * - TMR_OUTPUT_CONTROL_LOW + * - TMR_OUTPUT_CONTROL_SWITCH + * - TMR_OUTPUT_CONTROL_FORCE_HIGH + * - TMR_OUTPUT_CONTROL_FORCE_LOW + * - TMR_OUTPUT_CONTROL_PWM_MODE_A + * - TMR_OUTPUT_CONTROL_PWM_MODE_B + * @retval none + */ +void tmr_output_channel_mode_select(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + tmr_output_control_mode_type oc_mode) +{ + uint16_t channel; + + channel = tmr_channel; + + switch(channel) + { + case TMR_SELECT_CHANNEL_1: + tmr_x->cm1_output_bit.c1octrl = oc_mode; + break; + + case TMR_SELECT_CHANNEL_2: + tmr_x->cm1_output_bit.c2octrl = oc_mode; + break; + + case TMR_SELECT_CHANNEL_3: + tmr_x->cm2_output_bit.c3octrl = oc_mode; + break; + + case TMR_SELECT_CHANNEL_4: + tmr_x->cm2_output_bit.c4octrl = oc_mode; + break; + + case TMR_SELECT_CHANNEL_5: + tmr_x->cm3_output_bit.c5octrl = oc_mode; + break; + + default: + break; + } +} +/** + * @brief set tmr period value + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR6, TMR7, TMR8, + * TMR9, TMR10, TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_pr_value: timer period register value of counter + * (for 16 bit tmr 0x0000~0xFFFF, + * for 32 bit tmr 0x0000_0000~0xFFFF_FFFF) + * @retval none + */ +void tmr_period_value_set(tmr_type *tmr_x, uint32_t tmr_pr_value) +{ + /* set tmr period value */ + tmr_x->pr = tmr_pr_value; +} + +/** + * @brief get tmr period value + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR6, TMR7, TMR8, + * TMR9, TMR10, TMR11, TMR12, TMR13, TMR14, TMR20 + * @retval timer period register value of counter + * (for 16 bit tmr 0x0000~0xFFFF, for 32 bit tmr + * 0x0000_0000~0xFFFF_FFFF) + */ +uint32_t tmr_period_value_get(tmr_type *tmr_x) +{ + return tmr_x->pr; +} + +/** + * @brief set tmr channel value + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR10, + * TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_channel + * this parameter can be one of the following values: + * - TMR_SELECT_CHANNEL_1 + * - TMR_SELECT_CHANNEL_2 + * - TMR_SELECT_CHANNEL_3 + * - TMR_SELECT_CHANNEL_4 + * - TMR_SELECT_CHANNEL_5 + * @param tmr_channel_value (for 16 bit tmr 0x0000~0xFFFF, + * for 32 bit tmr 0x0000_0000~0xFFFF_FFFF) + * @retval none + */ +void tmr_channel_value_set(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + uint32_t tmr_channel_value) +{ + uint16_t channel; + + channel = tmr_channel; + + /* set tmr channel value */ + switch(channel) + { + case TMR_SELECT_CHANNEL_1: + tmr_x->c1dt = tmr_channel_value; + break; + + case TMR_SELECT_CHANNEL_2: + tmr_x->c2dt = tmr_channel_value; + break; + + case TMR_SELECT_CHANNEL_3: + tmr_x->c3dt = tmr_channel_value; + break; + + case TMR_SELECT_CHANNEL_4: + tmr_x->c4dt = tmr_channel_value; + break; + + case TMR_SELECT_CHANNEL_5: + tmr_x->c5dt = tmr_channel_value; + break; + + default: + break; + } +} + +/** + * @brief get tmr channel value + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR10, + * TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_channel + * this parameter can be one of the following values: + * - TMR_SELECT_CHANNEL_1 + * - TMR_SELECT_CHANNEL_2 + * - TMR_SELECT_CHANNEL_3 + * - TMR_SELECT_CHANNEL_4 + * - TMR_SELECT_CHANNEL_5 + * @retval tmr channel value + */ +uint32_t tmr_channel_value_get(tmr_type *tmr_x, tmr_channel_select_type tmr_channel) +{ + uint32_t cc_value_get = 0; + uint16_t channel; + + channel = tmr_channel; + + /* get tmr channel value */ + switch(channel) + { + case TMR_SELECT_CHANNEL_1: + cc_value_get = tmr_x->c1dt; + break; + + case TMR_SELECT_CHANNEL_2: + cc_value_get = tmr_x->c2dt; + break; + + case TMR_SELECT_CHANNEL_3: + cc_value_get = tmr_x->c3dt; + break; + + case TMR_SELECT_CHANNEL_4: + cc_value_get = tmr_x->c4dt; + break; + + case TMR_SELECT_CHANNEL_5: + cc_value_get = tmr_x->c5dt; + break; + + default: + break; + } + + return cc_value_get; +} +/** + * @brief set tmr period buffer + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR6, TMR7, TMR8, + * TMR9, TMR10, TMR11, TMR12, TMR13, TMR14, TMR20 + * @param new_state (TRUE or FALSE) + * @retval none + */ +void tmr_period_buffer_enable(tmr_type *tmr_x, confirm_state new_state) +{ + /* tmr period buffer set */ + tmr_x->ctrl1_bit.prben = new_state; +} + +/** + * @brief set tmr output channel buffer + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR10, + * TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_channel + * this parameter can be one of the following values: + * - TMR_SELECT_CHANNEL_1 + * - TMR_SELECT_CHANNEL_2 + * - TMR_SELECT_CHANNEL_3 + * - TMR_SELECT_CHANNEL_4 + * - TMR_SELECT_CHANNEL_5 + * @param new_state (TRUE or FALSE) + * @retval none + */ +void tmr_output_channel_buffer_enable(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + confirm_state new_state) +{ + uint16_t channel; + + channel = tmr_channel; + + /* get tmr channel value */ + switch(channel) + { + case TMR_SELECT_CHANNEL_1: + tmr_x->cm1_output_bit.c1oben = new_state; + break; + + case TMR_SELECT_CHANNEL_2: + tmr_x->cm1_output_bit.c2oben = new_state; + break; + + case TMR_SELECT_CHANNEL_3: + tmr_x->cm2_output_bit.c3oben = new_state; + break; + + case TMR_SELECT_CHANNEL_4: + tmr_x->cm2_output_bit.c4oben = new_state; + break; + + case TMR_SELECT_CHANNEL_5: + tmr_x->cm3_output_bit.c5oben = new_state; + break; + + default: + break; + } +} + +/** + * @brief set tmr output channel immediately + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR10, + * TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_channel + * this parameter can be one of the following values: + * - TMR_SELECT_CHANNEL_1 + * - TMR_SELECT_CHANNEL_2 + * - TMR_SELECT_CHANNEL_3 + * - TMR_SELECT_CHANNEL_4 + * - TMR_SELECT_CHANNEL_5 + * @param new_state (TRUE or FALSE) + * @retval none + */ +void tmr_output_channel_immediately_set(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + confirm_state new_state) +{ + uint16_t channel; + + channel = tmr_channel; + + /* get tmr channel value */ + switch(channel) + { + case TMR_SELECT_CHANNEL_1: + tmr_x->cm1_output_bit.c1oien = new_state; + break; + + case TMR_SELECT_CHANNEL_2: + tmr_x->cm1_output_bit.c2oien = new_state; + break; + + case TMR_SELECT_CHANNEL_3: + tmr_x->cm2_output_bit.c3oien = new_state; + break; + + case TMR_SELECT_CHANNEL_4: + tmr_x->cm2_output_bit.c4oien = new_state; + break; + + case TMR_SELECT_CHANNEL_5: + tmr_x->cm3_output_bit.c5oien = new_state; + break; + + default: + break; + } +} + +/** + * @brief set tmr output channel switch + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR10, + * TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_channel + * this parameter can be one of the following values: + * - TMR_SELECT_CHANNEL_1 + * - TMR_SELECT_CHANNEL_2 + * - TMR_SELECT_CHANNEL_3 + * - TMR_SELECT_CHANNEL_4 + * - TMR_SELECT_CHANNEL_5 + * @param new_state (TRUE or FALSE) + * @retval none + */ +void tmr_output_channel_switch_set(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + confirm_state new_state) +{ + uint16_t channel; + + channel = tmr_channel; + + /* get tmr channel value */ + switch(channel) + { + case TMR_SELECT_CHANNEL_1: + tmr_x->cm1_output_bit.c1osen = new_state; + break; + + case TMR_SELECT_CHANNEL_2: + tmr_x->cm1_output_bit.c2osen = new_state; + break; + + case TMR_SELECT_CHANNEL_3: + tmr_x->cm2_output_bit.c3osen = new_state; + break; + + case TMR_SELECT_CHANNEL_4: + tmr_x->cm2_output_bit.c4osen = new_state; + break; + + case TMR_SELECT_CHANNEL_5: + tmr_x->cm3_output_bit.c5osen = new_state; + break; + + default: + break; + } +} + +/** + * @brief enable or disable tmr one cycle mode + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR6, TMR7, TMR8, TMR9, TMR12, TMR20 + * @param new_state (TRUE or FALSE) + * @retval none + */ +void tmr_one_cycle_mode_enable(tmr_type *tmr_x, confirm_state new_state) +{ + /* tmr one cycle mode enable */ + tmr_x->ctrl1_bit.ocmen = new_state; +} + +/** + * @brief enable or disable tmr 32 bit function(plus mode) + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR2, TMR5 + * @param new_state (TRUE or FALSE) + * @retval none + */ +void tmr_32_bit_function_enable (tmr_type *tmr_x, confirm_state new_state) +{ + /* tmr 32 bit function(plus mode) enable,only for TMR2/TMR5 */ + if((tmr_x == TMR2) || (tmr_x == TMR5)) + { + tmr_x->ctrl1_bit.pmen = new_state; + } +} + +/** + * @brief select tmr the overflow event sources + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR6, TMR7, TMR8, + * TMR9, TMR10, TMR11, TMR12, TMR13, TMR14, TMR20 + * @param new_state (TRUE or FALSE) + * @retval none + */ +void tmr_overflow_request_source_set(tmr_type *tmr_x, confirm_state new_state) +{ + tmr_x->ctrl1_bit.ovfs = new_state; +} + +/** + * @brief enable or disable tmr overflow event generation + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR6, TMR7, TMR8, + * TMR9, TMR10, TMR11, TMR12, TMR13, TMR14, TMR20 + * @param new_state (TRUE or FALSE) + * @retval none + */ +void tmr_overflow_event_disable(tmr_type *tmr_x, confirm_state new_state) +{ + tmr_x->ctrl1_bit.ovfen = new_state; +} + +/** + * @brief init tmr input channel + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR10, + * TMR11, TMR12, TMR13, TMR14, TMR20 + * @param input_struct + * - to the structure of tmr_input_config_type + * @param divider_factor + * this parameter can be one of the following values: + * - TMR_CHANNEL_INPUT_DIV_1 + * - TMR_CHANNEL_INPUT_DIV_2 + * - TMR_CHANNEL_INPUT_DIV_4 + * - TMR_CHANNEL_INPUT_DIV_8 + * @retval none + */ +void tmr_input_channel_init(tmr_type *tmr_x, tmr_input_config_type *input_struct, \ + tmr_channel_input_divider_type divider_factor) +{ + uint16_t channel = 0; + + /* get channel selected */ + channel = input_struct->input_channel_select; + + switch(channel) + { + case TMR_SELECT_CHANNEL_1: + tmr_x->cctrl_bit.c1en = FALSE; + tmr_x->cctrl_bit.c1p = (uint32_t)input_struct->input_polarity_select; + tmr_x->cctrl_bit.c1cp = (input_struct->input_polarity_select & 0x2) >> 1; + tmr_x->cm1_input_bit.c1c = input_struct->input_mapped_select; + tmr_x->cm1_input_bit.c1df = input_struct->input_filter_value; + tmr_x->cm1_input_bit.c1idiv = divider_factor; + tmr_x->cctrl_bit.c1en = TRUE; + break; + + case TMR_SELECT_CHANNEL_2: + tmr_x->cctrl_bit.c2en = FALSE; + tmr_x->cctrl_bit.c2p = (uint32_t)input_struct->input_polarity_select; + tmr_x->cctrl_bit.c2cp = (input_struct->input_polarity_select & 0x2) >> 1; + tmr_x->cm1_input_bit.c2c = input_struct->input_mapped_select; + tmr_x->cm1_input_bit.c2df = input_struct->input_filter_value; + tmr_x->cm1_input_bit.c2idiv = divider_factor; + tmr_x->cctrl_bit.c2en = TRUE; + break; + + case TMR_SELECT_CHANNEL_3: + tmr_x->cctrl_bit.c3en = FALSE; + tmr_x->cctrl_bit.c3p = (uint32_t)input_struct->input_polarity_select; + tmr_x->cctrl_bit.c3cp = (input_struct->input_polarity_select & 0x2) >> 1; + tmr_x->cm2_input_bit.c3c = input_struct->input_mapped_select; + tmr_x->cm2_input_bit.c3df = input_struct->input_filter_value; + tmr_x->cm2_input_bit.c3idiv = divider_factor; + tmr_x->cctrl_bit.c3en = TRUE; + break; + + case TMR_SELECT_CHANNEL_4: + tmr_x->cctrl_bit.c4en = FALSE; + tmr_x->cctrl_bit.c4p = (uint32_t)input_struct->input_polarity_select; + tmr_x->cm2_input_bit.c4c = input_struct->input_mapped_select; + tmr_x->cm2_input_bit.c4df = input_struct->input_filter_value; + tmr_x->cm2_input_bit.c4idiv = divider_factor; + tmr_x->cctrl_bit.c4en = TRUE; + break; + + default: + break; + } +} + +/** + * @brief tmr channel enable + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR10, + * TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_channel + * this parameter can be one of the following values: + * - TMR_SELECT_CHANNEL_1 + * - TMR_SELECT_CHANNEL_1C + * - TMR_SELECT_CHANNEL_2 + * - TMR_SELECT_CHANNEL_2C + * - TMR_SELECT_CHANNEL_3 + * - TMR_SELECT_CHANNEL_3C + * - TMR_SELECT_CHANNEL_4 + * @param new_state (TRUE or FALSE) + * @retval none + */ +void tmr_channel_enable(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, confirm_state new_state) +{ + uint16_t channel; + + channel = tmr_channel; + + switch(channel) + { + case TMR_SELECT_CHANNEL_1: + tmr_x->cctrl_bit.c1en = new_state; + break; + + case TMR_SELECT_CHANNEL_1C: + tmr_x->cctrl_bit.c1cen = new_state; + break; + + case TMR_SELECT_CHANNEL_2: + tmr_x->cctrl_bit.c2en = new_state; + break; + + case TMR_SELECT_CHANNEL_2C: + tmr_x->cctrl_bit.c2cen = new_state; + break; + + case TMR_SELECT_CHANNEL_3: + tmr_x->cctrl_bit.c3en = new_state; + break; + + case TMR_SELECT_CHANNEL_3C: + tmr_x->cctrl_bit.c3cen = new_state; + break; + + case TMR_SELECT_CHANNEL_4: + tmr_x->cctrl_bit.c4en = new_state; + break; + + default: + break; + } +} + +/** + * @brief set tmr input channel filter + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR10, + * TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_channel + * this parameter can be one of the following values: + * - TMR_SELECT_CHANNEL_1 + * - TMR_SELECT_CHANNEL_2 + * - TMR_SELECT_CHANNEL_3 + * - TMR_SELECT_CHANNEL_4 + * @param filter_value (0x0~0xf) + * @retval none + */ +void tmr_input_channel_filter_set(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + uint16_t filter_value) +{ + uint16_t channel; + + channel = tmr_channel; + + switch(channel) + { + case TMR_SELECT_CHANNEL_1: + tmr_x->cm1_input_bit.c1df = filter_value; + break; + + case TMR_SELECT_CHANNEL_2: + tmr_x->cm1_input_bit.c2df = filter_value; + break; + + case TMR_SELECT_CHANNEL_3: + tmr_x->cm2_input_bit.c3df = filter_value; + break; + + case TMR_SELECT_CHANNEL_4: + tmr_x->cm2_input_bit.c4df = filter_value; + break; + + default: + break; + } +} + +/** + * @brief config tmr pwm input + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR10, + * TMR11, TMR12, TMR13, TMR14, TMR20 + * @param input_struct + * - to the structure of tmr_input_config_type + * @param divider_factor + * this parameter can be one of the following values: + * - TMR_CHANNEL_INPUT_DIV_1 + * - TMR_CHANNEL_INPUT_DIV_2 + * - TMR_CHANNEL_INPUT_DIV_4 + * - TMR_CHANNEL_INPUT_DIV_8 + * @retval none + */ +void tmr_pwm_input_config(tmr_type *tmr_x, tmr_input_config_type *input_struct, \ + tmr_channel_input_divider_type divider_factor) +{ + uint16_t channel = 0; + + /* get channel selected */ + channel = input_struct->input_channel_select; + + switch(channel) + { + case TMR_SELECT_CHANNEL_1: + if(input_struct->input_polarity_select == TMR_INPUT_RISING_EDGE) + { + /* set channel polarity */ + tmr_x->cctrl_bit.c1p = TMR_INPUT_RISING_EDGE; + tmr_x->cctrl_bit.c2p = TMR_INPUT_FALLING_EDGE; + } + else if(input_struct->input_polarity_select == TMR_INPUT_FALLING_EDGE) + { + /* set channel polarity */ + tmr_x->cctrl_bit.c1p = TMR_INPUT_FALLING_EDGE; + tmr_x->cctrl_bit.c2p = TMR_INPUT_RISING_EDGE; + } + + if(input_struct->input_mapped_select == TMR_CC_CHANNEL_MAPPED_DIRECT) + { + /* ic1 is mapped on ti1 */ + tmr_x->cm1_input_bit.c1c = TMR_CC_CHANNEL_MAPPED_DIRECT; + + /* ic1 is mapped on ti2 */ + tmr_x->cm1_input_bit.c2c = TMR_CC_CHANNEL_MAPPED_INDIRECT; + } + else if(input_struct->input_mapped_select == TMR_CC_CHANNEL_MAPPED_INDIRECT) + { + /* ic1 is mapped on ti1 */ + tmr_x->cm1_input_bit.c1c = TMR_CC_CHANNEL_MAPPED_INDIRECT; + + /* ic1 is mapped on ti2 */ + tmr_x->cm1_input_bit.c2c = TMR_CC_CHANNEL_MAPPED_DIRECT; + } + + /* set input ch1 and ch2 filter value*/ + tmr_x->cm1_input_bit.c1df = input_struct->input_filter_value; + tmr_x->cm1_input_bit.c2df = input_struct->input_filter_value; + + /*set input ch1 and ch2 divider value*/ + tmr_x->cm1_input_bit.c1idiv = divider_factor; + tmr_x->cm1_input_bit.c2idiv = divider_factor; + + tmr_x->cctrl_bit.c1en = TRUE; + tmr_x->cctrl_bit.c2en = TRUE; + break; + + case TMR_SELECT_CHANNEL_2: + if(input_struct->input_polarity_select == TMR_INPUT_RISING_EDGE) + { + /* set channel polarity */ + tmr_x->cctrl_bit.c2p = TMR_INPUT_RISING_EDGE; + tmr_x->cctrl_bit.c1p = TMR_INPUT_FALLING_EDGE; + } + else if(input_struct->input_polarity_select == TMR_INPUT_FALLING_EDGE) + { + /* set channel polarity */ + tmr_x->cctrl_bit.c2p = TMR_INPUT_FALLING_EDGE; + tmr_x->cctrl_bit.c1p = TMR_INPUT_RISING_EDGE; + } + + if(input_struct->input_mapped_select == TMR_CC_CHANNEL_MAPPED_DIRECT) + { + /* set mapped direct */ + tmr_x->cm1_input_bit.c2c = TMR_CC_CHANNEL_MAPPED_DIRECT; + tmr_x->cm1_input_bit.c1c = TMR_CC_CHANNEL_MAPPED_INDIRECT; + } + else if(input_struct->input_mapped_select == TMR_CC_CHANNEL_MAPPED_INDIRECT) + { + /* set mapped direct */ + tmr_x->cm1_input_bit.c2c = TMR_CC_CHANNEL_MAPPED_INDIRECT; + tmr_x->cm1_input_bit.c1c = TMR_CC_CHANNEL_MAPPED_DIRECT; + } + + /* set input ch1 and ch2 filter value*/ + tmr_x->cm1_input_bit.c1df = input_struct->input_filter_value; + tmr_x->cm1_input_bit.c2df = input_struct->input_filter_value; + + /*set input ch1 and ch2 divider value*/ + tmr_x->cm1_input_bit.c1idiv = divider_factor; + tmr_x->cm1_input_bit.c2idiv = divider_factor; + + tmr_x->cctrl_bit.c1en = TRUE; + tmr_x->cctrl_bit.c2en = TRUE; + break; + + default: + break; + } +} + +/** + * @brief select tmr channel1 input + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR20 + * @param ch1_connect + * this parameter can be one of the following values: + * - TMR_CHANEL1_CONNECTED_C1IRAW + * - TMR_CHANEL1_2_3_CONNECTED_C1IRAW_XOR + * @retval none + */ +void tmr_channel1_input_select(tmr_type *tmr_x, tmr_channel1_input_connected_type ch1_connect) +{ + tmr_x->ctrl2_bit.c1insel = ch1_connect; +} + +/** + * @brief set tmr input channel divider + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR10, + * TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_channel + * this parameter can be one of the following values: + * - TMR_SELECT_CHANNEL_1 + * - TMR_SELECT_CHANNEL_2 + * - TMR_SELECT_CHANNEL_3 + * - TMR_SELECT_CHANNEL_4 + * @param divider_factor + * this parameter can be one of the following values: + * - TMR_CHANNEL_INPUT_DIV_1 + * - TMR_CHANNEL_INPUT_DIV_2 + * - TMR_CHANNEL_INPUT_DIV_4 + * - TMR_CHANNEL_INPUT_DIV_8 + * @retval none + */ +void tmr_input_channel_divider_set(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + tmr_channel_input_divider_type divider_factor) +{ + uint16_t channel; + + channel = tmr_channel; + + switch(channel) + { + case TMR_SELECT_CHANNEL_1: + tmr_x->cm1_input_bit.c1idiv = divider_factor; + break; + + case TMR_SELECT_CHANNEL_2: + tmr_x->cm1_input_bit.c2idiv = divider_factor; + break; + + case TMR_SELECT_CHANNEL_3: + tmr_x->cm2_input_bit.c3idiv = divider_factor; + break; + + case TMR_SELECT_CHANNEL_4: + tmr_x->cm2_input_bit.c4idiv = divider_factor; + break; + + default: + break; + } +} + +/** + * @brief select tmr primary mode + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR6, TMR7, TMR8, TMR20 + * @param primary_mode + * this parameter can be one of the following values: + * - TMR_PRIMARY_SEL_RESET + * - TMR_PRIMARY_SEL_ENABLE + * - TMR_PRIMARY_SEL_OVERFLOW + * - TMR_PRIMARY_SEL_COMPARE + * - TMR_PRIMARY_SEL_C1ORAW + * - TMR_PRIMARY_SEL_C2ORAW + * - TMR_PRIMARY_SEL_C3ORAW + * - TMR_PRIMARY_SEL_C4ORAW + * @retval none + */ +void tmr_primary_mode_select(tmr_type *tmr_x, tmr_primary_select_type primary_mode) +{ + tmr_x->ctrl2_bit.ptos = primary_mode; +} + +/** + * @brief select tmr subordinate mode + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR12, TMR20 + * @param sub_mode + * this parameter can be one of the following values: + * - TMR_SUB_MODE_DIABLE + * - TMR_SUB_ENCODER_MODE_A + * - TMR_SUB_ENCODER_MODE_B + * - TMR_SUB_ENCODER_MODE_C + * - TMR_SUB_RESET_MODE + * - TMR_SUB_HANG_MODE + * - TMR_SUB_TRIGGER_MODE + * - TMR_SUB_EXTERNAL_CLOCK_MODE_A + + * @retval none + */ +void tmr_sub_mode_select(tmr_type *tmr_x, tmr_sub_mode_select_type sub_mode) +{ + tmr_x->stctrl_bit.smsel = sub_mode; +} + +/** + * @brief select tmr channel dma + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR12, TMR20 + * @param cc_dma_select + * this parameter can be one of the following values: + * - TMR_DMA_REQUEST_BY_CHANNEL + * - TMR_DMA_REQUEST_BY_OVERFLOW + * @retval none + */ +void tmr_channel_dma_select(tmr_type *tmr_x, tmr_dma_request_source_type cc_dma_select) +{ + tmr_x->ctrl2_bit.drs = cc_dma_select; +} + +/** + * @brief select tmr hall + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR8, TMR20 + * @param new_state (TRUE or FALSE) + * @retval none + */ +void tmr_hall_select(tmr_type *tmr_x, confirm_state new_state) +{ + tmr_x->ctrl2_bit.ccfs = new_state; +} + +/** + * @brief select tmr channel buffer + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR8, TMR20 + * @param new_state (TRUE or FALSE) + * @retval none + */ +void tmr_channel_buffer_enable(tmr_type *tmr_x, confirm_state new_state) +{ + tmr_x->ctrl2_bit.cbctrl = new_state; +} + +/** + * @brief select tmr trgout2 + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR8, TMR20 + * @param new_state (TRUE or FALSE) + * @retval none + */ +void tmr_trgout2_enable(tmr_type *tmr_x, confirm_state new_state) +{ + tmr_x->ctrl2_bit.trgout2en = new_state; +} + +/** + * @brief select tmr sub-trigger + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR12, TMR20 + * @param trigger_select + * this parameter can be one of the following values: + * - TMR_SUB_INPUT_SEL_IS0 + * - TMR_SUB_INPUT_SEL_IS1 + * - TMR_SUB_INPUT_SEL_IS2 + * - TMR_SUB_INPUT_SEL_IS3 + * - TMR_SUB_INPUT_SEL_C1INC + * - TMR_SUB_INPUT_SEL_C1DF1 + * - TMR_SUB_INPUT_SEL_C2DF2 + * - TMR_SUB_INPUT_SEL_EXTIN + * @retval none + */ +void tmr_trigger_input_select(tmr_type *tmr_x, sub_tmr_input_sel_type trigger_select) +{ + tmr_x->stctrl_bit.stis = trigger_select; +} + +/** + * @brief set tmr subordinate synchronization mode + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR12, TMR20 + * @param new_state (TRUE or FALSE) + * @retval none + */ +void tmr_sub_sync_mode_set(tmr_type *tmr_x, confirm_state new_state) +{ + tmr_x->stctrl_bit.sts = new_state; +} + +/** + * @brief enable or disable tmr dma request + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR6, TMR7, TMR8, + * TMR9, TMR10, TMR11, TMR12, TMR13, TMR14, TMR20 + * @param dma_request + * this parameter can be one of the following values: + * - TMR_OVERFLOW_DMA_REQUEST + * - TMR_C1_DMA_REQUEST + * - TMR_C2_DMA_REQUEST + * - TMR_C3_DMA_REQUEST + * - TMR_C4_DMA_REQUEST + * - TMR_HALL_DMA_REQUEST + * - TMR_TRIGGER_DMA_REQUEST + * @param new_state (TRUE or FALSE) + * @retval none + */ +void tmr_dma_request_enable(tmr_type *tmr_x, tmr_dma_request_type dma_request, confirm_state new_state) +{ + if(new_state == TRUE) + { + tmr_x->iden |= dma_request; + } + else if(new_state == FALSE) + { + tmr_x->iden &= ~dma_request; + } +} + +/** + * @brief enable or disable tmr interrupt + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR6, TMR7, TMR8, + * TMR9, TMR10, TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_interrupt + * this parameter can be one of the following values: + * - TMR_OVF_INT + * - TMR_C1_INT + * - TMR_C2_INT + * - TMR_C3_INT + * - TMR_C4_INT + * - TMR_HALL_INT + * - TMR_TRIGGER_INT + * - TMR_BRK_INT + * @param new_state (TRUE or FALSE) + * @retval none + */ +void tmr_interrupt_enable(tmr_type *tmr_x, uint32_t tmr_interrupt, confirm_state new_state) +{ + if(new_state == TRUE) + { + tmr_x->iden |= tmr_interrupt; + } + else if(new_state == FALSE) + { + tmr_x->iden &= ~tmr_interrupt; + } +} + +/** + * @brief get tmr flag + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR6, TMR7, TMR8, + * TMR9, TMR10, TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_flag + * this parameter can be one of the following values: + * - TMR_OVF_FLAG + * - TMR_C1_FLAG + * - TMR_C2_FLAG + * - TMR_C3_FLAG + * - TMR_C4_FLAG + * - TMR_C5_FLAG + * - TMR_HALL_FLAG + * - TMR_TRIGGER_FLAG + * - TMR_BRK_FLAG + * - TMR_C1_RECAPTURE_FLAG + * - TMR_C2_RECAPTURE_FLAG + * - TMR_C3_RECAPTURE_FLAG + * - TMR_C4_RECAPTURE_FLAG + * @retval state of tmr flag + */ +flag_status tmr_flag_get(tmr_type *tmr_x, uint32_t tmr_flag) +{ + flag_status status = RESET; + + if((tmr_x->ists & tmr_flag) != RESET) + { + status = SET; + } + else + { + status = RESET; + } + + return status; +} + +/** + * @brief clear tmr flag + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR6, TMR7, TMR8, + * TMR9, TMR10, TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_flag + * this parameter can be any combination of the following values: + * - TMR_OVF_FLAG + * - TMR_C1_FLAG + * - TMR_C2_FLAG + * - TMR_C3_FLAG + * - TMR_C4_FLAG + * - TMR_C5_FLAG + * - TMR_HALL_FLAG + * - TMR_TRIGGER_FLAG + * - TMR_BRK_FLAG + * - TMR_C1_RECAPTURE_FLAG + * - TMR_C2_RECAPTURE_FLAG + * - TMR_C3_RECAPTURE_FLAG + * - TMR_C4_RECAPTURE_FLAG + * @retval none + */ +void tmr_flag_clear(tmr_type *tmr_x, uint32_t tmr_flag) +{ + tmr_x->ists = ~tmr_flag; +} + +/** + * @brief generate tmr event + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR6, TMR7, TMR8, + * TMR9, TMR10, TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_event + * this parameter can be one of the following values: + * - TMR_OVERFLOW_SWTRIG + * - TMR_C1_SWTRIG + * - TMR_C2_SWTRIG + * - TMR_C3_SWTRIG + * - TMR_C4_SWTRIG + * - TMR_HALL_SWTRIG + * - TMR_TRIGGER_SWTRIG + * - TMR_BRK_SWTRIG + * @retval none + */ +void tmr_event_sw_trigger(tmr_type *tmr_x, tmr_event_trigger_type tmr_event) +{ + tmr_x->swevt |= tmr_event; +} + +/** + * @brief tmr output enable(oen),this function is important for advtm output enable + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR8, TMR20 + * @param new_state (TRUE or FALSE) + * @retval none + */ +void tmr_output_enable(tmr_type *tmr_x, confirm_state new_state) +{ + tmr_x->brk_bit.oen = new_state; +} + +/** + * @brief set tmr select internal clock + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR12, TMR20 + * @retval none + */ +void tmr_internal_clock_set(tmr_type *tmr_x) +{ + tmr_x->stctrl_bit.smsel = TMR_SUB_MODE_DIABLE; +} + +/** + * @brief set tmr output channel polarity + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR10, + * TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_channel + * this parameter can be one of the following values: + * - TMR_SELECT_CHANNEL_1 + * - TMR_SELECT_CHANNEL_2 + * - TMR_SELECT_CHANNEL_3 + * - TMR_SELECT_CHANNEL_4 + * - TMR_SELECT_CHANNEL_1C + * - TMR_SELECT_CHANNEL_2C + * - TMR_SELECT_CHANNEL_3C + * @param oc_polarity + * this parameter can be one of the following values: + * - TMR_POLARITY_ACTIVE_HIGH + * - TMR_POLARITY_ACTIVE_LOW + * @retval none + */ +void tmr_output_channel_polarity_set(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + tmr_polarity_active_type oc_polarity) +{ + uint16_t channel; + + channel = tmr_channel; + + switch(channel) + { + case TMR_SELECT_CHANNEL_1: + tmr_x->cctrl_bit.c1p = (uint32_t)oc_polarity; + break; + + case TMR_SELECT_CHANNEL_2: + tmr_x->cctrl_bit.c2p = (uint32_t)oc_polarity; + break; + + case TMR_SELECT_CHANNEL_3: + tmr_x->cctrl_bit.c3p = (uint32_t)oc_polarity; + break; + + case TMR_SELECT_CHANNEL_4: + tmr_x->cctrl_bit.c4p = (uint32_t)oc_polarity; + break; + + case TMR_SELECT_CHANNEL_1C: + tmr_x->cctrl_bit.c1cp = (uint32_t)oc_polarity; + break; + + case TMR_SELECT_CHANNEL_2C: + tmr_x->cctrl_bit.c2cp = (uint32_t)oc_polarity; + break; + + case TMR_SELECT_CHANNEL_3C: + tmr_x->cctrl_bit.c3cp = (uint32_t)oc_polarity; + break; + + default: + break; + } +} + +/** + * @brief config tmr external clock + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR20 + * @param es_divide + * this parameter can be one of the following values: + * - TMR_ES_FREQUENCY_DIV_1 + * - TMR_ES_FREQUENCY_DIV_2 + * - TMR_ES_FREQUENCY_DIV_4 + * - TMR_ES_FREQUENCY_DIV_8 + * @param es_polarity + * this parameter can be one of the following values: + * - TMR_ES_POLARITY_NON_INVERTED + * - TMR_ES_POLARITY_INVERTED + * @param es_filter (0x0~0xf) + * @retval none + */ +void tmr_external_clock_config(tmr_type *tmr_x, tmr_external_signal_divider_type es_divide, \ + tmr_external_signal_polarity_type es_polarity, uint16_t es_filter) +{ + tmr_x->stctrl_bit.esdiv = es_divide; + tmr_x->stctrl_bit.esp = es_polarity; + tmr_x->stctrl_bit.esf = es_filter; +} + +/** + * @brief config tmr external clock mode1 + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR12, TMR20 + * @param es_divide + * this parameter can be one of the following values: + * - TMR_ES_FREQUENCY_DIV_1 + * - TMR_ES_FREQUENCY_DIV_2 + * - TMR_ES_FREQUENCY_DIV_4 + * - TMR_ES_FREQUENCY_DIV_8 + * @param es_polarity + * this parameter can be one of the following values: + * - TMR_ES_POLARITY_NON_INVERTED + * - TMR_ES_POLARITY_INVERTED + * @param es_filter (0x0~0xf) + * @retval none + */ +void tmr_external_clock_mode1_config(tmr_type *tmr_x, tmr_external_signal_divider_type es_divide, \ + tmr_external_signal_polarity_type es_polarity, uint16_t es_filter) +{ + tmr_external_clock_config(tmr_x, es_divide, es_polarity, es_filter); + tmr_x->stctrl_bit.smsel = TMR_SUB_EXTERNAL_CLOCK_MODE_A; + tmr_x->stctrl_bit.stis = TMR_SUB_INPUT_SEL_EXTIN; +} + +/** + * @brief config tmr external clock mode2 + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR20 + * @param es_divide + * this parameter can be one of the following values: + * - TMR_ES_FREQUENCY_DIV_1 + * - TMR_ES_FREQUENCY_DIV_2 + * - TMR_ES_FREQUENCY_DIV_4 + * - TMR_ES_FREQUENCY_DIV_8 + * @param es_polarity + * this parameter can be one of the following values: + * - TMR_ES_POLARITY_NON_INVERTED + * - TMR_ES_POLARITY_INVERTED + * @param es_filter (0x0~0xf) + * @retval none + */ +void tmr_external_clock_mode2_config(tmr_type *tmr_x, tmr_external_signal_divider_type es_divide, \ + tmr_external_signal_polarity_type es_polarity, uint16_t es_filter) +{ + tmr_external_clock_config(tmr_x, es_divide, es_polarity, es_filter); + tmr_x->stctrl_bit.ecmben = TRUE; +} + +/** + * @brief config tmr encoder mode + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR20 + * @param encoder_mode + * this parameter can be one of the following values: + * - TMR_ENCODER_MODE_A + * - TMR_ENCODER_MODE_B + * - TMR_ENCODER_MODE_C + * @param ic1_polarity + * this parameter can be one of the following values: + * - TMR_INPUT_RISING_EDGE + * - TMR_INPUT_FALLING_EDGE + * - TMR_INPUT_BOTH_EDGE + * @param ic2_polarity + * this parameter can be one of the following values: + * - TMR_INPUT_RISING_EDGE + * - TMR_INPUT_FALLING_EDGE + * - TMR_INPUT_BOTH_EDGE + * @retval none + */ +void tmr_encoder_mode_config(tmr_type *tmr_x, tmr_encoder_mode_type encoder_mode, tmr_input_polarity_type \ + ic1_polarity, tmr_input_polarity_type ic2_polarity) +{ + tmr_x->stctrl_bit.smsel = encoder_mode; + + /* set ic1 polarity */ + tmr_x->cctrl_bit.c1p = (ic1_polarity & 0x1); + tmr_x->cctrl_bit.c1cp = (ic1_polarity >> 1); + /* set ic1 as input channel */ + tmr_x->cm1_input_bit.c1c = TMR_CC_CHANNEL_MAPPED_DIRECT; + + /* set ic2 polarity */ + tmr_x->cctrl_bit.c2p = (ic2_polarity & 0x1); + tmr_x->cctrl_bit.c2cp = (ic2_polarity >> 1); + /* set ic2 as input channel */ + tmr_x->cm1_input_bit.c2c = TMR_CC_CHANNEL_MAPPED_DIRECT; +} + +/** + * @brief set tmr force output + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR9, TMR10, + * TMR11, TMR12, TMR13, TMR14, TMR20 + * @param tmr_channel + * this parameter can be one of the following values: + * - TMR_SELECT_CHANNEL_1 + * - TMR_SELECT_CHANNEL_2 + * - TMR_SELECT_CHANNEL_3 + * - TMR_SELECT_CHANNEL_4 + * - TMR_SELECT_CHANNEL_5 + * @param force_output + * this parameter can be one of the following values: + * - TMR_FORCE_OUTPUT_HIGH + * - TMR_FORCE_OUTPUT_LOW + * @retval none + */ +void tmr_force_output_set(tmr_type *tmr_x, tmr_channel_select_type tmr_channel, \ + tmr_force_output_type force_output) +{ + uint16_t channel; + + channel = tmr_channel; + + switch(channel) + { + case TMR_SELECT_CHANNEL_1: + tmr_x->cm1_output_bit.c1octrl = force_output; + break; + + case TMR_SELECT_CHANNEL_2: + tmr_x->cm1_output_bit.c2octrl = force_output; + break; + + case TMR_SELECT_CHANNEL_3: + tmr_x->cm2_output_bit.c3octrl = force_output; + break; + + case TMR_SELECT_CHANNEL_4: + tmr_x->cm2_output_bit.c4octrl = force_output; + break; + + case TMR_SELECT_CHANNEL_5: + tmr_x->cm3_output_bit.c5octrl = force_output; + break; + + default: + break; + } +} + +/** + * @brief config tmr dma control + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR2, TMR3, TMR4, TMR5, TMR8, TMR20 + * @param dma_length + * this parameter can be one of the following values: + * - TMR_DMA_TRANSFER_1BYTE + * - TMR_DMA_TRANSFER_2BYTES + * - TMR_DMA_TRANSFER_3BYTES + * ... + * - TMR_DMA_TRANSFER_17BYTES + * - TMR_DMA_TRANSFER_18BYTES + * @param dma_base_address + * this parameter can be one of the following values: + * - TMR_CTRL1_ADDRESS + * - TMR_CTRL2_ADDRESS + * - TMR_STCTRL_ADDRESS + * - TMR_IDEN_ADDRESS + * - TMR_ISTS_ADDRESS + * - TMR_SWEVT_ADDRESS + * - TMR_CM1_ADDRESS + * - TMR_CM2_ADDRESS + * - TMR_CCTRL_ADDRESS + * - TMR_CVAL_ADDRESS + * - TMR_DIV_ADDRESS + * - TMR_PR_ADDRESS + * - TMR_RPR_ADDRESS + * - TMR_C1DT_ADDRESS + * - TMR_C2DT_ADDRESS + * - TMR_C3DT_ADDRESS + * - TMR_C4DT_ADDRESS + * - TMR_BRK_ADDRESS + * - TMR_DMACTRL_ADDRESS + * @retval none + */ +void tmr_dma_control_config(tmr_type *tmr_x, tmr_dma_transfer_length_type dma_length, \ + tmr_dma_address_type dma_base_address) +{ + tmr_x->dmactrl_bit.dtb = dma_length; + tmr_x->dmactrl_bit.addr = dma_base_address; +} + +/** + * @brief config tmr break mode and dead-time + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR1, TMR8, TMR20 + * @param brkdt_struct + * - to the structure of tmr_brkdt_config_type + * @retval none + */ +void tmr_brkdt_config(tmr_type *tmr_x, tmr_brkdt_config_type *brkdt_struct) +{ + tmr_x->brk_bit.brken = brkdt_struct->brk_enable; + tmr_x->brk_bit.dtc = brkdt_struct->deadtime; + tmr_x->brk_bit.fcsodis = brkdt_struct->fcsodis_state; + tmr_x->brk_bit.fcsoen = brkdt_struct->fcsoen_state; + tmr_x->brk_bit.brkv = brkdt_struct->brk_polarity; + tmr_x->brk_bit.aoen = brkdt_struct->auto_output_enable; + tmr_x->brk_bit.wpc = brkdt_struct->wp_level; +} + +/** + * @brief set tmr2/tmr5 input channel remap + * @param tmr_x: select the tmr peripheral. + * this parameter can be one of the following values: + * TMR2, TMR5 + * @param input_remap + * - TMR2_TMR8TRGOUT_TMR5_GPIO + * - TMR2_PTP_TMR5_LICK + * - TMR2_OTG1FS_TMR5_LEXT + * - TMR2_OTG2FS_TMR5_ERTC + * @retval none + */ +void tmr_iremap_config(tmr_type *tmr_x, tmr_input_remap_type input_remap) +{ + if(tmr_x == TMR2) + { + tmr_x->rmp_bit.tmr2_ch1_irmp = input_remap; + } + else if(tmr_x == TMR5) + { + tmr_x->rmp_bit.tmr5_ch4_irmp = input_remap; + } +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_usart.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_usart.c new file mode 100644 index 0000000000..eb3b75282f --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_usart.c @@ -0,0 +1,732 @@ +/** + ************************************************************************** + * @file at32f435_437_usart.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the usart firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* includes ------------------------------------------------------------------*/ +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup USART + * @brief USART driver modules + * @{ + */ + +#ifdef USART_MODULE_ENABLED + +/** @defgroup USART_private_functions + * @{ + */ + +/** + * @brief deinitialize the usart peripheral registers to their default reset values. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7,or UART8. + * @retval none + */ +void usart_reset(usart_type* usart_x) +{ + if(usart_x == USART1) + { + crm_periph_reset(CRM_USART1_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_USART1_PERIPH_RESET, FALSE); + } + else if(usart_x == USART2) + { + crm_periph_reset(CRM_USART2_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_USART2_PERIPH_RESET, FALSE); + } + else if(usart_x == USART3) + { + crm_periph_reset(CRM_USART3_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_USART3_PERIPH_RESET, FALSE); + } + else if(usart_x == UART4) + { + crm_periph_reset(CRM_UART4_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_UART4_PERIPH_RESET, FALSE); + } + else if(usart_x == UART5) + { + crm_periph_reset(CRM_UART5_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_UART5_PERIPH_RESET, FALSE); + } + else if(usart_x == USART6) + { + crm_periph_reset(CRM_USART6_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_USART6_PERIPH_RESET, FALSE); + } + else if(usart_x == UART7) + { + crm_periph_reset(CRM_UART7_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_UART7_PERIPH_RESET, FALSE); + } + else if(usart_x == UART8) + { + crm_periph_reset(CRM_UART8_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_UART8_PERIPH_RESET, FALSE); + } +} + +/** + * @brief initialize the usart peripheral according to the specified parameters. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4 ,UART5, USART6, UART7 or UART8. + * @param baud_rate: configure the usart communication baud rate. + * @param data_bit: data bits transmitted or received in a frame + * this parameter can be one of the following values: + * - USART_DATA_7BITS + * - USART_DATA_8BITS + * - USART_DATA_9BITS. + * @param stop_bit: stop bits transmitted + * this parameter can be one of the following values: + * - USART_STOP_1_BIT + * - USART_STOP_0_5_BIT. + * - USART_STOP_2_BIT + * - USART_STOP_1_5_BIT. + * @retval none + */ +void usart_init(usart_type* usart_x, uint32_t baud_rate, usart_data_bit_num_type data_bit, usart_stop_bit_num_type stop_bit) +{ + crm_clocks_freq_type clocks_freq; + uint32_t apb_clock, temp_val; + crm_clocks_freq_get(&clocks_freq); + if((usart_x == USART1) || (usart_x == USART6)) + { + apb_clock = clocks_freq.apb2_freq; + } + else + { + apb_clock = clocks_freq.apb1_freq; + } + temp_val = (apb_clock * 10 / baud_rate); + if((temp_val % 10) < 5) + { + temp_val = (temp_val / 10); + } + else + { + temp_val = (temp_val / 10) + 1; + } + usart_x->baudr_bit.div = temp_val; + if(data_bit == USART_DATA_7BITS) + { + usart_x->ctrl1_bit.dbn_h = 1; + usart_x->ctrl1_bit.dbn_l = 0; + } + else if(data_bit == USART_DATA_8BITS) + { + usart_x->ctrl1_bit.dbn_h = 0; + usart_x->ctrl1_bit.dbn_l = 0; + } + else + { + usart_x->ctrl1_bit.dbn_h = 0; + usart_x->ctrl1_bit.dbn_l = 1; + } + usart_x->ctrl2_bit.stopbn = stop_bit; +} + +/** + * @brief usart parity selection config. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4 ,UART5, USART6, UART7 or UART8. + * @param parity: select the none, odd or even parity. + * this parameter can be one of the following values: + * - USART_PARITY_NONE + * - USART_PARITY_EVEN. + * - USART_PARITY_ODD + * @retval none + */ +void usart_parity_selection_config(usart_type* usart_x, usart_parity_selection_type parity) +{ + if(parity == USART_PARITY_NONE) + { + usart_x->ctrl1_bit.psel = FALSE; + usart_x->ctrl1_bit.pen = FALSE; + } + else if(parity == USART_PARITY_EVEN) + { + usart_x->ctrl1_bit.psel = FALSE; + usart_x->ctrl1_bit.pen = TRUE; + } + else if(parity == USART_PARITY_ODD) + { + usart_x->ctrl1_bit.psel = TRUE; + usart_x->ctrl1_bit.pen = TRUE; + } +} + +/** + * @brief enable or disable the specified usart peripheral. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8. + * @param new_state: new state of the usart peripheral. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void usart_enable(usart_type* usart_x, confirm_state new_state) +{ + usart_x->ctrl1_bit.uen = new_state; +} + +/** + * @brief usart transmitter enable. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4 ,UART5, USART6, UART7 or UART8. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void usart_transmitter_enable(usart_type* usart_x, confirm_state new_state) +{ + usart_x->ctrl1_bit.ten = new_state; +} + +/** + * @brief usart receiver enable. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4 ,UART5, USART6, UART7 or UART8. + * @param new_state: TRUE or FALSE. + * @retval none + */ +void usart_receiver_enable(usart_type* usart_x, confirm_state new_state) +{ + usart_x->ctrl1_bit.ren = new_state; +} + +/** + * @brief usart clock config. + * @note clock config are not available for UART4, UART5, UART7 and UART8. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3 or USART6. + * @param clk_pol: polarity of the clock output on the ck pin. + * this parameter can be one of the following values: + * - USART_CLOCK_POLARITY_LOW + * - USART_CLOCK_POLARITY_HIGH + * @param clk_pha: phase of the clock output on the ck pin. + * this parameter can be one of the following values: + * - USART_CLOCK_PHASE_1EDGE + * - USART_CLOCK_PHASE_2EDGE + * @param clk_lb: whether the clock pulse of the last data bit transmitted (MSB) is outputted on the ck pin. + * this parameter can be one of the following values: + * - USART_CLOCK_LAST_BIT_NONE + * - USART_CLOCK_LAST_BIT_OUTPUT + * @retval none + */ +void usart_clock_config(usart_type* usart_x, usart_clock_polarity_type clk_pol, usart_clock_phase_type clk_pha, usart_lbcp_type clk_lb) +{ + usart_x->ctrl2_bit.clkpol = clk_pol; + usart_x->ctrl2_bit.clkpha = clk_pha; + usart_x->ctrl2_bit.lbcp = clk_lb; +} + +/** + * @brief usart enable the ck pin. + * @note clock enable are not available for UART4, UART5, UART7 and UART8. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3 or USART6. + * @param new_state: TRUE or FALSE + * @retval none + */ +void usart_clock_enable(usart_type* usart_x, confirm_state new_state) +{ + usart_x->ctrl2_bit.clken = new_state; +} + +/** + * @brief enable or disable the specified usart interrupts. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8. + * @param usart_int: specifies the USART interrupt sources to be enabled or disabled. + * this parameter can be one of the following values: + * - USART_IDLE_INT: idle interrupt + * - USART_RDBF_INT: rdbf interrupt + * - USART_TDC_INT: tdc interrupt + * - USART_TDBE_INT: tdbe interrupt + * - USART_PERR_INT: perr interrupt + * - USART_BF_INT: break frame interrupt + * - USART_ERR_INT: err interrupt + * - USART_CTSCF_INT: ctscf interrupt + * @param new_state: new state of the specified usart interrupts. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void usart_interrupt_enable(usart_type* usart_x, uint32_t usart_int, confirm_state new_state) +{ + if(new_state == TRUE) + PERIPH_REG((uint32_t)usart_x, usart_int) |= PERIPH_REG_BIT(usart_int); + else + PERIPH_REG((uint32_t)usart_x, usart_int) &= ~PERIPH_REG_BIT(usart_int); +} + +/** + * @brief enable or disable the usart's dma transmitter interface. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8. + * @param new_state: new state of the dma request sources. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void usart_dma_transmitter_enable(usart_type* usart_x, confirm_state new_state) +{ + usart_x->ctrl3_bit.dmaten = new_state; +} + +/** + * @brief enable or disable the usart's dma receiver interface. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8. + * @param new_state: new state of the dma request sources. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void usart_dma_receiver_enable(usart_type* usart_x, confirm_state new_state) +{ + usart_x->ctrl3_bit.dmaren = new_state; +} + +/** + * @brief set the wakeup id of the usart. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8. + * @param usart_id: the matching id(0x0~0xFF). + * @retval none + */ +void usart_wakeup_id_set(usart_type* usart_x, uint8_t usart_id) +{ + if(usart_x->ctrl2_bit.idbn == USART_ID_FIXED_4_BIT) + { + usart_x->ctrl2_bit.id_l = (usart_id & 0x0F); + usart_x->ctrl2_bit.id_h = 0; + } + else + { + usart_x->ctrl2_bit.id_l = (usart_id & 0x0F); + usart_x->ctrl2_bit.id_h = ((usart_id & 0xF0) >> 4); + } +} + +/** + * @brief select the usart wakeup method in multi-processor communication. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8. + * @param wakeup_mode: determines the way to wake up usart method. + * this parameter can be one of the following values: + * - USART_WAKEUP_BY_IDLE_FRAME + * - USART_WAKEUP_BY_MATCHING_ID + * @retval none + */ +void usart_wakeup_mode_set(usart_type* usart_x, usart_wakeup_mode_type wakeup_mode) +{ + usart_x->ctrl1_bit.wum = wakeup_mode; +} + +/** + * @brief config the usart in mute mode in multi-processor communication. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8. + * @param new_state: new state of the usart mute mode. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void usart_receiver_mute_enable(usart_type* usart_x, confirm_state new_state) +{ + usart_x->ctrl1_bit.rm = new_state; +} + +/** + * @brief set the usart break frame bit num. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8. + * @param break_bit: specifies the break bit num. + * this parameter can be one of the following values: + * - USART_BREAK_10BITS + * - USART_BREAK_11BITS + * @retval none + */ +void usart_break_bit_num_set(usart_type* usart_x, usart_break_bit_num_type break_bit) +{ + usart_x->ctrl2_bit.bfbn = break_bit; +} + +/** + * @brief enable or disable the usart lin mode. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8. + * @param new_state: new state of the usart lin mode. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void usart_lin_mode_enable(usart_type* usart_x, confirm_state new_state) +{ + usart_x->ctrl2_bit.linen = new_state; +} + +/** + * @brief transmit single data through the usart peripheral. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8. + * @param data: the data to transmit. + * @retval none + */ +void usart_data_transmit(usart_type* usart_x, uint16_t data) +{ + usart_x->dt = (data & 0x01FF); +} + +/** + * @brief return the most recent received data by the usart peripheral. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8. + * @retval the received data. + */ +uint16_t usart_data_receive(usart_type* usart_x) +{ + return (uint16_t)(usart_x->dt); +} + +/** + * @brief transmit break characters. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8. + * @retval none + */ +void usart_break_send(usart_type* usart_x) +{ + usart_x->ctrl1_bit.sbf = TRUE; +} + +/** + * @brief config the specified usart smartcard guard time. + * @note The guard time bits are not available for UART4, UART5, UART7 or UART8. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3 or USART6. + * @param guard_time_val: specifies the guard time (0x00~0xFF). + * @retval none + */ +void usart_smartcard_guard_time_set(usart_type* usart_x, uint8_t guard_time_val) +{ + usart_x->gdiv_bit.scgt = guard_time_val; +} + +/** + * @brief config the irda/smartcard division. + * @note the division are not available for UART4, UART5, UART7 or UART8. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3 or USART6. + * @param div_val: specifies the division. + * @retval none + */ +void usart_irda_smartcard_division_set(usart_type* usart_x, uint8_t div_val) +{ + usart_x->gdiv_bit.isdiv = div_val; +} + +/** + * @brief enable or disable the usart smart card mode. + * @note the smart card mode are not available for UART4, UART5, UART7 or UART8. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3 or USART6. + * @param new_state: new state of the smart card mode. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void usart_smartcard_mode_enable(usart_type* usart_x, confirm_state new_state) +{ + usart_x->ctrl3_bit.scmen = new_state; +} + +/** + * @brief enable or disable nack transmission in smartcard mode. + * @note the smart card nack are not available for UART4, UART5, UART7 or UART8. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3 or USART6. + * @param new_state: new state of the nack transmission. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void usart_smartcard_nack_set(usart_type* usart_x, confirm_state new_state) +{ + usart_x->ctrl3_bit.scnacken = new_state; +} + +/** + * @brief enable or disable the usart single line bidirectional half-duplex communication. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8. + * @param new_state: new state of the single line half-duplex select. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void usart_single_line_halfduplex_select(usart_type* usart_x, confirm_state new_state) +{ + usart_x->ctrl3_bit.slben = new_state; +} + +/** + * @brief enable or disable the usart's irda interface. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8. + * @param new_state: new state of the irda mode. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void usart_irda_mode_enable(usart_type* usart_x, confirm_state new_state) +{ + usart_x->ctrl3_bit.irdaen = new_state; +} + +/** + * @brief configure the usart's irda low power. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8. + * @param new_state: new state of the irda mode. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void usart_irda_low_power_enable(usart_type* usart_x, confirm_state new_state) +{ + usart_x->ctrl3_bit.irdalp = new_state; +} + +/** + * @brief configure the usart's hardware flow control. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3 + * @param flow_state: specifies the hardware flow control. + * this parameter can be one of the following values: + * - USART_HARDWARE_FLOW_NONE + * - USART_HARDWARE_FLOW_RTS, + * - USART_HARDWARE_FLOW_CTS, + * - USART_HARDWARE_FLOW_RTS_CTS + * @retval none + */ +void usart_hardware_flow_control_set(usart_type* usart_x,usart_hardware_flow_control_type flow_state) +{ + if(flow_state == USART_HARDWARE_FLOW_NONE) + { + usart_x->ctrl3_bit.rtsen = FALSE; + usart_x->ctrl3_bit.ctsen = FALSE; + } + else if(flow_state == USART_HARDWARE_FLOW_RTS) + { + usart_x->ctrl3_bit.rtsen = TRUE; + usart_x->ctrl3_bit.ctsen = FALSE; + } + else if(flow_state == USART_HARDWARE_FLOW_CTS) + { + usart_x->ctrl3_bit.rtsen = FALSE; + usart_x->ctrl3_bit.ctsen = TRUE; + } + else if(flow_state == USART_HARDWARE_FLOW_RTS_CTS) + { + usart_x->ctrl3_bit.rtsen = TRUE; + usart_x->ctrl3_bit.ctsen = TRUE; + } +} + +/** + * @brief check whether the specified usart flag is set or not. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8. + * @param flag: specifies the flag to check. + * this parameter can be one of the following values: + * - USART_CTSCF_FLAG: cts change flag (not available for UART4,UART5,USART6,UART7 and UART8) + * - USART_BFF_FLAG: break frame flag + * - USART_TDBE_FLAG: transmit data buffer empty flag + * - USART_TDC_FLAG: transmit data complete flag + * - USART_RDBF_FLAG: receive data buffer full flag + * - USART_IDLEF_FLAG: idle flag + * - USART_ROERR_FLAG: receiver overflow error flag + * - USART_NERR_FLAG: noise error flag + * - USART_FERR_FLAG: framing error flag + * - USART_PERR_FLAG: parity error flag + * @retval the new state of usart_flag (SET or RESET). + */ +flag_status usart_flag_get(usart_type* usart_x, uint32_t flag) +{ + if(usart_x->sts & flag) + { + return SET; + } + else + { + return RESET; + } +} + +/** + * @brief clear the usart's pending flags. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8. + * @param flag: specifies the flag to clear. + * this parameter can be any combination of the following values: + * - USART_CTSCF_FLAG: (not available for UART4,UART5,USART6,UART7 and UART8). + * - USART_BFF_FLAG: + * - USART_TDC_FLAG: + * - USART_RDBF_FLAG: + * - USART_PERR_FLAG: + * - USART_FERR_FLAG: + * - USART_NERR_FLAG: + * - USART_ROERR_FLAG: + * - USART_IDLEF_FLAG: + * @note + * - USART_PERR_FLAG, USART_FERR_FLAG, USART_NERR_FLAG, USART_ROERR_FLAG and USART_IDLEF_FLAG are cleared by software + * sequence: a read operation to usart sts register (usart_flag_get()) + * followed by a read operation to usart dt register (usart_data_receive()). + * - USART_RDBF_FLAG can be also cleared by a read to the usart dt register(usart_data_receive()). + * - USART_TDC_FLAG can be also cleared by software sequence: a read operation to usart sts register (usart_flag_get()) + * followed by a write operation to usart dt register (usart_data_transmit()). + * - USART_TDBE_FLAG is cleared only by a write to the usart dt register(usart_data_transmit()). + * @retval none + */ +void usart_flag_clear(usart_type* usart_x, uint32_t flag) +{ + if(flag & (USART_PERR_FLAG | USART_FERR_FLAG | USART_NERR_FLAG | USART_ROERR_FLAG | USART_IDLEF_FLAG)) + { + UNUSED(usart_x->sts); + UNUSED(usart_x->dt); + } + else + { + usart_x->sts = ~flag; + } +} + +/** + * @brief configure the usart's rs485 transmit delay time. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3 + * @param start_delay_time: transmit start delay time. + * @param complete_delay_time: transmit complete delay time. + * @retval none + */ +void usart_rs485_delay_time_config(usart_type* usart_x, uint8_t start_delay_time, uint8_t complete_delay_time) +{ + usart_x->ctrl1_bit.tsdt = start_delay_time; + usart_x->ctrl1_bit.tcdt = complete_delay_time; +} + +/** + * @brief swap the usart's transmit receive pin. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7,or UART8. + * @param new_state: new state of the usart peripheral. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void usart_transmit_receive_pin_swap(usart_type* usart_x, confirm_state new_state) +{ + usart_x->ctrl2_bit.trpswap = new_state; +} + +/** + * @brief set the usart's identification bit num. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3, UART4, UART5, USART6, UART7,or UART8. + * @param id_bit_num: the usart wakeup identification bit num. + * this parameter can be: USART_ID_FIXED_4_BIT or USART_ID_RELATED_DATA_BIT. + * @retval none + */ +void usart_id_bit_num_set(usart_type* usart_x, usart_identification_bit_num_type id_bit_num) +{ + usart_x->ctrl2_bit.idbn = (uint8_t)id_bit_num; +} + +/** + * @brief set the usart's de polarity. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3 + * @param de_polarity: the usart de polarity selection. + * this parameter can be: USART_DE_POLARITY_HIGH or USART_DE_POLARITY_LOW. + * @retval none + */ +void usart_de_polarity_set(usart_type* usart_x, usart_de_polarity_type de_polarity) +{ + usart_x->ctrl3_bit.dep = (uint8_t)de_polarity; +} + +/** + * @brief enable or disable the usart's rs485 mode. + * @param usart_x: select the usart or the uart peripheral. + * this parameter can be one of the following values: + * USART1, USART2, USART3 + * @param new_state: new state of the irda mode. + * this parameter can be: TRUE or FALSE. + * @retval none + */ +void usart_rs485_mode_enable(usart_type* usart_x, confirm_state new_state) +{ + usart_x->ctrl3_bit.rs485en = new_state; +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_usb.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_usb.c new file mode 100644 index 0000000000..8c7afcbaa5 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_usb.c @@ -0,0 +1,1096 @@ +/** + ************************************************************************** + * @file at32f435_437_usb.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the usb firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup USB + * @brief USB driver modules + * @{ + */ + +#ifdef USB_MODULE_ENABLED + +/** @defgroup USB_private_functions + * @{ + */ + +#ifdef OTGFS_USB_GLOBAL +/** + * @brief usb global core soft reset + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval error status + */ +error_status usb_global_reset(otg_global_type *usbx) +{ + uint32_t timeout = 0; + while(usbx->grstctl_bit.ahbidle == RESET) + { + if(timeout ++ > 200000) + { + break; + } + } + timeout = 0; + usbx->grstctl_bit.csftrst = TRUE; + while(usbx->grstctl_bit.csftrst == SET) + { + if(timeout ++ > 200000) + { + break; + } + } + return SUCCESS; +} + +/** + * @brief usb global initialization + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval none + */ +void usb_global_init(otg_global_type *usbx) +{ + /* reset otg moudle */ + usb_global_reset(usbx); + + /* exit power down mode */ + usbx->gccfg_bit.pwrdown = TRUE; +} + +/** + * @brief usb global select usb core (otg1 or otg2). + * @param usb_id: select otg1 or otg2 + * this parameter can be one of the following values: + * - USB_OTG1_ID + * - USB_OTG2_ID + * @retval usb global register type pointer + */ +otg_global_type *usb_global_select_core(uint8_t usb_id) +{ + if(usb_id == USB_OTG1_ID) + { + /* use otg1 */ + return OTG1_GLOBAL; + } + else + { + /* use otg2 */ + return OTG2_GLOBAL; + } +} + +/** + * @brief flush tx fifo + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param fifo_num: tx fifo num,when fifo_num=16,flush all tx fifo + * parameter as following values: 0-16 + * @retval none + */ +void usb_flush_tx_fifo(otg_global_type *usbx, uint32_t fifo_num) +{ + uint32_t timeout = 0; + /* set flush fifo number */ + usbx->grstctl_bit.txfnum = fifo_num; + + /* start flush fifo */ + usbx->grstctl_bit.txfflsh = TRUE; + + while(usbx->grstctl_bit.txfflsh == TRUE) + { + if(timeout ++ > 200000) + { + break; + } + } +} + +/** + * @brief flush rx fifo + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval none + */ +void usb_flush_rx_fifo(otg_global_type *usbx) +{ + uint32_t timeout = 0; + usbx->grstctl_bit.rxfflsh = TRUE; + while(usbx->grstctl_bit.rxfflsh == TRUE) + { + if(timeout ++ > 200000) + { + break; + } + } +} + +/** + * @brief usb interrupt mask enable + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param interrupt: + * this parameter can be any combination of the following values: + * - USB_OTG_MODEMIS_INT + * - USB_OTG_OTGINT_INT + * - USB_OTG_SOF_INT + * - USB_OTG_RXFLVL_INT + * - USB_OTG_NPTXFEMP_INT + * - USB_OTG_GINNAKEFF_INT + * - USB_OTG_GOUTNAKEFF_INT + * - USB_OTG_ERLYSUSP_INT + * - USB_OTG_USBSUSP_INT + * - USB_OTG_USBRST_INT + * - USB_OTG_ENUMDONE_INT + * - USB_OTG_ISOOUTDROP_INT + * - USB_OTG_IEPT_INT + * - USB_OTG_OEPT_INT + * - USB_OTG_INCOMISOIN_INT + * - USB_OTG_INCOMPIP_INCOMPISOOUT_INT + * - USB_OTG_PRT_INT + * - USB_OTG_HCH_INT + * - USB_OTG_PTXFEMP_INT + * - USB_OTG_CONIDSCHG_INT + * - USB_OTG_DISCON_INT + * - USB_OTG_WKUP_INT + * @param new_state: TRUE or FALSE + * @retval none + */ +void usb_global_interrupt_enable(otg_global_type *usbx, uint16_t interrupt, confirm_state new_state) +{ + if(new_state == TRUE) + { + usbx->gintmsk |= interrupt; + } + else + { + usbx->gintmsk &= ~interrupt; + } +} + +/** + * @brief get all global core interrupt flag + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval intterupt flag + */ +uint32_t usb_global_get_all_interrupt(otg_global_type *usbx) +{ + uint32_t intsts = usbx->gintsts; + return intsts & usbx->gintmsk; +} + +/** + * @brief clear the global interrupt flag + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param flag: interrupt flag + * this parameter can be any combination of the following values: + * - USB_OTG_MODEMIS_FLAG + * - USB_OTG_OTGINT_FLAG + * - USB_OTG_SOF_FLAG + * - USB_OTG_RXFLVL_FLAG + * - USB_OTG_NPTXFEMP_FLAG + * - USB_OTG_GINNAKEFF_FLAG + * - USB_OTG_GOUTNAKEFF_FLAG + * - USB_OTG_ERLYSUSP_FLAG + * - USB_OTG_USBSUSP_FLAG + * - USB_OTG_USBRST_FLAG + * - USB_OTG_ENUMDONE_FLAG + * - USB_OTG_ISOOUTDROP_FLAG + * - USB_OTG_EOPF_FLAG + * - USB_OTG_IEPT_FLAG + * - USB_OTG_OEPT_FLAG + * - USB_OTG_INCOMISOIN_FLAG + * - USB_OTG_INCOMPIP_INCOMPISOOUT_FLAG + * - USB_OTG_PRT_FLAG + * - USB_OTG_HCH_FLAG + * - USB_OTG_PTXFEMP_FLAG + * - USB_OTG_CONIDSCHG_FLAG + * - USB_OTG_DISCON_FLAG + * - USB_OTG_WKUP_FLAG + * @retval none + */ +void usb_global_clear_interrupt(otg_global_type *usbx, uint32_t flag) +{ + usbx->gintsts = flag; +} + +/** + * @brief usb global interrupt enable + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * OTG1_GLOBAL , OTG2_GLOBAL + * @retval none + */ +void usb_interrupt_enable(otg_global_type *usbx) +{ + usbx->gahbcfg_bit.glbintmsk = TRUE; +} + +/** + * @brief usb global interrupt disable + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval none + */ +void usb_interrupt_disable(otg_global_type *usbx) +{ + usbx->gahbcfg_bit.glbintmsk = FALSE; +} + +/** + * @brief usb set rx fifo size + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param size: rx fifo size + * @retval none + */ +void usb_set_rx_fifo(otg_global_type *usbx, uint16_t size) +{ + usbx->grxfsiz = size; +} + +/** + * @brief usb set tx fifo size + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param txfifo: the fifo number + * @param size: tx fifo size + * @retval none + */ +void usb_set_tx_fifo(otg_global_type *usbx, uint8_t txfifo, uint16_t size) +{ + uint8_t i_index = 0; + uint32_t offset = 0; + + offset = usbx->grxfsiz; + if(txfifo == 0) + { + usbx->gnptxfsiz_ept0tx = offset | (size << 16); + } + else + { + offset += usbx->gnptxfsiz_ept0tx_bit.nptxfdep; + for(i_index = 0; i_index < (txfifo - 1); i_index ++) + { + offset += usbx->dieptxfn_bit[i_index].ineptxfdep; + } + usbx->dieptxfn[txfifo - 1] = offset | (size << 16); + } +} + + +/** + * @brief set otg mode(device or host mode) + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param mode: + this parameter can be one of the following values: + * - OTG_DEVICE_MODE + * - OTG_HOST_MODE + * - OTG_DRD_MODE + * @retval none + */ +void usb_global_set_mode(otg_global_type *usbx, uint32_t mode) +{ + /* set otg to device mode */ + if(mode == OTG_DEVICE_MODE) + { + usbx->gusbcfg_bit.fhstmode = FALSE; + usbx->gusbcfg_bit.fdevmode = TRUE; + } + + /* set otg to host mode */ + if(mode == OTG_HOST_MODE) + { + usbx->gusbcfg_bit.fdevmode = FALSE; + usbx->gusbcfg_bit.fhstmode = TRUE; + } + + /* set otg to default mode */ + if(mode == OTG_DRD_MODE) + { + usbx->gusbcfg_bit.fdevmode = FALSE; + usbx->gusbcfg_bit.fhstmode = FALSE; + } +} + + +/** + * @brief disable the transceiver power down mode + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval none + */ +void usb_global_power_on(otg_global_type *usbx) +{ + /* core soft reset */ + usbx->grstctl_bit.csftrst = TRUE; + while(usbx->grstctl_bit.csftrst); + + /* disable power down mode */ + usbx->gccfg_bit.pwrdown = TRUE; + +} + +/** + * @brief usb stop phy clock + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval none + */ +void usb_stop_phy_clk(otg_global_type *usbx) +{ + OTG_PCGCCTL(usbx)->pcgcctl_bit.stoppclk = TRUE; +} + +/** + * @brief usb open phy clock + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval none + */ +void usb_open_phy_clk(otg_global_type *usbx) +{ + OTG_PCGCCTL(usbx)->pcgcctl_bit.stoppclk = FALSE; +} + + +/** + * @brief write data from user memory to usb buffer + * @param pusr_buf: point to user buffer + * @param offset_addr: endpoint tx offset address + * @param nbytes: number of bytes data write to usb buffer + * @retval none + */ +void usb_write_packet(otg_global_type *usbx, uint8_t *pusr_buf, uint16_t num, uint16_t nbytes) +{ + uint32_t n_index; + uint32_t nhbytes = (nbytes + 3) / 4; + uint32_t *pbuf = (uint32_t *)pusr_buf; + for(n_index = 0; n_index < nhbytes; n_index ++) + { +#if defined (__ICCARM__) && (__VER__ < 7000000) + USB_FIFO(usbx, num) = *(__packed uint32_t *)pbuf; +#else + USB_FIFO(usbx, num) = __UNALIGNED_UINT32_READ(pbuf); +#endif + pbuf ++; + } +} + +/** + * @brief read data from usb buffer to user buffer + * @param pusr_buf: point to user buffer + * @param offset_addr: endpoint rx offset address + * @param nbytes: number of bytes data write to usb buffer + * @retval none + */ +void usb_read_packet(otg_global_type *usbx, uint8_t *pusr_buf, uint16_t num, uint16_t nbytes) +{ + UNUSED(num); + uint32_t n_index; + uint32_t nhbytes = (nbytes + 3) / 4; + uint32_t *pbuf = (uint32_t *)pusr_buf; + for(n_index = 0; n_index < nhbytes; n_index ++) + { +#if defined (__ICCARM__) && (__VER__ < 7000000) + *(__packed uint32_t *)pbuf = USB_FIFO(usbx, 0); +#else + __UNALIGNED_UINT32_WRITE(pbuf, (USB_FIFO(usbx, 0))); +#endif + pbuf ++; + } +} +#endif + + +#ifdef OTGFS_USB_DEVICE +/** + * @brief open usb endpoint + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param ept_info: endpoint information structure + * @retval none + */ +void usb_ept_open(otg_global_type *usbx, usb_ept_info *ept_info) +{ + uint8_t mps = USB_EPT0_MPS_64; + if(ept_info->eptn == USB_EPT0) + { + if(ept_info->maxpacket == 0x40) + { + mps = USB_EPT0_MPS_64; + } + else if(ept_info->maxpacket == 0x20) + { + mps = USB_EPT0_MPS_32; + } + else if(ept_info->maxpacket == 0x10) + { + mps = USB_EPT0_MPS_16; + } + else if(ept_info->maxpacket == 0x08) + { + mps = USB_EPT0_MPS_8; + } + } + /* endpoint direction is in */ + if(ept_info->inout == EPT_DIR_IN) + { + OTG_DEVICE(usbx)->daintmsk |= 1 << ept_info->eptn; + if(ept_info->eptn == USB_EPT0) + { + USB_INEPT(usbx, ept_info->eptn)->diepctl_bit.mps = mps; + } + else + { + USB_INEPT(usbx, ept_info->eptn)->diepctl_bit.mps = ept_info->maxpacket; + } + USB_INEPT(usbx, ept_info->eptn)->diepctl_bit.eptype = ept_info->trans_type; + USB_INEPT(usbx, ept_info->eptn)->diepctl_bit.txfnum = ept_info->eptn; + USB_INEPT(usbx, ept_info->eptn)->diepctl_bit.setd0pid = TRUE; + USB_INEPT(usbx, ept_info->eptn)->diepctl_bit.usbacept = TRUE; + } + /* endpoint direction is out */ + else + { + OTG_DEVICE(usbx)->daintmsk |= (1 << ept_info->eptn) << 16; + if(ept_info->eptn == USB_EPT0) + { + USB_OUTEPT(usbx, ept_info->eptn)->doepctl_bit.mps = mps; + } + else + { + USB_OUTEPT(usbx, ept_info->eptn)->doepctl_bit.mps = ept_info->maxpacket; + } + USB_OUTEPT(usbx, ept_info->eptn)->doepctl_bit.eptype = ept_info->trans_type; + USB_OUTEPT(usbx, ept_info->eptn)->doepctl_bit.setd0pid = TRUE; + USB_OUTEPT(usbx, ept_info->eptn)->doepctl_bit.usbacept = TRUE; + } +} + +/** + * @brief close usb endpoint + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param ept_info: endpoint information structure + * @retval none + */ +void usb_ept_close(otg_global_type *usbx, usb_ept_info *ept_info) +{ + if(ept_info->inout == EPT_DIR_IN) + { + OTG_DEVICE(usbx)->daintmsk &= ~(1 << ept_info->eptn); + USB_INEPT(usbx, ept_info->eptn)->diepctl_bit.usbacept = FALSE; + } + else + { + OTG_DEVICE(usbx)->daintmsk &= ~((1 << ept_info->eptn) << 16); + USB_OUTEPT(usbx, ept_info->eptn)->doepctl_bit.usbacept = FALSE; + } +} + + +/** + * @brief set endpoint tx or rx status to stall + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param ept_info: endpoint information structure + * @retval none + */ +void usb_ept_stall(otg_global_type *usbx, usb_ept_info *ept_info) +{ + if(ept_info->inout == EPT_DIR_IN) + { + if(USB_INEPT(usbx, ept_info->eptn)->diepctl_bit.eptena == RESET) + { + USB_INEPT(usbx, ept_info->eptn)->diepctl_bit.eptdis = FALSE; + } + USB_INEPT(usbx, ept_info->eptn)->diepctl_bit.stall = SET; + } + else + { + if(USB_OUTEPT(usbx, ept_info->eptn)->doepctl_bit.eptena == RESET) + { + USB_OUTEPT(usbx, ept_info->eptn)->doepctl_bit.eptdis = FALSE; + } + USB_OUTEPT(usbx, ept_info->eptn)->doepctl_bit.stall = TRUE; + } +} + +/** + * @brief clear endpoint tx or rx status to stall + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param ept_info: endpoint information structure + * @retval none + */ +void usb_ept_clear_stall(otg_global_type *usbx, usb_ept_info *ept_info) +{ + if(ept_info->inout == EPT_DIR_IN) + { + USB_INEPT(usbx, ept_info->eptn)->diepctl_bit.stall = FALSE; + if(ept_info->trans_type == EPT_INT_TYPE || ept_info->trans_type == EPT_BULK_TYPE) + { + USB_INEPT(usbx, ept_info->eptn)->diepctl_bit.setd0pid = TRUE; + } + } + else + { + USB_OUTEPT(usbx, ept_info->eptn)->doepctl_bit.stall = FALSE; + if(ept_info->trans_type == EPT_INT_TYPE || ept_info->trans_type == EPT_BULK_TYPE) + { + USB_OUTEPT(usbx, ept_info->eptn)->doepctl_bit.setd0pid = TRUE; + } + } +} + +/** + * @brief get all out endpoint interrupt bits + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval out endpoint interrupt bits + */ +uint32_t usb_get_all_out_interrupt(otg_global_type *usbx) +{ + uint32_t intsts = OTG_DEVICE(usbx)->daint; + return ((intsts & (OTG_DEVICE(usbx)->daintmsk)) >> 16); +} + +/** + * @brief get all in endpoint interrupt bits + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval in endpoint interrupt bits + */ +uint32_t usb_get_all_in_interrupt(otg_global_type *usbx) +{ + uint32_t intsts = OTG_DEVICE(usbx)->daint; + return ((intsts & (OTG_DEVICE(usbx)->daintmsk)) & 0xFFFF); +} + + +/** + * @brief get out endpoint interrupt flag + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param eptn: endpoint number + * @retval out endpoint interrupt flags + */ +uint32_t usb_ept_out_interrupt(otg_global_type *usbx, uint32_t eptn) +{ + uint32_t intsts = USB_OUTEPT(usbx, eptn)->doepint; + return (intsts & (OTG_DEVICE(usbx)->doepmsk)); +} + +/** + * @brief get in endpoint interrupt flag + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param eptn: endpoint number + * @retval in endpoint intterupt flags + */ +uint32_t usb_ept_in_interrupt(otg_global_type *usbx, uint32_t eptn) +{ + uint32_t intsts, mask1, mask2; + mask1 = OTG_DEVICE(usbx)->diepmsk; + mask2 = OTG_DEVICE(usbx)->diepempmsk; + mask1 |= ((mask2 >> eptn) & 0x1) << 7; + intsts = USB_INEPT(usbx, eptn)->diepint & mask1; + return intsts; +} + +/** + * @brief clear out endpoint interrupt flag + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param eptn: endpoint number + * @retval flag: interrupt flag + * this parameter can be any combination of the following values: + * - USB_OTG_DOEPINT_XFERC_FLAG + * - USB_OTG_DOEPINT_EPTDISD_FLAG + * - USB_OTG_DOEPINT_SETUP_FLAG + * - USB_OTG_DOEPINT_OTEPDIS_FLAG + * - USB_OTG_DOEPINT_B2BSTUP_FLAG + */ +void usb_ept_out_clear(otg_global_type *usbx, uint32_t eptn, uint32_t flag) +{ + USB_OUTEPT(usbx, eptn)->doepint = flag; +} + +/** + * @brief clear in endpoint interrupt flag + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param eptn: endpoint number + * @retval flag: interrupt flag + * this parameter can be any combination of the following values: + * - USB_OTG_DIEPINT_XFERC_FLAG + * - USB_OTG_DIEPINT_EPTDISD_FLAG + * - USB_OTG_DIEPINT_TMROC_FLAG + * - USB_OTG_DIEPINT_INTTXFE_FLAG + * - USB_OTG_DIEPINT_INEPNE_FLAG + * - USB_OTG_DIEPINT_TXFE_FLAG + */ +void usb_ept_in_clear(otg_global_type *usbx, uint32_t eptn, uint32_t flag) +{ + USB_INEPT(usbx, eptn)->diepint = flag; +} + + +/** + * @brief set the host assignment address + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param address: host assignment address + * @retval none + */ +void usb_set_address(otg_global_type *usbx, uint8_t address) +{ + OTG_DEVICE(usbx)->dcfg_bit.devaddr = address; +} + +/** + * @brief enable endpoint 0 out + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval none + */ +void usb_ept0_start(otg_global_type *usbx) +{ + otg_eptout_type *usb_outept = USB_OUTEPT(usbx, 0); + usb_outept->doeptsiz = 0; + usb_outept->doeptsiz_bit.pktcnt = 1; + usb_outept->doeptsiz_bit.xfersize = 24; + usb_outept->doeptsiz_bit.rxdpid_setupcnt = 3; +} + + +/** + * @brief endpoint 0 start setup + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval none + */ +void usb_ept0_setup(otg_global_type *usbx) +{ + USB_INEPT(usbx, 0)->diepctl_bit.mps = 0; + OTG_DEVICE(usbx)->dctl_bit.cgnpinak = FALSE; +} + +/** + * @brief connect usb device by enable pull-up + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval none + */ +void usb_connect(otg_global_type *usbx) +{ + /* D+ 1.5k pull-up enable */ + OTG_DEVICE(usbx)->dctl_bit.sftdiscon = FALSE; +} + +/** + * @brief disconnect usb device by disable pull-up + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval none + */ +void usb_disconnect(otg_global_type *usbx) +{ + /* D+ 1.5k pull-up disable */ + OTG_DEVICE(usbx)->dctl_bit.sftdiscon = TRUE; +} + + +/** + * @brief usb remote wakeup set + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval none + */ +void usb_remote_wkup_set(otg_global_type *usbx) +{ + OTG_DEVICE(usbx)->dctl_bit.rwkupsig = TRUE; +} + +/** + * @brief usb remote wakeup clear + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval none + */ +void usb_remote_wkup_clear(otg_global_type *usbx) +{ + OTG_DEVICE(usbx)->dctl_bit.rwkupsig = FALSE; +} + +/** + * @brief usb suspend status get + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval usb suspend status + */ +uint8_t usb_suspend_status_get(otg_global_type *usbx) +{ + return OTG_DEVICE(usbx)->dsts_bit.suspsts; +} +#endif + +#ifdef OTGFS_USB_HOST +/** + * @brief usb port power on + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param state: state (TRUE or FALSE) + * @retval none + */ +void usb_port_power_on(otg_global_type *usbx, confirm_state state) +{ + otg_host_type *usb_host = OTG_HOST(usbx); + uint32_t hprt_val = usb_host->hprt; + + hprt_val &= ~(USB_OTG_HPRT_PRTENA | USB_OTG_HPRT_PRTENCHNG | + USB_OTG_HPRT_PRTOVRCACT | USB_OTG_HPRT_PRTCONDET); + + if(state == TRUE) + { + usb_host->hprt = hprt_val | USB_OTG_HPRT_PRTPWR; + } + else + { + usb_host->hprt = hprt_val & (~USB_OTG_HPRT_PRTPWR); + } +} + +/** + * @brief get current frame number + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval none + */ +uint32_t usbh_get_frame(otg_global_type *usbx) +{ + otg_host_type *usb_host = OTG_HOST(usbx); + return usb_host->hfnum & 0xFFFF; +} + +/** + * @brief enable one host channel + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param chn: host channel number + * @param ept_num: devvice endpoint number + * @param dev_address: device address + * @param type: channel transfer type + * this parameter can be one of the following values: + * - EPT_CONTROL_TYPE + * - EPT_BULK_TYPE + * - EPT_INT_TYPE + * - EPT_ISO_TYPE + * @param maxpacket: support max packe size for this channel + * @param speed: device speed + * this parameter can be one of the following values: + * - USB_PRTSPD_FULL_SPEED + * - USB_PRTSPD_LOW_SPEED + * @retval none + */ +void usb_hc_enable(otg_global_type *usbx, + uint8_t chn, + uint8_t ept_num, + uint8_t dev_address, + uint8_t type, + uint16_t maxpacket, + uint8_t speed) +{ + otg_hchannel_type *hch = USB_CHL(usbx, chn); + otg_host_type *usb_host = OTG_HOST(usbx); + + switch(type) + { + case EPT_CONTROL_TYPE: + case EPT_BULK_TYPE: + hch->hcintmsk |= USB_OTG_HC_XFERCM_INT | USB_OTG_HC_STALLM_INT | + USB_OTG_HC_XACTERRM_INT | USB_OTG_HC_NAKM_INT | + USB_OTG_HC_DTGLERRM_INT; + if(ept_num & 0x80) + { + hch->hcintmsk_bit.bblerrmsk = TRUE; + } + break; + case EPT_INT_TYPE: + hch->hcintmsk |= USB_OTG_HC_XFERCM_INT | USB_OTG_HC_STALLM_INT | + USB_OTG_HC_XACTERRM_INT | USB_OTG_HC_NAKM_INT | + USB_OTG_HC_DTGLERRM_INT | USB_OTG_HC_FRMOVRRUN_INT; + break; + case EPT_ISO_TYPE: + + hch->hcintmsk |= USB_OTG_HC_XFERCM_INT | USB_OTG_HC_ACKM_INT | + USB_OTG_HC_FRMOVRRUN_INT; + break; + } + usb_host->haintmsk |= 1 << chn; + usbx->gintmsk_bit.hchintmsk = TRUE; + + hch->hcchar_bit.devaddr = dev_address; + hch->hcchar_bit.eptnum = ept_num & 0x7F; + hch->hcchar_bit.eptdir = (ept_num & 0x80)?1:0; + hch->hcchar_bit.lspddev = (speed == USB_PRTSPD_LOW_SPEED)?1:0; + hch->hcchar_bit.eptype = type; + hch->hcchar_bit.mps = maxpacket; + + if(type == EPT_INT_TYPE) + { + hch->hcchar_bit.oddfrm = TRUE; + } +} + +/** + * @brief host read channel interrupt + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval interrupt flag + */ +uint32_t usb_hch_read_interrupt(otg_global_type *usbx) +{ + otg_host_type *usb_host = OTG_HOST(usbx); + return usb_host->haint & 0xFFFF; +} + +/** + * @brief disable host + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @retval none + */ +void usb_host_disable(otg_global_type *usbx) +{ + uint32_t i_index = 0, count = 0; + otg_hchannel_type *hch; + otg_host_type *usb_host = OTG_HOST(usbx); + + usbx->gahbcfg_bit.glbintmsk = FALSE; + usb_flush_rx_fifo(usbx); + usb_flush_tx_fifo(usbx, 0x10); + + for(i_index = 0; i_index < 16; i_index ++) + { + hch = USB_CHL(usbx, i_index); + hch->hcchar_bit.chdis = TRUE; + hch->hcchar_bit.chena = FALSE; + hch->hcchar_bit.eptdir = 0; + } + + for(i_index = 0; i_index < 16; i_index ++) + { + hch = USB_CHL(usbx, i_index); + hch->hcchar_bit.chdis = TRUE; + hch->hcchar_bit.chena = TRUE; + hch->hcchar_bit.eptdir = 0; + do + { + if(count ++ > 1000) + break; + }while(hch->hcchar_bit.chena); + } + usb_host->haint = 0xFFFFFFFF; + usbx->gintsts = 0xFFFFFFFF; + usbx->gahbcfg_bit.glbintmsk = TRUE; +} + +/** + * @brief halt channel + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param chn: channel number + * @retval none + */ +void usb_hch_halt(otg_global_type *usbx, uint8_t chn) +{ + uint32_t count = 0; + otg_hchannel_type *usb_chh = USB_CHL(usbx, chn); + otg_host_type *usb_host = OTG_HOST(usbx); + + /* endpoint type is control or bulk */ + if(usb_chh->hcchar_bit.eptype == EPT_CONTROL_TYPE || + usb_chh->hcchar_bit.eptype == EPT_BULK_TYPE) + { + usb_chh->hcchar_bit.chdis = TRUE; + if((usbx->gnptxsts_bit.nptxqspcavail) == 0) + { + usb_chh->hcchar_bit.chena = FALSE; + usb_chh->hcchar_bit.chena = TRUE; + do + { + if(count ++ > 1000) + break; + }while(usb_chh->hcchar_bit.chena == SET); + } + else + { + usb_chh->hcchar_bit.chena = TRUE; + } + } + else + { + usb_chh->hcchar_bit.chdis = TRUE; + if((usb_host->hptxsts_bit.ptxqspcavil) == 0) + { + usb_chh->hcchar_bit.chena = FALSE; + usb_chh->hcchar_bit.chena = TRUE; + do + { + if(count ++ > 1000) + break; + }while(usb_chh->hcchar_bit.chena == SET); + } + else + { + usb_chh->hcchar_bit.chena = TRUE; + } + } +} +/** + * @brief select full or low speed clock + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param clk: clock frequency + * @retval none + */ +void usbh_fsls_clksel(otg_global_type *usbx, uint8_t clk) +{ + otg_host_type *usb_host = OTG_HOST(usbx); + + usb_host->hcfg_bit.fslspclksel = clk; + if(clk == USB_HCFG_CLK_6M) + { + usb_host->hfir = 6000; + } + else + { + usb_host->hfir = 48000; + } +} +#endif + + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_wdt.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_wdt.c new file mode 100644 index 0000000000..e159ed604c --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_wdt.c @@ -0,0 +1,156 @@ +/** + ************************************************************************** + * @file at32f435_437_wdt.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the wdt firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup WDT + * @brief WDT driver modules + * @{ + */ + +#ifdef WDT_MODULE_ENABLED + +/** @defgroup WDT_private_functions + * @{ + */ + +/** + * @brief wdt enable ,the reload value will be sent to the counter + * @param none + * @retval none + */ +void wdt_enable(void) +{ + WDT->cmd = WDT_CMD_ENABLE; +} + +/** + * @brief reload wdt counter + * @param none + * @retval none + */ +void wdt_counter_reload(void) +{ + WDT->cmd = WDT_CMD_RELOAD; +} + +/** + * @brief set wdt counter reload value + * @param reload_value (0x0000~0x0FFF) + * @retval none + */ +void wdt_reload_value_set(uint16_t reload_value) +{ + WDT->rld = reload_value; +} + +/** + * @brief set wdt division divider + * @param division + * this parameter can be one of the following values: + * - WDT_CLK_DIV_4 + * - WDT_CLK_DIV_8 + * - WDT_CLK_DIV_16 + * - WDT_CLK_DIV_32 + * - WDT_CLK_DIV_64 + * - WDT_CLK_DIV_128 + * - WDT_CLK_DIV_256 + * @retval none + */ +void wdt_divider_set(wdt_division_type division) +{ + WDT->div_bit.div = division; +} + +/** + * @brief enable or disable wdt cmd register write + * @param new_state (TRUE or FALSE) + * @retval none + */ +void wdt_register_write_enable( confirm_state new_state) +{ + if(new_state == FALSE) + { + WDT->cmd = WDT_CMD_LOCK; + } + else + { + WDT->cmd = WDT_CMD_UNLOCK; + } +} + +/** + * @brief get wdt flag + * @param wdt_flag + * this parameter can be one of the following values: + * - WDT_DIVF_UPDATE_FLAG: division value update complete flag. + * - WDT_RLDF_UPDATE_FLAG: reload value update complete flag. + * - WDT_WINF_UPDATE_FLAG: window value update complete flag. + * @retval state of wdt flag + */ +flag_status wdt_flag_get(uint16_t wdt_flag) +{ + flag_status status = RESET; + + if ((WDT->sts & wdt_flag) != (uint16_t)RESET) + { + status = SET; + } + else + { + status = RESET; + } + + return status; +} + +/** + * @brief wdt window counter value set + * @param window_cnt (0x0000~0x0FFF) + * @retval none + */ +void wdt_window_counter_set(uint16_t window_cnt) +{ + WDT->win_bit.win = window_cnt; +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_wwdt.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_wwdt.c new file mode 100644 index 0000000000..4f03e650ce --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_wwdt.c @@ -0,0 +1,141 @@ +/** + ************************************************************************** + * @file at32f435_437_wwdt.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the wwdt firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup WWDT + * @brief WWDT driver modules + * @{ + */ + +#ifdef WWDT_MODULE_ENABLED + +/** @defgroup WWDT_private_functions + * @{ + */ + +/** + * @brief wwdt reset by crm reset register + * @retval none + */ +void wwdt_reset(void) +{ + crm_periph_reset(CRM_WWDT_PERIPH_RESET, TRUE); + crm_periph_reset(CRM_WWDT_PERIPH_RESET, FALSE); +} + +/** + * @brief wwdt division set + * @param division + * this parameter can be one of the following values: + * - WWDT_PCLK1_DIV_4096 (wwdt counter clock = (pclk1/4096)/1) + * - WWDT_PCLK1_DIV_8192 (wwdt counter clock = (pclk1/4096)/2) + * - WWDT_PCLK1_DIV_16384 (wwdt counter clock = (pclk1/4096)/4) + * - WWDT_PCLK1_DIV_32768 (wwdt counter clock = (pclk1/4096)/8) + * @retval none + */ +void wwdt_divider_set(wwdt_division_type division) +{ + WWDT->cfg_bit.div = division; +} + +/** + * @brief wwdt reload counter interrupt flag clear + * @param none + * @retval none + */ +void wwdt_flag_clear(void) +{ + WWDT->sts = 0; +} + +/** + * @brief wwdt enable and the counter value load + * @param wwdt_cnt (0x40~0x7f) + * @retval none + */ +void wwdt_enable(uint8_t wwdt_cnt) +{ + WWDT->ctrl = wwdt_cnt | WWDT_EN_BIT; +} + +/** + * @brief wwdt reload counter interrupt enable + * @param none + * @retval none + */ +void wwdt_interrupt_enable(void) +{ + WWDT->cfg_bit.rldien = TRUE; +} + +/** + * @brief wwdt reload counter interrupt flag get + * @param none + * @retval state of reload counter interrupt flag + */ +flag_status wwdt_flag_get(void) +{ + return (flag_status)WWDT->sts_bit.rldf; +} + +/** + * @brief wwdt counter value set + * @param wwdt_cnt (0x40~0x7f) + * @retval none + */ +void wwdt_counter_set(uint8_t wwdt_cnt) +{ + WWDT->ctrl_bit.cnt = wwdt_cnt; +} + +/** + * @brief wwdt window counter value set + * @param window_cnt (0x40~0x7f) + * @retval none + */ +void wwdt_window_counter_set(uint8_t window_cnt) +{ + WWDT->cfg_bit.win = window_cnt; +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_xmc.c b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_xmc.c new file mode 100644 index 0000000000..7cb2768320 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/AT32F43x_StdPeriph_Driver/src/at32f435_437_xmc.c @@ -0,0 +1,909 @@ +/** + ************************************************************************** + * @file at32f435_437_xmc.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for the xmc firmware library + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "at32f435_437_conf.h" + +/** @addtogroup AT32F435_437_periph_driver + * @{ + */ + +/** @defgroup XMC + * @brief XMC driver modules + * @{ + */ + +#ifdef XMC_MODULE_ENABLED + +/** @defgroup XMC_private_functions + * @{ + */ + +/** + * @brief xmc nor or sram registers reset + * @param xmc_subbank + * this parameter can be one of the following values: + * - XMC_BANK1_NOR_SRAM1 + * - XMC_BANK1_NOR_SRAM2 + * - XMC_BANK1_NOR_SRAM3 + * - XMC_BANK1_NOR_SRAM4 + * @retval none + */ +void xmc_nor_sram_reset(xmc_nor_sram_subbank_type xmc_subbank) +{ + /* XMC_BANK1_NORSRAM1 */ + if(xmc_subbank == XMC_BANK1_NOR_SRAM1) + { + XMC_BANK1->ctrl_tmg_group[xmc_subbank].bk1ctrl = 0x000030DB; + } + /* XMC_BANK1_NORSRAM2, XMC_BANK1_NORSRAM3 or XMC_BANK1_NORSRAM4 */ + else + { + XMC_BANK1->ctrl_tmg_group[xmc_subbank].bk1ctrl = 0x000030D2; + } + XMC_BANK1->ctrl_tmg_group[xmc_subbank].bk1tmg = 0x0FFFFFFF; + XMC_BANK1->tmgwr_group[xmc_subbank].bk1tmgwr = 0x0FFFFFFF; +} + +/** + * @brief initialize the xmc nor/sram banks according to the specified + * parameters in the xmc_norsraminitstruct. + * @param xmc_norsram_init_struct : pointer to a xmc_norsram_init_type + * structure that contains the configuration information for + * the xmc nor/sram specified banks. + * @retval none + */ +void xmc_nor_sram_init(xmc_norsram_init_type* xmc_norsram_init_struct) +{ + /* bank1 nor/sram control register configuration */ + XMC_BANK1->ctrl_tmg_group[xmc_norsram_init_struct->subbank].bk1ctrl = + (uint32_t)xmc_norsram_init_struct->data_addr_multiplex | + xmc_norsram_init_struct->device | + xmc_norsram_init_struct->bus_type | + xmc_norsram_init_struct->burst_mode_enable | + xmc_norsram_init_struct->asynwait_enable | + xmc_norsram_init_struct->wait_signal_lv | + xmc_norsram_init_struct->wrapped_mode_enable | + xmc_norsram_init_struct->wait_signal_config | + xmc_norsram_init_struct->write_enable | + xmc_norsram_init_struct->wait_signal_enable | + xmc_norsram_init_struct->write_timing_enable | + xmc_norsram_init_struct->write_burst_syn; + + /* if nor flash device */ + if(xmc_norsram_init_struct->device == XMC_DEVICE_NOR) + { + XMC_BANK1->ctrl_tmg_group[xmc_norsram_init_struct->subbank].bk1ctrl_bit.noren = 0x1; + } +} + +/** + * @brief initialize the xmc nor/sram banks according to the specified + * parameters in the xmc_rw_timing_struct and xmc_w_timing_struct. + * @param xmc_rw_timing_struct : pointer to a xmc_norsram_timing_init_type + * structure that contains the configuration information for + * the xmc nor/sram specified banks. + * @param xmc_w_timing_struct : pointer to a xmc_norsram_timing_init_type + * structure that contains the configuration information for + * the xmc nor/sram specified banks. + * @retval none + */ +void xmc_nor_sram_timing_config(xmc_norsram_timing_init_type* xmc_rw_timing_struct, + xmc_norsram_timing_init_type* xmc_w_timing_struct) +{ + /* bank1 nor/sram timing register configuration */ + XMC_BANK1->ctrl_tmg_group[xmc_rw_timing_struct->subbank].bk1tmg = + (uint32_t)xmc_rw_timing_struct->addr_setup_time | + (xmc_rw_timing_struct->addr_hold_time << 4) | + (xmc_rw_timing_struct->data_setup_time << 8) | + (xmc_rw_timing_struct->bus_latency_time <<16) | + (xmc_rw_timing_struct->clk_psc << 20) | + (xmc_rw_timing_struct->data_latency_time << 24) | + xmc_rw_timing_struct->mode; + + /* bank1 nor/sram timing register for write configuration, if extended mode is used */ + if(xmc_rw_timing_struct->write_timing_enable == XMC_WRITE_TIMING_ENABLE) + { + XMC_BANK1->tmgwr_group[xmc_w_timing_struct->subbank].bk1tmgwr = + (uint32_t)xmc_w_timing_struct->addr_setup_time | + (xmc_w_timing_struct->addr_hold_time << 4) | + (xmc_w_timing_struct->data_setup_time << 8) | + (xmc_w_timing_struct->bus_latency_time << 16) | + (xmc_w_timing_struct->clk_psc << 20) | + (xmc_w_timing_struct->data_latency_time << 24) | + xmc_w_timing_struct->mode; + } + else + { + XMC_BANK1->tmgwr_group[xmc_w_timing_struct->subbank].bk1tmgwr = 0x0FFFFFFF; + } +} + +/** + * @brief fill each xmc_nor_sram_init_struct member with its default value. + * @param xmc_nor_sram_init_struct: pointer to a xmc_norsram_init_type + * structure which will be initialized. + * @retval none + */ +void xmc_norsram_default_para_init(xmc_norsram_init_type* xmc_nor_sram_init_struct) +{ + /* reset nor/sram init structure parameters values */ + xmc_nor_sram_init_struct->subbank = XMC_BANK1_NOR_SRAM1; + xmc_nor_sram_init_struct->data_addr_multiplex = XMC_DATA_ADDR_MUX_ENABLE; + xmc_nor_sram_init_struct->device = XMC_DEVICE_SRAM; + xmc_nor_sram_init_struct->bus_type = XMC_BUSTYPE_8_BITS; + xmc_nor_sram_init_struct->burst_mode_enable = XMC_BURST_MODE_DISABLE; + xmc_nor_sram_init_struct->asynwait_enable = XMC_ASYN_WAIT_DISABLE; + xmc_nor_sram_init_struct->wait_signal_lv = XMC_WAIT_SIGNAL_LEVEL_LOW; + xmc_nor_sram_init_struct->wrapped_mode_enable = XMC_WRAPPED_MODE_DISABLE; + xmc_nor_sram_init_struct->wait_signal_config = XMC_WAIT_SIGNAL_SYN_BEFORE; + xmc_nor_sram_init_struct->write_enable = XMC_WRITE_OPERATION_ENABLE; + xmc_nor_sram_init_struct->wait_signal_enable = XMC_WAIT_SIGNAL_ENABLE; + xmc_nor_sram_init_struct->write_timing_enable = XMC_WRITE_TIMING_DISABLE; + xmc_nor_sram_init_struct->write_burst_syn = XMC_WRITE_BURST_SYN_DISABLE; +} + +/** + * @brief fill each xmc_rw_timing_struct and xmc_w_timing_struct member with its default value. + * @param xmc_rw_timing_struct: pointer to a xmc_norsram_timing_init_type + * structure which will be initialized. + * @param xmc_w_timing_struct: pointer to a xmc_norsram_timing_init_type + * structure which will be initialized. + * @retval none + */ +void xmc_norsram_timing_default_para_init(xmc_norsram_timing_init_type* xmc_rw_timing_struct, + xmc_norsram_timing_init_type* xmc_w_timing_struct) +{ + xmc_rw_timing_struct->subbank = XMC_BANK1_NOR_SRAM1; + xmc_rw_timing_struct->write_timing_enable = XMC_WRITE_TIMING_DISABLE; + xmc_rw_timing_struct->addr_setup_time = 0xF; + xmc_rw_timing_struct->addr_hold_time = 0xF; + xmc_rw_timing_struct->data_setup_time = 0xFF; + xmc_rw_timing_struct->bus_latency_time = 0xF; + xmc_rw_timing_struct->clk_psc = 0xF; + xmc_rw_timing_struct->data_latency_time = 0xF; + xmc_rw_timing_struct->mode = XMC_ACCESS_MODE_A; + xmc_w_timing_struct->subbank = XMC_BANK1_NOR_SRAM1; + xmc_w_timing_struct->write_timing_enable = XMC_WRITE_TIMING_DISABLE; + xmc_w_timing_struct->addr_setup_time = 0xF; + xmc_w_timing_struct->addr_hold_time = 0xF; + xmc_w_timing_struct->data_setup_time = 0xFF; + xmc_w_timing_struct->bus_latency_time = 0xF; + xmc_w_timing_struct->clk_psc = 0xF; + xmc_w_timing_struct->data_latency_time = 0xF; + xmc_w_timing_struct->mode = XMC_ACCESS_MODE_A; +} + +/** + * @brief enable or disable the specified nor/sram memory bank. + * @param xmc_subbank + * this parameter can be one of the following values: + * - XMC_BANK1_NOR_SRAM1 + * - XMC_BANK1_NOR_SRAM2 + * - XMC_BANK1_NOR_SRAM3 + * - XMC_BANK1_NOR_SRAM4 + * @param new_state (TRUE or FALSE) + * @retval none + */ +void xmc_nor_sram_enable(xmc_nor_sram_subbank_type xmc_subbank, confirm_state new_state) +{ + XMC_BANK1->ctrl_tmg_group[xmc_subbank].bk1ctrl_bit.en = new_state; +} + +/** + * @brief config the bus turnaround phase. + * @param xmc_sub_bank + * this parameter can be one of the following values: + * - XMC_BANK1_NOR_SRAM1 + * - XMC_BANK1_NOR_SRAM2 + * - XMC_BANK1_NOR_SRAM3 + * - XMC_BANK1_NOR_SRAM4 + * @param w2w_timing :write timing + * @param r2r_timing :read timing + * @retval none + */ +void xmc_ext_timing_config(xmc_nor_sram_subbank_type xmc_sub_bank, uint16_t w2w_timing, uint16_t r2r_timing) +{ + XMC_BANK1->ext_bit[xmc_sub_bank].buslatr2r = r2r_timing<<8; + XMC_BANK1->ext_bit[xmc_sub_bank].buslatw2w = w2w_timing; +} + +/** + * @brief xmc nand flash registers reset + * @param xmc_bank + * this parameter can be one of the following values: + * - XMC_BANK2_NAND + * - XMC_BANK3_NAND + * @retval none + */ +void xmc_nand_reset(xmc_class_bank_type xmc_bank) +{ + /* set the xmc_bank2_nand registers to their reset values */ + if(xmc_bank == XMC_BANK2_NAND) + { + XMC_BANK2->bk2ctrl = 0x00000018; + XMC_BANK2->bk2is = 0x00000040; + XMC_BANK2->bk2tmgatt = 0xFCFCFCFC; + XMC_BANK2->bk2tmgmem = 0xFCFCFCFC; + } + /* set the xmc_bank3_nand registers to their reset values */ + else + { + XMC_BANK3->bk3ctrl = 0x00000018; + XMC_BANK3->bk3is = 0x00000040; + XMC_BANK3->bk3tmgatt = 0xFCFCFCFC; + XMC_BANK3->bk3tmgmem = 0xFCFCFCFC; + } +} + +/** + * @brief initialize the xmc nand banks according to the specified + * parameters in the xmc_nandinitstruct. + * @param xmc_nand_init_struct : pointer to a xmc_nand_init_type + * structure that contains the configuration information for the xmc + * nand specified banks. + * @retval none + */ +void xmc_nand_init(xmc_nand_init_type* xmc_nand_init_struct) +{ + uint32_t tempctrl = 0x0; + + /* Set the tempctrl value according to xmc_nand_init_struct parameters */ + tempctrl = (uint32_t)xmc_nand_init_struct->wait_enable | + xmc_nand_init_struct->bus_type | + xmc_nand_init_struct->ecc_enable | + xmc_nand_init_struct->ecc_pagesize | + (xmc_nand_init_struct->delay_time_cycle << 9) | + (xmc_nand_init_struct->delay_time_ar << 13) | + 0x00000008; + + /* xmc_bank2_nand registers configuration */ + if(xmc_nand_init_struct->nand_bank == XMC_BANK2_NAND) + { + XMC_BANK2->bk2ctrl = tempctrl; + } + /* xmc_bank3_nand registers configuration */ + else + { + XMC_BANK3->bk3ctrl = tempctrl; + } +} + +/** + * @brief initialize the xmc nand banks according to the specified + * parameters in the xmc_nandinitstruct. + * @param xmc_regular_spacetiming_struct : pointer to a xmc_nand_pccard_timinginit_type + * structure that contains the configuration information for the xmc + * nand specified banks. + * @param xmc_special_spacetiming_struct : pointer to a xmc_nand_pccard_timinginit_type + * structure that contains the configuration information for the xmc + * nand specified banks. + * @retval none + */ +void xmc_nand_timing_config(xmc_nand_pccard_timinginit_type* xmc_regular_spacetiming_struct, + xmc_nand_pccard_timinginit_type* xmc_special_spacetiming_struct) +{ + uint32_t tempmem = 0x0, tempatt = 0x0; + + /* set the tempmem value according to xmc_nand_init_struct parameters */ + tempmem = (uint32_t)xmc_regular_spacetiming_struct->mem_setup_time | + (xmc_regular_spacetiming_struct->mem_waite_time << 8) | + (xmc_regular_spacetiming_struct->mem_hold_time << 16) | + (xmc_regular_spacetiming_struct->mem_hiz_time << 24); + + /* set the tempatt value according to xmc_nand_init_struct parameters */ + tempatt = (uint32_t)xmc_special_spacetiming_struct->mem_setup_time | + (xmc_special_spacetiming_struct->mem_waite_time << 8) | + (xmc_special_spacetiming_struct->mem_hold_time << 16) | + (xmc_special_spacetiming_struct->mem_hiz_time << 24); + /* xmc_bank2_nand registers configuration */ + if(xmc_regular_spacetiming_struct->class_bank == XMC_BANK2_NAND) + { + XMC_BANK2->bk2tmgatt = tempatt; + XMC_BANK2->bk2tmgmem = tempmem; + } + else + { + XMC_BANK3->bk3tmgatt = tempatt; + XMC_BANK3->bk3tmgmem = tempmem; + } +} + +/** + * @brief fill each xmc_nand_init_struct member with its default value. + * @param xmc_nand_init_struct: pointer to a xmc_nand_init_type + * structure which will be initialized. + * @retval none + */ +void xmc_nand_default_para_init(xmc_nand_init_type* xmc_nand_init_struct) +{ + /* reset nand init structure parameters values */ + xmc_nand_init_struct->nand_bank = XMC_BANK2_NAND; + xmc_nand_init_struct->wait_enable = XMC_WAIT_OPERATION_DISABLE; + xmc_nand_init_struct->bus_type = XMC_BUSTYPE_8_BITS; + xmc_nand_init_struct->ecc_enable = XMC_ECC_OPERATION_DISABLE; + xmc_nand_init_struct->ecc_pagesize = XMC_ECC_PAGESIZE_256_BYTES; + xmc_nand_init_struct->delay_time_cycle = 0x0; + xmc_nand_init_struct->delay_time_ar = 0x0; +} + +/** + * @brief fill each xmc_common_spacetiming_struct and xmc_attribute_spacetiming_struct member with its default value. + * @param xmc_common_spacetiming_struct: pointer to a xmc_nand_pccard_timinginit_type + * structure which will be initialized. + * @param xmc_special_spacetiming_struct: pointer to a xmc_nand_pccard_timinginit_type + * structure which will be initialized. + * @retval none + */ +void xmc_nand_timing_default_para_init(xmc_nand_pccard_timinginit_type* xmc_regular_spacetiming_struct, + xmc_nand_pccard_timinginit_type* xmc_special_spacetiming_struct) +{ + xmc_regular_spacetiming_struct->class_bank = XMC_BANK2_NAND; + xmc_regular_spacetiming_struct->mem_hold_time = 0xFC; + xmc_regular_spacetiming_struct->mem_waite_time = 0xFC; + xmc_regular_spacetiming_struct->mem_setup_time = 0xFC; + xmc_regular_spacetiming_struct->mem_hiz_time = 0xFC; + xmc_special_spacetiming_struct->class_bank = XMC_BANK2_NAND; + xmc_special_spacetiming_struct->mem_hold_time = 0xFC; + xmc_special_spacetiming_struct->mem_waite_time = 0xFC; + xmc_special_spacetiming_struct->mem_setup_time = 0xFC; + xmc_special_spacetiming_struct->mem_hiz_time = 0xFC; +} + +/** + * @brief enable or disable the specified nand memory bank. + * @param xmc_bank: specifies the xmc bank to be used + * this parameter can be one of the following values: + * - XMC_BANK2_NAND + * - XMC_BANK3_NAND + * @param new_state (TRUE or FALSE) + * @retval none + */ +void xmc_nand_enable(xmc_class_bank_type xmc_bank, confirm_state new_state) +{ + /* enable or disable the nand bank2 by setting the en bit in the bk2ctrl register */ + if(xmc_bank == XMC_BANK2_NAND) + { + XMC_BANK2->bk2ctrl_bit.en = new_state; + } + /* enable or disable the nand bank3 by setting the en bit in the bk3ctrl register */ + else + { + XMC_BANK3->bk3ctrl_bit.en = new_state; + } +} + +/** + * @brief enable or disable the xmc nand ecc feature. + * @param xmc_bank: specifies the xmc bank to be used + * this parameter can be one of the following values: + * - XMC_BANK2_NAND + * - XMC_BANK3_NAND + * @param new_state (TRUE or FALSE) + * @retval none + */ +void xmc_nand_ecc_enable(xmc_class_bank_type xmc_bank, confirm_state new_state) +{ + /* enable the selected nand bank2 ecc function by setting the eccen bit in the bk2ctrl register */ + if(xmc_bank == XMC_BANK2_NAND) + { + XMC_BANK2->bk2ctrl_bit.eccen = new_state; + } + /* enable the selected nand bank3 ecc function by setting the eccen bit in the bk3ctrl register */ + else + { + XMC_BANK3->bk3ctrl_bit.eccen = new_state; + } +} + +/** + * @brief return the error correction code register value. + * @param xmc_bank: specifies the xmc bank to be used + * this parameter can be one of the following values: + * - XMC_BANK2_NAND + * - XMC_BANK3_NAND + * @retval the error correction code (ecc) value. + */ +uint32_t xmc_ecc_get(xmc_class_bank_type xmc_bank) +{ + uint32_t eccvaule = 0x0; + + /* get the bk2ecc register value */ + if(xmc_bank == XMC_BANK2_NAND) + { + eccvaule = XMC_BANK2->bk2ecc; + } + /* get the bk3ecc register value */ + else + { + eccvaule = XMC_BANK3->bk3ecc; + } + /* return the error correction code value */ + return eccvaule; +} + +/** + * @brief xmc sdram registers reset + * @param xmc_bank + * this parameter can be one of the following values: + * - XMC_SDRAM_BANK1 + * - XMC_SDRAM_BANK2 + * @retval none + */ +void xmc_sdram_reset(xmc_sdram_bank_type xmc_bank) +{ + XMC_SDRAM->ctrl[xmc_bank] = 0x000002D0; + XMC_SDRAM->tm[xmc_bank] = 0x0FFFFFFF; + XMC_SDRAM->cmd = 0x00000000; + XMC_SDRAM->rcnt = 0x00000000; + XMC_SDRAM->sts = 0x00000000; +} + +/** + * @brief initialize the xmc sdram banks according to the specified + * parameters in the xmc_sdram_init_struct and xmc_sdram_timing_struct. + * @param xmc_sdram_init_struct : pointer to a xmc_sdram_init_type + * structure that contains the configuration information for the xmc + * sdram specified banks. + * @param xmc_sdram_timing_struct : pointer to a xmc_sdram_timing_type + * structure that contains the configuration information for the xmc + * sdram specified banks. + * @retval none + */ +void xmc_sdram_init(xmc_sdram_init_type *xmc_sdram_init_struct, xmc_sdram_timing_type *xmc_sdram_timing_struct) +{ + if(xmc_sdram_init_struct->sdram_bank == XMC_SDRAM_BANK1) + { + XMC_SDRAM->ctrl_bit[XMC_SDRAM_BANK1].ca = xmc_sdram_init_struct->column_address; + XMC_SDRAM->ctrl_bit[XMC_SDRAM_BANK1].ra = xmc_sdram_init_struct->row_address; + XMC_SDRAM->ctrl_bit[XMC_SDRAM_BANK1].db = xmc_sdram_init_struct->width; + XMC_SDRAM->ctrl_bit[XMC_SDRAM_BANK1].inbk = xmc_sdram_init_struct->internel_banks; + XMC_SDRAM->ctrl_bit[XMC_SDRAM_BANK1].cas = xmc_sdram_init_struct->cas; + XMC_SDRAM->ctrl_bit[XMC_SDRAM_BANK1].wrp = xmc_sdram_init_struct->write_protection; + XMC_SDRAM->ctrl_bit[XMC_SDRAM_BANK1].bstr = xmc_sdram_init_struct->burst_read; + XMC_SDRAM->ctrl_bit[XMC_SDRAM_BANK1].rd = xmc_sdram_init_struct->read_delay; + XMC_SDRAM->ctrl_bit[XMC_SDRAM_BANK1].clkdiv = xmc_sdram_init_struct->clkdiv; + + XMC_SDRAM->tm_bit[XMC_SDRAM_BANK1].tmrd = xmc_sdram_timing_struct->tmrd; + XMC_SDRAM->tm_bit[XMC_SDRAM_BANK1].txsr = xmc_sdram_timing_struct->txsr; + XMC_SDRAM->tm_bit[XMC_SDRAM_BANK1].tras = xmc_sdram_timing_struct->tras; + XMC_SDRAM->tm_bit[XMC_SDRAM_BANK1].trc = xmc_sdram_timing_struct->trc; + XMC_SDRAM->tm_bit[XMC_SDRAM_BANK1].twr = xmc_sdram_timing_struct->twr; + XMC_SDRAM->tm_bit[XMC_SDRAM_BANK1].trp = xmc_sdram_timing_struct->trp; + XMC_SDRAM->tm_bit[XMC_SDRAM_BANK1].trcd = xmc_sdram_timing_struct->trcd; + } + + if(xmc_sdram_init_struct->sdram_bank == XMC_SDRAM_BANK2) + { + XMC_SDRAM->ctrl_bit[XMC_SDRAM_BANK2].ca = xmc_sdram_init_struct->column_address; + XMC_SDRAM->ctrl_bit[XMC_SDRAM_BANK2].ra = xmc_sdram_init_struct->row_address; + XMC_SDRAM->ctrl_bit[XMC_SDRAM_BANK2].db = xmc_sdram_init_struct->width; + XMC_SDRAM->ctrl_bit[XMC_SDRAM_BANK2].inbk = xmc_sdram_init_struct->internel_banks; + XMC_SDRAM->ctrl_bit[XMC_SDRAM_BANK2].cas = xmc_sdram_init_struct->cas; + XMC_SDRAM->ctrl_bit[XMC_SDRAM_BANK2].wrp = xmc_sdram_init_struct->write_protection; + /* sdctrl2 bstr is not care */ + XMC_SDRAM->ctrl_bit[XMC_SDRAM_BANK1].bstr = xmc_sdram_init_struct->burst_read; + XMC_SDRAM->ctrl_bit[XMC_SDRAM_BANK1].rd = xmc_sdram_init_struct->read_delay; + /* sdctrl2 clkdiv is not care */ + XMC_SDRAM->ctrl_bit[XMC_SDRAM_BANK1].clkdiv = xmc_sdram_init_struct->clkdiv; + + XMC_SDRAM->tm_bit[XMC_SDRAM_BANK2].tmrd = xmc_sdram_timing_struct->tmrd; + XMC_SDRAM->tm_bit[XMC_SDRAM_BANK2].txsr = xmc_sdram_timing_struct->txsr; + XMC_SDRAM->tm_bit[XMC_SDRAM_BANK2].tras = xmc_sdram_timing_struct->tras; + /* sdtm2 trc is not care */ + XMC_SDRAM->tm_bit[XMC_SDRAM_BANK1].trc = xmc_sdram_timing_struct->trc; + XMC_SDRAM->tm_bit[XMC_SDRAM_BANK2].twr = xmc_sdram_timing_struct->twr; + /* sdtm2 trp is not care */ + XMC_SDRAM->tm_bit[XMC_SDRAM_BANK1].trp = xmc_sdram_timing_struct->trp; + XMC_SDRAM->tm_bit[XMC_SDRAM_BANK2].trcd = xmc_sdram_timing_struct->trcd; + } +} + +/** + * @brief fill each xmc_sdram_init_struct member with its default value. + * @param xmc_sdram_init_struct: pointer to a xmc_sdram_init_type + * structure which will be initialized. + * @param xmc_sdram_timing_struct: pointer to a xmc_sdram_timing_type + * structure which will be initialized. + * @retval none + */ +void xmc_sdram_default_para_init(xmc_sdram_init_type *xmc_sdram_init_struct, xmc_sdram_timing_type *xmc_sdram_timing_struct) +{ + /* reset sdram init structure parameters values */ + xmc_sdram_init_struct->sdram_bank = XMC_SDRAM_BANK1; + xmc_sdram_init_struct->internel_banks = XMC_INBK_4; + xmc_sdram_init_struct->clkdiv = XMC_NO_CLK; + xmc_sdram_init_struct->write_protection = FALSE; + xmc_sdram_init_struct->burst_read = FALSE; + xmc_sdram_init_struct->column_address = XMC_COLUMN_8; + xmc_sdram_init_struct->row_address = XMC_ROW_11; + xmc_sdram_init_struct->cas = XMC_CAS_1; + xmc_sdram_init_struct->width = XMC_MEM_WIDTH_8; + xmc_sdram_init_struct->read_delay = XMC_READ_DELAY_1; + + xmc_sdram_timing_struct->tmrd = XMC_DELAY_CYCLE_16; + xmc_sdram_timing_struct->txsr = XMC_DELAY_CYCLE_16; + xmc_sdram_timing_struct->tras = XMC_DELAY_CYCLE_16; + xmc_sdram_timing_struct->trc = XMC_DELAY_CYCLE_16; + xmc_sdram_timing_struct->twr = XMC_DELAY_CYCLE_16; + xmc_sdram_timing_struct->trp = XMC_DELAY_CYCLE_16; + xmc_sdram_timing_struct->trcd = XMC_DELAY_CYCLE_16; +} + +/** + * @brief sdram command confg + * @param xmc_sdram_cmd_struct: pointer to a xmc_sdram_cmd_type + * structure which will be initialized. + * @retval none + */ +void xmc_sdram_cmd(xmc_sdram_cmd_type *xmc_sdram_cmd_struct) +{ + XMC_SDRAM->cmd = (xmc_sdram_cmd_struct->auto_refresh << 5) | + (xmc_sdram_cmd_struct->data << 9) | + xmc_sdram_cmd_struct->cmd | + xmc_sdram_cmd_struct->cmd_banks; +} + + +/** + * @brief get sdram bank status + * @param xmc_bank: specifies the xmc bank to be used + * this parameter can be one of the following values: + * - XMC_SDRAM_BANK1 + * - XMC_SDRAM_BANK1 + * @retval the bank status + */ +uint32_t xmc_sdram_status_get(xmc_sdram_bank_type xmc_bank) +{ + if(xmc_bank == XMC_SDRAM_BANK1) + { + return ((XMC_SDRAM->sts >> 1) & XMC_STATUS_MASK); + } + else + { + return ((XMC_SDRAM->sts >> 3) & XMC_STATUS_MASK); + } +} + +/** + * @brief set sdram refresh counter + * @param counter: xmc sdram refresh counter + * @retval none + */ +void xmc_sdram_refresh_counter_set(uint32_t counter) +{ + XMC_SDRAM->rcnt_bit.rc = counter; +} + +/** + * @brief set sdram auto refresh number + * @param number: xmc sdram auto refresh number + * @retval none + */ +void xmc_sdram_auto_refresh_set(uint32_t number) +{ + XMC_SDRAM->cmd_bit.art = number; +} + +/** + * @brief enable or disable the specified xmc interrupts. + * @param xmc_bank: specifies the xmc bank to be used + * this parameter can be one of the following values: + * - XMC_BANK2_NAND + * - XMC_BANK3_NAND + * - XMC_BANK4_PCCARD + * - XMC_BANK5_6_SDRAM + * @param xmc_int: specifies the xmc interrupt sources to be enabled or disabled. + * this parameter can be any combination of the following values: + * - XMC_INT_RISING_EDGE + * - XMC_INT_LEVEL + * - XMC_INT_FALLING_EDGE + * - XMC_INT_ERR + * @param new_state (TRUE or FALSE) + * @retval none + */ +void xmc_interrupt_enable(xmc_class_bank_type xmc_bank, xmc_interrupt_sources_type xmc_int, confirm_state new_state) +{ + if(new_state != FALSE) + { + /* enable the selected xmc_bank2 interrupts */ + if(xmc_bank == XMC_BANK2_NAND) + { + XMC_BANK2->bk2is |= xmc_int; + } + /* enable the selected xmc_bank3 interrupts */ + else if(xmc_bank == XMC_BANK3_NAND) + { + XMC_BANK3->bk3is |= xmc_int; + } + /* enable the selected xmc_bank4 interrupts */ + else if(xmc_bank == XMC_BANK4_PCCARD) + { + XMC_BANK4->bk4is |= xmc_int; + } + /* enable the selected xmc_sdram interrupts */ + else + { + XMC_SDRAM->rcnt |= xmc_int; + } + } + else + { + /* disable the selected xmc_bank2 interrupts */ + if(xmc_bank == XMC_BANK2_NAND) + { + XMC_BANK2->bk2is &= ~xmc_int; + } + /* disable the selected xmc_bank3 interrupts */ + else if(xmc_bank == XMC_BANK3_NAND) + { + XMC_BANK3->bk3is &= ~xmc_int; + } + /* disable the selected xmc_bank4 interrupts */ + else if(xmc_bank == XMC_BANK4_PCCARD) + { + XMC_BANK4->bk4is &= ~xmc_int; + } + /* disable the selected xmc_sdram interrupts */ + else + { + XMC_SDRAM->rcnt &= ~xmc_int; + } + } +} + +/** + * @brief check whether the specified xmc flag is set or not. + * @param xmc_bank: specifies the xmc bank to be used + * this parameter can be one of the following values: + * - XMC_BANK2_NAND + * - XMC_BANK3_NAND + * - XMC_BANK4_PCCARD + * - XMC_BANK5_6_SDRAM + * @param xmc_flag: specifies the flag to check. + * this parameter can be any combination of the following values: + * - XMC_RISINGEDGE_FLAG + * - XMC_LEVEL_FLAG + * - XMC_FALLINGEDGE_FLAG + * - XMC_FEMPT_FLAG + * - XMC_BUSY_FLAG + * - XMC_ERR_FLAG + * @retval none + */ +flag_status xmc_flag_status_get(xmc_class_bank_type xmc_bank, xmc_interrupt_flag_type xmc_flag) +{ + flag_status status = RESET; + uint32_t temp = 0; + + if(xmc_bank == XMC_BANK2_NAND) + { + temp = XMC_BANK2->bk2is; + } + else if(xmc_bank == XMC_BANK3_NAND) + { + temp = XMC_BANK3->bk3is; + } + else if(xmc_bank == XMC_BANK4_PCCARD) + { + temp = XMC_BANK4->bk4is; + } + else + { + temp = XMC_SDRAM->sts; + } + /* get the flag status */ + if((temp & xmc_flag) == RESET) + { + status = RESET; + } + else + { + status = SET; + } + /* return the flag status */ + return status; +} + +/** + * @brief clear the xmc's pending flags. + * @param xmc_bank: specifies the xmc bank to be used + * this parameter can be one of the following values: + * - XMC_BANK2_NAND + * - XMC_BANK3_NAND + * - XMC_BANK4_PCCARD + * - XMC_BANK5_6_SDRAM + * @param xmc_flag: specifies the flag to check. + * this parameter can be any combination of the following values: + * - XMC_RISINGEDGE_FLAG + * - XMC_LEVEL_FLAG + * - XMC_FALLINGEDGE_FLAG + * - XMC_ERR_FLAG + * @retval none + */ +void xmc_flag_clear(xmc_class_bank_type xmc_bank, xmc_interrupt_flag_type xmc_flag) +{ + __IO uint32_t int_state; + if(xmc_bank == XMC_BANK2_NAND) + { + int_state = XMC_BANK2->bk2is & 0x38; /* keep interrupt state */ + XMC_BANK2->bk2is = (~(xmc_flag | 0x38) | int_state); + } + else if(xmc_bank == XMC_BANK3_NAND) + { + int_state = XMC_BANK3->bk3is & 0x38; /* keep interrupt state */ + XMC_BANK3->bk3is = (~(xmc_flag | 0x38) | int_state); + } + else if(xmc_bank == XMC_BANK4_PCCARD) + { + int_state = XMC_BANK4->bk4is & 0x38; /* keep interrupt state */ + XMC_BANK4->bk4is = (~(xmc_flag | 0x38) | int_state); + } + else + { + XMC_SDRAM->rcnt |= xmc_flag; + } +} + +/** + * @brief xmc pc card registers reset + * @param none + * @retval none + */ +void xmc_pccard_reset(void) +{ + /* Set the XMC_Bank4 registers to their reset values */ + XMC_BANK4->bk4ctrl = 0x00000018; + XMC_BANK4->bk4is = 0x00000000; + XMC_BANK4->bk4tmgatt = 0xFCFCFCFC; + XMC_BANK4->bk4tmgio = 0xFCFCFCFC; + XMC_BANK4->bk4tmgmem = 0xFCFCFCFC; +} + +/** + * @brief initialize the xmc pccard bank according to the specified + * parameters in the xmc_pccard_init_struct. + * @param xmc_pccard_init_struct : pointer to a xmc_pccard_init_type + * structure that contains the configuration information for the xmc + * pccard bank. + * @retval none + */ +void xmc_pccard_init(xmc_pccard_init_type* xmc_pccard_init_struct) +{ + /* set the bk4ctrl register value according to xmc_pccard_init_struct parameters */ + XMC_BANK4->bk4ctrl = (uint32_t)xmc_pccard_init_struct->enable_wait | + XMC_BUSTYPE_16_BITS | + (xmc_pccard_init_struct->delay_time_cr << 9) | + (xmc_pccard_init_struct->delay_time_ar << 13); +} + +/** + * @brief initialize the xmc pccard bank according to the specified + * parameters in the xmc_common_spacetiming_struct/xmc_attribute_spacetiming_struct + * and xmc_iospace_timing_struct. + * @param xmc_regular_spacetiming_struct : pointer to a xmc_pccard_init_type + * structure that contains the configuration information for the xmc + * pccard bank. + * @param xmc_special_spacetiming_struct : pointer to a xmc_pccard_init_type + * structure that contains the configuration information for the xmc + * pccard bank. + * @param xmc_iospace_timing_struct : pointer to a xmc_pccard_init_type + * structure that contains the configuration information for the xmc + * pccard bank. + * @retval none + */ +void xmc_pccard_timing_config(xmc_nand_pccard_timinginit_type* xmc_regular_spacetiming_struct, + xmc_nand_pccard_timinginit_type* xmc_special_spacetiming_struct, + xmc_nand_pccard_timinginit_type* xmc_iospace_timing_struct) +{ + /* set bk4tmgmem register value according to xmc_regular_spacetiming_struct parameters */ + XMC_BANK4->bk4tmgmem = (uint32_t)xmc_regular_spacetiming_struct->mem_setup_time | + (xmc_regular_spacetiming_struct->mem_waite_time << 8) | + (xmc_regular_spacetiming_struct->mem_hold_time << 16) | + (xmc_regular_spacetiming_struct->mem_hiz_time << 24); + + /* Set bk4tmgatt register value according to xmc_special_spacetiming_struct parameters */ + XMC_BANK4->bk4tmgatt = (uint32_t)xmc_special_spacetiming_struct->mem_setup_time | + (xmc_special_spacetiming_struct->mem_waite_time << 8) | + (xmc_special_spacetiming_struct->mem_hold_time << 16) | + (xmc_special_spacetiming_struct->mem_hiz_time << 24); + + /* Set bk4tmgio register value according to xmc_iospace_timing_struct parameters */ + XMC_BANK4->bk4tmgio = (uint32_t)xmc_iospace_timing_struct->mem_setup_time | + (xmc_iospace_timing_struct->mem_waite_time << 8) | + (xmc_iospace_timing_struct->mem_hold_time << 16) | + (xmc_iospace_timing_struct->mem_hiz_time << 24); +} +/** + * @brief fill each xmc_pccard_init_struct member with its default value. + * @param xmc_pccard_init_struct: pointer to a xmc_pccardinittype + * structure which will be initialized. + * @retval none + */ +void xmc_pccard_default_para_init(xmc_pccard_init_type* xmc_pccard_init_struct) +{ + /* reset pccard init structure parameters values */ + xmc_pccard_init_struct->enable_wait = XMC_WAIT_OPERATION_DISABLE; + xmc_pccard_init_struct->delay_time_ar = 0x0; + xmc_pccard_init_struct->delay_time_cr = 0x0; + +} +/** + * @brief fill each xmc_common_spacetiming_struct/xmc_attribute_spacetiming_struct + * and xmc_iospace_timing_struct member with its default value. + * @param xmc_regular_spacetiming_struct : pointer to a xmc_pccard_init_type + * structure that contains the configuration information for the xmc + * pccard bank. + * @param xmc_special_spacetiming_struct : pointer to a xmc_pccard_init_type + * structure that contains the configuration information for the xmc + * pccard bank. + * @param xmc_iospace_timing_struct : pointer to a xmc_pccard_init_type + * structure that contains the configuration information for the xmc + * pccard bank. + * @retval none + */ +void xmc_pccard_timing_default_para_init(xmc_nand_pccard_timinginit_type* xmc_regular_spacetiming_struct, + xmc_nand_pccard_timinginit_type* xmc_special_spacetiming_struct, + xmc_nand_pccard_timinginit_type* xmc_iospace_timing_struct) +{ + xmc_regular_spacetiming_struct->class_bank = XMC_BANK4_PCCARD; + xmc_regular_spacetiming_struct->mem_hold_time = 0xFC; + xmc_regular_spacetiming_struct->mem_waite_time = 0xFC; + xmc_regular_spacetiming_struct->mem_setup_time = 0xFC; + xmc_regular_spacetiming_struct->mem_hiz_time = 0xFC; + xmc_special_spacetiming_struct->class_bank = XMC_BANK4_PCCARD; + xmc_special_spacetiming_struct->mem_hold_time = 0xFC; + xmc_special_spacetiming_struct->mem_waite_time = 0xFC; + xmc_special_spacetiming_struct->mem_setup_time = 0xFC; + xmc_special_spacetiming_struct->mem_hiz_time = 0xFC; + xmc_iospace_timing_struct->class_bank = XMC_BANK4_PCCARD; + xmc_iospace_timing_struct->mem_hold_time = 0xFC; + xmc_iospace_timing_struct->mem_waite_time = 0xFC; + xmc_iospace_timing_struct->mem_setup_time = 0xFC; + xmc_iospace_timing_struct->mem_hiz_time = 0xFC; +} +/** + * @brief enable or disable the pccard memory bank. + * @param new_state (TRUE or FALSE) + * @retval none + */ +void xmc_pccard_enable(confirm_state new_state) +{ + /* enable the pccard bank4 by setting the en bit in the bk4ctrl register */ + XMC_BANK4->bk4ctrl_bit.en = new_state; +} + +/** + * @} + */ + +#endif + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Drivers/CMSIS/Device/ST/AT32F43x/at32f435_437.h b/lib/main/AT32F43x/Drivers/CMSIS/Device/ST/AT32F43x/at32f435_437.h new file mode 100644 index 0000000000..e0b1d4a281 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/Device/ST/AT32F43x/at32f435_437.h @@ -0,0 +1,783 @@ +/** + ************************************************************************** + * @file at32f435_437.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#ifndef __AT32F435_437_H +#define __AT32F435_437_H + +#ifdef __cplusplus +extern "C" { +#endif + +#if defined (__CC_ARM) + #pragma anon_unions +#endif + + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup AT32F435_437 + * @{ + */ + +/** @addtogroup Library_configuration_section + * @{ + */ + +/** + * tip: to avoid modifying this file each time you need to switch between these + * devices, you can define the device in your toolchain compiler preprocessor. + */ + +#if !defined (AT32F435CCU7) && !defined (AT32F435CGU7) && !defined (AT32F435CMU7) && \ + !defined (AT32F435CCT7) && !defined (AT32F435CGT7) && !defined (AT32F435CMT7) && \ + !defined (AT32F435RCT7) && !defined (AT32F435RGT7) && !defined (AT32F435RMT7) && \ + !defined (AT32F435VCT7) && !defined (AT32F435VGT7) && !defined (AT32F435VMT7) && \ + !defined (AT32F435ZCT7) && !defined (AT32F435ZGT7) && !defined (AT32F435ZMT7) && \ + !defined (AT32F437RCT7) && !defined (AT32F437RGT7) && !defined (AT32F437RMT7) && \ + !defined (AT32F437VCT7) && !defined (AT32F437VGT7) && !defined (AT32F437VMT7) && \ + !defined (AT32F437ZCT7) && !defined (AT32F437ZGT7) && !defined (AT32F437ZMT7) + + #error "Please select first the target device used in your application (in at32f435_437.h file)" +#endif + +#if defined (AT32F435CCU7) || defined (AT32F435CGU7) || defined (AT32F435CMU7) || \ + defined (AT32F435CCT7) || defined (AT32F435CGT7) || defined (AT32F435CMT7) || \ + defined (AT32F435RCT7) || defined (AT32F435RGT7) || defined (AT32F435RMT7) || \ + defined (AT32F435VCT7) || defined (AT32F435VGT7) || defined (AT32F435VMT7) || \ + defined (AT32F435ZCT7) || defined (AT32F435ZGT7) || defined (AT32F435ZMT7) + + #define AT32F435xx + //#define AT32F43x +#endif + +#if defined (AT32F437RCT7) || defined (AT32F437RGT7) || defined (AT32F437RMT7) || \ + defined (AT32F437VCT7) || defined (AT32F437VGT7) || defined (AT32F437VMT7) || \ + defined (AT32F437ZCT7) || defined (AT32F437ZGT7) || defined (AT32F437ZMT7) + + #define AT32F437xx + //#define AT32F43x +#endif + +#ifndef USE_STDPERIPH_DRIVER +/** + * @brief comment the line below if you will not use the peripherals drivers. + * in this case, these drivers will not be included and the application code will + * be based on direct access to peripherals registers + */ + #ifdef _RTE_ + #include "RTE_Components.h" + #ifdef RTE_DEVICE_STDPERIPH_FRAMEWORK + #define USE_STDPERIPH_DRIVER + #endif + #endif +#endif + +/** + * @brief at32f435_437 standard peripheral library version number + */ +#define __AT32F435_437_LIBRARY_VERSION_MAJOR (0x02) /*!< [31:24] major version */ +#define __AT32F435_437_LIBRARY_VERSION_MIDDLE (0x01) /*!< [23:16] middle version */ +#define __AT32F435_437_LIBRARY_VERSION_MINOR (0x00) /*!< [15:8] minor version */ +#define __AT32F435_437_LIBRARY_VERSION_RC (0x00) /*!< [7:0] release candidate */ +#define __AT32F435_437_LIBRARY_VERSION ((__AT32F435_437_LIBRARY_VERSION_MAJOR << 24) | \ + (__AT32F435_437_LIBRARY_VERSION_MIDDLE << 16) | \ + (__AT32F435_437_LIBRARY_VERSION_MINOR << 8) | \ + (__AT32F435_437_LIBRARY_VERSION_RC)) + +/** + * @} + */ + +/** @addtogroup configuration_section_for_cmsis + * @{ + */ + +/** + * @brief configuration of the cortex-m4 processor and core peripherals + */ +#define __CM4_REV 0x0001U /*!< core revision r0p1 */ +#define __MPU_PRESENT 1 /*!< mpu present */ +#define __NVIC_PRIO_BITS 4 /*!< at32 uses 4 bits for the priority levels */ +#define __Vendor_SysTickConfig 0 /*!< set to 1 if different systick config is used */ +//#define __FPU_PRESENT 1U /*!< fpu present */ + +/** + * @brief at32f435_437 interrupt number definition, according to the selected device + * in @ref library_configuration_section + */ +typedef enum IRQn +{ + /****** cortex-m4 processor exceptions numbers ***************************************************/ + Reset_IRQn = -15, /*!< 1 reset vector, invoked on power up and warm reset */ + NonMaskableInt_IRQn = -14, /*!< 2 non maskable interrupt */ + HardFault_IRQn = -13, /*!< 3 hard fault, all classes of fault */ + MemoryManagement_IRQn = -12, /*!< 4 cortex-m4 memory management interrupt */ + BusFault_IRQn = -11, /*!< 5 cortex-m4 bus fault interrupt */ + UsageFault_IRQn = -10, /*!< 6 cortex-m4 usage fault interrupt */ + SVCall_IRQn = -5, /*!< 11 cortex-m4 sv call interrupt */ + DebugMonitor_IRQn = -4, /*!< 12 cortex-m4 debug monitor interrupt */ + PendSV_IRQn = -2, /*!< 14 cortex-m4 pend sv interrupt */ + SysTick_IRQn = -1, /*!< 15 cortex-m4 system tick interrupt */ + + /****** at32 specific interrupt numbers *********************************************************/ + WWDT_IRQn = 0, /*!< window watchdog timer interrupt */ + PVM_IRQn = 1, /*!< pvm through exint line detection interrupt */ + TAMP_STAMP_IRQn = 2, /*!< tamper and timestamp interrupts through the exint line */ + ERTC_WKUP_IRQn = 3, /*!< ertc wakeup through the exint line */ + FLASH_IRQn = 4, /*!< flash global interrupt */ + CRM_IRQn = 5, /*!< crm global interrupt */ + EXINT0_IRQn = 6, /*!< exint line0 interrupt */ + EXINT1_IRQn = 7, /*!< exint line1 interrupt */ + EXINT2_IRQn = 8, /*!< exint line2 interrupt */ + EXINT3_IRQn = 9, /*!< exint line3 interrupt */ + EXINT4_IRQn = 10, /*!< exint line4 interrupt */ + EDMA_Stream1_IRQn = 11, /*!< edma stream 1 global interrupt */ + EDMA_Stream2_IRQn = 12, /*!< edma stream 2 global interrupt */ + EDMA_Stream3_IRQn = 13, /*!< edma stream 3 global interrupt */ + EDMA_Stream4_IRQn = 14, /*!< edma stream 4 global interrupt */ + EDMA_Stream5_IRQn = 15, /*!< edma stream 5 global interrupt */ + EDMA_Stream6_IRQn = 16, /*!< edma stream 6 global interrupt */ + EDMA_Stream7_IRQn = 17, /*!< edma stream 7 global interrupt */ + +#if defined (AT32F435xx) + ADC1_2_3_IRQn = 18, /*!< adc1 adc2 and adc3 global interrupt */ + CAN1_TX_IRQn = 19, /*!< can1 tx interrupts */ + CAN1_RX0_IRQn = 20, /*!< can1 rx0 interrupts */ + CAN1_RX1_IRQn = 21, /*!< can1 rx1 interrupt */ + CAN1_SE_IRQn = 22, /*!< can1 se interrupt */ + EXINT9_5_IRQn = 23, /*!< external line[9:5] interrupts */ + TMR1_BRK_TMR9_IRQn = 24, /*!< tmr1 brake interrupt */ + TMR1_OVF_TMR10_IRQn = 25, /*!< tmr1 overflow interrupt */ + TMR1_TRG_HALL_TMR11_IRQn = 26, /*!< tmr1 trigger and hall interrupt */ + TMR1_CH_IRQn = 27, /*!< tmr1 channel interrupt */ + TMR2_GLOBAL_IRQn = 28, /*!< tmr2 global interrupt */ + TMR3_GLOBAL_IRQn = 29, /*!< tmr3 global interrupt */ + TMR4_GLOBAL_IRQn = 30, /*!< tmr4 global interrupt */ + I2C1_EVT_IRQn = 31, /*!< i2c1 event interrupt */ + I2C1_ERR_IRQn = 32, /*!< i2c1 error interrupt */ + I2C2_EVT_IRQn = 33, /*!< i2c2 event interrupt */ + I2C2_ERR_IRQn = 34, /*!< i2c2 error interrupt */ + SPI1_IRQn = 35, /*!< spi1 global interrupt */ + SPI2_I2S2EXT_IRQn = 36, /*!< spi2 global interrupt */ + USART1_IRQn = 37, /*!< usart1 global interrupt */ + USART2_IRQn = 38, /*!< usart2 global interrupt */ + USART3_IRQn = 39, /*!< usart3 global interrupt */ + EXINT15_10_IRQn = 40, /*!< external line[15:10] interrupts */ + ERTCAlarm_IRQn = 41, /*!< ertc alarm through exint line interrupt */ + OTGFS1_WKUP_IRQn = 42, /*!< otgfs1 wakeup from suspend through exint line interrupt */ + TMR8_BRK_TMR12_IRQn = 43, /*!< tmr8 brake interrupt */ + TMR8_OVF_TMR13_IRQn = 44, /*!< tmr8 overflow interrupt */ + TMR8_TRG_HALL_TMR14_IRQn = 45, /*!< tmr8 trigger and hall interrupt */ + TMR8_CH_IRQn = 46, /*!< tmr8 channel interrupt */ + EDMA_Stream8_IRQn = 47, /*!< edma stream 8 global interrupt */ + XMC_IRQn = 48, /*!< xmc global interrupt */ + SDIO1_IRQn = 49, /*!< sdio global interrupt */ + TMR5_GLOBAL_IRQn = 50, /*!< tmr5 global interrupt */ + SPI3_I2S3EXT_IRQn = 51, /*!< spi3 global interrupt */ + UART4_IRQn = 52, /*!< uart4 global interrupt */ + UART5_IRQn = 53, /*!< uart5 global interrupt */ + TMR6_DAC_GLOBAL_IRQn = 54, /*!< tmr6 and dac global interrupt */ + TMR7_GLOBAL_IRQn = 55, /*!< tmr7 global interrupt */ + DMA1_Channel1_IRQn = 56, /*!< dma1 channel 0 global interrupt */ + DMA1_Channel2_IRQn = 57, /*!< dma1 channel 1 global interrupt */ + DMA1_Channel3_IRQn = 58, /*!< dma1 channel 2 global interrupt */ + DMA1_Channel4_IRQn = 59, /*!< dma1 channel 3 global interrupt */ + DMA1_Channel5_IRQn = 60, /*!< dma1 channel 4 global interrupt */ + CAN2_TX_IRQn = 63, /*!< can2 tx interrupt */ + CAN2_RX0_IRQn = 64, /*!< can2 rx0 interrupt */ + CAN2_RX1_IRQn = 65, /*!< can2 rx1 interrupt */ + CAN2_SE_IRQn = 66, /*!< can2 se interrupt */ + OTGFS1_IRQn = 67, /*!< otgfs1 interrupt */ + DMA1_Channel6_IRQn = 68, /*!< dma1 channel 5 global interrupt */ + DMA1_Channel7_IRQn = 69, /*!< dma1 channel 6 global interrupt */ + USART6_IRQn = 71, /*!< usart6 interrupt */ + I2C3_EVT_IRQn = 72, /*!< i2c3 event interrupt */ + I2C3_ERR_IRQn = 73, /*!< i2c3 error interrupt */ + OTGFS2_WKUP_IRQn = 76, /*!< otgfs2 wakeup from suspend through exint line interrupt */ + OTGFS2_IRQn = 77, /*!< otgfs2 interrupt */ + DVP_IRQn = 78, /*!< dvp interrupt */ + FPU_IRQn = 81, /*!< fpu interrupt */ + UART7_IRQn = 82, /*!< uart7 interrupt */ + UART8_IRQn = 83, /*!< uart8 interrupt */ + SPI4_IRQn = 84, /*!< spi4 global interrupt */ + QSPI2_IRQn = 91, /*!< qspi2 global interrupt */ + QSPI1_IRQn = 92, /*!< qspi1 global interrupt */ + DMAMUX_IRQn = 94, /*!< dmamux global interrupt */ + SDIO2_IRQn = 102, /*!< sdio2 global interrupt */ + ACC_IRQn = 103, /*!< acc interrupt */ + TMR20_BRK_IRQn = 104, /*!< tmr20 brake interrupt */ + TMR20_OVF_IRQn = 105, /*!< tmr20 overflow interrupt */ + TMR20_TRG_HALL_IRQn = 106, /*!< tmr20 trigger and hall interrupt */ + TMR20_CH_IRQn = 107, /*!< tmr20 channel interrupt */ + DMA2_Channel1_IRQn = 108, /*!< dma2 channel 1 global interrupt */ + DMA2_Channel2_IRQn = 109, /*!< dma2 channel 2 global interrupt */ + DMA2_Channel3_IRQn = 110, /*!< dma2 channel 3 global interrupt */ + DMA2_Channel4_IRQn = 111, /*!< dma2 channel 4 global interrupt */ + DMA2_Channel5_IRQn = 112, /*!< dma2 channel 5 global interrupt */ + DMA2_Channel6_IRQn = 113, /*!< dma2 channel 6 global interrupt */ + DMA2_Channel7_IRQn = 114, /*!< dma2 channel 7 global interrupt */ +#endif + +#if defined (AT32F437xx) + ADC1_2_3_IRQn = 18, /*!< adc1 adc2 and adc3 global interrupt */ + CAN1_TX_IRQn = 19, /*!< can1 tx interrupts */ + CAN1_RX0_IRQn = 20, /*!< can1 rx0 interrupts */ + CAN1_RX1_IRQn = 21, /*!< can1 rx1 interrupt */ + CAN1_SE_IRQn = 22, /*!< can1 se interrupt */ + EXINT9_5_IRQn = 23, /*!< external line[9:5] interrupts */ + TMR1_BRK_TMR9_IRQn = 24, /*!< tmr1 brake interrupt */ + TMR1_OVF_TMR10_IRQn = 25, /*!< tmr1 overflow interrupt */ + TMR1_TRG_HALL_TMR11_IRQn = 26, /*!< tmr1 trigger and hall interrupt */ + TMR1_CH_IRQn = 27, /*!< tmr1 channel interrupt */ + TMR2_GLOBAL_IRQn = 28, /*!< tmr2 global interrupt */ + TMR3_GLOBAL_IRQn = 29, /*!< tmr3 global interrupt */ + TMR4_GLOBAL_IRQn = 30, /*!< tmr4 global interrupt */ + I2C1_EVT_IRQn = 31, /*!< i2c1 event interrupt */ + I2C1_ERR_IRQn = 32, /*!< i2c1 error interrupt */ + I2C2_EVT_IRQn = 33, /*!< i2c2 event interrupt */ + I2C2_ERR_IRQn = 34, /*!< i2c2 error interrupt */ + SPI1_IRQn = 35, /*!< spi1 global interrupt */ + SPI2_I2S2EXT_IRQn = 36, /*!< spi2 global interrupt */ + USART1_IRQn = 37, /*!< usart1 global interrupt */ + USART2_IRQn = 38, /*!< usart2 global interrupt */ + USART3_IRQn = 39, /*!< usart3 global interrupt */ + EXINT15_10_IRQn = 40, /*!< external line[15:10] interrupts */ + ERTCAlarm_IRQn = 41, /*!< ertc alarm through exint line interrupt */ + OTGFS1_WKUP_IRQn = 42, /*!< otgfs1 wakeup from suspend through exint line interrupt */ + TMR8_BRK_TMR12_IRQn = 43, /*!< tmr8 brake interrupt */ + TMR8_OVF_TMR13_IRQn = 44, /*!< tmr8 overflow interrupt */ + TMR8_TRG_HALL_TMR14_IRQn = 45, /*!< tmr8 trigger and hall interrupt */ + TMR8_CH_IRQn = 46, /*!< tmr8 channel interrupt */ + EDMA_Stream8_IRQn = 47, /*!< dma1 stream 8 global interrupt */ + XMC_IRQn = 48, /*!< xmc global interrupt */ + SDIO1_IRQn = 49, /*!< sdio global interrupt */ + TMR5_GLOBAL_IRQn = 50, /*!< tmr5 global interrupt */ + SPI3_I2S3EXT_IRQn = 51, /*!< spi3 global interrupt */ + UART4_IRQn = 52, /*!< uart4 global interrupt */ + UART5_IRQn = 53, /*!< uart5 global interrupt */ + TMR6_DAC_GLOBAL_IRQn = 54, /*!< tmr6 and dac global interrupt */ + TMR7_GLOBAL_IRQn = 55, /*!< tmr7 global interrupt */ + DMA1_Channel1_IRQn = 56, /*!< dma1 channel 0 global interrupt */ + DMA1_Channel2_IRQn = 57, /*!< dma1 channel 1 global interrupt */ + DMA1_Channel3_IRQn = 58, /*!< dma1 channel 2 global interrupt */ + DMA1_Channel4_IRQn = 59, /*!< dma1 channel 3 global interrupt */ + DMA1_Channel5_IRQn = 60, /*!< dma1 channel 4 global interrupt */ + EMAC_IRQn = 61, /*!< emac interrupt */ + EMAC_WKUP_IRQn = 62, /*!< emac wakeup interrupt */ + CAN2_TX_IRQn = 63, /*!< can2 tx interrupt */ + CAN2_RX0_IRQn = 64, /*!< can2 rx0 interrupt */ + CAN2_RX1_IRQn = 65, /*!< can2 rx1 interrupt */ + CAN2_SE_IRQn = 66, /*!< can2 se interrupt */ + OTGFS1_IRQn = 67, /*!< otgfs1 interrupt */ + DMA1_Channel6_IRQn = 68, /*!< dma1 channel 5 global interrupt */ + DMA1_Channel7_IRQn = 69, /*!< dma1 channel 6 global interrupt */ + USART6_IRQn = 71, /*!< usart6 interrupt */ + I2C3_EVT_IRQn = 72, /*!< i2c3 event interrupt */ + I2C3_ERR_IRQn = 73, /*!< i2c3 error interrupt */ + OTGFS2_WKUP_IRQn = 76, /*!< otgfs2 wakeup from suspend through exint line interrupt */ + OTGFS2_IRQn = 77, /*!< otgfs2 interrupt */ + DVP_IRQn = 78, /*!< dvp interrupt */ + FPU_IRQn = 81, /*!< fpu interrupt */ + UART7_IRQn = 82, /*!< uart7 interrupt */ + UART8_IRQn = 83, /*!< uart8 interrupt */ + SPI4_IRQn = 84, /*!< spi4 global interrupt */ + QSPI2_IRQn = 91, /*!< qspi2 global interrupt */ + QSPI1_IRQn = 92, /*!< qspi1 global interrupt */ + DMAMUX_IRQn = 94, /*!< dmamux global interrupt */ + SDIO2_IRQn = 102, /*!< sdio2 global interrupt */ + ACC_IRQn = 103, /*!< acc interrupt */ + TMR20_BRK_IRQn = 104, /*!< tmr20 brake interrupt */ + TMR20_OVF_IRQn = 105, /*!< tmr20 overflow interrupt */ + TMR20_TRG_HALL_IRQn = 106, /*!< tmr20 trigger and hall interrupt */ + TMR20_CH_IRQn = 107, /*!< tmr20 channel interrupt */ + DMA2_Channel1_IRQn = 108, /*!< dma2 channel 1 global interrupt */ + DMA2_Channel2_IRQn = 109, /*!< dma2 channel 2 global interrupt */ + DMA2_Channel3_IRQn = 110, /*!< dma2 channel 3 global interrupt */ + DMA2_Channel4_IRQn = 111, /*!< dma2 channel 4 global interrupt */ + DMA2_Channel5_IRQn = 112, /*!< dma2 channel 5 global interrupt */ + DMA2_Channel6_IRQn = 113, /*!< dma2 channel 6 global interrupt */ + DMA2_Channel7_IRQn = 114, /*!< dma2 channel 7 global interrupt */ +#endif + +} IRQn_Type; + +/** + * @} + */ + +#include "core_cm4.h" +#include "system_at32f435_437.h" +#include + +/** @addtogroup Exported_types + * @{ + */ + +typedef int32_t INT32; +typedef int16_t INT16; +typedef int8_t INT8; +typedef uint32_t UINT32; +typedef uint16_t UINT16; +typedef uint8_t UINT8; + +typedef int32_t s32; +typedef int16_t s16; +typedef int8_t s8; + +typedef const int32_t sc32; /*!< read only */ +typedef const int16_t sc16; /*!< read only */ +typedef const int8_t sc8; /*!< read only */ + +typedef __IO int32_t vs32; +typedef __IO int16_t vs16; +typedef __IO int8_t vs8; + +typedef __I int32_t vsc32; /*!< read only */ +typedef __I int16_t vsc16; /*!< read only */ +typedef __I int8_t vsc8; /*!< read only */ + +typedef uint32_t u32; +typedef uint16_t u16; +typedef uint8_t u8; + +typedef const uint32_t uc32; /*!< read only */ +typedef const uint16_t uc16; /*!< read only */ +typedef const uint8_t uc8; /*!< read only */ + +typedef __IO uint32_t vu32; +typedef __IO uint16_t vu16; +typedef __IO uint8_t vu8; + +typedef __I uint32_t vuc32; /*!< read only */ +typedef __I uint16_t vuc16; /*!< read only */ +typedef __I uint8_t vuc8; /*!< read only */ + +typedef enum {RESET = 0, SET = !RESET} flag_status; +typedef enum {FALSE = 0, TRUE = !FALSE} confirm_state; +typedef enum {ERROR = 0, SUCCESS = !ERROR} error_status; + + + +/** + * @} + */ + +/** @addtogroup Exported_macro + * @{ + */ + +#define REG8(addr) *(volatile uint8_t *)(addr) +#define REG16(addr) *(volatile uint16_t *)(addr) +#define REG32(addr) *(volatile uint32_t *)(addr) + +#define MAKE_VALUE(reg_offset, bit_num) (((reg_offset) << 16) | (bit_num & 0x1f)) + +#define PERIPH_REG(periph_base, value) REG32((periph_base + (value >> 16))) +#define PERIPH_REG_BIT(value) (0x1u << (value & 0x1f)) + +/** + * @} + */ + +/** @addtogroup Peripheral_memory_map + * @{ + */ + +#define XMC_SDRAM_MEM_BASE ((uint32_t)0xC0000000) +#define QSPI2_MEM_BASE ((uint32_t)0xB0000000) +#define XMC_CARD_MEM_BASE ((uint32_t)0xA8000000) +#define QSPI2_REG_BASE ((uint32_t)0xA0002000) +#define QSPI1_REG_BASE ((uint32_t)0xA0001000) +#define XMC_REG_BASE ((uint32_t)0xA0000000) +#define XMC_BANK1_REG_BASE (XMC_REG_BASE + 0x0000) +#define XMC_BANK2_REG_BASE (XMC_REG_BASE + 0x0060) +#define XMC_BANK3_REG_BASE (XMC_REG_BASE + 0x0080) +#define XMC_BANK4_REG_BASE (XMC_REG_BASE + 0x00A0) +#define XMC_SDRAM_REG_BASE (XMC_REG_BASE + 0x0140) +#define QSPI1_MEM_BASE ((uint32_t)0x90000000) +#define XMC_MEM_BASE ((uint32_t)0x60000000) +#define PERIPH_BASE ((uint32_t)0x40000000) +#define SRAM_BB_BASE ((uint32_t)0x22000000) +#define PERIPH_BB_BASE ((uint32_t)0x42000000) +#define SRAM_BASE ((uint32_t)0x20000000) +#define USD_BASE ((uint32_t)0x1FFFC000) +#define FLASH_BASE ((uint32_t)0x08000000) + +#define DEBUG_BASE ((uint32_t)0xE0042000) + +#define APB1PERIPH_BASE (PERIPH_BASE) +#define APB2PERIPH_BASE (PERIPH_BASE + 0x10000) +#define AHBPERIPH1_BASE (PERIPH_BASE + 0x20000) +#define AHBPERIPH2_BASE (PERIPH_BASE + 0x10000000) + +#if defined (AT32F435xx) +/* apb1 bus base address */ +#define UART8_BASE (APB1PERIPH_BASE + 0x7C00) +#define UART7_BASE (APB1PERIPH_BASE + 0x7800) +#define DAC_BASE (APB1PERIPH_BASE + 0x7400) +#define PWC_BASE (APB1PERIPH_BASE + 0x7000) +#define CAN2_BASE (APB1PERIPH_BASE + 0x6800) +#define CAN1_BASE (APB1PERIPH_BASE + 0x6400) +#define I2C3_BASE (APB1PERIPH_BASE + 0x5C00) +#define I2C2_BASE (APB1PERIPH_BASE + 0x5800) +#define I2C1_BASE (APB1PERIPH_BASE + 0x5400) +#define UART5_BASE (APB1PERIPH_BASE + 0x5000) +#define UART4_BASE (APB1PERIPH_BASE + 0x4C00) +#define USART3_BASE (APB1PERIPH_BASE + 0x4800) +#define USART2_BASE (APB1PERIPH_BASE + 0x4400) +#define SPI3_BASE (APB1PERIPH_BASE + 0x3C00) +#define SPI2_BASE (APB1PERIPH_BASE + 0x3800) +#define WDT_BASE (APB1PERIPH_BASE + 0x3000) +#define WWDT_BASE (APB1PERIPH_BASE + 0x2C00) +#define ERTC_BASE (APB1PERIPH_BASE + 0x2800) +#define TMR14_BASE (APB1PERIPH_BASE + 0x2000) +#define TMR13_BASE (APB1PERIPH_BASE + 0x1C00) +#define TMR12_BASE (APB1PERIPH_BASE + 0x1800) +#define TMR7_BASE (APB1PERIPH_BASE + 0x1400) +#define TMR6_BASE (APB1PERIPH_BASE + 0x1000) +#define TMR5_BASE (APB1PERIPH_BASE + 0x0C00) +#define TMR4_BASE (APB1PERIPH_BASE + 0x0800) +#define TMR3_BASE (APB1PERIPH_BASE + 0x0400) +#define TMR2_BASE (APB1PERIPH_BASE + 0x0000) +/* apb2 bus base address */ +#define I2S2EXT_BASE (APB2PERIPH_BASE + 0x7800) +#define I2S3EXT_BASE (APB2PERIPH_BASE + 0x7C00) +#define ACC_BASE (APB2PERIPH_BASE + 0x7400) +#define TMR20_BASE (APB2PERIPH_BASE + 0x4C00) +#define TMR11_BASE (APB2PERIPH_BASE + 0x4800) +#define TMR10_BASE (APB2PERIPH_BASE + 0x4400) +#define TMR9_BASE (APB2PERIPH_BASE + 0x4000) +#define EXINT_BASE (APB2PERIPH_BASE + 0x3C00) +#define SCFG_BASE (APB2PERIPH_BASE + 0x3800) +#define SPI4_BASE (APB2PERIPH_BASE + 0x3400) +#define SPI1_BASE (APB2PERIPH_BASE + 0x3000) +#define ADC1_BASE (APB2PERIPH_BASE + 0x2000) +#define ADC2_BASE (APB2PERIPH_BASE + 0x2100) +#define ADC3_BASE (APB2PERIPH_BASE + 0x2200) +#define ADCCOM_BASE (APB2PERIPH_BASE + 0x2300) +#define USART6_BASE (APB2PERIPH_BASE + 0x1400) +#define USART1_BASE (APB2PERIPH_BASE + 0x1000) +#define TMR8_BASE (APB2PERIPH_BASE + 0x0400) +#define TMR1_BASE (APB2PERIPH_BASE + 0x0000) +/* ahb bus base address */ +#define OTGFS2_BASE (AHBPERIPH1_BASE + 0x20000) +#define SDIO1_BASE (AHBPERIPH1_BASE + 0xC400) +#define GPIOH_BASE (AHBPERIPH1_BASE + 0x1C00) +#define GPIOG_BASE (AHBPERIPH1_BASE + 0x1800) +#define GPIOF_BASE (AHBPERIPH1_BASE + 0x1400) +#define GPIOE_BASE (AHBPERIPH1_BASE + 0x1000) +#define GPIOD_BASE (AHBPERIPH1_BASE + 0x0C00) +#define GPIOC_BASE (AHBPERIPH1_BASE + 0x0800) +#define GPIOB_BASE (AHBPERIPH1_BASE + 0x0400) +#define GPIOA_BASE (AHBPERIPH1_BASE + 0x0000) + +#define DMA1_BASE (AHBPERIPH1_BASE + 0x6400) +#define DMA1_CHANNEL1_BASE (DMA1_BASE + 0x0008) +#define DMA1_CHANNEL2_BASE (DMA1_BASE + 0x001C) +#define DMA1_CHANNEL3_BASE (DMA1_BASE + 0x0030) +#define DMA1_CHANNEL4_BASE (DMA1_BASE + 0x0044) +#define DMA1_CHANNEL5_BASE (DMA1_BASE + 0x0058) +#define DMA1_CHANNEL6_BASE (DMA1_BASE + 0x006C) +#define DMA1_CHANNEL7_BASE (DMA1_BASE + 0x0080) + +#define DMA1MUX_BASE (DMA1_BASE + 0x0104) +#define DMA1MUX_CHANNEL1_BASE (DMA1MUX_BASE) +#define DMA1MUX_CHANNEL2_BASE (DMA1MUX_BASE + 0x0004) +#define DMA1MUX_CHANNEL3_BASE (DMA1MUX_BASE + 0x0008) +#define DMA1MUX_CHANNEL4_BASE (DMA1MUX_BASE + 0x000C) +#define DMA1MUX_CHANNEL5_BASE (DMA1MUX_BASE + 0x0010) +#define DMA1MUX_CHANNEL6_BASE (DMA1MUX_BASE + 0x0014) +#define DMA1MUX_CHANNEL7_BASE (DMA1MUX_BASE + 0x0018) + +#define DMA1MUX_GENERATOR1_BASE (DMA1_BASE + 0x0120) +#define DMA1MUX_GENERATOR2_BASE (DMA1_BASE + 0x0124) +#define DMA1MUX_GENERATOR3_BASE (DMA1_BASE + 0x0128) +#define DMA1MUX_GENERATOR4_BASE (DMA1_BASE + 0x012C) + +#define DMA2_BASE (AHBPERIPH1_BASE + 0x6600) +#define DMA2_CHANNEL1_BASE (DMA2_BASE + 0x0008) +#define DMA2_CHANNEL2_BASE (DMA2_BASE + 0x001C) +#define DMA2_CHANNEL3_BASE (DMA2_BASE + 0x0030) +#define DMA2_CHANNEL4_BASE (DMA2_BASE + 0x0044) +#define DMA2_CHANNEL5_BASE (DMA2_BASE + 0x0058) +#define DMA2_CHANNEL6_BASE (DMA2_BASE + 0x006C) +#define DMA2_CHANNEL7_BASE (DMA2_BASE + 0x0080) + +#define DMA2MUX_BASE (DMA2_BASE + 0x0104) +#define DMA2MUX_CHANNEL1_BASE (DMA2MUX_BASE) +#define DMA2MUX_CHANNEL2_BASE (DMA2MUX_BASE + 0x0004) +#define DMA2MUX_CHANNEL3_BASE (DMA2MUX_BASE + 0x0008) +#define DMA2MUX_CHANNEL4_BASE (DMA2MUX_BASE + 0x000C) +#define DMA2MUX_CHANNEL5_BASE (DMA2MUX_BASE + 0x0010) +#define DMA2MUX_CHANNEL6_BASE (DMA2MUX_BASE + 0x0014) +#define DMA2MUX_CHANNEL7_BASE (DMA2MUX_BASE + 0x0018) + +#define DMA2MUX_GENERATOR1_BASE (DMA2_BASE + 0x0120) +#define DMA2MUX_GENERATOR2_BASE (DMA2_BASE + 0x0124) +#define DMA2MUX_GENERATOR3_BASE (DMA2_BASE + 0x0128) +#define DMA2MUX_GENERATOR4_BASE (DMA2_BASE + 0x012C) + +#define EDMA_BASE (AHBPERIPH1_BASE + 0x6000) +#define EDMA_STREAM1_BASE (EDMA_BASE + 0x0010) +#define EDMA_STREAM2_BASE (EDMA_BASE + 0x0028) +#define EDMA_STREAM3_BASE (EDMA_BASE + 0x0040) +#define EDMA_STREAM4_BASE (EDMA_BASE + 0x0058) +#define EDMA_STREAM5_BASE (EDMA_BASE + 0x0070) +#define EDMA_STREAM6_BASE (EDMA_BASE + 0x0088) +#define EDMA_STREAM7_BASE (EDMA_BASE + 0x00A0) +#define EDMA_STREAM8_BASE (EDMA_BASE + 0x00B8) + +#define EDMA_2D_BASE (EDMA_BASE + 0x00F4) +#define EDMA_STREAM1_2D_BASE (EDMA_2D_BASE + 0x0004) +#define EDMA_STREAM2_2D_BASE (EDMA_2D_BASE + 0x000C) +#define EDMA_STREAM3_2D_BASE (EDMA_2D_BASE + 0x0014) +#define EDMA_STREAM4_2D_BASE (EDMA_2D_BASE + 0x001C) +#define EDMA_STREAM5_2D_BASE (EDMA_2D_BASE + 0x0024) +#define EDMA_STREAM6_2D_BASE (EDMA_2D_BASE + 0x002C) +#define EDMA_STREAM7_2D_BASE (EDMA_2D_BASE + 0x0034) +#define EDMA_STREAM8_2D_BASE (EDMA_2D_BASE + 0x003C) + +#define EDMA_LL_BASE (EDMA_BASE + 0x00D0) +#define EDMA_STREAM1_LL_BASE (EDMA_LL_BASE + 0x0004) +#define EDMA_STREAM2_LL_BASE (EDMA_LL_BASE + 0x0008) +#define EDMA_STREAM3_LL_BASE (EDMA_LL_BASE + 0x000C) +#define EDMA_STREAM4_LL_BASE (EDMA_LL_BASE + 0x0010) +#define EDMA_STREAM5_LL_BASE (EDMA_LL_BASE + 0x0014) +#define EDMA_STREAM6_LL_BASE (EDMA_LL_BASE + 0x0018) +#define EDMA_STREAM7_LL_BASE (EDMA_LL_BASE + 0x001C) +#define EDMA_STREAM8_LL_BASE (EDMA_LL_BASE + 0x0020) + +#define EDMAMUX_BASE (EDMA_BASE + 0x0140) +#define EDMAMUX_CHANNEL1_BASE (EDMAMUX_BASE) +#define EDMAMUX_CHANNEL2_BASE (EDMAMUX_BASE + 0x0004) +#define EDMAMUX_CHANNEL3_BASE (EDMAMUX_BASE + 0x0008) +#define EDMAMUX_CHANNEL4_BASE (EDMAMUX_BASE + 0x000C) +#define EDMAMUX_CHANNEL5_BASE (EDMAMUX_BASE + 0x0010) +#define EDMAMUX_CHANNEL6_BASE (EDMAMUX_BASE + 0x0014) +#define EDMAMUX_CHANNEL7_BASE (EDMAMUX_BASE + 0x0018) +#define EDMAMUX_CHANNEL8_BASE (EDMAMUX_BASE + 0x001C) + +#define EDMAMUX_GENERATOR1_BASE (EDMA_BASE + 0x0160) +#define EDMAMUX_GENERATOR2_BASE (EDMA_BASE + 0x0164) +#define EDMAMUX_GENERATOR3_BASE (EDMA_BASE + 0x0168) +#define EDMAMUX_GENERATOR4_BASE (EDMA_BASE + 0x016C) + +#define FLASH_REG_BASE (AHBPERIPH1_BASE + 0x3C00) +#define CRM_BASE (AHBPERIPH1_BASE + 0x3800) +#define CRC_BASE (AHBPERIPH1_BASE + 0x3000) +#define SDIO2_BASE (AHBPERIPH2_BASE + 0x61000) +#define DVP_BASE (AHBPERIPH2_BASE + 0x50000) +#define OTGFS1_BASE (AHBPERIPH2_BASE + 0x00000) +#endif + +#if defined (AT32F437xx) +/* apb1 bus base address */ +#define UART8_BASE (APB1PERIPH_BASE + 0x7C00) +#define UART7_BASE (APB1PERIPH_BASE + 0x7800) +#define DAC_BASE (APB1PERIPH_BASE + 0x7400) +#define PWC_BASE (APB1PERIPH_BASE + 0x7000) +#define CAN2_BASE (APB1PERIPH_BASE + 0x6800) +#define CAN1_BASE (APB1PERIPH_BASE + 0x6400) +#define I2C3_BASE (APB1PERIPH_BASE + 0x5C00) +#define I2C2_BASE (APB1PERIPH_BASE + 0x5800) +#define I2C1_BASE (APB1PERIPH_BASE + 0x5400) +#define UART5_BASE (APB1PERIPH_BASE + 0x5000) +#define UART4_BASE (APB1PERIPH_BASE + 0x4C00) +#define USART3_BASE (APB1PERIPH_BASE + 0x4800) +#define USART2_BASE (APB1PERIPH_BASE + 0x4400) +#define SPI3_BASE (APB1PERIPH_BASE + 0x3C00) +#define SPI2_BASE (APB1PERIPH_BASE + 0x3800) +#define WDT_BASE (APB1PERIPH_BASE + 0x3000) +#define WWDT_BASE (APB1PERIPH_BASE + 0x2C00) +#define ERTC_BASE (APB1PERIPH_BASE + 0x2800) +#define TMR14_BASE (APB1PERIPH_BASE + 0x2000) +#define TMR13_BASE (APB1PERIPH_BASE + 0x1C00) +#define TMR12_BASE (APB1PERIPH_BASE + 0x1800) +#define TMR7_BASE (APB1PERIPH_BASE + 0x1400) +#define TMR6_BASE (APB1PERIPH_BASE + 0x1000) +#define TMR5_BASE (APB1PERIPH_BASE + 0x0C00) +#define TMR4_BASE (APB1PERIPH_BASE + 0x0800) +#define TMR3_BASE (APB1PERIPH_BASE + 0x0400) +#define TMR2_BASE (APB1PERIPH_BASE + 0x0000) +/* apb2 bus base address */ +#define I2S2EXT_BASE (APB2PERIPH_BASE + 0x7800) +#define I2S3EXT_BASE (APB2PERIPH_BASE + 0x7C00) +#define ACC_BASE (APB2PERIPH_BASE + 0x7400) +#define TMR20_BASE (APB2PERIPH_BASE + 0x4C00) +#define TMR11_BASE (APB2PERIPH_BASE + 0x4800) +#define TMR10_BASE (APB2PERIPH_BASE + 0x4400) +#define TMR9_BASE (APB2PERIPH_BASE + 0x4000) +#define EXINT_BASE (APB2PERIPH_BASE + 0x3C00) +#define SCFG_BASE (APB2PERIPH_BASE + 0x3800) +#define SPI4_BASE (APB2PERIPH_BASE + 0x3400) +#define SPI1_BASE (APB2PERIPH_BASE + 0x3000) +#define ADC1_BASE (APB2PERIPH_BASE + 0x2000) +#define ADC2_BASE (APB2PERIPH_BASE + 0x2100) +#define ADC3_BASE (APB2PERIPH_BASE + 0x2200) +#define ADCCOM_BASE (APB2PERIPH_BASE + 0x2300) +#define USART6_BASE (APB2PERIPH_BASE + 0x1400) +#define USART1_BASE (APB2PERIPH_BASE + 0x1000) +#define TMR8_BASE (APB2PERIPH_BASE + 0x0400) +#define TMR1_BASE (APB2PERIPH_BASE + 0x0000) +/* ahb bus base address */ +#define OTGFS2_BASE (AHBPERIPH1_BASE + 0x20000) +#define SDIO1_BASE (AHBPERIPH1_BASE + 0xC400) +#define EMAC_BASE (AHBPERIPH1_BASE + 0x8000) +#define GPIOH_BASE (AHBPERIPH1_BASE + 0x1C00) +#define GPIOG_BASE (AHBPERIPH1_BASE + 0x1800) +#define GPIOF_BASE (AHBPERIPH1_BASE + 0x1400) +#define GPIOE_BASE (AHBPERIPH1_BASE + 0x1000) +#define GPIOD_BASE (AHBPERIPH1_BASE + 0x0C00) +#define GPIOC_BASE (AHBPERIPH1_BASE + 0x0800) +#define GPIOB_BASE (AHBPERIPH1_BASE + 0x0400) +#define GPIOA_BASE (AHBPERIPH1_BASE + 0x0000) + +#define DMA1_BASE (AHBPERIPH1_BASE + 0x6400) +#define DMA1_CHANNEL1_BASE (DMA1_BASE + 0x0008) +#define DMA1_CHANNEL2_BASE (DMA1_BASE + 0x001C) +#define DMA1_CHANNEL3_BASE (DMA1_BASE + 0x0030) +#define DMA1_CHANNEL4_BASE (DMA1_BASE + 0x0044) +#define DMA1_CHANNEL5_BASE (DMA1_BASE + 0x0058) +#define DMA1_CHANNEL6_BASE (DMA1_BASE + 0x006C) +#define DMA1_CHANNEL7_BASE (DMA1_BASE + 0x0080) + +#define DMA1MUX_BASE (DMA1_BASE + 0x0104) +#define DMA1MUX_CHANNEL1_BASE (DMA1MUX_BASE) +#define DMA1MUX_CHANNEL2_BASE (DMA1MUX_BASE + 0x0004) +#define DMA1MUX_CHANNEL3_BASE (DMA1MUX_BASE + 0x0008) +#define DMA1MUX_CHANNEL4_BASE (DMA1MUX_BASE + 0x000C) +#define DMA1MUX_CHANNEL5_BASE (DMA1MUX_BASE + 0x0010) +#define DMA1MUX_CHANNEL6_BASE (DMA1MUX_BASE + 0x0014) +#define DMA1MUX_CHANNEL7_BASE (DMA1MUX_BASE + 0x0018) + +#define DMA1MUX_GENERATOR1_BASE (DMA1_BASE + 0x0120) +#define DMA1MUX_GENERATOR2_BASE (DMA1_BASE + 0x0124) +#define DMA1MUX_GENERATOR3_BASE (DMA1_BASE + 0x0128) +#define DMA1MUX_GENERATOR4_BASE (DMA1_BASE + 0x012C) + +#define DMA2_BASE (AHBPERIPH1_BASE + 0x6600) +#define DMA2_CHANNEL1_BASE (DMA2_BASE + 0x0008) +#define DMA2_CHANNEL2_BASE (DMA2_BASE + 0x001C) +#define DMA2_CHANNEL3_BASE (DMA2_BASE + 0x0030) +#define DMA2_CHANNEL4_BASE (DMA2_BASE + 0x0044) +#define DMA2_CHANNEL5_BASE (DMA2_BASE + 0x0058) +#define DMA2_CHANNEL6_BASE (DMA2_BASE + 0x006C) +#define DMA2_CHANNEL7_BASE (DMA2_BASE + 0x0080) + +#define DMA2MUX_BASE (DMA2_BASE + 0x0104) +#define DMA2MUX_CHANNEL1_BASE (DMA2MUX_BASE) +#define DMA2MUX_CHANNEL2_BASE (DMA2MUX_BASE + 0x0004) +#define DMA2MUX_CHANNEL3_BASE (DMA2MUX_BASE + 0x0008) +#define DMA2MUX_CHANNEL4_BASE (DMA2MUX_BASE + 0x000C) +#define DMA2MUX_CHANNEL5_BASE (DMA2MUX_BASE + 0x0010) +#define DMA2MUX_CHANNEL6_BASE (DMA2MUX_BASE + 0x0014) +#define DMA2MUX_CHANNEL7_BASE (DMA2MUX_BASE + 0x0018) + +#define DMA2MUX_GENERATOR1_BASE (DMA2_BASE + 0x0120) +#define DMA2MUX_GENERATOR2_BASE (DMA2_BASE + 0x0124) +#define DMA2MUX_GENERATOR3_BASE (DMA2_BASE + 0x0128) +#define DMA2MUX_GENERATOR4_BASE (DMA2_BASE + 0x012C) + +#define EDMA_BASE (AHBPERIPH1_BASE + 0x6000) +#define EDMA_STREAM1_BASE (EDMA_BASE + 0x0010) +#define EDMA_STREAM2_BASE (EDMA_BASE + 0x0028) +#define EDMA_STREAM3_BASE (EDMA_BASE + 0x0040) +#define EDMA_STREAM4_BASE (EDMA_BASE + 0x0058) +#define EDMA_STREAM5_BASE (EDMA_BASE + 0x0070) +#define EDMA_STREAM6_BASE (EDMA_BASE + 0x0088) +#define EDMA_STREAM7_BASE (EDMA_BASE + 0x00A0) +#define EDMA_STREAM8_BASE (EDMA_BASE + 0x00B8) + +#define EDMA_2D_BASE (EDMA_BASE + 0x00F4) +#define EDMA_STREAM1_2D_BASE (EDMA_2D_BASE + 0x0004) +#define EDMA_STREAM2_2D_BASE (EDMA_2D_BASE + 0x000C) +#define EDMA_STREAM3_2D_BASE (EDMA_2D_BASE + 0x0014) +#define EDMA_STREAM4_2D_BASE (EDMA_2D_BASE + 0x001C) +#define EDMA_STREAM5_2D_BASE (EDMA_2D_BASE + 0x0024) +#define EDMA_STREAM6_2D_BASE (EDMA_2D_BASE + 0x002C) +#define EDMA_STREAM7_2D_BASE (EDMA_2D_BASE + 0x0034) +#define EDMA_STREAM8_2D_BASE (EDMA_2D_BASE + 0x003C) + +#define EDMA_LL_BASE (EDMA_BASE + 0x00D0) +#define EDMA_STREAM1_LL_BASE (EDMA_LL_BASE + 0x0004) +#define EDMA_STREAM2_LL_BASE (EDMA_LL_BASE + 0x0008) +#define EDMA_STREAM3_LL_BASE (EDMA_LL_BASE + 0x000C) +#define EDMA_STREAM4_LL_BASE (EDMA_LL_BASE + 0x0010) +#define EDMA_STREAM5_LL_BASE (EDMA_LL_BASE + 0x0014) +#define EDMA_STREAM6_LL_BASE (EDMA_LL_BASE + 0x0018) +#define EDMA_STREAM7_LL_BASE (EDMA_LL_BASE + 0x001C) +#define EDMA_STREAM8_LL_BASE (EDMA_LL_BASE + 0x0020) + +#define EDMAMUX_BASE (EDMA_BASE + 0x0140) +#define EDMAMUX_CHANNEL1_BASE (EDMAMUX_BASE) +#define EDMAMUX_CHANNEL2_BASE (EDMAMUX_BASE + 0x0004) +#define EDMAMUX_CHANNEL3_BASE (EDMAMUX_BASE + 0x0008) +#define EDMAMUX_CHANNEL4_BASE (EDMAMUX_BASE + 0x000C) +#define EDMAMUX_CHANNEL5_BASE (EDMAMUX_BASE + 0x0010) +#define EDMAMUX_CHANNEL6_BASE (EDMAMUX_BASE + 0x0014) +#define EDMAMUX_CHANNEL7_BASE (EDMAMUX_BASE + 0x0018) +#define EDMAMUX_CHANNEL8_BASE (EDMAMUX_BASE + 0x001C) + +#define EDMAMUX_GENERATOR1_BASE (EDMA_BASE + 0x0160) +#define EDMAMUX_GENERATOR2_BASE (EDMA_BASE + 0x0164) +#define EDMAMUX_GENERATOR3_BASE (EDMA_BASE + 0x0168) +#define EDMAMUX_GENERATOR4_BASE (EDMA_BASE + 0x016C) + +#define FLASH_REG_BASE (AHBPERIPH1_BASE + 0x3C00) +#define CRM_BASE (AHBPERIPH1_BASE + 0x3800) +#define CRC_BASE (AHBPERIPH1_BASE + 0x3000) +#define SDIO2_BASE (AHBPERIPH2_BASE + 0x61000) +#define DVP_BASE (AHBPERIPH2_BASE + 0x50000) +#define OTGFS1_BASE (AHBPERIPH2_BASE + 0x00000) + +#define EMAC_MAC_BASE (EMAC_BASE) +#define EMAC_MMC_BASE (EMAC_BASE + 0x0100) +#define EMAC_PTP_BASE (EMAC_BASE + 0x0700) +#define EMAC_DMA_BASE (EMAC_BASE + 0x1000) +#endif + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#include "at32f435_437_def.h" +#include "at32f435_437_conf.h" + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/CMSIS/Device/ST/AT32F43x/at32f435_437_clock.c b/lib/main/AT32F43x/Drivers/CMSIS/Device/ST/AT32F43x/at32f435_437_clock.c new file mode 100644 index 0000000000..4c3ddc3565 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/Device/ST/AT32F43x/at32f435_437_clock.c @@ -0,0 +1,142 @@ +/** + ************************************************************************** + * @file at32f435_437_clock.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief system clock config program + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* includes ------------------------------------------------------------------*/ +#include "at32f435_437_clock.h" + +/** @addtogroup AT32F437_periph_template + * @{ + */ + +/** @addtogroup 437_System_clock_configuration System_clock_configuration + * @{ + */ + +/** + * @brief system clock config program + * @note the system clock is configured as follow: + * - system clock = (hext * pll_ns)/(pll_ms * pll_fr) + * - system clock source = pll (hext) + * - hext = 8000000 + * - sclk = 288000000 + * - ahbdiv = 1 + * - ahbclk = 288000000 + * - apb2div = 2 + * - apb2clk = 144000000 + * - apb1div = 2 + * - apb1clk = 144000000 + * - pll_ns = 72 + * - pll_ms = 1 + * - pll_fr = 2 + * @param none + * @retval none + */ +void system_clock_config(void) +{ + /* enable pwc periph clock */ + crm_periph_clock_enable(CRM_PWC_PERIPH_CLOCK, TRUE); + + /* config ldo voltage */ + pwc_ldo_output_voltage_set(PWC_LDO_OUTPUT_1V3); + + /* set the flash clock divider */ + flash_clock_divider_set(FLASH_CLOCK_DIV_3); + + /* reset crm */ + crm_reset(); + + crm_clock_source_enable(CRM_CLOCK_SOURCE_HEXT, TRUE); + + /* wait till hext is ready */ + while(crm_hext_stable_wait() == ERROR) + { + } + + /* config pll clock resource + common frequency config list: pll source selected hick or hext(8mhz) + _______________________________________________________________________________________ + | | | | | | | | | | + |pll(mhz)| 288 | 252 | 216 | 180 | 144 | 108 | 72 | 36 | + |________|_________|_________|_________|_________|_________|_________|_________________| + | | | | | | | | | | + |pll_ns | 72 | 63 | 108 | 90 | 72 | 108 | 72 | 72 | + | | | | | | | | | | + |pll_ms | 1 | 1 | 1 | 1 | 1 | 1 | 1 | 1 | + | | | | | | | | | | + |pll_fr | FR_2 | FR_2 | FR_4 | FR_4 | FR_4 | FR_8 | FR_8 | FR_16| + |________|_________|_________|_________|_________|_________|_________|________|________| + + if pll clock source selects hext with other frequency values, or configure pll to other + frequency values, please use the at32 new clock configuration tool for configuration. */ + crm_pll_config(CRM_PLL_SOURCE_HEXT, 72, 1, CRM_PLL_FR_2); + + /* enable pll */ + crm_clock_source_enable(CRM_CLOCK_SOURCE_PLL, TRUE); + + /* wait till pll is ready */ + while(crm_flag_get(CRM_PLL_STABLE_FLAG) != SET) + { + } + + /* config ahbclk */ + crm_ahb_div_set(CRM_AHB_DIV_1); + + /* config apb2clk */ + crm_apb2_div_set(CRM_APB2_DIV_2); + + /* config apb1clk */ + crm_apb1_div_set(CRM_APB1_DIV_2); + + /* enable auto step mode */ + crm_auto_step_mode_enable(TRUE); + + /* select pll as system clock source */ + crm_sysclk_switch(CRM_SCLK_PLL); + + /* wait till pll is used as system clock source */ + while(crm_sysclk_switch_status_get() != CRM_SCLK_PLL) + { + } + + /* disable auto step mode */ + crm_auto_step_mode_enable(FALSE); + + /* config usbclk from pll */ + crm_usb_clock_div_set(CRM_USB_DIV_6); + crm_usb_clock_source_select(CRM_USB_CLOCK_SOURCE_PLL); + + /* update system_core_clock global variable */ + system_core_clock_update(); +} + +/** + * @} + */ + +/** + * @} + */ + diff --git a/lib/main/AT32F43x/Drivers/CMSIS/Device/ST/AT32F43x/at32f435_437_clock.h b/lib/main/AT32F43x/Drivers/CMSIS/Device/ST/AT32F43x/at32f435_437_clock.h new file mode 100644 index 0000000000..5199f2b4c0 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/Device/ST/AT32F43x/at32f435_437_clock.h @@ -0,0 +1,46 @@ +/** + ************************************************************************** + * @file at32f435_437_clock.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief header file of clock program + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_CLOCK_H +#define __AT32F435_437_CLOCK_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/* exported functions ------------------------------------------------------- */ +void system_clock_config(void); + +#ifdef __cplusplus +} +#endif + +#endif + diff --git a/lib/main/AT32F43x/Drivers/CMSIS/Device/ST/AT32F43x/at32f435_437_conf.h b/lib/main/AT32F43x/Drivers/CMSIS/Device/ST/AT32F43x/at32f435_437_conf.h new file mode 100644 index 0000000000..d715960033 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/Device/ST/AT32F43x/at32f435_437_conf.h @@ -0,0 +1,249 @@ +/** + ************************************************************************** + * @file at32f435_437_conf.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 config header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __AT32F435_437_CONF_H +#define __AT32F435_437_CONF_H + +#ifdef __cplusplus +extern "C" { +#endif + +#ifndef NULL +#ifdef __cplusplus +#define NULL 0 +#else +#define NULL ((void *) 0) +#endif +#endif + + +/** @addtogroup AT32F437_periph_template + * @{ + */ + +/** @addtogroup 437_Library_configuration Library_configuration + * @{ + */ + +/** + * @brief in the following line adjust the value of high speed exernal crystal (hext) + * used in your application + * + * tip: to avoid modifying this file each time you need to use different hext, you + * can define the hext value in your toolchain compiler preprocessor. + * + */ +#if !defined HEXT_VALUE +#define HEXT_VALUE ((uint32_t)8000000) /*!< value of the high speed exernal crystal in hz */ +#endif + +/** + * @brief in the following line adjust the high speed exernal crystal (hext) startup + * timeout value + */ +#define HEXT_STARTUP_TIMEOUT ((uint16_t)0x3000) /*!< time out for hext start up */ +#define HICK_VALUE ((uint32_t)8000000) /*!< value of the high speed internal clock in hz */ + +/* module define -------------------------------------------------------------*/ +#define CRM_MODULE_ENABLED +#define TMR_MODULE_ENABLED +#define ERTC_MODULE_ENABLED +#define GPIO_MODULE_ENABLED +#define I2C_MODULE_ENABLED +#define USART_MODULE_ENABLED +#define PWC_MODULE_ENABLED +#define CAN_MODULE_ENABLED +#define ADC_MODULE_ENABLED +#define DAC_MODULE_ENABLED +#define SPI_MODULE_ENABLED +#define EDMA_MODULE_ENABLED +#define DMA_MODULE_ENABLED +#define DEBUG_MODULE_ENABLED +#define FLASH_MODULE_ENABLED +#define CRC_MODULE_ENABLED +#define WWDT_MODULE_ENABLED +#define WDT_MODULE_ENABLED +#define EXINT_MODULE_ENABLED +#define SDIO_MODULE_ENABLED +#define XMC_MODULE_ENABLED +#define USB_MODULE_ENABLED +#define ACC_MODULE_ENABLED +#define MISC_MODULE_ENABLED +#define QSPI_MODULE_ENABLED +#define DVP_MODULE_ENABLED +#define SCFG_MODULE_ENABLED +#define EMAC_MODULE_ENABLED + +/* includes ------------------------------------------------------------------*/ +#ifdef CRM_MODULE_ENABLED +#include "at32f435_437_crm.h" +#endif +#ifdef TMR_MODULE_ENABLED + +#include "at32f435_437_tmr.h" + +#endif +#ifdef ERTC_MODULE_ENABLED + +#include "at32f435_437_ertc.h" + +#endif +#ifdef GPIO_MODULE_ENABLED + +#include "at32f435_437_gpio.h" + +#endif +#ifdef I2C_MODULE_ENABLED + +#include "at32f435_437_i2c.h" + +#endif +#ifdef USART_MODULE_ENABLED + +#include "at32f435_437_usart.h" + +#endif +#ifdef PWC_MODULE_ENABLED + +#include "at32f435_437_pwc.h" + +#endif +#ifdef CAN_MODULE_ENABLED + +#include "at32f435_437_can.h" + +#endif +#ifdef ADC_MODULE_ENABLED + +#include "at32f435_437_adc.h" + +#endif +#ifdef DAC_MODULE_ENABLED + +#include "at32f435_437_dac.h" + +#endif +#ifdef SPI_MODULE_ENABLED + +#include "at32f435_437_spi.h" + +#endif +#ifdef DMA_MODULE_ENABLED + +#include "at32f435_437_dma.h" + +#endif +#ifdef DEBUG_MODULE_ENABLED + +#include "at32f435_437_debug.h" + +#endif +#ifdef FLASH_MODULE_ENABLED + +#include "at32f435_437_flash.h" + +#endif +#ifdef CRC_MODULE_ENABLED + +#include "at32f435_437_crc.h" + +#endif +#ifdef WWDT_MODULE_ENABLED + +#include "at32f435_437_wwdt.h" + +#endif +#ifdef WDT_MODULE_ENABLED + +#include "at32f435_437_wdt.h" + +#endif +#ifdef EXINT_MODULE_ENABLED + +#include "at32f435_437_exint.h" + +#endif +#ifdef SDIO_MODULE_ENABLED + +#include "at32f435_437_sdio.h" + +#endif +#ifdef XMC_MODULE_ENABLED + +#include "at32f435_437_xmc.h" + +#endif +#ifdef ACC_MODULE_ENABLED + +#include "at32f435_437_acc.h" + +#endif +#ifdef MISC_MODULE_ENABLED + +#include "at32f435_437_misc.h" + +#endif +#ifdef EDMA_MODULE_ENABLED + +#include "at32f435_437_edma.h" + +#endif +#ifdef QSPI_MODULE_ENABLED +#include "at32f435_437_qspi.h" + +#endif +#ifdef SCFG_MODULE_ENABLED +#include "at32f435_437_scfg.h" + +#endif +#ifdef EMAC_MODULE_ENABLED +#include "at32f435_437_emac.h" + +#endif +#ifdef DVP_MODULE_ENABLED +#include "at32f435_437_dvp.h" + +#endif +#ifdef USB_MODULE_ENABLED + +#include "at32f435_437_usb.h" + +#endif + +/** + * @} + */ + + /** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_common_tables.h b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_common_tables.h new file mode 100644 index 0000000000..721b18dd2d --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_common_tables.h @@ -0,0 +1,517 @@ +/* ---------------------------------------------------------------------- + * Project: CMSIS DSP Library + * Title: arm_common_tables.h + * Description: Extern declaration for common tables + * + * $Date: 27. January 2017 + * $Revision: V.1.5.1 + * + * Target Processor: Cortex-M cores + * -------------------------------------------------------------------- */ +/* + * Copyright (C) 2010-2017 ARM Limited or its affiliates. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * 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 + * + * www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an AS IS BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef _ARM_COMMON_TABLES_H +#define _ARM_COMMON_TABLES_H + +#include "arm_math.h" + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_FFT_ALLOW_TABLES) + /* Double Precision Float CFFT twiddles */ + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREV_1024) + extern const uint16_t armBitRevTable[1024]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F64_16) + extern const uint64_t twiddleCoefF64_16[32]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F64_32) + extern const uint64_t twiddleCoefF64_32[64]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F64_64) + extern const uint64_t twiddleCoefF64_64[128]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F64_128) + extern const uint64_t twiddleCoefF64_128[256]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F64_256) + extern const uint64_t twiddleCoefF64_256[512]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F64_512) + extern const uint64_t twiddleCoefF64_512[1024]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F64_1024) + extern const uint64_t twiddleCoefF64_1024[2048]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F64_2048) + extern const uint64_t twiddleCoefF64_2048[4096]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F64_4096) + extern const uint64_t twiddleCoefF64_4096[8192]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F32_16) + extern const float32_t twiddleCoef_16[32]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F32_32) + extern const float32_t twiddleCoef_32[64]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F32_64) + extern const float32_t twiddleCoef_64[128]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F32_128) + extern const float32_t twiddleCoef_128[256]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F32_256) + extern const float32_t twiddleCoef_256[512]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F32_512) + extern const float32_t twiddleCoef_512[1024]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F32_1024) + extern const float32_t twiddleCoef_1024[2048]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F32_2048) + extern const float32_t twiddleCoef_2048[4096]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F32_4096) + extern const float32_t twiddleCoef_4096[8192]; + #define twiddleCoef twiddleCoef_4096 + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q31_16) + extern const q31_t twiddleCoef_16_q31[24]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q31_32) + extern const q31_t twiddleCoef_32_q31[48]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q31_64) + extern const q31_t twiddleCoef_64_q31[96]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q31_128) + extern const q31_t twiddleCoef_128_q31[192]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q31_256) + extern const q31_t twiddleCoef_256_q31[384]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q31_512) + extern const q31_t twiddleCoef_512_q31[768]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q31_1024) + extern const q31_t twiddleCoef_1024_q31[1536]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q31_2048) + extern const q31_t twiddleCoef_2048_q31[3072]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q31_4096) + extern const q31_t twiddleCoef_4096_q31[6144]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q15_16) + extern const q15_t twiddleCoef_16_q15[24]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q15_32) + extern const q15_t twiddleCoef_32_q15[48]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q15_64) + extern const q15_t twiddleCoef_64_q15[96]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q15_128) + extern const q15_t twiddleCoef_128_q15[192]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q15_256) + extern const q15_t twiddleCoef_256_q15[384]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q15_512) + extern const q15_t twiddleCoef_512_q15[768]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q15_1024) + extern const q15_t twiddleCoef_1024_q15[1536]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q15_2048) + extern const q15_t twiddleCoef_2048_q15[3072]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q15_4096) + extern const q15_t twiddleCoef_4096_q15[6144]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + /* Double Precision Float RFFT twiddles */ + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F64_32) + extern const uint64_t twiddleCoefF64_rfft_32[32]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F64_64) + extern const uint64_t twiddleCoefF64_rfft_64[64]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F64_128) + extern const uint64_t twiddleCoefF64_rfft_128[128]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F64_256) + extern const uint64_t twiddleCoefF64_rfft_256[256]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F64_512) + extern const uint64_t twiddleCoefF64_rfft_512[512]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F64_1024) + extern const uint64_t twiddleCoefF64_rfft_1024[1024]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F64_2048) + extern const uint64_t twiddleCoefF64_rfft_2048[2048]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F64_4096) + extern const uint64_t twiddleCoefF64_rfft_4096[4096]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F32_32) + extern const float32_t twiddleCoef_rfft_32[32]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F32_64) + extern const float32_t twiddleCoef_rfft_64[64]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F32_128) + extern const float32_t twiddleCoef_rfft_128[128]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F32_256) + extern const float32_t twiddleCoef_rfft_256[256]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F32_512) + extern const float32_t twiddleCoef_rfft_512[512]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F32_1024) + extern const float32_t twiddleCoef_rfft_1024[1024]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F32_2048) + extern const float32_t twiddleCoef_rfft_2048[2048]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_RFFT_F32_4096) + extern const float32_t twiddleCoef_rfft_4096[4096]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + + /* Double precision floating-point bit reversal tables */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT64_16) + #define ARMBITREVINDEXTABLEF64_16_TABLE_LENGTH ((uint16_t)12) + extern const uint16_t armBitRevIndexTableF64_16[ARMBITREVINDEXTABLEF64_16_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT64_32) + #define ARMBITREVINDEXTABLEF64_32_TABLE_LENGTH ((uint16_t)24) + extern const uint16_t armBitRevIndexTableF64_32[ARMBITREVINDEXTABLEF64_32_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT64_64) + #define ARMBITREVINDEXTABLEF64_64_TABLE_LENGTH ((uint16_t)56) + extern const uint16_t armBitRevIndexTableF64_64[ARMBITREVINDEXTABLEF64_64_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT64_128) + #define ARMBITREVINDEXTABLEF64_128_TABLE_LENGTH ((uint16_t)112) + extern const uint16_t armBitRevIndexTableF64_128[ARMBITREVINDEXTABLEF64_128_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT64_256) + #define ARMBITREVINDEXTABLEF64_256_TABLE_LENGTH ((uint16_t)240) + extern const uint16_t armBitRevIndexTableF64_256[ARMBITREVINDEXTABLEF64_256_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT64_512) + #define ARMBITREVINDEXTABLEF64_512_TABLE_LENGTH ((uint16_t)480) + extern const uint16_t armBitRevIndexTableF64_512[ARMBITREVINDEXTABLEF64_512_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT64_1024) + #define ARMBITREVINDEXTABLEF64_1024_TABLE_LENGTH ((uint16_t)992) + extern const uint16_t armBitRevIndexTableF64_1024[ARMBITREVINDEXTABLEF64_1024_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT64_2048) + #define ARMBITREVINDEXTABLEF64_2048_TABLE_LENGTH ((uint16_t)1984) + extern const uint16_t armBitRevIndexTableF64_2048[ARMBITREVINDEXTABLEF64_2048_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT64_4096) + #define ARMBITREVINDEXTABLEF64_4096_TABLE_LENGTH ((uint16_t)4032) + extern const uint16_t armBitRevIndexTableF64_4096[ARMBITREVINDEXTABLEF64_4096_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + /* floating-point bit reversal tables */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT_16) + #define ARMBITREVINDEXTABLE_16_TABLE_LENGTH ((uint16_t)20) + extern const uint16_t armBitRevIndexTable16[ARMBITREVINDEXTABLE_16_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT_32) + #define ARMBITREVINDEXTABLE_32_TABLE_LENGTH ((uint16_t)48) + extern const uint16_t armBitRevIndexTable32[ARMBITREVINDEXTABLE_32_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT_64) + #define ARMBITREVINDEXTABLE_64_TABLE_LENGTH ((uint16_t)56) + extern const uint16_t armBitRevIndexTable64[ARMBITREVINDEXTABLE_64_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT_128) + #define ARMBITREVINDEXTABLE_128_TABLE_LENGTH ((uint16_t)208) + extern const uint16_t armBitRevIndexTable128[ARMBITREVINDEXTABLE_128_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT_256) + #define ARMBITREVINDEXTABLE_256_TABLE_LENGTH ((uint16_t)440) + extern const uint16_t armBitRevIndexTable256[ARMBITREVINDEXTABLE_256_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT_512) + #define ARMBITREVINDEXTABLE_512_TABLE_LENGTH ((uint16_t)448) + extern const uint16_t armBitRevIndexTable512[ARMBITREVINDEXTABLE_512_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT_1024) + #define ARMBITREVINDEXTABLE_1024_TABLE_LENGTH ((uint16_t)1800) + extern const uint16_t armBitRevIndexTable1024[ARMBITREVINDEXTABLE_1024_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT_2048) + #define ARMBITREVINDEXTABLE_2048_TABLE_LENGTH ((uint16_t)3808) + extern const uint16_t armBitRevIndexTable2048[ARMBITREVINDEXTABLE_2048_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FLT_4096) + #define ARMBITREVINDEXTABLE_4096_TABLE_LENGTH ((uint16_t)4032) + extern const uint16_t armBitRevIndexTable4096[ARMBITREVINDEXTABLE_4096_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + + /* fixed-point bit reversal tables */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FXT_16) + #define ARMBITREVINDEXTABLE_FIXED_16_TABLE_LENGTH ((uint16_t)12) + extern const uint16_t armBitRevIndexTable_fixed_16[ARMBITREVINDEXTABLE_FIXED_16_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FXT_32) + #define ARMBITREVINDEXTABLE_FIXED_32_TABLE_LENGTH ((uint16_t)24) + extern const uint16_t armBitRevIndexTable_fixed_32[ARMBITREVINDEXTABLE_FIXED_32_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FXT_64) + #define ARMBITREVINDEXTABLE_FIXED_64_TABLE_LENGTH ((uint16_t)56) + extern const uint16_t armBitRevIndexTable_fixed_64[ARMBITREVINDEXTABLE_FIXED_64_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FXT_128) + #define ARMBITREVINDEXTABLE_FIXED_128_TABLE_LENGTH ((uint16_t)112) + extern const uint16_t armBitRevIndexTable_fixed_128[ARMBITREVINDEXTABLE_FIXED_128_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FXT_256) + #define ARMBITREVINDEXTABLE_FIXED_256_TABLE_LENGTH ((uint16_t)240) + extern const uint16_t armBitRevIndexTable_fixed_256[ARMBITREVINDEXTABLE_FIXED_256_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FXT_512) + #define ARMBITREVINDEXTABLE_FIXED_512_TABLE_LENGTH ((uint16_t)480) + extern const uint16_t armBitRevIndexTable_fixed_512[ARMBITREVINDEXTABLE_FIXED_512_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FXT_1024) + #define ARMBITREVINDEXTABLE_FIXED_1024_TABLE_LENGTH ((uint16_t)992) + extern const uint16_t armBitRevIndexTable_fixed_1024[ARMBITREVINDEXTABLE_FIXED_1024_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FXT_2048) + #define ARMBITREVINDEXTABLE_FIXED_2048_TABLE_LENGTH ((uint16_t)1984) + extern const uint16_t armBitRevIndexTable_fixed_2048[ARMBITREVINDEXTABLE_FIXED_2048_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_BITREVIDX_FXT_4096) + #define ARMBITREVINDEXTABLE_FIXED_4096_TABLE_LENGTH ((uint16_t)4032) + extern const uint16_t armBitRevIndexTable_fixed_4096[ARMBITREVINDEXTABLE_FIXED_4096_TABLE_LENGTH]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_REALCOEF_F32) + extern const float32_t realCoefA[8192]; + extern const float32_t realCoefB[8192]; + #endif + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_REALCOEF_Q31) + extern const q31_t realCoefAQ31[8192]; + extern const q31_t realCoefBQ31[8192]; + #endif + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_REALCOEF_Q15) + extern const q15_t realCoefAQ15[8192]; + extern const q15_t realCoefBQ15[8192]; + #endif + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_DCT4_F32_128) + extern const float32_t Weights_128[256]; + extern const float32_t cos_factors_128[128]; + #endif + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_DCT4_F32_512) + extern const float32_t Weights_512[1024]; + extern const float32_t cos_factors_512[512]; + #endif + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_DCT4_F32_2048) + extern const float32_t Weights_2048[4096]; + extern const float32_t cos_factors_2048[2048]; + #endif + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_DCT4_F32_8192) + extern const float32_t Weights_8192[16384]; + extern const float32_t cos_factors_8192[8192]; + #endif + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_DCT4_Q15_128) + extern const q15_t WeightsQ15_128[256]; + extern const q15_t cos_factorsQ15_128[128]; + #endif + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_DCT4_Q15_512) + extern const q15_t WeightsQ15_512[1024]; + extern const q15_t cos_factorsQ15_512[512]; + #endif + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_DCT4_Q15_2048) + extern const q15_t WeightsQ15_2048[4096]; + extern const q15_t cos_factorsQ15_2048[2048]; + #endif + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_DCT4_Q15_8192) + extern const q15_t WeightsQ15_8192[16384]; + extern const q15_t cos_factorsQ15_8192[8192]; + #endif + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_DCT4_Q31_128) + extern const q31_t WeightsQ31_128[256]; + extern const q31_t cos_factorsQ31_128[128]; + #endif + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_DCT4_Q31_512) + extern const q31_t WeightsQ31_512[1024]; + extern const q31_t cos_factorsQ31_512[512]; + #endif + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_DCT4_Q31_2048) + extern const q31_t WeightsQ31_2048[4096]; + extern const q31_t cos_factorsQ31_2048[2048]; + #endif + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_DCT4_Q31_8192) + extern const q31_t WeightsQ31_8192[16384]; + extern const q31_t cos_factorsQ31_8192[8192]; + #endif + +#endif /* if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_FFT_TABLES) */ + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_FAST_ALLOW_TABLES) + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FAST_TABLES) || defined(ARM_TABLE_RECIP_Q15) + extern const q15_t armRecipTableQ15[64]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) defined(ARM_ALL_FAST_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FAST_TABLES) || defined(ARM_TABLE_RECIP_Q31) + extern const q31_t armRecipTableQ31[64]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) defined(ARM_ALL_FAST_TABLES) */ + + /* Tables for Fast Math Sine and Cosine */ + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FAST_TABLES) || defined(ARM_TABLE_SIN_F32) + extern const float32_t sinTable_f32[FAST_MATH_TABLE_SIZE + 1]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) defined(ARM_ALL_FAST_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FAST_TABLES) || defined(ARM_TABLE_SIN_Q31) + extern const q31_t sinTable_q31[FAST_MATH_TABLE_SIZE + 1]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) defined(ARM_ALL_FAST_TABLES) */ + + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FAST_TABLES) || defined(ARM_TABLE_SIN_Q15) + extern const q15_t sinTable_q15[FAST_MATH_TABLE_SIZE + 1]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) defined(ARM_ALL_FAST_TABLES) */ + + #if defined(ARM_MATH_MVEI) + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FAST_TABLES) || defined(ARM_TABLE_FAST_SQRT_Q31_MVE) + extern const q31_t sqrtTable_Q31[256]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) defined(ARM_ALL_FAST_TABLES) */ + #endif + + #if defined(ARM_MATH_MVEI) + #if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FAST_TABLES) || defined(ARM_TABLE_FAST_SQRT_Q15_MVE) + extern const q15_t sqrtTable_Q15[256]; + #endif /* !defined(ARM_DSP_CONFIG_TABLES) defined(ARM_ALL_FAST_TABLES) */ + #endif + +#endif /* if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_FAST_TABLES) */ + +#if (defined(ARM_MATH_MVEF) || defined(ARM_MATH_HELIUM)) && !defined(ARM_MATH_AUTOVECTORIZE) + extern const float32_t exp_tab[8]; + extern const float32_t __logf_lut_f32[8]; +#endif /* (defined(ARM_MATH_MVEF) || defined(ARM_MATH_HELIUM)) && !defined(ARM_MATH_AUTOVECTORIZE) */ + +#if (defined(ARM_MATH_MVEI) || defined(ARM_MATH_HELIUM)) +extern const unsigned char hwLUT[256]; +#endif /* (defined(ARM_MATH_MVEI) || defined(ARM_MATH_HELIUM)) */ + +#endif /* ARM_COMMON_TABLES_H */ + diff --git a/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_const_structs.h b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_const_structs.h new file mode 100644 index 0000000000..83984c40cd --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_const_structs.h @@ -0,0 +1,76 @@ +/* ---------------------------------------------------------------------- + * Project: CMSIS DSP Library + * Title: arm_const_structs.h + * Description: Constant structs that are initialized for user convenience. + * For example, some can be given as arguments to the arm_cfft_f32() function. + * + * $Date: 27. January 2017 + * $Revision: V.1.5.1 + * + * Target Processor: Cortex-M cores + * -------------------------------------------------------------------- */ +/* + * Copyright (C) 2010-2017 ARM Limited or its affiliates. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * 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 + * + * www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an AS IS BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef _ARM_CONST_STRUCTS_H +#define _ARM_CONST_STRUCTS_H + +#include "arm_math.h" +#include "arm_common_tables.h" + + extern const arm_cfft_instance_f64 arm_cfft_sR_f64_len16; + extern const arm_cfft_instance_f64 arm_cfft_sR_f64_len32; + extern const arm_cfft_instance_f64 arm_cfft_sR_f64_len64; + extern const arm_cfft_instance_f64 arm_cfft_sR_f64_len128; + extern const arm_cfft_instance_f64 arm_cfft_sR_f64_len256; + extern const arm_cfft_instance_f64 arm_cfft_sR_f64_len512; + extern const arm_cfft_instance_f64 arm_cfft_sR_f64_len1024; + extern const arm_cfft_instance_f64 arm_cfft_sR_f64_len2048; + extern const arm_cfft_instance_f64 arm_cfft_sR_f64_len4096; + + extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len16; + extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len32; + extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len64; + extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len128; + extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len256; + extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len512; + extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len1024; + extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len2048; + extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len4096; + + extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len16; + extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len32; + extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len64; + extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len128; + extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len256; + extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len512; + extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len1024; + extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len2048; + extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len4096; + + extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len16; + extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len32; + extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len64; + extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len128; + extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len256; + extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len512; + extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len1024; + extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len2048; + extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len4096; + +#endif diff --git a/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_helium_utils.h b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_helium_utils.h new file mode 100644 index 0000000000..7609d329f0 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_helium_utils.h @@ -0,0 +1,348 @@ +/* ---------------------------------------------------------------------- + * Project: CMSIS DSP Library + * Title: arm_helium_utils.h + * Description: Utility functions for Helium development + * + * $Date: 09. September 2019 + * $Revision: V.1.5.1 + * + * Target Processor: Cortex-M cores + * -------------------------------------------------------------------- */ +/* + * Copyright (C) 2010-2019 ARM Limited or its affiliates. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * 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 + * + * www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an AS IS BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef _ARM_UTILS_HELIUM_H_ +#define _ARM_UTILS_HELIUM_H_ + +/*************************************** + +Definitions available for MVEF and MVEI + +***************************************/ +#if defined (ARM_MATH_HELIUM) || defined(ARM_MATH_MVEF) || defined(ARM_MATH_MVEI) + +#define INACTIVELANE 0 /* inactive lane content */ + + +#endif /* defined (ARM_MATH_HELIUM) || defined(ARM_MATH_MVEF) || defined(ARM_MATH_MVEI) */ + +/*************************************** + +Definitions available for MVEF only + +***************************************/ +#if defined (ARM_MATH_HELIUM) || defined(ARM_MATH_MVEF) + +__STATIC_FORCEINLINE float32_t vecAddAcrossF32Mve(float32x4_t in) +{ + float32_t acc; + + acc = vgetq_lane(in, 0) + vgetq_lane(in, 1) + + vgetq_lane(in, 2) + vgetq_lane(in, 3); + + return acc; +} + +/* newton initial guess */ +#define INVSQRT_MAGIC_F32 0x5f3759df + +#define INVSQRT_NEWTON_MVE_F32(invSqrt, xHalf, xStart)\ +{ \ + float32x4_t tmp; \ + \ + /* tmp = xhalf * x * x */ \ + tmp = vmulq(xStart, xStart); \ + tmp = vmulq(tmp, xHalf); \ + /* (1.5f - xhalf * x * x) */ \ + tmp = vsubq(vdupq_n_f32(1.5f), tmp); \ + /* x = x*(1.5f-xhalf*x*x); */ \ + invSqrt = vmulq(tmp, xStart); \ +} +#endif /* defined (ARM_MATH_HELIUM) || defined(ARM_MATH_MVEF) */ + +/*************************************** + +Definitions available for MVEI only + +***************************************/ +#if defined (ARM_MATH_HELIUM) || defined(ARM_MATH_MVEI) + + +#include "arm_common_tables.h" + +/* Following functions are used to transpose matrix in f32 and q31 cases */ +__STATIC_INLINE arm_status arm_mat_trans_32bit_2x2_mve( + uint32_t * pDataSrc, + uint32_t * pDataDest) +{ + static const uint32x4_t vecOffs = { 0, 2, 1, 3 }; + /* + * + * | 0 1 | => | 0 2 | + * | 2 3 | | 1 3 | + * + */ + uint32x4_t vecIn = vldrwq_u32((uint32_t const *)pDataSrc); + vstrwq_scatter_shifted_offset_u32(pDataDest, vecOffs, vecIn); + + return (ARM_MATH_SUCCESS); +} + +__STATIC_INLINE arm_status arm_mat_trans_32bit_3x3_mve( + uint32_t * pDataSrc, + uint32_t * pDataDest) +{ + const uint32x4_t vecOffs1 = { 0, 3, 6, 1}; + const uint32x4_t vecOffs2 = { 4, 7, 2, 5}; + /* + * + * | 0 1 2 | | 0 3 6 | 4 x 32 flattened version | 0 3 6 1 | + * | 3 4 5 | => | 1 4 7 | => | 4 7 2 5 | + * | 6 7 8 | | 2 5 8 | (row major) | 8 . . . | + * + */ + uint32x4_t vecIn1 = vldrwq_u32((uint32_t const *) pDataSrc); + uint32x4_t vecIn2 = vldrwq_u32((uint32_t const *) &pDataSrc[4]); + + vstrwq_scatter_shifted_offset_u32(pDataDest, vecOffs1, vecIn1); + vstrwq_scatter_shifted_offset_u32(pDataDest, vecOffs2, vecIn2); + + pDataDest[8] = pDataSrc[8]; + + return (ARM_MATH_SUCCESS); +} + +__STATIC_INLINE arm_status arm_mat_trans_32bit_4x4_mve(uint32_t * pDataSrc, uint32_t * pDataDest) +{ + /* + * 4x4 Matrix transposition + * is 4 x de-interleave operation + * + * 0 1 2 3 0 4 8 12 + * 4 5 6 7 1 5 9 13 + * 8 9 10 11 2 6 10 14 + * 12 13 14 15 3 7 11 15 + */ + + uint32x4x4_t vecIn; + + vecIn = vld4q((uint32_t const *) pDataSrc); + vstrwq(pDataDest, vecIn.val[0]); + pDataDest += 4; + vstrwq(pDataDest, vecIn.val[1]); + pDataDest += 4; + vstrwq(pDataDest, vecIn.val[2]); + pDataDest += 4; + vstrwq(pDataDest, vecIn.val[3]); + + return (ARM_MATH_SUCCESS); +} + + +__STATIC_INLINE arm_status arm_mat_trans_32bit_generic_mve( + uint16_t srcRows, + uint16_t srcCols, + uint32_t * pDataSrc, + uint32_t * pDataDest) +{ + uint32x4_t vecOffs; + uint32_t i; + uint32_t blkCnt; + uint32_t const *pDataC; + uint32_t *pDataDestR; + uint32x4_t vecIn; + + vecOffs = vidupq_u32((uint32_t)0, 1); + vecOffs = vecOffs * srcCols; + + i = srcCols; + do + { + pDataC = (uint32_t const *) pDataSrc; + pDataDestR = pDataDest; + + blkCnt = srcRows >> 2; + while (blkCnt > 0U) + { + vecIn = vldrwq_gather_shifted_offset_u32(pDataC, vecOffs); + vstrwq(pDataDestR, vecIn); + pDataDestR += 4; + pDataC = pDataC + srcCols * 4; + /* + * Decrement the blockSize loop counter + */ + blkCnt--; + } + + /* + * tail + */ + blkCnt = srcRows & 3; + if (blkCnt > 0U) + { + mve_pred16_t p0 = vctp32q(blkCnt); + vecIn = vldrwq_gather_shifted_offset_u32(pDataC, vecOffs); + vstrwq_p(pDataDestR, vecIn, p0); + } + + pDataSrc += 1; + pDataDest += srcRows; + } + while (--i); + + return (ARM_MATH_SUCCESS); +} + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FAST_TABLES) || defined(ARM_TABLE_FAST_SQRT_Q31_MVE) +__STATIC_INLINE q31x4_t FAST_VSQRT_Q31(q31x4_t vecIn) +{ + q63x2_t vecTmpLL; + q31x4_t vecTmp0, vecTmp1; + q31_t scale; + q63_t tmp64; + q31x4_t vecNrm, vecDst, vecIdx, vecSignBits; + + + vecSignBits = vclsq(vecIn); + vecSignBits = vbicq(vecSignBits, 1); + /* + * in = in << no_of_sign_bits; + */ + vecNrm = vshlq(vecIn, vecSignBits); + /* + * index = in >> 24; + */ + vecIdx = vecNrm >> 24; + vecIdx = vecIdx << 1; + + vecTmp0 = vldrwq_gather_shifted_offset_s32(sqrtTable_Q31, vecIdx); + + vecIdx = vecIdx + 1; + + vecTmp1 = vldrwq_gather_shifted_offset_s32(sqrtTable_Q31, vecIdx); + + vecTmp1 = vqrdmulhq(vecTmp1, vecNrm); + vecTmp0 = vecTmp0 - vecTmp1; + vecTmp1 = vqrdmulhq(vecTmp0, vecTmp0); + vecTmp1 = vqrdmulhq(vecNrm, vecTmp1); + vecTmp1 = vdupq_n_s32(0x18000000) - vecTmp1; + vecTmp0 = vqrdmulhq(vecTmp0, vecTmp1); + vecTmpLL = vmullbq_int(vecNrm, vecTmp0); + + /* + * scale elements 0, 2 + */ + scale = 26 + (vecSignBits[0] >> 1); + tmp64 = asrl(vecTmpLL[0], scale); + vecDst[0] = (q31_t) tmp64; + + scale = 26 + (vecSignBits[2] >> 1); + tmp64 = asrl(vecTmpLL[1], scale); + vecDst[2] = (q31_t) tmp64; + + vecTmpLL = vmulltq_int(vecNrm, vecTmp0); + + /* + * scale elements 1, 3 + */ + scale = 26 + (vecSignBits[1] >> 1); + tmp64 = asrl(vecTmpLL[0], scale); + vecDst[1] = (q31_t) tmp64; + + scale = 26 + (vecSignBits[3] >> 1); + tmp64 = asrl(vecTmpLL[1], scale); + vecDst[3] = (q31_t) tmp64; + /* + * set negative values to 0 + */ + vecDst = vdupq_m(vecDst, 0, vcmpltq_n_s32(vecIn, 0)); + + return vecDst; +} +#endif + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FAST_TABLES) || defined(ARM_TABLE_FAST_SQRT_Q15_MVE) +__STATIC_INLINE q15x8_t FAST_VSQRT_Q15(q15x8_t vecIn) +{ + q31x4_t vecTmpLev, vecTmpLodd, vecSignL; + q15x8_t vecTmp0, vecTmp1; + q15x8_t vecNrm, vecDst, vecIdx, vecSignBits; + + vecDst = vuninitializedq_s16(); + + vecSignBits = vclsq(vecIn); + vecSignBits = vbicq(vecSignBits, 1); + /* + * in = in << no_of_sign_bits; + */ + vecNrm = vshlq(vecIn, vecSignBits); + + vecIdx = vecNrm >> 8; + vecIdx = vecIdx << 1; + + vecTmp0 = vldrhq_gather_shifted_offset_s16(sqrtTable_Q15, vecIdx); + + vecIdx = vecIdx + 1; + + vecTmp1 = vldrhq_gather_shifted_offset_s16(sqrtTable_Q15, vecIdx); + + vecTmp1 = vqrdmulhq(vecTmp1, vecNrm); + vecTmp0 = vecTmp0 - vecTmp1; + vecTmp1 = vqrdmulhq(vecTmp0, vecTmp0); + vecTmp1 = vqrdmulhq(vecNrm, vecTmp1); + vecTmp1 = vdupq_n_s16(0x1800) - vecTmp1; + vecTmp0 = vqrdmulhq(vecTmp0, vecTmp1); + + vecSignBits = vecSignBits >> 1; + + vecTmpLev = vmullbq_int(vecNrm, vecTmp0); + vecTmpLodd = vmulltq_int(vecNrm, vecTmp0); + + vecTmp0 = vecSignBits + 10; + /* + * negate sign to apply register based vshl + */ + vecTmp0 = -vecTmp0; + + /* + * shift even elements + */ + vecSignL = vmovlbq(vecTmp0); + vecTmpLev = vshlq(vecTmpLev, vecSignL); + /* + * shift odd elements + */ + vecSignL = vmovltq(vecTmp0); + vecTmpLodd = vshlq(vecTmpLodd, vecSignL); + /* + * merge and narrow odd and even parts + */ + vecDst = vmovnbq_s32(vecDst, vecTmpLev); + vecDst = vmovntq_s32(vecDst, vecTmpLodd); + /* + * set negative values to 0 + */ + vecDst = vdupq_m(vecDst, 0, vcmpltq_n_s16(vecIn, 0)); + + return vecDst; +} +#endif + +#endif /* defined (ARM_MATH_HELIUM) || defined(ARM_MATH_MVEI) */ + +#endif diff --git a/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_math.h b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_math.h new file mode 100644 index 0000000000..48bee62cd9 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_math.h @@ -0,0 +1,8970 @@ +/****************************************************************************** + * @file arm_math.h + * @brief Public header file for CMSIS DSP Library + * @version V1.7.0 + * @date 18. March 2019 + ******************************************************************************/ +/* + * Copyright (c) 2010-2019 Arm Limited or its affiliates. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * 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 + * + * 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. + */ + +/** + \mainpage CMSIS DSP Software Library + * + * Introduction + * ------------ + * + * This user manual describes the CMSIS DSP software library, + * a suite of common signal processing functions for use on Cortex-M and Cortex-A processor + * based devices. + * + * The library is divided into a number of functions each covering a specific category: + * - Basic math functions + * - Fast math functions + * - Complex math functions + * - Filtering functions + * - Matrix functions + * - Transform functions + * - Motor control functions + * - Statistical functions + * - Support functions + * - Interpolation functions + * - Support Vector Machine functions (SVM) + * - Bayes classifier functions + * - Distance functions + * + * The library has generally separate functions for operating on 8-bit integers, 16-bit integers, + * 32-bit integer and 32-bit floating-point values. + * + * Using the Library + * ------------ + * + * The library installer contains prebuilt versions of the libraries in the Lib folder. + * + * Here is the list of pre-built libraries : + * - arm_cortexM7lfdp_math.lib (Cortex-M7, Little endian, Double Precision Floating Point Unit) + * - arm_cortexM7bfdp_math.lib (Cortex-M7, Big endian, Double Precision Floating Point Unit) + * - arm_cortexM7lfsp_math.lib (Cortex-M7, Little endian, Single Precision Floating Point Unit) + * - arm_cortexM7bfsp_math.lib (Cortex-M7, Big endian and Single Precision Floating Point Unit on) + * - arm_cortexM7l_math.lib (Cortex-M7, Little endian) + * - arm_cortexM7b_math.lib (Cortex-M7, Big endian) + * - arm_cortexM4lf_math.lib (Cortex-M4, Little endian, Floating Point Unit) + * - arm_cortexM4bf_math.lib (Cortex-M4, Big endian, Floating Point Unit) + * - arm_cortexM4l_math.lib (Cortex-M4, Little endian) + * - arm_cortexM4b_math.lib (Cortex-M4, Big endian) + * - arm_cortexM3l_math.lib (Cortex-M3, Little endian) + * - arm_cortexM3b_math.lib (Cortex-M3, Big endian) + * - arm_cortexM0l_math.lib (Cortex-M0 / Cortex-M0+, Little endian) + * - arm_cortexM0b_math.lib (Cortex-M0 / Cortex-M0+, Big endian) + * - arm_ARMv8MBLl_math.lib (Armv8-M Baseline, Little endian) + * - arm_ARMv8MMLl_math.lib (Armv8-M Mainline, Little endian) + * - arm_ARMv8MMLlfsp_math.lib (Armv8-M Mainline, Little endian, Single Precision Floating Point Unit) + * - arm_ARMv8MMLld_math.lib (Armv8-M Mainline, Little endian, DSP instructions) + * - arm_ARMv8MMLldfsp_math.lib (Armv8-M Mainline, Little endian, DSP instructions, Single Precision Floating Point Unit) + * + * The library functions are declared in the public file arm_math.h which is placed in the Include folder. + * Simply include this file and link the appropriate library in the application and begin calling the library functions. The Library supports single + * public header file arm_math.h for Cortex-M cores with little endian and big endian. Same header file will be used for floating point unit(FPU) variants. + * + * + * Examples + * -------- + * + * The library ships with a number of examples which demonstrate how to use the library functions. + * + * Toolchain Support + * ------------ + * + * The library is now tested on Fast Models building with cmake. + * Core M0, M7, A5 are tested. + * + * + * + * Building the Library + * ------------ + * + * The library installer contains a project file to rebuild libraries on MDK toolchain in the CMSIS\\DSP\\Projects\\ARM folder. + * - arm_cortexM_math.uvprojx + * + * + * The libraries can be built by opening the arm_cortexM_math.uvprojx project in MDK-ARM, selecting a specific target, and defining the optional preprocessor macros detailed above. + * + * There is also a work in progress cmake build. The README file is giving more details. + * + * Preprocessor Macros + * ------------ + * + * Each library project have different preprocessor macros. + * + * - ARM_MATH_BIG_ENDIAN: + * + * Define macro ARM_MATH_BIG_ENDIAN to build the library for big endian targets. By default library builds for little endian targets. + * + * - ARM_MATH_MATRIX_CHECK: + * + * Define macro ARM_MATH_MATRIX_CHECK for checking on the input and output sizes of matrices + * + * - ARM_MATH_ROUNDING: + * + * Define macro ARM_MATH_ROUNDING for rounding on support functions + * + * - ARM_MATH_LOOPUNROLL: + * + * Define macro ARM_MATH_LOOPUNROLL to enable manual loop unrolling in DSP functions + * + * - ARM_MATH_NEON: + * + * Define macro ARM_MATH_NEON to enable Neon versions of the DSP functions. + * It is not enabled by default when Neon is available because performances are + * dependent on the compiler and target architecture. + * + * - ARM_MATH_NEON_EXPERIMENTAL: + * + * Define macro ARM_MATH_NEON_EXPERIMENTAL to enable experimental Neon versions of + * of some DSP functions. Experimental Neon versions currently do not have better + * performances than the scalar versions. + * + * - ARM_MATH_HELIUM: + * + * It implies the flags ARM_MATH_MVEF and ARM_MATH_MVEI and ARM_MATH_FLOAT16. + * + * - ARM_MATH_MVEF: + * + * Select Helium versions of the f32 algorithms. + * It implies ARM_MATH_FLOAT16 and ARM_MATH_MVEI. + * + * - ARM_MATH_MVEI: + * + * Select Helium versions of the int and fixed point algorithms. + * + * - ARM_MATH_FLOAT16: + * + * Float16 implementations of some algorithms (Requires MVE extension). + * + *


+ * CMSIS-DSP in ARM::CMSIS Pack + * ----------------------------- + * + * The following files relevant to CMSIS-DSP are present in the ARM::CMSIS Pack directories: + * |File/Folder |Content | + * |---------------------------------|------------------------------------------------------------------------| + * |\b CMSIS\\Documentation\\DSP | This documentation | + * |\b CMSIS\\DSP\\DSP_Lib_TestSuite | DSP_Lib test suite | + * |\b CMSIS\\DSP\\Examples | Example projects demonstrating the usage of the library functions | + * |\b CMSIS\\DSP\\Include | DSP_Lib include files | + * |\b CMSIS\\DSP\\Lib | DSP_Lib binaries | + * |\b CMSIS\\DSP\\Projects | Projects to rebuild DSP_Lib binaries | + * |\b CMSIS\\DSP\\Source | DSP_Lib source files | + * + *
+ * Revision History of CMSIS-DSP + * ------------ + * Please refer to \ref ChangeLog_pg. + */ + + +/** + * @defgroup groupMath Basic Math Functions + */ + +/** + * @defgroup groupFastMath Fast Math Functions + * This set of functions provides a fast approximation to sine, cosine, and square root. + * As compared to most of the other functions in the CMSIS math library, the fast math functions + * operate on individual values and not arrays. + * There are separate functions for Q15, Q31, and floating-point data. + * + */ + +/** + * @defgroup groupCmplxMath Complex Math Functions + * This set of functions operates on complex data vectors. + * The data in the complex arrays is stored in an interleaved fashion + * (real, imag, real, imag, ...). + * In the API functions, the number of samples in a complex array refers + * to the number of complex values; the array contains twice this number of + * real values. + */ + +/** + * @defgroup groupFilters Filtering Functions + */ + +/** + * @defgroup groupMatrix Matrix Functions + * + * This set of functions provides basic matrix math operations. + * The functions operate on matrix data structures. For example, + * the type + * definition for the floating-point matrix structure is shown + * below: + *
+ *     typedef struct
+ *     {
+ *       uint16_t numRows;     // number of rows of the matrix.
+ *       uint16_t numCols;     // number of columns of the matrix.
+ *       float32_t *pData;     // points to the data of the matrix.
+ *     } arm_matrix_instance_f32;
+ * 
+ * There are similar definitions for Q15 and Q31 data types. + * + * The structure specifies the size of the matrix and then points to + * an array of data. The array is of size numRows X numCols + * and the values are arranged in row order. That is, the + * matrix element (i, j) is stored at: + *
+ *     pData[i*numCols + j]
+ * 
+ * + * \par Init Functions + * There is an associated initialization function for each type of matrix + * data structure. + * The initialization function sets the values of the internal structure fields. + * Refer to \ref arm_mat_init_f32(), \ref arm_mat_init_q31() and \ref arm_mat_init_q15() + * for floating-point, Q31 and Q15 types, respectively. + * + * \par + * Use of the initialization function is optional. However, if initialization function is used + * then the instance structure cannot be placed into a const data section. + * To place the instance structure in a const data + * section, manually initialize the data structure. For example: + *
+ * arm_matrix_instance_f32 S = {nRows, nColumns, pData};
+ * arm_matrix_instance_q31 S = {nRows, nColumns, pData};
+ * arm_matrix_instance_q15 S = {nRows, nColumns, pData};
+ * 
+ * where nRows specifies the number of rows, nColumns + * specifies the number of columns, and pData points to the + * data array. + * + * \par Size Checking + * By default all of the matrix functions perform size checking on the input and + * output matrices. For example, the matrix addition function verifies that the + * two input matrices and the output matrix all have the same number of rows and + * columns. If the size check fails the functions return: + *
+ *     ARM_MATH_SIZE_MISMATCH
+ * 
+ * Otherwise the functions return + *
+ *     ARM_MATH_SUCCESS
+ * 
+ * There is some overhead associated with this matrix size checking. + * The matrix size checking is enabled via the \#define + *
+ *     ARM_MATH_MATRIX_CHECK
+ * 
+ * within the library project settings. By default this macro is defined + * and size checking is enabled. By changing the project settings and + * undefining this macro size checking is eliminated and the functions + * run a bit faster. With size checking disabled the functions always + * return ARM_MATH_SUCCESS. + */ + +/** + * @defgroup groupTransforms Transform Functions + */ + +/** + * @defgroup groupController Controller Functions + */ + +/** + * @defgroup groupStats Statistics Functions + */ + +/** + * @defgroup groupSupport Support Functions + */ + +/** + * @defgroup groupInterpolation Interpolation Functions + * These functions perform 1- and 2-dimensional interpolation of data. + * Linear interpolation is used for 1-dimensional data and + * bilinear interpolation is used for 2-dimensional data. + */ + +/** + * @defgroup groupExamples Examples + */ + +/** + * @defgroup groupSVM SVM Functions + * This set of functions is implementing SVM classification on 2 classes. + * The training must be done from scikit-learn. The parameters can be easily + * generated from the scikit-learn object. Some examples are given in + * DSP/Testing/PatternGeneration/SVM.py + * + * If more than 2 classes are needed, the functions in this folder + * will have to be used, as building blocks, to do multi-class classification. + * + * No multi-class classification is provided in this SVM folder. + * + */ + + +/** + * @defgroup groupBayes Bayesian estimators + * + * Implement the naive gaussian Bayes estimator. + * The training must be done from scikit-learn. + * + * The parameters can be easily + * generated from the scikit-learn object. Some examples are given in + * DSP/Testing/PatternGeneration/Bayes.py + */ + +/** + * @defgroup groupDistance Distance functions + * + * Distance functions for use with clustering algorithms. + * There are distance functions for float vectors and boolean vectors. + * + */ + + +#ifndef _ARM_MATH_H +#define _ARM_MATH_H + +#ifdef __cplusplus +extern "C" +{ +#endif + +/* Compiler specific diagnostic adjustment */ +#if defined ( __CC_ARM ) + +#elif defined ( __ARMCC_VERSION ) && ( __ARMCC_VERSION >= 6010050 ) + +#elif defined ( __GNUC__ ) + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wsign-conversion" + #pragma GCC diagnostic ignored "-Wconversion" + #pragma GCC diagnostic ignored "-Wunused-parameter" + +#elif defined ( __ICCARM__ ) + +#elif defined ( __TI_ARM__ ) + +#elif defined ( __CSMC__ ) + +#elif defined ( __TASKING__ ) + +#elif defined ( _MSC_VER ) + +#else + #error Unknown compiler +#endif + + +/* Included for instrinsics definitions */ +#if defined (_MSC_VER ) +#include +#define __STATIC_FORCEINLINE static __forceinline +#define __STATIC_INLINE static __inline +#define __ALIGNED(x) __declspec(align(x)) + +#elif defined (__GNUC_PYTHON__) +#include +#define __ALIGNED(x) __attribute__((aligned(x))) +#define __STATIC_FORCEINLINE static __attribute__((inline)) +#define __STATIC_INLINE static __attribute__((inline)) +#pragma GCC diagnostic ignored "-Wunused-function" +#pragma GCC diagnostic ignored "-Wattributes" + +#else +#include "cmsis_compiler.h" +#endif + + + +#include +#include +#include +#include + + +#define F64_MAX ((float64_t)DBL_MAX) +#define F32_MAX ((float32_t)FLT_MAX) + +#if defined(ARM_MATH_FLOAT16) +#define F16_MAX ((float16_t)FLT_MAX) +#endif + +#define F64_MIN (-DBL_MAX) +#define F32_MIN (-FLT_MAX) + +#if defined(ARM_MATH_FLOAT16) +#define F16_MIN (-(float16_t)FLT_MAX) +#endif + +#define F64_ABSMAX ((float64_t)DBL_MAX) +#define F32_ABSMAX ((float32_t)FLT_MAX) + +#if defined(ARM_MATH_FLOAT16) +#define F16_ABSMAX ((float16_t)FLT_MAX) +#endif + +#define F64_ABSMIN ((float64_t)0.0) +#define F32_ABSMIN ((float32_t)0.0) + +#if defined(ARM_MATH_FLOAT16) +#define F16_ABSMIN ((float16_t)0.0) +#endif + +#define Q31_MAX ((q31_t)(0x7FFFFFFFL)) +#define Q15_MAX ((q15_t)(0x7FFF)) +#define Q7_MAX ((q7_t)(0x7F)) +#define Q31_MIN ((q31_t)(0x80000000L)) +#define Q15_MIN ((q15_t)(0x8000)) +#define Q7_MIN ((q7_t)(0x80)) + +#define Q31_ABSMAX ((q31_t)(0x7FFFFFFFL)) +#define Q15_ABSMAX ((q15_t)(0x7FFF)) +#define Q7_ABSMAX ((q7_t)(0x7F)) +#define Q31_ABSMIN ((q31_t)0) +#define Q15_ABSMIN ((q15_t)0) +#define Q7_ABSMIN ((q7_t)0) + +/* evaluate ARM DSP feature */ +#if (defined (__ARM_FEATURE_DSP) && (__ARM_FEATURE_DSP == 1)) + #define ARM_MATH_DSP 1 +#endif + +#if defined(ARM_MATH_NEON) +#include +#endif + +#if defined (ARM_MATH_HELIUM) + #define ARM_MATH_MVEF + #define ARM_MATH_FLOAT16 +#endif + +#if defined (ARM_MATH_MVEF) + #define ARM_MATH_MVEI + #define ARM_MATH_FLOAT16 +#endif + +#if defined (ARM_MATH_HELIUM) || defined(ARM_MATH_MVEF) || defined(ARM_MATH_MVEI) +#include +#endif + + + /** + * @brief Macros required for reciprocal calculation in Normalized LMS + */ + +#define DELTA_Q31 ((q31_t)(0x100)) +#define DELTA_Q15 ((q15_t)0x5) +#define INDEX_MASK 0x0000003F +#ifndef PI + #define PI 3.14159265358979f +#endif + + /** + * @brief Macros required for SINE and COSINE Fast math approximations + */ + +#define FAST_MATH_TABLE_SIZE 512 +#define FAST_MATH_Q31_SHIFT (32 - 10) +#define FAST_MATH_Q15_SHIFT (16 - 10) +#define CONTROLLER_Q31_SHIFT (32 - 9) +#define TABLE_SPACING_Q31 0x400000 +#define TABLE_SPACING_Q15 0x80 + + /** + * @brief Macros required for SINE and COSINE Controller functions + */ + /* 1.31(q31) Fixed value of 2/360 */ + /* -1 to +1 is divided into 360 values so total spacing is (2/360) */ +#define INPUT_SPACING 0xB60B61 + + /** + * @brief Macros for complex numbers + */ + + /* Dimension C vector space */ + #define CMPLX_DIM 2 + + /** + * @brief Error status returned by some functions in the library. + */ + + typedef enum + { + ARM_MATH_SUCCESS = 0, /**< No error */ + ARM_MATH_ARGUMENT_ERROR = -1, /**< One or more arguments are incorrect */ + ARM_MATH_LENGTH_ERROR = -2, /**< Length of data buffer is incorrect */ + ARM_MATH_SIZE_MISMATCH = -3, /**< Size of matrices is not compatible with the operation */ + ARM_MATH_NANINF = -4, /**< Not-a-number (NaN) or infinity is generated */ + ARM_MATH_SINGULAR = -5, /**< Input matrix is singular and cannot be inverted */ + ARM_MATH_TEST_FAILURE = -6 /**< Test Failed */ + } arm_status; + + /** + * @brief 8-bit fractional data type in 1.7 format. + */ + typedef int8_t q7_t; + + /** + * @brief 16-bit fractional data type in 1.15 format. + */ + typedef int16_t q15_t; + + /** + * @brief 32-bit fractional data type in 1.31 format. + */ + typedef int32_t q31_t; + + /** + * @brief 64-bit fractional data type in 1.63 format. + */ + typedef int64_t q63_t; + + /** + * @brief 32-bit floating-point type definition. + */ + typedef float float32_t; + + /** + * @brief 64-bit floating-point type definition. + */ + typedef double float64_t; + + /** + * @brief vector types + */ +#if defined(ARM_MATH_NEON) || defined (ARM_MATH_MVEI) + /** + * @brief 64-bit fractional 128-bit vector data type in 1.63 format + */ + typedef int64x2_t q63x2_t; + + /** + * @brief 32-bit fractional 128-bit vector data type in 1.31 format. + */ + typedef int32x4_t q31x4_t; + + /** + * @brief 16-bit fractional 128-bit vector data type with 16-bit alignement in 1.15 format. + */ + typedef __ALIGNED(2) int16x8_t q15x8_t; + + /** + * @brief 8-bit fractional 128-bit vector data type with 8-bit alignement in 1.7 format. + */ + typedef __ALIGNED(1) int8x16_t q7x16_t; + + /** + * @brief 32-bit fractional 128-bit vector pair data type in 1.31 format. + */ + typedef int32x4x2_t q31x4x2_t; + + /** + * @brief 32-bit fractional 128-bit vector quadruplet data type in 1.31 format. + */ + typedef int32x4x4_t q31x4x4_t; + + /** + * @brief 16-bit fractional 128-bit vector pair data type in 1.15 format. + */ + typedef int16x8x2_t q15x8x2_t; + + /** + * @brief 16-bit fractional 128-bit vector quadruplet data type in 1.15 format. + */ + typedef int16x8x4_t q15x8x4_t; + + /** + * @brief 8-bit fractional 128-bit vector pair data type in 1.7 format. + */ + typedef int8x16x2_t q7x16x2_t; + + /** + * @brief 8-bit fractional 128-bit vector quadruplet data type in 1.7 format. + */ + typedef int8x16x4_t q7x16x4_t; + + /** + * @brief 32-bit fractional data type in 9.23 format. + */ + typedef int32_t q23_t; + + /** + * @brief 32-bit fractional 128-bit vector data type in 9.23 format. + */ + typedef int32x4_t q23x4_t; + + /** + * @brief 64-bit status 128-bit vector data type. + */ + typedef int64x2_t status64x2_t; + + /** + * @brief 32-bit status 128-bit vector data type. + */ + typedef int32x4_t status32x4_t; + + /** + * @brief 16-bit status 128-bit vector data type. + */ + typedef int16x8_t status16x8_t; + + /** + * @brief 8-bit status 128-bit vector data type. + */ + typedef int8x16_t status8x16_t; + + +#endif + +#if defined(ARM_MATH_NEON) || defined(ARM_MATH_MVEF) /* floating point vector*/ + /** + * @brief 32-bit floating-point 128-bit vector type + */ + typedef float32x4_t f32x4_t; + +#if defined(ARM_MATH_FLOAT16) + /** + * @brief 16-bit floating-point 128-bit vector data type + */ + typedef __ALIGNED(2) float16x8_t f16x8_t; +#endif + + /** + * @brief 32-bit floating-point 128-bit vector pair data type + */ + typedef float32x4x2_t f32x4x2_t; + + /** + * @brief 32-bit floating-point 128-bit vector quadruplet data type + */ + typedef float32x4x4_t f32x4x4_t; + +#if defined(ARM_MATH_FLOAT16) + /** + * @brief 16-bit floating-point 128-bit vector pair data type + */ + typedef float16x8x2_t f16x8x2_t; + + /** + * @brief 16-bit floating-point 128-bit vector quadruplet data type + */ + typedef float16x8x4_t f16x8x4_t; +#endif + + /** + * @brief 32-bit ubiquitous 128-bit vector data type + */ + typedef union _any32x4_t + { + float32x4_t f; + int32x4_t i; + } any32x4_t; + +#if defined(ARM_MATH_FLOAT16) + /** + * @brief 16-bit ubiquitous 128-bit vector data type + */ + typedef union _any16x8_t + { + float16x8_t f; + int16x8_t i; + } any16x8_t; +#endif + +#endif + +#if defined(ARM_MATH_NEON) + /** + * @brief 32-bit fractional 64-bit vector data type in 1.31 format. + */ + typedef int32x2_t q31x2_t; + + /** + * @brief 16-bit fractional 64-bit vector data type in 1.15 format. + */ + typedef __ALIGNED(2) int16x4_t q15x4_t; + + /** + * @brief 8-bit fractional 64-bit vector data type in 1.7 format. + */ + typedef __ALIGNED(1) int8x8_t q7x8_t; + + /** + * @brief 32-bit float 64-bit vector data type. + */ + typedef float32x2_t f32x2_t; + +#if defined(ARM_MATH_FLOAT16) + /** + * @brief 16-bit float 64-bit vector data type. + */ + typedef __ALIGNED(2) float16x4_t f16x4_t; +#endif + + /** + * @brief 32-bit floating-point 128-bit vector triplet data type + */ + typedef float32x4x3_t f32x4x3_t; + +#if defined(ARM_MATH_FLOAT16) + /** + * @brief 16-bit floating-point 128-bit vector triplet data type + */ + typedef float16x8x3_t f16x8x3_t; +#endif + + /** + * @brief 32-bit fractional 128-bit vector triplet data type in 1.31 format + */ + typedef int32x4x3_t q31x4x3_t; + + /** + * @brief 16-bit fractional 128-bit vector triplet data type in 1.15 format + */ + typedef int16x8x3_t q15x8x3_t; + + /** + * @brief 8-bit fractional 128-bit vector triplet data type in 1.7 format + */ + typedef int8x16x3_t q7x16x3_t; + + /** + * @brief 32-bit floating-point 64-bit vector pair data type + */ + typedef float32x2x2_t f32x2x2_t; + + /** + * @brief 32-bit floating-point 64-bit vector triplet data type + */ + typedef float32x2x3_t f32x2x3_t; + + /** + * @brief 32-bit floating-point 64-bit vector quadruplet data type + */ + typedef float32x2x4_t f32x2x4_t; + +#if defined(ARM_MATH_FLOAT16) + /** + * @brief 16-bit floating-point 64-bit vector pair data type + */ + typedef float16x4x2_t f16x4x2_t; + + /** + * @brief 16-bit floating-point 64-bit vector triplet data type + */ + typedef float16x4x3_t f16x4x3_t; + + /** + * @brief 16-bit floating-point 64-bit vector quadruplet data type + */ + typedef float16x4x4_t f16x4x4_t; +#endif + + /** + * @brief 32-bit fractional 64-bit vector pair data type in 1.31 format + */ + typedef int32x2x2_t q31x2x2_t; + + /** + * @brief 32-bit fractional 64-bit vector triplet data type in 1.31 format + */ + typedef int32x2x3_t q31x2x3_t; + + /** + * @brief 32-bit fractional 64-bit vector quadruplet data type in 1.31 format + */ + typedef int32x4x3_t q31x2x4_t; + + /** + * @brief 16-bit fractional 64-bit vector pair data type in 1.15 format + */ + typedef int16x4x2_t q15x4x2_t; + + /** + * @brief 16-bit fractional 64-bit vector triplet data type in 1.15 format + */ + typedef int16x4x2_t q15x4x3_t; + + /** + * @brief 16-bit fractional 64-bit vector quadruplet data type in 1.15 format + */ + typedef int16x4x3_t q15x4x4_t; + + /** + * @brief 8-bit fractional 64-bit vector pair data type in 1.7 format + */ + typedef int8x8x2_t q7x8x2_t; + + /** + * @brief 8-bit fractional 64-bit vector triplet data type in 1.7 format + */ + typedef int8x8x3_t q7x8x3_t; + + /** + * @brief 8-bit fractional 64-bit vector quadruplet data type in 1.7 format + */ + typedef int8x8x4_t q7x8x4_t; + + /** + * @brief 32-bit ubiquitous 64-bit vector data type + */ + typedef union _any32x2_t + { + float32x2_t f; + int32x2_t i; + } any32x2_t; + +#if defined(ARM_MATH_FLOAT16) + /** + * @brief 16-bit ubiquitous 64-bit vector data type + */ + typedef union _any16x4_t + { + float16x4_t f; + int16x4_t i; + } any16x4_t; +#endif + + /** + * @brief 32-bit status 64-bit vector data type. + */ + typedef int32x4_t status32x2_t; + + /** + * @brief 16-bit status 64-bit vector data type. + */ + typedef int16x8_t status16x4_t; + + /** + * @brief 8-bit status 64-bit vector data type. + */ + typedef int8x16_t status8x8_t; + +#endif + + + +/** + @brief definition to read/write two 16 bit values. + @deprecated + */ +#if defined ( __CC_ARM ) + #define __SIMD32_TYPE int32_t __packed +#elif defined ( __ARMCC_VERSION ) && ( __ARMCC_VERSION >= 6010050 ) + #define __SIMD32_TYPE int32_t +#elif defined ( __GNUC__ ) + #define __SIMD32_TYPE int32_t +#elif defined ( __ICCARM__ ) + #define __SIMD32_TYPE int32_t __packed +#elif defined ( __TI_ARM__ ) + #define __SIMD32_TYPE int32_t +#elif defined ( __CSMC__ ) + #define __SIMD32_TYPE int32_t +#elif defined ( __TASKING__ ) + #define __SIMD32_TYPE __un(aligned) int32_t +#elif defined(_MSC_VER ) + #define __SIMD32_TYPE int32_t +#else + #error Unknown compiler +#endif + +#define __SIMD32(addr) (*(__SIMD32_TYPE **) & (addr)) +#define __SIMD32_CONST(addr) ( (__SIMD32_TYPE * ) (addr)) +#define _SIMD32_OFFSET(addr) (*(__SIMD32_TYPE * ) (addr)) +#define __SIMD64(addr) (*( int64_t **) & (addr)) + +#define STEP(x) (x) <= 0 ? 0 : 1 +#define SQ(x) ((x) * (x)) + +/* SIMD replacement */ + + +/** + @brief Read 2 Q15 from Q15 pointer. + @param[in] pQ15 points to input value + @return Q31 value + */ +__STATIC_FORCEINLINE q31_t read_q15x2 ( + q15_t * pQ15) +{ + q31_t val; + +#ifdef __ARM_FEATURE_UNALIGNED + memcpy (&val, pQ15, 4); +#else + val = (pQ15[1] << 16) | (pQ15[0] & 0x0FFFF) ; +#endif + + return (val); +} + +/** + @brief Read 2 Q15 from Q15 pointer and increment pointer afterwards. + @param[in] pQ15 points to input value + @return Q31 value + */ +__STATIC_FORCEINLINE q31_t read_q15x2_ia ( + q15_t ** pQ15) +{ + q31_t val; + +#ifdef __ARM_FEATURE_UNALIGNED + memcpy (&val, *pQ15, 4); +#else + val = ((*pQ15)[1] << 16) | ((*pQ15)[0] & 0x0FFFF); +#endif + + *pQ15 += 2; + return (val); +} + +/** + @brief Read 2 Q15 from Q15 pointer and decrement pointer afterwards. + @param[in] pQ15 points to input value + @return Q31 value + */ +__STATIC_FORCEINLINE q31_t read_q15x2_da ( + q15_t ** pQ15) +{ + q31_t val; + +#ifdef __ARM_FEATURE_UNALIGNED + memcpy (&val, *pQ15, 4); +#else + val = ((*pQ15)[1] << 16) | ((*pQ15)[0] & 0x0FFFF); +#endif + + *pQ15 -= 2; + return (val); +} + +/** + @brief Write 2 Q15 to Q15 pointer and increment pointer afterwards. + @param[in] pQ15 points to input value + @param[in] value Q31 value + @return none + */ +__STATIC_FORCEINLINE void write_q15x2_ia ( + q15_t ** pQ15, + q31_t value) +{ + q31_t val = value; +#ifdef __ARM_FEATURE_UNALIGNED + memcpy (*pQ15, &val, 4); +#else + (*pQ15)[0] = (val & 0x0FFFF); + (*pQ15)[1] = (val >> 16) & 0x0FFFF; +#endif + + *pQ15 += 2; +} + +/** + @brief Write 2 Q15 to Q15 pointer. + @param[in] pQ15 points to input value + @param[in] value Q31 value + @return none + */ +__STATIC_FORCEINLINE void write_q15x2 ( + q15_t * pQ15, + q31_t value) +{ + q31_t val = value; + +#ifdef __ARM_FEATURE_UNALIGNED + memcpy (pQ15, &val, 4); +#else + pQ15[0] = val & 0x0FFFF; + pQ15[1] = val >> 16; +#endif +} + + +/** + @brief Read 4 Q7 from Q7 pointer and increment pointer afterwards. + @param[in] pQ7 points to input value + @return Q31 value + */ +__STATIC_FORCEINLINE q31_t read_q7x4_ia ( + q7_t ** pQ7) +{ + q31_t val; + + +#ifdef __ARM_FEATURE_UNALIGNED + memcpy (&val, *pQ7, 4); +#else + val =(((*pQ7)[3] & 0x0FF) << 24) | (((*pQ7)[2] & 0x0FF) << 16) | (((*pQ7)[1] & 0x0FF) << 8) | ((*pQ7)[0] & 0x0FF); +#endif + + *pQ7 += 4; + + return (val); +} + +/** + @brief Read 4 Q7 from Q7 pointer and decrement pointer afterwards. + @param[in] pQ7 points to input value + @return Q31 value + */ +__STATIC_FORCEINLINE q31_t read_q7x4_da ( + q7_t ** pQ7) +{ + q31_t val; +#ifdef __ARM_FEATURE_UNALIGNED + memcpy (&val, *pQ7, 4); +#else + val = ((((*pQ7)[3]) & 0x0FF) << 24) | ((((*pQ7)[2]) & 0x0FF) << 16) | ((((*pQ7)[1]) & 0x0FF) << 8) | ((*pQ7)[0] & 0x0FF); +#endif + *pQ7 -= 4; + + return (val); +} + +/** + @brief Write 4 Q7 to Q7 pointer and increment pointer afterwards. + @param[in] pQ7 points to input value + @param[in] value Q31 value + @return none + */ +__STATIC_FORCEINLINE void write_q7x4_ia ( + q7_t ** pQ7, + q31_t value) +{ + q31_t val = value; +#ifdef __ARM_FEATURE_UNALIGNED + memcpy (*pQ7, &val, 4); +#else + (*pQ7)[0] = val & 0x0FF; + (*pQ7)[1] = (val >> 8) & 0x0FF; + (*pQ7)[2] = (val >> 16) & 0x0FF; + (*pQ7)[3] = (val >> 24) & 0x0FF; + +#endif + *pQ7 += 4; +} + +/* + +Normally those kind of definitions are in a compiler file +in Core or Core_A. + +But for MSVC compiler it is a bit special. The goal is very specific +to CMSIS-DSP and only to allow the use of this library from other +systems like Python or Matlab. + +MSVC is not going to be used to cross-compile to ARM. So, having a MSVC +compiler file in Core or Core_A would not make sense. + +*/ +#if defined ( _MSC_VER ) || defined(__GNUC_PYTHON__) + __STATIC_FORCEINLINE uint8_t __CLZ(uint32_t data) + { + if (data == 0U) { return 32U; } + + uint32_t count = 0U; + uint32_t mask = 0x80000000U; + + while ((data & mask) == 0U) + { + count += 1U; + mask = mask >> 1U; + } + return count; + } + + __STATIC_FORCEINLINE int32_t __SSAT(int32_t val, uint32_t sat) + { + if ((sat >= 1U) && (sat <= 32U)) + { + const int32_t max = (int32_t)((1U << (sat - 1U)) - 1U); + const int32_t min = -1 - max ; + if (val > max) + { + return max; + } + else if (val < min) + { + return min; + } + } + return val; + } + + __STATIC_FORCEINLINE uint32_t __USAT(int32_t val, uint32_t sat) + { + if (sat <= 31U) + { + const uint32_t max = ((1U << sat) - 1U); + if (val > (int32_t)max) + { + return max; + } + else if (val < 0) + { + return 0U; + } + } + return (uint32_t)val; + } +#endif + +#ifndef ARM_MATH_DSP + /** + * @brief definition to pack two 16 bit values. + */ + #define __PKHBT(ARG1, ARG2, ARG3) ( (((int32_t)(ARG1) << 0) & (int32_t)0x0000FFFF) | \ + (((int32_t)(ARG2) << ARG3) & (int32_t)0xFFFF0000) ) + #define __PKHTB(ARG1, ARG2, ARG3) ( (((int32_t)(ARG1) << 0) & (int32_t)0xFFFF0000) | \ + (((int32_t)(ARG2) >> ARG3) & (int32_t)0x0000FFFF) ) +#endif + + /** + * @brief definition to pack four 8 bit values. + */ +#ifndef ARM_MATH_BIG_ENDIAN + #define __PACKq7(v0,v1,v2,v3) ( (((int32_t)(v0) << 0) & (int32_t)0x000000FF) | \ + (((int32_t)(v1) << 8) & (int32_t)0x0000FF00) | \ + (((int32_t)(v2) << 16) & (int32_t)0x00FF0000) | \ + (((int32_t)(v3) << 24) & (int32_t)0xFF000000) ) +#else + #define __PACKq7(v0,v1,v2,v3) ( (((int32_t)(v3) << 0) & (int32_t)0x000000FF) | \ + (((int32_t)(v2) << 8) & (int32_t)0x0000FF00) | \ + (((int32_t)(v1) << 16) & (int32_t)0x00FF0000) | \ + (((int32_t)(v0) << 24) & (int32_t)0xFF000000) ) +#endif + + + /** + * @brief Clips Q63 to Q31 values. + */ + __STATIC_FORCEINLINE q31_t clip_q63_to_q31( + q63_t x) + { + return ((q31_t) (x >> 32) != ((q31_t) x >> 31)) ? + ((0x7FFFFFFF ^ ((q31_t) (x >> 63)))) : (q31_t) x; + } + + /** + * @brief Clips Q63 to Q15 values. + */ + __STATIC_FORCEINLINE q15_t clip_q63_to_q15( + q63_t x) + { + return ((q31_t) (x >> 32) != ((q31_t) x >> 31)) ? + ((0x7FFF ^ ((q15_t) (x >> 63)))) : (q15_t) (x >> 15); + } + + /** + * @brief Clips Q31 to Q7 values. + */ + __STATIC_FORCEINLINE q7_t clip_q31_to_q7( + q31_t x) + { + return ((q31_t) (x >> 24) != ((q31_t) x >> 23)) ? + ((0x7F ^ ((q7_t) (x >> 31)))) : (q7_t) x; + } + + /** + * @brief Clips Q31 to Q15 values. + */ + __STATIC_FORCEINLINE q15_t clip_q31_to_q15( + q31_t x) + { + return ((q31_t) (x >> 16) != ((q31_t) x >> 15)) ? + ((0x7FFF ^ ((q15_t) (x >> 31)))) : (q15_t) x; + } + + /** + * @brief Multiplies 32 X 64 and returns 32 bit result in 2.30 format. + */ + __STATIC_FORCEINLINE q63_t mult32x64( + q63_t x, + q31_t y) + { + return ((((q63_t) (x & 0x00000000FFFFFFFF) * y) >> 32) + + (((q63_t) (x >> 32) * y) ) ); + } + + /** + * @brief Function to Calculates 1/in (reciprocal) value of Q31 Data type. + */ + __STATIC_FORCEINLINE uint32_t arm_recip_q31( + q31_t in, + q31_t * dst, + const q31_t * pRecipTable) + { + q31_t out; + uint32_t tempVal; + uint32_t index, i; + uint32_t signBits; + + if (in > 0) + { + signBits = ((uint32_t) (__CLZ( in) - 1)); + } + else + { + signBits = ((uint32_t) (__CLZ(-in) - 1)); + } + + /* Convert input sample to 1.31 format */ + in = (in << signBits); + + /* calculation of index for initial approximated Val */ + index = (uint32_t)(in >> 24); + index = (index & INDEX_MASK); + + /* 1.31 with exp 1 */ + out = pRecipTable[index]; + + /* calculation of reciprocal value */ + /* running approximation for two iterations */ + for (i = 0U; i < 2U; i++) + { + tempVal = (uint32_t) (((q63_t) in * out) >> 31); + tempVal = 0x7FFFFFFFu - tempVal; + /* 1.31 with exp 1 */ + /* out = (q31_t) (((q63_t) out * tempVal) >> 30); */ + out = clip_q63_to_q31(((q63_t) out * tempVal) >> 30); + } + + /* write output */ + *dst = out; + + /* return num of signbits of out = 1/in value */ + return (signBits + 1U); + } + + + /** + * @brief Function to Calculates 1/in (reciprocal) value of Q15 Data type. + */ + __STATIC_FORCEINLINE uint32_t arm_recip_q15( + q15_t in, + q15_t * dst, + const q15_t * pRecipTable) + { + q15_t out = 0; + uint32_t tempVal = 0; + uint32_t index = 0, i = 0; + uint32_t signBits = 0; + + if (in > 0) + { + signBits = ((uint32_t)(__CLZ( in) - 17)); + } + else + { + signBits = ((uint32_t)(__CLZ(-in) - 17)); + } + + /* Convert input sample to 1.15 format */ + in = (in << signBits); + + /* calculation of index for initial approximated Val */ + index = (uint32_t)(in >> 8); + index = (index & INDEX_MASK); + + /* 1.15 with exp 1 */ + out = pRecipTable[index]; + + /* calculation of reciprocal value */ + /* running approximation for two iterations */ + for (i = 0U; i < 2U; i++) + { + tempVal = (uint32_t) (((q31_t) in * out) >> 15); + tempVal = 0x7FFFu - tempVal; + /* 1.15 with exp 1 */ + out = (q15_t) (((q31_t) out * tempVal) >> 14); + /* out = clip_q31_to_q15(((q31_t) out * tempVal) >> 14); */ + } + + /* write output */ + *dst = out; + + /* return num of signbits of out = 1/in value */ + return (signBits + 1); + } + +/** + * @brief Integer exponentiation + * @param[in] x value + * @param[in] nb integer exponent >= 1 + * @return x^nb + * + */ +__STATIC_INLINE float32_t arm_exponent_f32(float32_t x, int32_t nb) +{ + float32_t r = x; + nb --; + while(nb > 0) + { + r = r * x; + nb--; + } + return(r); +} + +/** + * @brief 64-bit to 32-bit unsigned normalization + * @param[in] in is input unsigned long long value + * @param[out] normalized is the 32-bit normalized value + * @param[out] norm is norm scale + */ +__STATIC_INLINE void arm_norm_64_to_32u(uint64_t in, int32_t * normalized, int32_t *norm) +{ + int32_t n1; + int32_t hi = (int32_t) (in >> 32); + int32_t lo = (int32_t) ((in << 32) >> 32); + + n1 = __CLZ(hi) - 32; + if (!n1) + { + /* + * input fits in 32-bit + */ + n1 = __CLZ(lo); + if (!n1) + { + /* + * MSB set, need to scale down by 1 + */ + *norm = -1; + *normalized = (((uint32_t) lo) >> 1); + } else + { + if (n1 == 32) + { + /* + * input is zero + */ + *norm = 0; + *normalized = 0; + } else + { + /* + * 32-bit normalization + */ + *norm = n1 - 1; + *normalized = lo << *norm; + } + } + } else + { + /* + * input fits in 64-bit + */ + n1 = 1 - n1; + *norm = -n1; + /* + * 64 bit normalization + */ + *normalized = (((uint32_t) lo) >> n1) | (hi << (32 - n1)); + } +} + +__STATIC_INLINE q31_t arm_div_q63_to_q31(q63_t num, q31_t den) +{ + q31_t result; + uint64_t absNum; + int32_t normalized; + int32_t norm; + + /* + * if sum fits in 32bits + * avoid costly 64-bit division + */ + absNum = num > 0 ? num : -num; + arm_norm_64_to_32u(absNum, &normalized, &norm); + if (norm > 0) + /* + * 32-bit division + */ + result = (q31_t) num / den; + else + /* + * 64-bit division + */ + result = (q31_t) (num / den); + + return result; +} + + +/* + * @brief C custom defined intrinsic functions + */ +#if !defined (ARM_MATH_DSP) + + /* + * @brief C custom defined QADD8 + */ + __STATIC_FORCEINLINE uint32_t __QADD8( + uint32_t x, + uint32_t y) + { + q31_t r, s, t, u; + + r = __SSAT(((((q31_t)x << 24) >> 24) + (((q31_t)y << 24) >> 24)), 8) & (int32_t)0x000000FF; + s = __SSAT(((((q31_t)x << 16) >> 24) + (((q31_t)y << 16) >> 24)), 8) & (int32_t)0x000000FF; + t = __SSAT(((((q31_t)x << 8) >> 24) + (((q31_t)y << 8) >> 24)), 8) & (int32_t)0x000000FF; + u = __SSAT(((((q31_t)x ) >> 24) + (((q31_t)y ) >> 24)), 8) & (int32_t)0x000000FF; + + return ((uint32_t)((u << 24) | (t << 16) | (s << 8) | (r ))); + } + + + /* + * @brief C custom defined QSUB8 + */ + __STATIC_FORCEINLINE uint32_t __QSUB8( + uint32_t x, + uint32_t y) + { + q31_t r, s, t, u; + + r = __SSAT(((((q31_t)x << 24) >> 24) - (((q31_t)y << 24) >> 24)), 8) & (int32_t)0x000000FF; + s = __SSAT(((((q31_t)x << 16) >> 24) - (((q31_t)y << 16) >> 24)), 8) & (int32_t)0x000000FF; + t = __SSAT(((((q31_t)x << 8) >> 24) - (((q31_t)y << 8) >> 24)), 8) & (int32_t)0x000000FF; + u = __SSAT(((((q31_t)x ) >> 24) - (((q31_t)y ) >> 24)), 8) & (int32_t)0x000000FF; + + return ((uint32_t)((u << 24) | (t << 16) | (s << 8) | (r ))); + } + + + /* + * @brief C custom defined QADD16 + */ + __STATIC_FORCEINLINE uint32_t __QADD16( + uint32_t x, + uint32_t y) + { +/* q31_t r, s; without initialisation 'arm_offset_q15 test' fails but 'intrinsic' tests pass! for armCC */ + q31_t r = 0, s = 0; + + r = __SSAT(((((q31_t)x << 16) >> 16) + (((q31_t)y << 16) >> 16)), 16) & (int32_t)0x0000FFFF; + s = __SSAT(((((q31_t)x ) >> 16) + (((q31_t)y ) >> 16)), 16) & (int32_t)0x0000FFFF; + + return ((uint32_t)((s << 16) | (r ))); + } + + + /* + * @brief C custom defined SHADD16 + */ + __STATIC_FORCEINLINE uint32_t __SHADD16( + uint32_t x, + uint32_t y) + { + q31_t r, s; + + r = (((((q31_t)x << 16) >> 16) + (((q31_t)y << 16) >> 16)) >> 1) & (int32_t)0x0000FFFF; + s = (((((q31_t)x ) >> 16) + (((q31_t)y ) >> 16)) >> 1) & (int32_t)0x0000FFFF; + + return ((uint32_t)((s << 16) | (r ))); + } + + + /* + * @brief C custom defined QSUB16 + */ + __STATIC_FORCEINLINE uint32_t __QSUB16( + uint32_t x, + uint32_t y) + { + q31_t r, s; + + r = __SSAT(((((q31_t)x << 16) >> 16) - (((q31_t)y << 16) >> 16)), 16) & (int32_t)0x0000FFFF; + s = __SSAT(((((q31_t)x ) >> 16) - (((q31_t)y ) >> 16)), 16) & (int32_t)0x0000FFFF; + + return ((uint32_t)((s << 16) | (r ))); + } + + + /* + * @brief C custom defined SHSUB16 + */ + __STATIC_FORCEINLINE uint32_t __SHSUB16( + uint32_t x, + uint32_t y) + { + q31_t r, s; + + r = (((((q31_t)x << 16) >> 16) - (((q31_t)y << 16) >> 16)) >> 1) & (int32_t)0x0000FFFF; + s = (((((q31_t)x ) >> 16) - (((q31_t)y ) >> 16)) >> 1) & (int32_t)0x0000FFFF; + + return ((uint32_t)((s << 16) | (r ))); + } + + + /* + * @brief C custom defined QASX + */ + __STATIC_FORCEINLINE uint32_t __QASX( + uint32_t x, + uint32_t y) + { + q31_t r, s; + + r = __SSAT(((((q31_t)x << 16) >> 16) - (((q31_t)y ) >> 16)), 16) & (int32_t)0x0000FFFF; + s = __SSAT(((((q31_t)x ) >> 16) + (((q31_t)y << 16) >> 16)), 16) & (int32_t)0x0000FFFF; + + return ((uint32_t)((s << 16) | (r ))); + } + + + /* + * @brief C custom defined SHASX + */ + __STATIC_FORCEINLINE uint32_t __SHASX( + uint32_t x, + uint32_t y) + { + q31_t r, s; + + r = (((((q31_t)x << 16) >> 16) - (((q31_t)y ) >> 16)) >> 1) & (int32_t)0x0000FFFF; + s = (((((q31_t)x ) >> 16) + (((q31_t)y << 16) >> 16)) >> 1) & (int32_t)0x0000FFFF; + + return ((uint32_t)((s << 16) | (r ))); + } + + + /* + * @brief C custom defined QSAX + */ + __STATIC_FORCEINLINE uint32_t __QSAX( + uint32_t x, + uint32_t y) + { + q31_t r, s; + + r = __SSAT(((((q31_t)x << 16) >> 16) + (((q31_t)y ) >> 16)), 16) & (int32_t)0x0000FFFF; + s = __SSAT(((((q31_t)x ) >> 16) - (((q31_t)y << 16) >> 16)), 16) & (int32_t)0x0000FFFF; + + return ((uint32_t)((s << 16) | (r ))); + } + + + /* + * @brief C custom defined SHSAX + */ + __STATIC_FORCEINLINE uint32_t __SHSAX( + uint32_t x, + uint32_t y) + { + q31_t r, s; + + r = (((((q31_t)x << 16) >> 16) + (((q31_t)y ) >> 16)) >> 1) & (int32_t)0x0000FFFF; + s = (((((q31_t)x ) >> 16) - (((q31_t)y << 16) >> 16)) >> 1) & (int32_t)0x0000FFFF; + + return ((uint32_t)((s << 16) | (r ))); + } + + + /* + * @brief C custom defined SMUSDX + */ + __STATIC_FORCEINLINE uint32_t __SMUSDX( + uint32_t x, + uint32_t y) + { + return ((uint32_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y ) >> 16)) - + ((((q31_t)x ) >> 16) * (((q31_t)y << 16) >> 16)) )); + } + + /* + * @brief C custom defined SMUADX + */ + __STATIC_FORCEINLINE uint32_t __SMUADX( + uint32_t x, + uint32_t y) + { + return ((uint32_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y ) >> 16)) + + ((((q31_t)x ) >> 16) * (((q31_t)y << 16) >> 16)) )); + } + + + /* + * @brief C custom defined QADD + */ + __STATIC_FORCEINLINE int32_t __QADD( + int32_t x, + int32_t y) + { + return ((int32_t)(clip_q63_to_q31((q63_t)x + (q31_t)y))); + } + + + /* + * @brief C custom defined QSUB + */ + __STATIC_FORCEINLINE int32_t __QSUB( + int32_t x, + int32_t y) + { + return ((int32_t)(clip_q63_to_q31((q63_t)x - (q31_t)y))); + } + + + /* + * @brief C custom defined SMLAD + */ + __STATIC_FORCEINLINE uint32_t __SMLAD( + uint32_t x, + uint32_t y, + uint32_t sum) + { + return ((uint32_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y << 16) >> 16)) + + ((((q31_t)x ) >> 16) * (((q31_t)y ) >> 16)) + + ( ((q31_t)sum ) ) )); + } + + + /* + * @brief C custom defined SMLADX + */ + __STATIC_FORCEINLINE uint32_t __SMLADX( + uint32_t x, + uint32_t y, + uint32_t sum) + { + return ((uint32_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y ) >> 16)) + + ((((q31_t)x ) >> 16) * (((q31_t)y << 16) >> 16)) + + ( ((q31_t)sum ) ) )); + } + + + /* + * @brief C custom defined SMLSDX + */ + __STATIC_FORCEINLINE uint32_t __SMLSDX( + uint32_t x, + uint32_t y, + uint32_t sum) + { + return ((uint32_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y ) >> 16)) - + ((((q31_t)x ) >> 16) * (((q31_t)y << 16) >> 16)) + + ( ((q31_t)sum ) ) )); + } + + + /* + * @brief C custom defined SMLALD + */ + __STATIC_FORCEINLINE uint64_t __SMLALD( + uint32_t x, + uint32_t y, + uint64_t sum) + { +/* return (sum + ((q15_t) (x >> 16) * (q15_t) (y >> 16)) + ((q15_t) x * (q15_t) y)); */ + return ((uint64_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y << 16) >> 16)) + + ((((q31_t)x ) >> 16) * (((q31_t)y ) >> 16)) + + ( ((q63_t)sum ) ) )); + } + + + /* + * @brief C custom defined SMLALDX + */ + __STATIC_FORCEINLINE uint64_t __SMLALDX( + uint32_t x, + uint32_t y, + uint64_t sum) + { +/* return (sum + ((q15_t) (x >> 16) * (q15_t) y)) + ((q15_t) x * (q15_t) (y >> 16)); */ + return ((uint64_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y ) >> 16)) + + ((((q31_t)x ) >> 16) * (((q31_t)y << 16) >> 16)) + + ( ((q63_t)sum ) ) )); + } + + + /* + * @brief C custom defined SMUAD + */ + __STATIC_FORCEINLINE uint32_t __SMUAD( + uint32_t x, + uint32_t y) + { + return ((uint32_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y << 16) >> 16)) + + ((((q31_t)x ) >> 16) * (((q31_t)y ) >> 16)) )); + } + + + /* + * @brief C custom defined SMUSD + */ + __STATIC_FORCEINLINE uint32_t __SMUSD( + uint32_t x, + uint32_t y) + { + return ((uint32_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y << 16) >> 16)) - + ((((q31_t)x ) >> 16) * (((q31_t)y ) >> 16)) )); + } + + + /* + * @brief C custom defined SXTB16 + */ + __STATIC_FORCEINLINE uint32_t __SXTB16( + uint32_t x) + { + return ((uint32_t)(((((q31_t)x << 24) >> 24) & (q31_t)0x0000FFFF) | + ((((q31_t)x << 8) >> 8) & (q31_t)0xFFFF0000) )); + } + + /* + * @brief C custom defined SMMLA + */ + __STATIC_FORCEINLINE int32_t __SMMLA( + int32_t x, + int32_t y, + int32_t sum) + { + return (sum + (int32_t) (((int64_t) x * y) >> 32)); + } + +#endif /* !defined (ARM_MATH_DSP) */ + + + /** + * @brief Instance structure for the Q7 FIR filter. + */ + typedef struct + { + uint16_t numTaps; /**< number of filter coefficients in the filter. */ + q7_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + const q7_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ + } arm_fir_instance_q7; + + /** + * @brief Instance structure for the Q15 FIR filter. + */ + typedef struct + { + uint16_t numTaps; /**< number of filter coefficients in the filter. */ + q15_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + const q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ + } arm_fir_instance_q15; + + /** + * @brief Instance structure for the Q31 FIR filter. + */ + typedef struct + { + uint16_t numTaps; /**< number of filter coefficients in the filter. */ + q31_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + const q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ + } arm_fir_instance_q31; + + /** + * @brief Instance structure for the floating-point FIR filter. + */ + typedef struct + { + uint16_t numTaps; /**< number of filter coefficients in the filter. */ + float32_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + const float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ + } arm_fir_instance_f32; + + /** + * @brief Processing function for the Q7 FIR filter. + * @param[in] S points to an instance of the Q7 FIR filter structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + */ + void arm_fir_q7( + const arm_fir_instance_q7 * S, + const q7_t * pSrc, + q7_t * pDst, + uint32_t blockSize); + + /** + * @brief Initialization function for the Q7 FIR filter. + * @param[in,out] S points to an instance of the Q7 FIR structure. + * @param[in] numTaps Number of filter coefficients in the filter. + * @param[in] pCoeffs points to the filter coefficients. + * @param[in] pState points to the state buffer. + * @param[in] blockSize number of samples that are processed. + */ + void arm_fir_init_q7( + arm_fir_instance_q7 * S, + uint16_t numTaps, + const q7_t * pCoeffs, + q7_t * pState, + uint32_t blockSize); + + /** + * @brief Processing function for the Q15 FIR filter. + * @param[in] S points to an instance of the Q15 FIR structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + */ + void arm_fir_q15( + const arm_fir_instance_q15 * S, + const q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + /** + * @brief Processing function for the fast Q15 FIR filter (fast version). + * @param[in] S points to an instance of the Q15 FIR filter structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + */ + void arm_fir_fast_q15( + const arm_fir_instance_q15 * S, + const q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + /** + * @brief Initialization function for the Q15 FIR filter. + * @param[in,out] S points to an instance of the Q15 FIR filter structure. + * @param[in] numTaps Number of filter coefficients in the filter. Must be even and greater than or equal to 4. + * @param[in] pCoeffs points to the filter coefficients. + * @param[in] pState points to the state buffer. + * @param[in] blockSize number of samples that are processed at a time. + * @return The function returns either + * ARM_MATH_SUCCESS if initialization was successful or + * ARM_MATH_ARGUMENT_ERROR if numTaps is not a supported value. + */ + arm_status arm_fir_init_q15( + arm_fir_instance_q15 * S, + uint16_t numTaps, + const q15_t * pCoeffs, + q15_t * pState, + uint32_t blockSize); + + /** + * @brief Processing function for the Q31 FIR filter. + * @param[in] S points to an instance of the Q31 FIR filter structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + */ + void arm_fir_q31( + const arm_fir_instance_q31 * S, + const q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + /** + * @brief Processing function for the fast Q31 FIR filter (fast version). + * @param[in] S points to an instance of the Q31 FIR filter structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + */ + void arm_fir_fast_q31( + const arm_fir_instance_q31 * S, + const q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + /** + * @brief Initialization function for the Q31 FIR filter. + * @param[in,out] S points to an instance of the Q31 FIR structure. + * @param[in] numTaps Number of filter coefficients in the filter. + * @param[in] pCoeffs points to the filter coefficients. + * @param[in] pState points to the state buffer. + * @param[in] blockSize number of samples that are processed at a time. + */ + void arm_fir_init_q31( + arm_fir_instance_q31 * S, + uint16_t numTaps, + const q31_t * pCoeffs, + q31_t * pState, + uint32_t blockSize); + + /** + * @brief Processing function for the floating-point FIR filter. + * @param[in] S points to an instance of the floating-point FIR structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + */ + void arm_fir_f32( + const arm_fir_instance_f32 * S, + const float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + /** + * @brief Initialization function for the floating-point FIR filter. + * @param[in,out] S points to an instance of the floating-point FIR filter structure. + * @param[in] numTaps Number of filter coefficients in the filter. + * @param[in] pCoeffs points to the filter coefficients. + * @param[in] pState points to the state buffer. + * @param[in] blockSize number of samples that are processed at a time. + */ + void arm_fir_init_f32( + arm_fir_instance_f32 * S, + uint16_t numTaps, + const float32_t * pCoeffs, + float32_t * pState, + uint32_t blockSize); + + /** + * @brief Instance structure for the Q15 Biquad cascade filter. + */ + typedef struct + { + int8_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */ + q15_t *pState; /**< Points to the array of state coefficients. The array is of length 4*numStages. */ + const q15_t *pCoeffs; /**< Points to the array of coefficients. The array is of length 5*numStages. */ + int8_t postShift; /**< Additional shift, in bits, applied to each output sample. */ + } arm_biquad_casd_df1_inst_q15; + + /** + * @brief Instance structure for the Q31 Biquad cascade filter. + */ + typedef struct + { + uint32_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */ + q31_t *pState; /**< Points to the array of state coefficients. The array is of length 4*numStages. */ + const q31_t *pCoeffs; /**< Points to the array of coefficients. The array is of length 5*numStages. */ + uint8_t postShift; /**< Additional shift, in bits, applied to each output sample. */ + } arm_biquad_casd_df1_inst_q31; + + /** + * @brief Instance structure for the floating-point Biquad cascade filter. + */ + typedef struct + { + uint32_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */ + float32_t *pState; /**< Points to the array of state coefficients. The array is of length 4*numStages. */ + const float32_t *pCoeffs; /**< Points to the array of coefficients. The array is of length 5*numStages. */ + } arm_biquad_casd_df1_inst_f32; + +#if defined(ARM_MATH_MVEF) && !defined(ARM_MATH_AUTOVECTORIZE) + /** + * @brief Instance structure for the modified Biquad coefs required by vectorized code. + */ + typedef struct + { + float32_t coeffs[8][4]; /**< Points to the array of modified coefficients. The array is of length 32. There is one per stage */ + } arm_biquad_mod_coef_f32; +#endif + + /** + * @brief Processing function for the Q15 Biquad cascade filter. + * @param[in] S points to an instance of the Q15 Biquad cascade structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + */ + void arm_biquad_cascade_df1_q15( + const arm_biquad_casd_df1_inst_q15 * S, + const q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + /** + * @brief Initialization function for the Q15 Biquad cascade filter. + * @param[in,out] S points to an instance of the Q15 Biquad cascade structure. + * @param[in] numStages number of 2nd order stages in the filter. + * @param[in] pCoeffs points to the filter coefficients. + * @param[in] pState points to the state buffer. + * @param[in] postShift Shift to be applied to the output. Varies according to the coefficients format + */ + void arm_biquad_cascade_df1_init_q15( + arm_biquad_casd_df1_inst_q15 * S, + uint8_t numStages, + const q15_t * pCoeffs, + q15_t * pState, + int8_t postShift); + + /** + * @brief Fast but less precise processing function for the Q15 Biquad cascade filter for Cortex-M3 and Cortex-M4. + * @param[in] S points to an instance of the Q15 Biquad cascade structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + */ + void arm_biquad_cascade_df1_fast_q15( + const arm_biquad_casd_df1_inst_q15 * S, + const q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + /** + * @brief Processing function for the Q31 Biquad cascade filter + * @param[in] S points to an instance of the Q31 Biquad cascade structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + */ + void arm_biquad_cascade_df1_q31( + const arm_biquad_casd_df1_inst_q31 * S, + const q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + /** + * @brief Fast but less precise processing function for the Q31 Biquad cascade filter for Cortex-M3 and Cortex-M4. + * @param[in] S points to an instance of the Q31 Biquad cascade structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + */ + void arm_biquad_cascade_df1_fast_q31( + const arm_biquad_casd_df1_inst_q31 * S, + const q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + /** + * @brief Initialization function for the Q31 Biquad cascade filter. + * @param[in,out] S points to an instance of the Q31 Biquad cascade structure. + * @param[in] numStages number of 2nd order stages in the filter. + * @param[in] pCoeffs points to the filter coefficients. + * @param[in] pState points to the state buffer. + * @param[in] postShift Shift to be applied to the output. Varies according to the coefficients format + */ + void arm_biquad_cascade_df1_init_q31( + arm_biquad_casd_df1_inst_q31 * S, + uint8_t numStages, + const q31_t * pCoeffs, + q31_t * pState, + int8_t postShift); + + /** + * @brief Processing function for the floating-point Biquad cascade filter. + * @param[in] S points to an instance of the floating-point Biquad cascade structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + */ + void arm_biquad_cascade_df1_f32( + const arm_biquad_casd_df1_inst_f32 * S, + const float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + /** + * @brief Initialization function for the floating-point Biquad cascade filter. + * @param[in,out] S points to an instance of the floating-point Biquad cascade structure. + * @param[in] numStages number of 2nd order stages in the filter. + * @param[in] pCoeffs points to the filter coefficients. + * @param[in] pCoeffsMod points to the modified filter coefficients (only MVE version). + * @param[in] pState points to the state buffer. + */ +#if defined(ARM_MATH_MVEF) && !defined(ARM_MATH_AUTOVECTORIZE) + void arm_biquad_cascade_df1_mve_init_f32( + arm_biquad_casd_df1_inst_f32 * S, + uint8_t numStages, + const float32_t * pCoeffs, + arm_biquad_mod_coef_f32 * pCoeffsMod, + float32_t * pState); +#endif + + void arm_biquad_cascade_df1_init_f32( + arm_biquad_casd_df1_inst_f32 * S, + uint8_t numStages, + const float32_t * pCoeffs, + float32_t * pState); + + + /** + * @brief Compute the logical bitwise AND of two fixed-point vectors. + * @param[in] pSrcA points to input vector A + * @param[in] pSrcB points to input vector B + * @param[out] pDst points to output vector + * @param[in] blockSize number of samples in each vector + * @return none + */ + void arm_and_u16( + const uint16_t * pSrcA, + const uint16_t * pSrcB, + uint16_t * pDst, + uint32_t blockSize); + + /** + * @brief Compute the logical bitwise AND of two fixed-point vectors. + * @param[in] pSrcA points to input vector A + * @param[in] pSrcB points to input vector B + * @param[out] pDst points to output vector + * @param[in] blockSize number of samples in each vector + * @return none + */ + void arm_and_u32( + const uint32_t * pSrcA, + const uint32_t * pSrcB, + uint32_t * pDst, + uint32_t blockSize); + + /** + * @brief Compute the logical bitwise AND of two fixed-point vectors. + * @param[in] pSrcA points to input vector A + * @param[in] pSrcB points to input vector B + * @param[out] pDst points to output vector + * @param[in] blockSize number of samples in each vector + * @return none + */ + void arm_and_u8( + const uint8_t * pSrcA, + const uint8_t * pSrcB, + uint8_t * pDst, + uint32_t blockSize); + + /** + * @brief Compute the logical bitwise OR of two fixed-point vectors. + * @param[in] pSrcA points to input vector A + * @param[in] pSrcB points to input vector B + * @param[out] pDst points to output vector + * @param[in] blockSize number of samples in each vector + * @return none + */ + void arm_or_u16( + const uint16_t * pSrcA, + const uint16_t * pSrcB, + uint16_t * pDst, + uint32_t blockSize); + + /** + * @brief Compute the logical bitwise OR of two fixed-point vectors. + * @param[in] pSrcA points to input vector A + * @param[in] pSrcB points to input vector B + * @param[out] pDst points to output vector + * @param[in] blockSize number of samples in each vector + * @return none + */ + void arm_or_u32( + const uint32_t * pSrcA, + const uint32_t * pSrcB, + uint32_t * pDst, + uint32_t blockSize); + + /** + * @brief Compute the logical bitwise OR of two fixed-point vectors. + * @param[in] pSrcA points to input vector A + * @param[in] pSrcB points to input vector B + * @param[out] pDst points to output vector + * @param[in] blockSize number of samples in each vector + * @return none + */ + void arm_or_u8( + const uint8_t * pSrcA, + const uint8_t * pSrcB, + uint8_t * pDst, + uint32_t blockSize); + + /** + * @brief Compute the logical bitwise NOT of a fixed-point vector. + * @param[in] pSrc points to input vector + * @param[out] pDst points to output vector + * @param[in] blockSize number of samples in each vector + * @return none + */ + void arm_not_u16( + const uint16_t * pSrc, + uint16_t * pDst, + uint32_t blockSize); + + /** + * @brief Compute the logical bitwise NOT of a fixed-point vector. + * @param[in] pSrc points to input vector + * @param[out] pDst points to output vector + * @param[in] blockSize number of samples in each vector + * @return none + */ + void arm_not_u32( + const uint32_t * pSrc, + uint32_t * pDst, + uint32_t blockSize); + + /** + * @brief Compute the logical bitwise NOT of a fixed-point vector. + * @param[in] pSrc points to input vector + * @param[out] pDst points to output vector + * @param[in] blockSize number of samples in each vector + * @return none + */ + void arm_not_u8( + const uint8_t * pSrc, + uint8_t * pDst, + uint32_t blockSize); + +/** + * @brief Compute the logical bitwise XOR of two fixed-point vectors. + * @param[in] pSrcA points to input vector A + * @param[in] pSrcB points to input vector B + * @param[out] pDst points to output vector + * @param[in] blockSize number of samples in each vector + * @return none + */ + void arm_xor_u16( + const uint16_t * pSrcA, + const uint16_t * pSrcB, + uint16_t * pDst, + uint32_t blockSize); + + /** + * @brief Compute the logical bitwise XOR of two fixed-point vectors. + * @param[in] pSrcA points to input vector A + * @param[in] pSrcB points to input vector B + * @param[out] pDst points to output vector + * @param[in] blockSize number of samples in each vector + * @return none + */ + void arm_xor_u32( + const uint32_t * pSrcA, + const uint32_t * pSrcB, + uint32_t * pDst, + uint32_t blockSize); + + /** + * @brief Compute the logical bitwise XOR of two fixed-point vectors. + * @param[in] pSrcA points to input vector A + * @param[in] pSrcB points to input vector B + * @param[out] pDst points to output vector + * @param[in] blockSize number of samples in each vector + * @return none + */ + void arm_xor_u8( + const uint8_t * pSrcA, + const uint8_t * pSrcB, + uint8_t * pDst, + uint32_t blockSize); + + /** + * @brief Struct for specifying sorting algorithm + */ + typedef enum + { + ARM_SORT_BITONIC = 0, + /**< Bitonic sort */ + ARM_SORT_BUBBLE = 1, + /**< Bubble sort */ + ARM_SORT_HEAP = 2, + /**< Heap sort */ + ARM_SORT_INSERTION = 3, + /**< Insertion sort */ + ARM_SORT_QUICK = 4, + /**< Quick sort */ + ARM_SORT_SELECTION = 5 + /**< Selection sort */ + } arm_sort_alg; + + /** + * @brief Struct for specifying sorting algorithm + */ + typedef enum + { + ARM_SORT_DESCENDING = 0, + /**< Descending order (9 to 0) */ + ARM_SORT_ASCENDING = 1 + /**< Ascending order (0 to 9) */ + } arm_sort_dir; + + /** + * @brief Instance structure for the sorting algorithms. + */ + typedef struct + { + arm_sort_alg alg; /**< Sorting algorithm selected */ + arm_sort_dir dir; /**< Sorting order (direction) */ + } arm_sort_instance_f32; + + /** + * @param[in] S points to an instance of the sorting structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + */ + void arm_sort_f32( + const arm_sort_instance_f32 * S, + float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + /** + * @param[in,out] S points to an instance of the sorting structure. + * @param[in] alg Selected algorithm. + * @param[in] dir Sorting order. + */ + void arm_sort_init_f32( + arm_sort_instance_f32 * S, + arm_sort_alg alg, + arm_sort_dir dir); + + /** + * @brief Instance structure for the sorting algorithms. + */ + typedef struct + { + arm_sort_dir dir; /**< Sorting order (direction) */ + float32_t * buffer; /**< Working buffer */ + } arm_merge_sort_instance_f32; + + /** + * @param[in] S points to an instance of the sorting structure. + * @param[in,out] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data + * @param[in] blockSize number of samples to process. + */ + void arm_merge_sort_f32( + const arm_merge_sort_instance_f32 * S, + float32_t *pSrc, + float32_t *pDst, + uint32_t blockSize); + + /** + * @param[in,out] S points to an instance of the sorting structure. + * @param[in] dir Sorting order. + * @param[in] buffer Working buffer. + */ + void arm_merge_sort_init_f32( + arm_merge_sort_instance_f32 * S, + arm_sort_dir dir, + float32_t * buffer); + + /** + * @brief Struct for specifying cubic spline type + */ + typedef enum + { + ARM_SPLINE_NATURAL = 0, /**< Natural spline */ + ARM_SPLINE_PARABOLIC_RUNOUT = 1 /**< Parabolic runout spline */ + } arm_spline_type; + + /** + * @brief Instance structure for the floating-point cubic spline interpolation. + */ + typedef struct + { + arm_spline_type type; /**< Type (boundary conditions) */ + const float32_t * x; /**< x values */ + const float32_t * y; /**< y values */ + uint32_t n_x; /**< Number of known data points */ + float32_t * coeffs; /**< Coefficients buffer (b,c, and d) */ + } arm_spline_instance_f32; + + /** + * @brief Processing function for the floating-point cubic spline interpolation. + * @param[in] S points to an instance of the floating-point spline structure. + * @param[in] xq points to the x values ot the interpolated data points. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of samples of output data. + */ + void arm_spline_f32( + arm_spline_instance_f32 * S, + const float32_t * xq, + float32_t * pDst, + uint32_t blockSize); + + /** + * @brief Initialization function for the floating-point cubic spline interpolation. + * @param[in,out] S points to an instance of the floating-point spline structure. + * @param[in] type type of cubic spline interpolation (boundary conditions) + * @param[in] x points to the x values of the known data points. + * @param[in] y points to the y values of the known data points. + * @param[in] n number of known data points. + * @param[in] coeffs coefficients array for b, c, and d + * @param[in] tempBuffer buffer array for internal computations + */ + void arm_spline_init_f32( + arm_spline_instance_f32 * S, + arm_spline_type type, + const float32_t * x, + const float32_t * y, + uint32_t n, + float32_t * coeffs, + float32_t * tempBuffer); + + /** + * @brief Instance structure for the floating-point matrix structure. + */ + typedef struct + { + uint16_t numRows; /**< number of rows of the matrix. */ + uint16_t numCols; /**< number of columns of the matrix. */ + float32_t *pData; /**< points to the data of the matrix. */ + } arm_matrix_instance_f32; + + /** + * @brief Instance structure for the floating-point matrix structure. + */ + typedef struct + { + uint16_t numRows; /**< number of rows of the matrix. */ + uint16_t numCols; /**< number of columns of the matrix. */ + float64_t *pData; /**< points to the data of the matrix. */ + } arm_matrix_instance_f64; + + /** + * @brief Instance structure for the Q15 matrix structure. + */ + typedef struct + { + uint16_t numRows; /**< number of rows of the matrix. */ + uint16_t numCols; /**< number of columns of the matrix. */ + q15_t *pData; /**< points to the data of the matrix. */ + } arm_matrix_instance_q15; + + /** + * @brief Instance structure for the Q31 matrix structure. + */ + typedef struct + { + uint16_t numRows; /**< number of rows of the matrix. */ + uint16_t numCols; /**< number of columns of the matrix. */ + q31_t *pData; /**< points to the data of the matrix. */ + } arm_matrix_instance_q31; + + /** + * @brief Floating-point matrix addition. + * @param[in] pSrcA points to the first input matrix structure + * @param[in] pSrcB points to the second input matrix structure + * @param[out] pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_add_f32( + const arm_matrix_instance_f32 * pSrcA, + const arm_matrix_instance_f32 * pSrcB, + arm_matrix_instance_f32 * pDst); + + /** + * @brief Q15 matrix addition. + * @param[in] pSrcA points to the first input matrix structure + * @param[in] pSrcB points to the second input matrix structure + * @param[out] pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_add_q15( + const arm_matrix_instance_q15 * pSrcA, + const arm_matrix_instance_q15 * pSrcB, + arm_matrix_instance_q15 * pDst); + + /** + * @brief Q31 matrix addition. + * @param[in] pSrcA points to the first input matrix structure + * @param[in] pSrcB points to the second input matrix structure + * @param[out] pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_add_q31( + const arm_matrix_instance_q31 * pSrcA, + const arm_matrix_instance_q31 * pSrcB, + arm_matrix_instance_q31 * pDst); + + /** + * @brief Floating-point, complex, matrix multiplication. + * @param[in] pSrcA points to the first input matrix structure + * @param[in] pSrcB points to the second input matrix structure + * @param[out] pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_cmplx_mult_f32( + const arm_matrix_instance_f32 * pSrcA, + const arm_matrix_instance_f32 * pSrcB, + arm_matrix_instance_f32 * pDst); + + /** + * @brief Q15, complex, matrix multiplication. + * @param[in] pSrcA points to the first input matrix structure + * @param[in] pSrcB points to the second input matrix structure + * @param[out] pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_cmplx_mult_q15( + const arm_matrix_instance_q15 * pSrcA, + const arm_matrix_instance_q15 * pSrcB, + arm_matrix_instance_q15 * pDst, + q15_t * pScratch); + + /** + * @brief Q31, complex, matrix multiplication. + * @param[in] pSrcA points to the first input matrix structure + * @param[in] pSrcB points to the second input matrix structure + * @param[out] pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_cmplx_mult_q31( + const arm_matrix_instance_q31 * pSrcA, + const arm_matrix_instance_q31 * pSrcB, + arm_matrix_instance_q31 * pDst); + + /** + * @brief Floating-point matrix transpose. + * @param[in] pSrc points to the input matrix + * @param[out] pDst points to the output matrix + * @return The function returns either ARM_MATH_SIZE_MISMATCH + * or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_trans_f32( + const arm_matrix_instance_f32 * pSrc, + arm_matrix_instance_f32 * pDst); + + /** + * @brief Q15 matrix transpose. + * @param[in] pSrc points to the input matrix + * @param[out] pDst points to the output matrix + * @return The function returns either ARM_MATH_SIZE_MISMATCH + * or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_trans_q15( + const arm_matrix_instance_q15 * pSrc, + arm_matrix_instance_q15 * pDst); + + /** + * @brief Q31 matrix transpose. + * @param[in] pSrc points to the input matrix + * @param[out] pDst points to the output matrix + * @return The function returns either ARM_MATH_SIZE_MISMATCH + * or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_trans_q31( + const arm_matrix_instance_q31 * pSrc, + arm_matrix_instance_q31 * pDst); + + /** + * @brief Floating-point matrix multiplication + * @param[in] pSrcA points to the first input matrix structure + * @param[in] pSrcB points to the second input matrix structure + * @param[out] pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_mult_f32( + const arm_matrix_instance_f32 * pSrcA, + const arm_matrix_instance_f32 * pSrcB, + arm_matrix_instance_f32 * pDst); + + /** + * @brief Q15 matrix multiplication + * @param[in] pSrcA points to the first input matrix structure + * @param[in] pSrcB points to the second input matrix structure + * @param[out] pDst points to output matrix structure + * @param[in] pState points to the array for storing intermediate results + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_mult_q15( + const arm_matrix_instance_q15 * pSrcA, + const arm_matrix_instance_q15 * pSrcB, + arm_matrix_instance_q15 * pDst, + q15_t * pState); + + /** + * @brief Q15 matrix multiplication (fast variant) for Cortex-M3 and Cortex-M4 + * @param[in] pSrcA points to the first input matrix structure + * @param[in] pSrcB points to the second input matrix structure + * @param[out] pDst points to output matrix structure + * @param[in] pState points to the array for storing intermediate results + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_mult_fast_q15( + const arm_matrix_instance_q15 * pSrcA, + const arm_matrix_instance_q15 * pSrcB, + arm_matrix_instance_q15 * pDst, + q15_t * pState); + + /** + * @brief Q31 matrix multiplication + * @param[in] pSrcA points to the first input matrix structure + * @param[in] pSrcB points to the second input matrix structure + * @param[out] pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_mult_q31( + const arm_matrix_instance_q31 * pSrcA, + const arm_matrix_instance_q31 * pSrcB, + arm_matrix_instance_q31 * pDst); + + /** + * @brief Q31 matrix multiplication (fast variant) for Cortex-M3 and Cortex-M4 + * @param[in] pSrcA points to the first input matrix structure + * @param[in] pSrcB points to the second input matrix structure + * @param[out] pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_mult_fast_q31( + const arm_matrix_instance_q31 * pSrcA, + const arm_matrix_instance_q31 * pSrcB, + arm_matrix_instance_q31 * pDst); + + /** + * @brief Floating-point matrix subtraction + * @param[in] pSrcA points to the first input matrix structure + * @param[in] pSrcB points to the second input matrix structure + * @param[out] pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_sub_f32( + const arm_matrix_instance_f32 * pSrcA, + const arm_matrix_instance_f32 * pSrcB, + arm_matrix_instance_f32 * pDst); + + /** + * @brief Q15 matrix subtraction + * @param[in] pSrcA points to the first input matrix structure + * @param[in] pSrcB points to the second input matrix structure + * @param[out] pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_sub_q15( + const arm_matrix_instance_q15 * pSrcA, + const arm_matrix_instance_q15 * pSrcB, + arm_matrix_instance_q15 * pDst); + + /** + * @brief Q31 matrix subtraction + * @param[in] pSrcA points to the first input matrix structure + * @param[in] pSrcB points to the second input matrix structure + * @param[out] pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_sub_q31( + const arm_matrix_instance_q31 * pSrcA, + const arm_matrix_instance_q31 * pSrcB, + arm_matrix_instance_q31 * pDst); + + /** + * @brief Floating-point matrix scaling. + * @param[in] pSrc points to the input matrix + * @param[in] scale scale factor + * @param[out] pDst points to the output matrix + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_scale_f32( + const arm_matrix_instance_f32 * pSrc, + float32_t scale, + arm_matrix_instance_f32 * pDst); + + /** + * @brief Q15 matrix scaling. + * @param[in] pSrc points to input matrix + * @param[in] scaleFract fractional portion of the scale factor + * @param[in] shift number of bits to shift the result by + * @param[out] pDst points to output matrix + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_scale_q15( + const arm_matrix_instance_q15 * pSrc, + q15_t scaleFract, + int32_t shift, + arm_matrix_instance_q15 * pDst); + + /** + * @brief Q31 matrix scaling. + * @param[in] pSrc points to input matrix + * @param[in] scaleFract fractional portion of the scale factor + * @param[in] shift number of bits to shift the result by + * @param[out] pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ +arm_status arm_mat_scale_q31( + const arm_matrix_instance_q31 * pSrc, + q31_t scaleFract, + int32_t shift, + arm_matrix_instance_q31 * pDst); + + /** + * @brief Q31 matrix initialization. + * @param[in,out] S points to an instance of the floating-point matrix structure. + * @param[in] nRows number of rows in the matrix. + * @param[in] nColumns number of columns in the matrix. + * @param[in] pData points to the matrix data array. + */ +void arm_mat_init_q31( + arm_matrix_instance_q31 * S, + uint16_t nRows, + uint16_t nColumns, + q31_t * pData); + + /** + * @brief Q15 matrix initialization. + * @param[in,out] S points to an instance of the floating-point matrix structure. + * @param[in] nRows number of rows in the matrix. + * @param[in] nColumns number of columns in the matrix. + * @param[in] pData points to the matrix data array. + */ +void arm_mat_init_q15( + arm_matrix_instance_q15 * S, + uint16_t nRows, + uint16_t nColumns, + q15_t * pData); + + /** + * @brief Floating-point matrix initialization. + * @param[in,out] S points to an instance of the floating-point matrix structure. + * @param[in] nRows number of rows in the matrix. + * @param[in] nColumns number of columns in the matrix. + * @param[in] pData points to the matrix data array. + */ +void arm_mat_init_f32( + arm_matrix_instance_f32 * S, + uint16_t nRows, + uint16_t nColumns, + float32_t * pData); + + + /** + * @brief Instance structure for the Q15 PID Control. + */ + typedef struct + { + q15_t A0; /**< The derived gain, A0 = Kp + Ki + Kd . */ +#if !defined (ARM_MATH_DSP) + q15_t A1; + q15_t A2; +#else + q31_t A1; /**< The derived gain A1 = -Kp - 2Kd | Kd.*/ +#endif + q15_t state[3]; /**< The state array of length 3. */ + q15_t Kp; /**< The proportional gain. */ + q15_t Ki; /**< The integral gain. */ + q15_t Kd; /**< The derivative gain. */ + } arm_pid_instance_q15; + + /** + * @brief Instance structure for the Q31 PID Control. + */ + typedef struct + { + q31_t A0; /**< The derived gain, A0 = Kp + Ki + Kd . */ + q31_t A1; /**< The derived gain, A1 = -Kp - 2Kd. */ + q31_t A2; /**< The derived gain, A2 = Kd . */ + q31_t state[3]; /**< The state array of length 3. */ + q31_t Kp; /**< The proportional gain. */ + q31_t Ki; /**< The integral gain. */ + q31_t Kd; /**< The derivative gain. */ + } arm_pid_instance_q31; + + /** + * @brief Instance structure for the floating-point PID Control. + */ + typedef struct + { + float32_t A0; /**< The derived gain, A0 = Kp + Ki + Kd . */ + float32_t A1; /**< The derived gain, A1 = -Kp - 2Kd. */ + float32_t A2; /**< The derived gain, A2 = Kd . */ + float32_t state[3]; /**< The state array of length 3. */ + float32_t Kp; /**< The proportional gain. */ + float32_t Ki; /**< The integral gain. */ + float32_t Kd; /**< The derivative gain. */ + } arm_pid_instance_f32; + + + + /** + * @brief Initialization function for the floating-point PID Control. + * @param[in,out] S points to an instance of the PID structure. + * @param[in] resetStateFlag flag to reset the state. 0 = no change in state 1 = reset the state. + */ + void arm_pid_init_f32( + arm_pid_instance_f32 * S, + int32_t resetStateFlag); + + + /** + * @brief Reset function for the floating-point PID Control. + * @param[in,out] S is an instance of the floating-point PID Control structure + */ + void arm_pid_reset_f32( + arm_pid_instance_f32 * S); + + + /** + * @brief Initialization function for the Q31 PID Control. + * @param[in,out] S points to an instance of the Q15 PID structure. + * @param[in] resetStateFlag flag to reset the state. 0 = no change in state 1 = reset the state. + */ + void arm_pid_init_q31( + arm_pid_instance_q31 * S, + int32_t resetStateFlag); + + + /** + * @brief Reset function for the Q31 PID Control. + * @param[in,out] S points to an instance of the Q31 PID Control structure + */ + + void arm_pid_reset_q31( + arm_pid_instance_q31 * S); + + + /** + * @brief Initialization function for the Q15 PID Control. + * @param[in,out] S points to an instance of the Q15 PID structure. + * @param[in] resetStateFlag flag to reset the state. 0 = no change in state 1 = reset the state. + */ + void arm_pid_init_q15( + arm_pid_instance_q15 * S, + int32_t resetStateFlag); + + + /** + * @brief Reset function for the Q15 PID Control. + * @param[in,out] S points to an instance of the q15 PID Control structure + */ + void arm_pid_reset_q15( + arm_pid_instance_q15 * S); + + + /** + * @brief Instance structure for the floating-point Linear Interpolate function. + */ + typedef struct + { + uint32_t nValues; /**< nValues */ + float32_t x1; /**< x1 */ + float32_t xSpacing; /**< xSpacing */ + float32_t *pYData; /**< pointer to the table of Y values */ + } arm_linear_interp_instance_f32; + + /** + * @brief Instance structure for the floating-point bilinear interpolation function. + */ + typedef struct + { + uint16_t numRows; /**< number of rows in the data table. */ + uint16_t numCols; /**< number of columns in the data table. */ + float32_t *pData; /**< points to the data table. */ + } arm_bilinear_interp_instance_f32; + + /** + * @brief Instance structure for the Q31 bilinear interpolation function. + */ + typedef struct + { + uint16_t numRows; /**< number of rows in the data table. */ + uint16_t numCols; /**< number of columns in the data table. */ + q31_t *pData; /**< points to the data table. */ + } arm_bilinear_interp_instance_q31; + + /** + * @brief Instance structure for the Q15 bilinear interpolation function. + */ + typedef struct + { + uint16_t numRows; /**< number of rows in the data table. */ + uint16_t numCols; /**< number of columns in the data table. */ + q15_t *pData; /**< points to the data table. */ + } arm_bilinear_interp_instance_q15; + + /** + * @brief Instance structure for the Q15 bilinear interpolation function. + */ + typedef struct + { + uint16_t numRows; /**< number of rows in the data table. */ + uint16_t numCols; /**< number of columns in the data table. */ + q7_t *pData; /**< points to the data table. */ + } arm_bilinear_interp_instance_q7; + + + /** + * @brief Q7 vector multiplication. + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in each vector + */ + void arm_mult_q7( + const q7_t * pSrcA, + const q7_t * pSrcB, + q7_t * pDst, + uint32_t blockSize); + + + /** + * @brief Q15 vector multiplication. + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in each vector + */ + void arm_mult_q15( + const q15_t * pSrcA, + const q15_t * pSrcB, + q15_t * pDst, + uint32_t blockSize); + + + /** + * @brief Q31 vector multiplication. + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in each vector + */ + void arm_mult_q31( + const q31_t * pSrcA, + const q31_t * pSrcB, + q31_t * pDst, + uint32_t blockSize); + + + /** + * @brief Floating-point vector multiplication. + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in each vector + */ + void arm_mult_f32( + const float32_t * pSrcA, + const float32_t * pSrcB, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @brief Instance structure for the Q15 CFFT/CIFFT function. + */ + typedef struct + { + uint16_t fftLen; /**< length of the FFT. */ + uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */ + uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */ + const q15_t *pTwiddle; /**< points to the Sin twiddle factor table. */ + const uint16_t *pBitRevTable; /**< points to the bit reversal table. */ + uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ + uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */ + } arm_cfft_radix2_instance_q15; + +/* Deprecated */ + arm_status arm_cfft_radix2_init_q15( + arm_cfft_radix2_instance_q15 * S, + uint16_t fftLen, + uint8_t ifftFlag, + uint8_t bitReverseFlag); + +/* Deprecated */ + void arm_cfft_radix2_q15( + const arm_cfft_radix2_instance_q15 * S, + q15_t * pSrc); + + + /** + * @brief Instance structure for the Q15 CFFT/CIFFT function. + */ + typedef struct + { + uint16_t fftLen; /**< length of the FFT. */ + uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */ + uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */ + const q15_t *pTwiddle; /**< points to the twiddle factor table. */ + const uint16_t *pBitRevTable; /**< points to the bit reversal table. */ + uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ + uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */ + } arm_cfft_radix4_instance_q15; + +/* Deprecated */ + arm_status arm_cfft_radix4_init_q15( + arm_cfft_radix4_instance_q15 * S, + uint16_t fftLen, + uint8_t ifftFlag, + uint8_t bitReverseFlag); + +/* Deprecated */ + void arm_cfft_radix4_q15( + const arm_cfft_radix4_instance_q15 * S, + q15_t * pSrc); + + /** + * @brief Instance structure for the Radix-2 Q31 CFFT/CIFFT function. + */ + typedef struct + { + uint16_t fftLen; /**< length of the FFT. */ + uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */ + uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */ + const q31_t *pTwiddle; /**< points to the Twiddle factor table. */ + const uint16_t *pBitRevTable; /**< points to the bit reversal table. */ + uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ + uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */ + } arm_cfft_radix2_instance_q31; + +/* Deprecated */ + arm_status arm_cfft_radix2_init_q31( + arm_cfft_radix2_instance_q31 * S, + uint16_t fftLen, + uint8_t ifftFlag, + uint8_t bitReverseFlag); + +/* Deprecated */ + void arm_cfft_radix2_q31( + const arm_cfft_radix2_instance_q31 * S, + q31_t * pSrc); + + /** + * @brief Instance structure for the Q31 CFFT/CIFFT function. + */ + typedef struct + { + uint16_t fftLen; /**< length of the FFT. */ + uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */ + uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */ + const q31_t *pTwiddle; /**< points to the twiddle factor table. */ + const uint16_t *pBitRevTable; /**< points to the bit reversal table. */ + uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ + uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */ + } arm_cfft_radix4_instance_q31; + +/* Deprecated */ + void arm_cfft_radix4_q31( + const arm_cfft_radix4_instance_q31 * S, + q31_t * pSrc); + +/* Deprecated */ + arm_status arm_cfft_radix4_init_q31( + arm_cfft_radix4_instance_q31 * S, + uint16_t fftLen, + uint8_t ifftFlag, + uint8_t bitReverseFlag); + + /** + * @brief Instance structure for the floating-point CFFT/CIFFT function. + */ + typedef struct + { + uint16_t fftLen; /**< length of the FFT. */ + uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */ + uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */ + const float32_t *pTwiddle; /**< points to the Twiddle factor table. */ + const uint16_t *pBitRevTable; /**< points to the bit reversal table. */ + uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ + uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */ + float32_t onebyfftLen; /**< value of 1/fftLen. */ + } arm_cfft_radix2_instance_f32; + +/* Deprecated */ + arm_status arm_cfft_radix2_init_f32( + arm_cfft_radix2_instance_f32 * S, + uint16_t fftLen, + uint8_t ifftFlag, + uint8_t bitReverseFlag); + +/* Deprecated */ + void arm_cfft_radix2_f32( + const arm_cfft_radix2_instance_f32 * S, + float32_t * pSrc); + + /** + * @brief Instance structure for the floating-point CFFT/CIFFT function. + */ + typedef struct + { + uint16_t fftLen; /**< length of the FFT. */ + uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */ + uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */ + const float32_t *pTwiddle; /**< points to the Twiddle factor table. */ + const uint16_t *pBitRevTable; /**< points to the bit reversal table. */ + uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ + uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */ + float32_t onebyfftLen; /**< value of 1/fftLen. */ + } arm_cfft_radix4_instance_f32; + +/* Deprecated */ + arm_status arm_cfft_radix4_init_f32( + arm_cfft_radix4_instance_f32 * S, + uint16_t fftLen, + uint8_t ifftFlag, + uint8_t bitReverseFlag); + +/* Deprecated */ + void arm_cfft_radix4_f32( + const arm_cfft_radix4_instance_f32 * S, + float32_t * pSrc); + + /** + * @brief Instance structure for the fixed-point CFFT/CIFFT function. + */ + typedef struct + { + uint16_t fftLen; /**< length of the FFT. */ + const q15_t *pTwiddle; /**< points to the Twiddle factor table. */ + const uint16_t *pBitRevTable; /**< points to the bit reversal table. */ + uint16_t bitRevLength; /**< bit reversal table length. */ +#if defined(ARM_MATH_MVEI) + const uint32_t *rearranged_twiddle_tab_stride1_arr; /**< Per stage reordered twiddle pointer (offset 1) */ \ + const uint32_t *rearranged_twiddle_tab_stride2_arr; /**< Per stage reordered twiddle pointer (offset 2) */ \ + const uint32_t *rearranged_twiddle_tab_stride3_arr; /**< Per stage reordered twiddle pointer (offset 3) */ \ + const q15_t *rearranged_twiddle_stride1; /**< reordered twiddle offset 1 storage */ \ + const q15_t *rearranged_twiddle_stride2; /**< reordered twiddle offset 2 storage */ \ + const q15_t *rearranged_twiddle_stride3; +#endif + } arm_cfft_instance_q15; + +arm_status arm_cfft_init_q15( + arm_cfft_instance_q15 * S, + uint16_t fftLen); + +void arm_cfft_q15( + const arm_cfft_instance_q15 * S, + q15_t * p1, + uint8_t ifftFlag, + uint8_t bitReverseFlag); + + /** + * @brief Instance structure for the fixed-point CFFT/CIFFT function. + */ + typedef struct + { + uint16_t fftLen; /**< length of the FFT. */ + const q31_t *pTwiddle; /**< points to the Twiddle factor table. */ + const uint16_t *pBitRevTable; /**< points to the bit reversal table. */ + uint16_t bitRevLength; /**< bit reversal table length. */ +#if defined(ARM_MATH_MVEI) + const uint32_t *rearranged_twiddle_tab_stride1_arr; /**< Per stage reordered twiddle pointer (offset 1) */ \ + const uint32_t *rearranged_twiddle_tab_stride2_arr; /**< Per stage reordered twiddle pointer (offset 2) */ \ + const uint32_t *rearranged_twiddle_tab_stride3_arr; /**< Per stage reordered twiddle pointer (offset 3) */ \ + const q31_t *rearranged_twiddle_stride1; /**< reordered twiddle offset 1 storage */ \ + const q31_t *rearranged_twiddle_stride2; /**< reordered twiddle offset 2 storage */ \ + const q31_t *rearranged_twiddle_stride3; +#endif + } arm_cfft_instance_q31; + +arm_status arm_cfft_init_q31( + arm_cfft_instance_q31 * S, + uint16_t fftLen); + +void arm_cfft_q31( + const arm_cfft_instance_q31 * S, + q31_t * p1, + uint8_t ifftFlag, + uint8_t bitReverseFlag); + + /** + * @brief Instance structure for the floating-point CFFT/CIFFT function. + */ + typedef struct + { + uint16_t fftLen; /**< length of the FFT. */ + const float32_t *pTwiddle; /**< points to the Twiddle factor table. */ + const uint16_t *pBitRevTable; /**< points to the bit reversal table. */ + uint16_t bitRevLength; /**< bit reversal table length. */ +#if defined(ARM_MATH_MVEF) && !defined(ARM_MATH_AUTOVECTORIZE) + const uint32_t *rearranged_twiddle_tab_stride1_arr; /**< Per stage reordered twiddle pointer (offset 1) */ \ + const uint32_t *rearranged_twiddle_tab_stride2_arr; /**< Per stage reordered twiddle pointer (offset 2) */ \ + const uint32_t *rearranged_twiddle_tab_stride3_arr; /**< Per stage reordered twiddle pointer (offset 3) */ \ + const float32_t *rearranged_twiddle_stride1; /**< reordered twiddle offset 1 storage */ \ + const float32_t *rearranged_twiddle_stride2; /**< reordered twiddle offset 2 storage */ \ + const float32_t *rearranged_twiddle_stride3; +#endif + } arm_cfft_instance_f32; + + + arm_status arm_cfft_init_f32( + arm_cfft_instance_f32 * S, + uint16_t fftLen); + + void arm_cfft_f32( + const arm_cfft_instance_f32 * S, + float32_t * p1, + uint8_t ifftFlag, + uint8_t bitReverseFlag); + + + /** + * @brief Instance structure for the Double Precision Floating-point CFFT/CIFFT function. + */ + typedef struct + { + uint16_t fftLen; /**< length of the FFT. */ + const float64_t *pTwiddle; /**< points to the Twiddle factor table. */ + const uint16_t *pBitRevTable; /**< points to the bit reversal table. */ + uint16_t bitRevLength; /**< bit reversal table length. */ + } arm_cfft_instance_f64; + + void arm_cfft_f64( + const arm_cfft_instance_f64 * S, + float64_t * p1, + uint8_t ifftFlag, + uint8_t bitReverseFlag); + + /** + * @brief Instance structure for the Q15 RFFT/RIFFT function. + */ + typedef struct + { + uint32_t fftLenReal; /**< length of the real FFT. */ + uint8_t ifftFlagR; /**< flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. */ + uint8_t bitReverseFlagR; /**< flag that enables (bitReverseFlagR=1) or disables (bitReverseFlagR=0) bit reversal of output. */ + uint32_t twidCoefRModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ + const q15_t *pTwiddleAReal; /**< points to the real twiddle factor table. */ + const q15_t *pTwiddleBReal; /**< points to the imag twiddle factor table. */ +#if defined(ARM_MATH_MVEI) + arm_cfft_instance_q15 cfftInst; +#else + const arm_cfft_instance_q15 *pCfft; /**< points to the complex FFT instance. */ +#endif + } arm_rfft_instance_q15; + + arm_status arm_rfft_init_q15( + arm_rfft_instance_q15 * S, + uint32_t fftLenReal, + uint32_t ifftFlagR, + uint32_t bitReverseFlag); + + void arm_rfft_q15( + const arm_rfft_instance_q15 * S, + q15_t * pSrc, + q15_t * pDst); + + /** + * @brief Instance structure for the Q31 RFFT/RIFFT function. + */ + typedef struct + { + uint32_t fftLenReal; /**< length of the real FFT. */ + uint8_t ifftFlagR; /**< flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. */ + uint8_t bitReverseFlagR; /**< flag that enables (bitReverseFlagR=1) or disables (bitReverseFlagR=0) bit reversal of output. */ + uint32_t twidCoefRModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ + const q31_t *pTwiddleAReal; /**< points to the real twiddle factor table. */ + const q31_t *pTwiddleBReal; /**< points to the imag twiddle factor table. */ +#if defined(ARM_MATH_MVEI) + arm_cfft_instance_q31 cfftInst; +#else + const arm_cfft_instance_q31 *pCfft; /**< points to the complex FFT instance. */ +#endif + } arm_rfft_instance_q31; + + arm_status arm_rfft_init_q31( + arm_rfft_instance_q31 * S, + uint32_t fftLenReal, + uint32_t ifftFlagR, + uint32_t bitReverseFlag); + + void arm_rfft_q31( + const arm_rfft_instance_q31 * S, + q31_t * pSrc, + q31_t * pDst); + + /** + * @brief Instance structure for the floating-point RFFT/RIFFT function. + */ + typedef struct + { + uint32_t fftLenReal; /**< length of the real FFT. */ + uint16_t fftLenBy2; /**< length of the complex FFT. */ + uint8_t ifftFlagR; /**< flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. */ + uint8_t bitReverseFlagR; /**< flag that enables (bitReverseFlagR=1) or disables (bitReverseFlagR=0) bit reversal of output. */ + uint32_t twidCoefRModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ + const float32_t *pTwiddleAReal; /**< points to the real twiddle factor table. */ + const float32_t *pTwiddleBReal; /**< points to the imag twiddle factor table. */ + arm_cfft_radix4_instance_f32 *pCfft; /**< points to the complex FFT instance. */ + } arm_rfft_instance_f32; + + arm_status arm_rfft_init_f32( + arm_rfft_instance_f32 * S, + arm_cfft_radix4_instance_f32 * S_CFFT, + uint32_t fftLenReal, + uint32_t ifftFlagR, + uint32_t bitReverseFlag); + + void arm_rfft_f32( + const arm_rfft_instance_f32 * S, + float32_t * pSrc, + float32_t * pDst); + + /** + * @brief Instance structure for the Double Precision Floating-point RFFT/RIFFT function. + */ +typedef struct + { + arm_cfft_instance_f64 Sint; /**< Internal CFFT structure. */ + uint16_t fftLenRFFT; /**< length of the real sequence */ + const float64_t * pTwiddleRFFT; /**< Twiddle factors real stage */ + } arm_rfft_fast_instance_f64 ; + +arm_status arm_rfft_fast_init_f64 ( + arm_rfft_fast_instance_f64 * S, + uint16_t fftLen); + + +void arm_rfft_fast_f64( + arm_rfft_fast_instance_f64 * S, + float64_t * p, float64_t * pOut, + uint8_t ifftFlag); + + + /** + * @brief Instance structure for the floating-point RFFT/RIFFT function. + */ +typedef struct + { + arm_cfft_instance_f32 Sint; /**< Internal CFFT structure. */ + uint16_t fftLenRFFT; /**< length of the real sequence */ + const float32_t * pTwiddleRFFT; /**< Twiddle factors real stage */ + } arm_rfft_fast_instance_f32 ; + +arm_status arm_rfft_fast_init_f32 ( + arm_rfft_fast_instance_f32 * S, + uint16_t fftLen); + + + void arm_rfft_fast_f32( + const arm_rfft_fast_instance_f32 * S, + float32_t * p, float32_t * pOut, + uint8_t ifftFlag); + + /** + * @brief Instance structure for the floating-point DCT4/IDCT4 function. + */ + typedef struct + { + uint16_t N; /**< length of the DCT4. */ + uint16_t Nby2; /**< half of the length of the DCT4. */ + float32_t normalize; /**< normalizing factor. */ + const float32_t *pTwiddle; /**< points to the twiddle factor table. */ + const float32_t *pCosFactor; /**< points to the cosFactor table. */ + arm_rfft_instance_f32 *pRfft; /**< points to the real FFT instance. */ + arm_cfft_radix4_instance_f32 *pCfft; /**< points to the complex FFT instance. */ + } arm_dct4_instance_f32; + + + /** + * @brief Initialization function for the floating-point DCT4/IDCT4. + * @param[in,out] S points to an instance of floating-point DCT4/IDCT4 structure. + * @param[in] S_RFFT points to an instance of floating-point RFFT/RIFFT structure. + * @param[in] S_CFFT points to an instance of floating-point CFFT/CIFFT structure. + * @param[in] N length of the DCT4. + * @param[in] Nby2 half of the length of the DCT4. + * @param[in] normalize normalizing factor. + * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLenReal is not a supported transform length. + */ + arm_status arm_dct4_init_f32( + arm_dct4_instance_f32 * S, + arm_rfft_instance_f32 * S_RFFT, + arm_cfft_radix4_instance_f32 * S_CFFT, + uint16_t N, + uint16_t Nby2, + float32_t normalize); + + + /** + * @brief Processing function for the floating-point DCT4/IDCT4. + * @param[in] S points to an instance of the floating-point DCT4/IDCT4 structure. + * @param[in] pState points to state buffer. + * @param[in,out] pInlineBuffer points to the in-place input and output buffer. + */ + void arm_dct4_f32( + const arm_dct4_instance_f32 * S, + float32_t * pState, + float32_t * pInlineBuffer); + + + /** + * @brief Instance structure for the Q31 DCT4/IDCT4 function. + */ + typedef struct + { + uint16_t N; /**< length of the DCT4. */ + uint16_t Nby2; /**< half of the length of the DCT4. */ + q31_t normalize; /**< normalizing factor. */ + const q31_t *pTwiddle; /**< points to the twiddle factor table. */ + const q31_t *pCosFactor; /**< points to the cosFactor table. */ + arm_rfft_instance_q31 *pRfft; /**< points to the real FFT instance. */ + arm_cfft_radix4_instance_q31 *pCfft; /**< points to the complex FFT instance. */ + } arm_dct4_instance_q31; + + + /** + * @brief Initialization function for the Q31 DCT4/IDCT4. + * @param[in,out] S points to an instance of Q31 DCT4/IDCT4 structure. + * @param[in] S_RFFT points to an instance of Q31 RFFT/RIFFT structure + * @param[in] S_CFFT points to an instance of Q31 CFFT/CIFFT structure + * @param[in] N length of the DCT4. + * @param[in] Nby2 half of the length of the DCT4. + * @param[in] normalize normalizing factor. + * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if N is not a supported transform length. + */ + arm_status arm_dct4_init_q31( + arm_dct4_instance_q31 * S, + arm_rfft_instance_q31 * S_RFFT, + arm_cfft_radix4_instance_q31 * S_CFFT, + uint16_t N, + uint16_t Nby2, + q31_t normalize); + + + /** + * @brief Processing function for the Q31 DCT4/IDCT4. + * @param[in] S points to an instance of the Q31 DCT4 structure. + * @param[in] pState points to state buffer. + * @param[in,out] pInlineBuffer points to the in-place input and output buffer. + */ + void arm_dct4_q31( + const arm_dct4_instance_q31 * S, + q31_t * pState, + q31_t * pInlineBuffer); + + + /** + * @brief Instance structure for the Q15 DCT4/IDCT4 function. + */ + typedef struct + { + uint16_t N; /**< length of the DCT4. */ + uint16_t Nby2; /**< half of the length of the DCT4. */ + q15_t normalize; /**< normalizing factor. */ + const q15_t *pTwiddle; /**< points to the twiddle factor table. */ + const q15_t *pCosFactor; /**< points to the cosFactor table. */ + arm_rfft_instance_q15 *pRfft; /**< points to the real FFT instance. */ + arm_cfft_radix4_instance_q15 *pCfft; /**< points to the complex FFT instance. */ + } arm_dct4_instance_q15; + + + /** + * @brief Initialization function for the Q15 DCT4/IDCT4. + * @param[in,out] S points to an instance of Q15 DCT4/IDCT4 structure. + * @param[in] S_RFFT points to an instance of Q15 RFFT/RIFFT structure. + * @param[in] S_CFFT points to an instance of Q15 CFFT/CIFFT structure. + * @param[in] N length of the DCT4. + * @param[in] Nby2 half of the length of the DCT4. + * @param[in] normalize normalizing factor. + * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if N is not a supported transform length. + */ + arm_status arm_dct4_init_q15( + arm_dct4_instance_q15 * S, + arm_rfft_instance_q15 * S_RFFT, + arm_cfft_radix4_instance_q15 * S_CFFT, + uint16_t N, + uint16_t Nby2, + q15_t normalize); + + + /** + * @brief Processing function for the Q15 DCT4/IDCT4. + * @param[in] S points to an instance of the Q15 DCT4 structure. + * @param[in] pState points to state buffer. + * @param[in,out] pInlineBuffer points to the in-place input and output buffer. + */ + void arm_dct4_q15( + const arm_dct4_instance_q15 * S, + q15_t * pState, + q15_t * pInlineBuffer); + + + /** + * @brief Floating-point vector addition. + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in each vector + */ + void arm_add_f32( + const float32_t * pSrcA, + const float32_t * pSrcB, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @brief Q7 vector addition. + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in each vector + */ + void arm_add_q7( + const q7_t * pSrcA, + const q7_t * pSrcB, + q7_t * pDst, + uint32_t blockSize); + + + /** + * @brief Q15 vector addition. + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in each vector + */ + void arm_add_q15( + const q15_t * pSrcA, + const q15_t * pSrcB, + q15_t * pDst, + uint32_t blockSize); + + + /** + * @brief Q31 vector addition. + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in each vector + */ + void arm_add_q31( + const q31_t * pSrcA, + const q31_t * pSrcB, + q31_t * pDst, + uint32_t blockSize); + + + /** + * @brief Floating-point vector subtraction. + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in each vector + */ + void arm_sub_f32( + const float32_t * pSrcA, + const float32_t * pSrcB, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @brief Q7 vector subtraction. + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in each vector + */ + void arm_sub_q7( + const q7_t * pSrcA, + const q7_t * pSrcB, + q7_t * pDst, + uint32_t blockSize); + + + /** + * @brief Q15 vector subtraction. + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in each vector + */ + void arm_sub_q15( + const q15_t * pSrcA, + const q15_t * pSrcB, + q15_t * pDst, + uint32_t blockSize); + + + /** + * @brief Q31 vector subtraction. + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in each vector + */ + void arm_sub_q31( + const q31_t * pSrcA, + const q31_t * pSrcB, + q31_t * pDst, + uint32_t blockSize); + + + /** + * @brief Multiplies a floating-point vector by a scalar. + * @param[in] pSrc points to the input vector + * @param[in] scale scale factor to be applied + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in the vector + */ + void arm_scale_f32( + const float32_t * pSrc, + float32_t scale, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @brief Multiplies a Q7 vector by a scalar. + * @param[in] pSrc points to the input vector + * @param[in] scaleFract fractional portion of the scale value + * @param[in] shift number of bits to shift the result by + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in the vector + */ + void arm_scale_q7( + const q7_t * pSrc, + q7_t scaleFract, + int8_t shift, + q7_t * pDst, + uint32_t blockSize); + + + /** + * @brief Multiplies a Q15 vector by a scalar. + * @param[in] pSrc points to the input vector + * @param[in] scaleFract fractional portion of the scale value + * @param[in] shift number of bits to shift the result by + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in the vector + */ + void arm_scale_q15( + const q15_t * pSrc, + q15_t scaleFract, + int8_t shift, + q15_t * pDst, + uint32_t blockSize); + + + /** + * @brief Multiplies a Q31 vector by a scalar. + * @param[in] pSrc points to the input vector + * @param[in] scaleFract fractional portion of the scale value + * @param[in] shift number of bits to shift the result by + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in the vector + */ + void arm_scale_q31( + const q31_t * pSrc, + q31_t scaleFract, + int8_t shift, + q31_t * pDst, + uint32_t blockSize); + + + /** + * @brief Q7 vector absolute value. + * @param[in] pSrc points to the input buffer + * @param[out] pDst points to the output buffer + * @param[in] blockSize number of samples in each vector + */ + void arm_abs_q7( + const q7_t * pSrc, + q7_t * pDst, + uint32_t blockSize); + + + /** + * @brief Floating-point vector absolute value. + * @param[in] pSrc points to the input buffer + * @param[out] pDst points to the output buffer + * @param[in] blockSize number of samples in each vector + */ + void arm_abs_f32( + const float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @brief Q15 vector absolute value. + * @param[in] pSrc points to the input buffer + * @param[out] pDst points to the output buffer + * @param[in] blockSize number of samples in each vector + */ + void arm_abs_q15( + const q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + + /** + * @brief Q31 vector absolute value. + * @param[in] pSrc points to the input buffer + * @param[out] pDst points to the output buffer + * @param[in] blockSize number of samples in each vector + */ + void arm_abs_q31( + const q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + + /** + * @brief Dot product of floating-point vectors. + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[in] blockSize number of samples in each vector + * @param[out] result output result returned here + */ + void arm_dot_prod_f32( + const float32_t * pSrcA, + const float32_t * pSrcB, + uint32_t blockSize, + float32_t * result); + + + /** + * @brief Dot product of Q7 vectors. + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[in] blockSize number of samples in each vector + * @param[out] result output result returned here + */ + void arm_dot_prod_q7( + const q7_t * pSrcA, + const q7_t * pSrcB, + uint32_t blockSize, + q31_t * result); + + + /** + * @brief Dot product of Q15 vectors. + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[in] blockSize number of samples in each vector + * @param[out] result output result returned here + */ + void arm_dot_prod_q15( + const q15_t * pSrcA, + const q15_t * pSrcB, + uint32_t blockSize, + q63_t * result); + + + /** + * @brief Dot product of Q31 vectors. + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[in] blockSize number of samples in each vector + * @param[out] result output result returned here + */ + void arm_dot_prod_q31( + const q31_t * pSrcA, + const q31_t * pSrcB, + uint32_t blockSize, + q63_t * result); + + + /** + * @brief Shifts the elements of a Q7 vector a specified number of bits. + * @param[in] pSrc points to the input vector + * @param[in] shiftBits number of bits to shift. A positive value shifts left; a negative value shifts right. + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in the vector + */ + void arm_shift_q7( + const q7_t * pSrc, + int8_t shiftBits, + q7_t * pDst, + uint32_t blockSize); + + + /** + * @brief Shifts the elements of a Q15 vector a specified number of bits. + * @param[in] pSrc points to the input vector + * @param[in] shiftBits number of bits to shift. A positive value shifts left; a negative value shifts right. + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in the vector + */ + void arm_shift_q15( + const q15_t * pSrc, + int8_t shiftBits, + q15_t * pDst, + uint32_t blockSize); + + + /** + * @brief Shifts the elements of a Q31 vector a specified number of bits. + * @param[in] pSrc points to the input vector + * @param[in] shiftBits number of bits to shift. A positive value shifts left; a negative value shifts right. + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in the vector + */ + void arm_shift_q31( + const q31_t * pSrc, + int8_t shiftBits, + q31_t * pDst, + uint32_t blockSize); + + + /** + * @brief Adds a constant offset to a floating-point vector. + * @param[in] pSrc points to the input vector + * @param[in] offset is the offset to be added + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in the vector + */ + void arm_offset_f32( + const float32_t * pSrc, + float32_t offset, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @brief Adds a constant offset to a Q7 vector. + * @param[in] pSrc points to the input vector + * @param[in] offset is the offset to be added + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in the vector + */ + void arm_offset_q7( + const q7_t * pSrc, + q7_t offset, + q7_t * pDst, + uint32_t blockSize); + + + /** + * @brief Adds a constant offset to a Q15 vector. + * @param[in] pSrc points to the input vector + * @param[in] offset is the offset to be added + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in the vector + */ + void arm_offset_q15( + const q15_t * pSrc, + q15_t offset, + q15_t * pDst, + uint32_t blockSize); + + + /** + * @brief Adds a constant offset to a Q31 vector. + * @param[in] pSrc points to the input vector + * @param[in] offset is the offset to be added + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in the vector + */ + void arm_offset_q31( + const q31_t * pSrc, + q31_t offset, + q31_t * pDst, + uint32_t blockSize); + + + /** + * @brief Negates the elements of a floating-point vector. + * @param[in] pSrc points to the input vector + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in the vector + */ + void arm_negate_f32( + const float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @brief Negates the elements of a Q7 vector. + * @param[in] pSrc points to the input vector + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in the vector + */ + void arm_negate_q7( + const q7_t * pSrc, + q7_t * pDst, + uint32_t blockSize); + + + /** + * @brief Negates the elements of a Q15 vector. + * @param[in] pSrc points to the input vector + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in the vector + */ + void arm_negate_q15( + const q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + + /** + * @brief Negates the elements of a Q31 vector. + * @param[in] pSrc points to the input vector + * @param[out] pDst points to the output vector + * @param[in] blockSize number of samples in the vector + */ + void arm_negate_q31( + const q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + + /** + * @brief Copies the elements of a floating-point vector. + * @param[in] pSrc input pointer + * @param[out] pDst output pointer + * @param[in] blockSize number of samples to process + */ + void arm_copy_f32( + const float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @brief Copies the elements of a Q7 vector. + * @param[in] pSrc input pointer + * @param[out] pDst output pointer + * @param[in] blockSize number of samples to process + */ + void arm_copy_q7( + const q7_t * pSrc, + q7_t * pDst, + uint32_t blockSize); + + + /** + * @brief Copies the elements of a Q15 vector. + * @param[in] pSrc input pointer + * @param[out] pDst output pointer + * @param[in] blockSize number of samples to process + */ + void arm_copy_q15( + const q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + + /** + * @brief Copies the elements of a Q31 vector. + * @param[in] pSrc input pointer + * @param[out] pDst output pointer + * @param[in] blockSize number of samples to process + */ + void arm_copy_q31( + const q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + + /** + * @brief Fills a constant value into a floating-point vector. + * @param[in] value input value to be filled + * @param[out] pDst output pointer + * @param[in] blockSize number of samples to process + */ + void arm_fill_f32( + float32_t value, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @brief Fills a constant value into a Q7 vector. + * @param[in] value input value to be filled + * @param[out] pDst output pointer + * @param[in] blockSize number of samples to process + */ + void arm_fill_q7( + q7_t value, + q7_t * pDst, + uint32_t blockSize); + + + /** + * @brief Fills a constant value into a Q15 vector. + * @param[in] value input value to be filled + * @param[out] pDst output pointer + * @param[in] blockSize number of samples to process + */ + void arm_fill_q15( + q15_t value, + q15_t * pDst, + uint32_t blockSize); + + + /** + * @brief Fills a constant value into a Q31 vector. + * @param[in] value input value to be filled + * @param[out] pDst output pointer + * @param[in] blockSize number of samples to process + */ + void arm_fill_q31( + q31_t value, + q31_t * pDst, + uint32_t blockSize); + + +/** + * @brief Convolution of floating-point sequences. + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the location where the output result is written. Length srcALen+srcBLen-1. + */ + void arm_conv_f32( + const float32_t * pSrcA, + uint32_t srcALen, + const float32_t * pSrcB, + uint32_t srcBLen, + float32_t * pDst); + + + /** + * @brief Convolution of Q15 sequences. + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data Length srcALen+srcBLen-1. + * @param[in] pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. + * @param[in] pScratch2 points to scratch buffer of size min(srcALen, srcBLen). + */ + void arm_conv_opt_q15( + const q15_t * pSrcA, + uint32_t srcALen, + const q15_t * pSrcB, + uint32_t srcBLen, + q15_t * pDst, + q15_t * pScratch1, + q15_t * pScratch2); + + +/** + * @brief Convolution of Q15 sequences. + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the location where the output result is written. Length srcALen+srcBLen-1. + */ + void arm_conv_q15( + const q15_t * pSrcA, + uint32_t srcALen, + const q15_t * pSrcB, + uint32_t srcBLen, + q15_t * pDst); + + + /** + * @brief Convolution of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4 + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data Length srcALen+srcBLen-1. + */ + void arm_conv_fast_q15( + const q15_t * pSrcA, + uint32_t srcALen, + const q15_t * pSrcB, + uint32_t srcBLen, + q15_t * pDst); + + + /** + * @brief Convolution of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4 + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data Length srcALen+srcBLen-1. + * @param[in] pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. + * @param[in] pScratch2 points to scratch buffer of size min(srcALen, srcBLen). + */ + void arm_conv_fast_opt_q15( + const q15_t * pSrcA, + uint32_t srcALen, + const q15_t * pSrcB, + uint32_t srcBLen, + q15_t * pDst, + q15_t * pScratch1, + q15_t * pScratch2); + + + /** + * @brief Convolution of Q31 sequences. + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data Length srcALen+srcBLen-1. + */ + void arm_conv_q31( + const q31_t * pSrcA, + uint32_t srcALen, + const q31_t * pSrcB, + uint32_t srcBLen, + q31_t * pDst); + + + /** + * @brief Convolution of Q31 sequences (fast version) for Cortex-M3 and Cortex-M4 + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data Length srcALen+srcBLen-1. + */ + void arm_conv_fast_q31( + const q31_t * pSrcA, + uint32_t srcALen, + const q31_t * pSrcB, + uint32_t srcBLen, + q31_t * pDst); + + + /** + * @brief Convolution of Q7 sequences. + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data Length srcALen+srcBLen-1. + * @param[in] pScratch1 points to scratch buffer(of type q15_t) of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. + * @param[in] pScratch2 points to scratch buffer (of type q15_t) of size min(srcALen, srcBLen). + */ + void arm_conv_opt_q7( + const q7_t * pSrcA, + uint32_t srcALen, + const q7_t * pSrcB, + uint32_t srcBLen, + q7_t * pDst, + q15_t * pScratch1, + q15_t * pScratch2); + + + /** + * @brief Convolution of Q7 sequences. + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data Length srcALen+srcBLen-1. + */ + void arm_conv_q7( + const q7_t * pSrcA, + uint32_t srcALen, + const q7_t * pSrcB, + uint32_t srcBLen, + q7_t * pDst); + + + /** + * @brief Partial convolution of floating-point sequences. + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data + * @param[in] firstIndex is the first output sample to start with. + * @param[in] numPoints is the number of output points to be computed. + * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. + */ + arm_status arm_conv_partial_f32( + const float32_t * pSrcA, + uint32_t srcALen, + const float32_t * pSrcB, + uint32_t srcBLen, + float32_t * pDst, + uint32_t firstIndex, + uint32_t numPoints); + + + /** + * @brief Partial convolution of Q15 sequences. + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data + * @param[in] firstIndex is the first output sample to start with. + * @param[in] numPoints is the number of output points to be computed. + * @param[in] pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. + * @param[in] pScratch2 points to scratch buffer of size min(srcALen, srcBLen). + * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. + */ + arm_status arm_conv_partial_opt_q15( + const q15_t * pSrcA, + uint32_t srcALen, + const q15_t * pSrcB, + uint32_t srcBLen, + q15_t * pDst, + uint32_t firstIndex, + uint32_t numPoints, + q15_t * pScratch1, + q15_t * pScratch2); + + + /** + * @brief Partial convolution of Q15 sequences. + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data + * @param[in] firstIndex is the first output sample to start with. + * @param[in] numPoints is the number of output points to be computed. + * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. + */ + arm_status arm_conv_partial_q15( + const q15_t * pSrcA, + uint32_t srcALen, + const q15_t * pSrcB, + uint32_t srcBLen, + q15_t * pDst, + uint32_t firstIndex, + uint32_t numPoints); + + + /** + * @brief Partial convolution of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4 + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data + * @param[in] firstIndex is the first output sample to start with. + * @param[in] numPoints is the number of output points to be computed. + * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. + */ + arm_status arm_conv_partial_fast_q15( + const q15_t * pSrcA, + uint32_t srcALen, + const q15_t * pSrcB, + uint32_t srcBLen, + q15_t * pDst, + uint32_t firstIndex, + uint32_t numPoints); + + + /** + * @brief Partial convolution of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4 + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data + * @param[in] firstIndex is the first output sample to start with. + * @param[in] numPoints is the number of output points to be computed. + * @param[in] pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. + * @param[in] pScratch2 points to scratch buffer of size min(srcALen, srcBLen). + * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. + */ + arm_status arm_conv_partial_fast_opt_q15( + const q15_t * pSrcA, + uint32_t srcALen, + const q15_t * pSrcB, + uint32_t srcBLen, + q15_t * pDst, + uint32_t firstIndex, + uint32_t numPoints, + q15_t * pScratch1, + q15_t * pScratch2); + + + /** + * @brief Partial convolution of Q31 sequences. + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data + * @param[in] firstIndex is the first output sample to start with. + * @param[in] numPoints is the number of output points to be computed. + * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. + */ + arm_status arm_conv_partial_q31( + const q31_t * pSrcA, + uint32_t srcALen, + const q31_t * pSrcB, + uint32_t srcBLen, + q31_t * pDst, + uint32_t firstIndex, + uint32_t numPoints); + + + /** + * @brief Partial convolution of Q31 sequences (fast version) for Cortex-M3 and Cortex-M4 + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data + * @param[in] firstIndex is the first output sample to start with. + * @param[in] numPoints is the number of output points to be computed. + * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. + */ + arm_status arm_conv_partial_fast_q31( + const q31_t * pSrcA, + uint32_t srcALen, + const q31_t * pSrcB, + uint32_t srcBLen, + q31_t * pDst, + uint32_t firstIndex, + uint32_t numPoints); + + + /** + * @brief Partial convolution of Q7 sequences + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data + * @param[in] firstIndex is the first output sample to start with. + * @param[in] numPoints is the number of output points to be computed. + * @param[in] pScratch1 points to scratch buffer(of type q15_t) of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. + * @param[in] pScratch2 points to scratch buffer (of type q15_t) of size min(srcALen, srcBLen). + * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. + */ + arm_status arm_conv_partial_opt_q7( + const q7_t * pSrcA, + uint32_t srcALen, + const q7_t * pSrcB, + uint32_t srcBLen, + q7_t * pDst, + uint32_t firstIndex, + uint32_t numPoints, + q15_t * pScratch1, + q15_t * pScratch2); + + +/** + * @brief Partial convolution of Q7 sequences. + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data + * @param[in] firstIndex is the first output sample to start with. + * @param[in] numPoints is the number of output points to be computed. + * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. + */ + arm_status arm_conv_partial_q7( + const q7_t * pSrcA, + uint32_t srcALen, + const q7_t * pSrcB, + uint32_t srcBLen, + q7_t * pDst, + uint32_t firstIndex, + uint32_t numPoints); + + + /** + * @brief Instance structure for the Q15 FIR decimator. + */ + typedef struct + { + uint8_t M; /**< decimation factor. */ + uint16_t numTaps; /**< number of coefficients in the filter. */ + const q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ + q15_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + } arm_fir_decimate_instance_q15; + + /** + * @brief Instance structure for the Q31 FIR decimator. + */ + typedef struct + { + uint8_t M; /**< decimation factor. */ + uint16_t numTaps; /**< number of coefficients in the filter. */ + const q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ + q31_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + } arm_fir_decimate_instance_q31; + +/** + @brief Instance structure for floating-point FIR decimator. + */ +typedef struct + { + uint8_t M; /**< decimation factor. */ + uint16_t numTaps; /**< number of coefficients in the filter. */ + const float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ + float32_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + } arm_fir_decimate_instance_f32; + + +/** + @brief Processing function for floating-point FIR decimator. + @param[in] S points to an instance of the floating-point FIR decimator structure + @param[in] pSrc points to the block of input data + @param[out] pDst points to the block of output data + @param[in] blockSize number of samples to process + */ +void arm_fir_decimate_f32( + const arm_fir_decimate_instance_f32 * S, + const float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + +/** + @brief Initialization function for the floating-point FIR decimator. + @param[in,out] S points to an instance of the floating-point FIR decimator structure + @param[in] numTaps number of coefficients in the filter + @param[in] M decimation factor + @param[in] pCoeffs points to the filter coefficients + @param[in] pState points to the state buffer + @param[in] blockSize number of input samples to process per call + @return execution status + - \ref ARM_MATH_SUCCESS : Operation successful + - \ref ARM_MATH_LENGTH_ERROR : blockSize is not a multiple of M + */ +arm_status arm_fir_decimate_init_f32( + arm_fir_decimate_instance_f32 * S, + uint16_t numTaps, + uint8_t M, + const float32_t * pCoeffs, + float32_t * pState, + uint32_t blockSize); + + + /** + * @brief Processing function for the Q15 FIR decimator. + * @param[in] S points to an instance of the Q15 FIR decimator structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data + * @param[in] blockSize number of input samples to process per call. + */ + void arm_fir_decimate_q15( + const arm_fir_decimate_instance_q15 * S, + const q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + + /** + * @brief Processing function for the Q15 FIR decimator (fast variant) for Cortex-M3 and Cortex-M4. + * @param[in] S points to an instance of the Q15 FIR decimator structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data + * @param[in] blockSize number of input samples to process per call. + */ + void arm_fir_decimate_fast_q15( + const arm_fir_decimate_instance_q15 * S, + const q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + + /** + * @brief Initialization function for the Q15 FIR decimator. + * @param[in,out] S points to an instance of the Q15 FIR decimator structure. + * @param[in] numTaps number of coefficients in the filter. + * @param[in] M decimation factor. + * @param[in] pCoeffs points to the filter coefficients. + * @param[in] pState points to the state buffer. + * @param[in] blockSize number of input samples to process per call. + * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if + * blockSize is not a multiple of M. + */ + arm_status arm_fir_decimate_init_q15( + arm_fir_decimate_instance_q15 * S, + uint16_t numTaps, + uint8_t M, + const q15_t * pCoeffs, + q15_t * pState, + uint32_t blockSize); + + + /** + * @brief Processing function for the Q31 FIR decimator. + * @param[in] S points to an instance of the Q31 FIR decimator structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data + * @param[in] blockSize number of input samples to process per call. + */ + void arm_fir_decimate_q31( + const arm_fir_decimate_instance_q31 * S, + const q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + /** + * @brief Processing function for the Q31 FIR decimator (fast variant) for Cortex-M3 and Cortex-M4. + * @param[in] S points to an instance of the Q31 FIR decimator structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data + * @param[in] blockSize number of input samples to process per call. + */ + void arm_fir_decimate_fast_q31( + const arm_fir_decimate_instance_q31 * S, + const q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + + /** + * @brief Initialization function for the Q31 FIR decimator. + * @param[in,out] S points to an instance of the Q31 FIR decimator structure. + * @param[in] numTaps number of coefficients in the filter. + * @param[in] M decimation factor. + * @param[in] pCoeffs points to the filter coefficients. + * @param[in] pState points to the state buffer. + * @param[in] blockSize number of input samples to process per call. + * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if + * blockSize is not a multiple of M. + */ + arm_status arm_fir_decimate_init_q31( + arm_fir_decimate_instance_q31 * S, + uint16_t numTaps, + uint8_t M, + const q31_t * pCoeffs, + q31_t * pState, + uint32_t blockSize); + + + /** + * @brief Instance structure for the Q15 FIR interpolator. + */ + typedef struct + { + uint8_t L; /**< upsample factor. */ + uint16_t phaseLength; /**< length of each polyphase filter component. */ + const q15_t *pCoeffs; /**< points to the coefficient array. The array is of length L*phaseLength. */ + q15_t *pState; /**< points to the state variable array. The array is of length blockSize+phaseLength-1. */ + } arm_fir_interpolate_instance_q15; + + /** + * @brief Instance structure for the Q31 FIR interpolator. + */ + typedef struct + { + uint8_t L; /**< upsample factor. */ + uint16_t phaseLength; /**< length of each polyphase filter component. */ + const q31_t *pCoeffs; /**< points to the coefficient array. The array is of length L*phaseLength. */ + q31_t *pState; /**< points to the state variable array. The array is of length blockSize+phaseLength-1. */ + } arm_fir_interpolate_instance_q31; + + /** + * @brief Instance structure for the floating-point FIR interpolator. + */ + typedef struct + { + uint8_t L; /**< upsample factor. */ + uint16_t phaseLength; /**< length of each polyphase filter component. */ + const float32_t *pCoeffs; /**< points to the coefficient array. The array is of length L*phaseLength. */ + float32_t *pState; /**< points to the state variable array. The array is of length phaseLength+numTaps-1. */ + } arm_fir_interpolate_instance_f32; + + + /** + * @brief Processing function for the Q15 FIR interpolator. + * @param[in] S points to an instance of the Q15 FIR interpolator structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of input samples to process per call. + */ + void arm_fir_interpolate_q15( + const arm_fir_interpolate_instance_q15 * S, + const q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + + /** + * @brief Initialization function for the Q15 FIR interpolator. + * @param[in,out] S points to an instance of the Q15 FIR interpolator structure. + * @param[in] L upsample factor. + * @param[in] numTaps number of filter coefficients in the filter. + * @param[in] pCoeffs points to the filter coefficient buffer. + * @param[in] pState points to the state buffer. + * @param[in] blockSize number of input samples to process per call. + * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if + * the filter length numTaps is not a multiple of the interpolation factor L. + */ + arm_status arm_fir_interpolate_init_q15( + arm_fir_interpolate_instance_q15 * S, + uint8_t L, + uint16_t numTaps, + const q15_t * pCoeffs, + q15_t * pState, + uint32_t blockSize); + + + /** + * @brief Processing function for the Q31 FIR interpolator. + * @param[in] S points to an instance of the Q15 FIR interpolator structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of input samples to process per call. + */ + void arm_fir_interpolate_q31( + const arm_fir_interpolate_instance_q31 * S, + const q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + + /** + * @brief Initialization function for the Q31 FIR interpolator. + * @param[in,out] S points to an instance of the Q31 FIR interpolator structure. + * @param[in] L upsample factor. + * @param[in] numTaps number of filter coefficients in the filter. + * @param[in] pCoeffs points to the filter coefficient buffer. + * @param[in] pState points to the state buffer. + * @param[in] blockSize number of input samples to process per call. + * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if + * the filter length numTaps is not a multiple of the interpolation factor L. + */ + arm_status arm_fir_interpolate_init_q31( + arm_fir_interpolate_instance_q31 * S, + uint8_t L, + uint16_t numTaps, + const q31_t * pCoeffs, + q31_t * pState, + uint32_t blockSize); + + + /** + * @brief Processing function for the floating-point FIR interpolator. + * @param[in] S points to an instance of the floating-point FIR interpolator structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of input samples to process per call. + */ + void arm_fir_interpolate_f32( + const arm_fir_interpolate_instance_f32 * S, + const float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @brief Initialization function for the floating-point FIR interpolator. + * @param[in,out] S points to an instance of the floating-point FIR interpolator structure. + * @param[in] L upsample factor. + * @param[in] numTaps number of filter coefficients in the filter. + * @param[in] pCoeffs points to the filter coefficient buffer. + * @param[in] pState points to the state buffer. + * @param[in] blockSize number of input samples to process per call. + * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if + * the filter length numTaps is not a multiple of the interpolation factor L. + */ + arm_status arm_fir_interpolate_init_f32( + arm_fir_interpolate_instance_f32 * S, + uint8_t L, + uint16_t numTaps, + const float32_t * pCoeffs, + float32_t * pState, + uint32_t blockSize); + + + /** + * @brief Instance structure for the high precision Q31 Biquad cascade filter. + */ + typedef struct + { + uint8_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */ + q63_t *pState; /**< points to the array of state coefficients. The array is of length 4*numStages. */ + const q31_t *pCoeffs; /**< points to the array of coefficients. The array is of length 5*numStages. */ + uint8_t postShift; /**< additional shift, in bits, applied to each output sample. */ + } arm_biquad_cas_df1_32x64_ins_q31; + + + /** + * @param[in] S points to an instance of the high precision Q31 Biquad cascade filter structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data + * @param[in] blockSize number of samples to process. + */ + void arm_biquad_cas_df1_32x64_q31( + const arm_biquad_cas_df1_32x64_ins_q31 * S, + const q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + + /** + * @param[in,out] S points to an instance of the high precision Q31 Biquad cascade filter structure. + * @param[in] numStages number of 2nd order stages in the filter. + * @param[in] pCoeffs points to the filter coefficients. + * @param[in] pState points to the state buffer. + * @param[in] postShift shift to be applied to the output. Varies according to the coefficients format + */ + void arm_biquad_cas_df1_32x64_init_q31( + arm_biquad_cas_df1_32x64_ins_q31 * S, + uint8_t numStages, + const q31_t * pCoeffs, + q63_t * pState, + uint8_t postShift); + + + /** + * @brief Instance structure for the floating-point transposed direct form II Biquad cascade filter. + */ + typedef struct + { + uint8_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */ + float32_t *pState; /**< points to the array of state coefficients. The array is of length 2*numStages. */ + const float32_t *pCoeffs; /**< points to the array of coefficients. The array is of length 5*numStages. */ + } arm_biquad_cascade_df2T_instance_f32; + + /** + * @brief Instance structure for the floating-point transposed direct form II Biquad cascade filter. + */ + typedef struct + { + uint8_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */ + float32_t *pState; /**< points to the array of state coefficients. The array is of length 4*numStages. */ + const float32_t *pCoeffs; /**< points to the array of coefficients. The array is of length 5*numStages. */ + } arm_biquad_cascade_stereo_df2T_instance_f32; + + /** + * @brief Instance structure for the floating-point transposed direct form II Biquad cascade filter. + */ + typedef struct + { + uint8_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */ + float64_t *pState; /**< points to the array of state coefficients. The array is of length 2*numStages. */ + const float64_t *pCoeffs; /**< points to the array of coefficients. The array is of length 5*numStages. */ + } arm_biquad_cascade_df2T_instance_f64; + + + /** + * @brief Processing function for the floating-point transposed direct form II Biquad cascade filter. + * @param[in] S points to an instance of the filter data structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data + * @param[in] blockSize number of samples to process. + */ + void arm_biquad_cascade_df2T_f32( + const arm_biquad_cascade_df2T_instance_f32 * S, + const float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @brief Processing function for the floating-point transposed direct form II Biquad cascade filter. 2 channels + * @param[in] S points to an instance of the filter data structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data + * @param[in] blockSize number of samples to process. + */ + void arm_biquad_cascade_stereo_df2T_f32( + const arm_biquad_cascade_stereo_df2T_instance_f32 * S, + const float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @brief Processing function for the floating-point transposed direct form II Biquad cascade filter. + * @param[in] S points to an instance of the filter data structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data + * @param[in] blockSize number of samples to process. + */ + void arm_biquad_cascade_df2T_f64( + const arm_biquad_cascade_df2T_instance_f64 * S, + const float64_t * pSrc, + float64_t * pDst, + uint32_t blockSize); + + +#if defined(ARM_MATH_NEON) +void arm_biquad_cascade_df2T_compute_coefs_f32( + arm_biquad_cascade_df2T_instance_f32 * S, + uint8_t numStages, + float32_t * pCoeffs); +#endif + /** + * @brief Initialization function for the floating-point transposed direct form II Biquad cascade filter. + * @param[in,out] S points to an instance of the filter data structure. + * @param[in] numStages number of 2nd order stages in the filter. + * @param[in] pCoeffs points to the filter coefficients. + * @param[in] pState points to the state buffer. + */ + void arm_biquad_cascade_df2T_init_f32( + arm_biquad_cascade_df2T_instance_f32 * S, + uint8_t numStages, + const float32_t * pCoeffs, + float32_t * pState); + + + /** + * @brief Initialization function for the floating-point transposed direct form II Biquad cascade filter. + * @param[in,out] S points to an instance of the filter data structure. + * @param[in] numStages number of 2nd order stages in the filter. + * @param[in] pCoeffs points to the filter coefficients. + * @param[in] pState points to the state buffer. + */ + void arm_biquad_cascade_stereo_df2T_init_f32( + arm_biquad_cascade_stereo_df2T_instance_f32 * S, + uint8_t numStages, + const float32_t * pCoeffs, + float32_t * pState); + + + /** + * @brief Initialization function for the floating-point transposed direct form II Biquad cascade filter. + * @param[in,out] S points to an instance of the filter data structure. + * @param[in] numStages number of 2nd order stages in the filter. + * @param[in] pCoeffs points to the filter coefficients. + * @param[in] pState points to the state buffer. + */ + void arm_biquad_cascade_df2T_init_f64( + arm_biquad_cascade_df2T_instance_f64 * S, + uint8_t numStages, + const float64_t * pCoeffs, + float64_t * pState); + + + /** + * @brief Instance structure for the Q15 FIR lattice filter. + */ + typedef struct + { + uint16_t numStages; /**< number of filter stages. */ + q15_t *pState; /**< points to the state variable array. The array is of length numStages. */ + const q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numStages. */ + } arm_fir_lattice_instance_q15; + + /** + * @brief Instance structure for the Q31 FIR lattice filter. + */ + typedef struct + { + uint16_t numStages; /**< number of filter stages. */ + q31_t *pState; /**< points to the state variable array. The array is of length numStages. */ + const q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numStages. */ + } arm_fir_lattice_instance_q31; + + /** + * @brief Instance structure for the floating-point FIR lattice filter. + */ + typedef struct + { + uint16_t numStages; /**< number of filter stages. */ + float32_t *pState; /**< points to the state variable array. The array is of length numStages. */ + const float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numStages. */ + } arm_fir_lattice_instance_f32; + + + /** + * @brief Initialization function for the Q15 FIR lattice filter. + * @param[in] S points to an instance of the Q15 FIR lattice structure. + * @param[in] numStages number of filter stages. + * @param[in] pCoeffs points to the coefficient buffer. The array is of length numStages. + * @param[in] pState points to the state buffer. The array is of length numStages. + */ + void arm_fir_lattice_init_q15( + arm_fir_lattice_instance_q15 * S, + uint16_t numStages, + const q15_t * pCoeffs, + q15_t * pState); + + + /** + * @brief Processing function for the Q15 FIR lattice filter. + * @param[in] S points to an instance of the Q15 FIR lattice structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + */ + void arm_fir_lattice_q15( + const arm_fir_lattice_instance_q15 * S, + const q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + + /** + * @brief Initialization function for the Q31 FIR lattice filter. + * @param[in] S points to an instance of the Q31 FIR lattice structure. + * @param[in] numStages number of filter stages. + * @param[in] pCoeffs points to the coefficient buffer. The array is of length numStages. + * @param[in] pState points to the state buffer. The array is of length numStages. + */ + void arm_fir_lattice_init_q31( + arm_fir_lattice_instance_q31 * S, + uint16_t numStages, + const q31_t * pCoeffs, + q31_t * pState); + + + /** + * @brief Processing function for the Q31 FIR lattice filter. + * @param[in] S points to an instance of the Q31 FIR lattice structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data + * @param[in] blockSize number of samples to process. + */ + void arm_fir_lattice_q31( + const arm_fir_lattice_instance_q31 * S, + const q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + +/** + * @brief Initialization function for the floating-point FIR lattice filter. + * @param[in] S points to an instance of the floating-point FIR lattice structure. + * @param[in] numStages number of filter stages. + * @param[in] pCoeffs points to the coefficient buffer. The array is of length numStages. + * @param[in] pState points to the state buffer. The array is of length numStages. + */ + void arm_fir_lattice_init_f32( + arm_fir_lattice_instance_f32 * S, + uint16_t numStages, + const float32_t * pCoeffs, + float32_t * pState); + + + /** + * @brief Processing function for the floating-point FIR lattice filter. + * @param[in] S points to an instance of the floating-point FIR lattice structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data + * @param[in] blockSize number of samples to process. + */ + void arm_fir_lattice_f32( + const arm_fir_lattice_instance_f32 * S, + const float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @brief Instance structure for the Q15 IIR lattice filter. + */ + typedef struct + { + uint16_t numStages; /**< number of stages in the filter. */ + q15_t *pState; /**< points to the state variable array. The array is of length numStages+blockSize. */ + q15_t *pkCoeffs; /**< points to the reflection coefficient array. The array is of length numStages. */ + q15_t *pvCoeffs; /**< points to the ladder coefficient array. The array is of length numStages+1. */ + } arm_iir_lattice_instance_q15; + + /** + * @brief Instance structure for the Q31 IIR lattice filter. + */ + typedef struct + { + uint16_t numStages; /**< number of stages in the filter. */ + q31_t *pState; /**< points to the state variable array. The array is of length numStages+blockSize. */ + q31_t *pkCoeffs; /**< points to the reflection coefficient array. The array is of length numStages. */ + q31_t *pvCoeffs; /**< points to the ladder coefficient array. The array is of length numStages+1. */ + } arm_iir_lattice_instance_q31; + + /** + * @brief Instance structure for the floating-point IIR lattice filter. + */ + typedef struct + { + uint16_t numStages; /**< number of stages in the filter. */ + float32_t *pState; /**< points to the state variable array. The array is of length numStages+blockSize. */ + float32_t *pkCoeffs; /**< points to the reflection coefficient array. The array is of length numStages. */ + float32_t *pvCoeffs; /**< points to the ladder coefficient array. The array is of length numStages+1. */ + } arm_iir_lattice_instance_f32; + + + /** + * @brief Processing function for the floating-point IIR lattice filter. + * @param[in] S points to an instance of the floating-point IIR lattice structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + */ + void arm_iir_lattice_f32( + const arm_iir_lattice_instance_f32 * S, + const float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @brief Initialization function for the floating-point IIR lattice filter. + * @param[in] S points to an instance of the floating-point IIR lattice structure. + * @param[in] numStages number of stages in the filter. + * @param[in] pkCoeffs points to the reflection coefficient buffer. The array is of length numStages. + * @param[in] pvCoeffs points to the ladder coefficient buffer. The array is of length numStages+1. + * @param[in] pState points to the state buffer. The array is of length numStages+blockSize-1. + * @param[in] blockSize number of samples to process. + */ + void arm_iir_lattice_init_f32( + arm_iir_lattice_instance_f32 * S, + uint16_t numStages, + float32_t * pkCoeffs, + float32_t * pvCoeffs, + float32_t * pState, + uint32_t blockSize); + + + /** + * @brief Processing function for the Q31 IIR lattice filter. + * @param[in] S points to an instance of the Q31 IIR lattice structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + */ + void arm_iir_lattice_q31( + const arm_iir_lattice_instance_q31 * S, + const q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + + /** + * @brief Initialization function for the Q31 IIR lattice filter. + * @param[in] S points to an instance of the Q31 IIR lattice structure. + * @param[in] numStages number of stages in the filter. + * @param[in] pkCoeffs points to the reflection coefficient buffer. The array is of length numStages. + * @param[in] pvCoeffs points to the ladder coefficient buffer. The array is of length numStages+1. + * @param[in] pState points to the state buffer. The array is of length numStages+blockSize. + * @param[in] blockSize number of samples to process. + */ + void arm_iir_lattice_init_q31( + arm_iir_lattice_instance_q31 * S, + uint16_t numStages, + q31_t * pkCoeffs, + q31_t * pvCoeffs, + q31_t * pState, + uint32_t blockSize); + + + /** + * @brief Processing function for the Q15 IIR lattice filter. + * @param[in] S points to an instance of the Q15 IIR lattice structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + */ + void arm_iir_lattice_q15( + const arm_iir_lattice_instance_q15 * S, + const q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + +/** + * @brief Initialization function for the Q15 IIR lattice filter. + * @param[in] S points to an instance of the fixed-point Q15 IIR lattice structure. + * @param[in] numStages number of stages in the filter. + * @param[in] pkCoeffs points to reflection coefficient buffer. The array is of length numStages. + * @param[in] pvCoeffs points to ladder coefficient buffer. The array is of length numStages+1. + * @param[in] pState points to state buffer. The array is of length numStages+blockSize. + * @param[in] blockSize number of samples to process per call. + */ + void arm_iir_lattice_init_q15( + arm_iir_lattice_instance_q15 * S, + uint16_t numStages, + q15_t * pkCoeffs, + q15_t * pvCoeffs, + q15_t * pState, + uint32_t blockSize); + + + /** + * @brief Instance structure for the floating-point LMS filter. + */ + typedef struct + { + uint16_t numTaps; /**< number of coefficients in the filter. */ + float32_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ + float32_t mu; /**< step size that controls filter coefficient updates. */ + } arm_lms_instance_f32; + + + /** + * @brief Processing function for floating-point LMS filter. + * @param[in] S points to an instance of the floating-point LMS filter structure. + * @param[in] pSrc points to the block of input data. + * @param[in] pRef points to the block of reference data. + * @param[out] pOut points to the block of output data. + * @param[out] pErr points to the block of error data. + * @param[in] blockSize number of samples to process. + */ + void arm_lms_f32( + const arm_lms_instance_f32 * S, + const float32_t * pSrc, + float32_t * pRef, + float32_t * pOut, + float32_t * pErr, + uint32_t blockSize); + + + /** + * @brief Initialization function for floating-point LMS filter. + * @param[in] S points to an instance of the floating-point LMS filter structure. + * @param[in] numTaps number of filter coefficients. + * @param[in] pCoeffs points to the coefficient buffer. + * @param[in] pState points to state buffer. + * @param[in] mu step size that controls filter coefficient updates. + * @param[in] blockSize number of samples to process. + */ + void arm_lms_init_f32( + arm_lms_instance_f32 * S, + uint16_t numTaps, + float32_t * pCoeffs, + float32_t * pState, + float32_t mu, + uint32_t blockSize); + + + /** + * @brief Instance structure for the Q15 LMS filter. + */ + typedef struct + { + uint16_t numTaps; /**< number of coefficients in the filter. */ + q15_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ + q15_t mu; /**< step size that controls filter coefficient updates. */ + uint32_t postShift; /**< bit shift applied to coefficients. */ + } arm_lms_instance_q15; + + + /** + * @brief Initialization function for the Q15 LMS filter. + * @param[in] S points to an instance of the Q15 LMS filter structure. + * @param[in] numTaps number of filter coefficients. + * @param[in] pCoeffs points to the coefficient buffer. + * @param[in] pState points to the state buffer. + * @param[in] mu step size that controls filter coefficient updates. + * @param[in] blockSize number of samples to process. + * @param[in] postShift bit shift applied to coefficients. + */ + void arm_lms_init_q15( + arm_lms_instance_q15 * S, + uint16_t numTaps, + q15_t * pCoeffs, + q15_t * pState, + q15_t mu, + uint32_t blockSize, + uint32_t postShift); + + + /** + * @brief Processing function for Q15 LMS filter. + * @param[in] S points to an instance of the Q15 LMS filter structure. + * @param[in] pSrc points to the block of input data. + * @param[in] pRef points to the block of reference data. + * @param[out] pOut points to the block of output data. + * @param[out] pErr points to the block of error data. + * @param[in] blockSize number of samples to process. + */ + void arm_lms_q15( + const arm_lms_instance_q15 * S, + const q15_t * pSrc, + q15_t * pRef, + q15_t * pOut, + q15_t * pErr, + uint32_t blockSize); + + + /** + * @brief Instance structure for the Q31 LMS filter. + */ + typedef struct + { + uint16_t numTaps; /**< number of coefficients in the filter. */ + q31_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ + q31_t mu; /**< step size that controls filter coefficient updates. */ + uint32_t postShift; /**< bit shift applied to coefficients. */ + } arm_lms_instance_q31; + + + /** + * @brief Processing function for Q31 LMS filter. + * @param[in] S points to an instance of the Q15 LMS filter structure. + * @param[in] pSrc points to the block of input data. + * @param[in] pRef points to the block of reference data. + * @param[out] pOut points to the block of output data. + * @param[out] pErr points to the block of error data. + * @param[in] blockSize number of samples to process. + */ + void arm_lms_q31( + const arm_lms_instance_q31 * S, + const q31_t * pSrc, + q31_t * pRef, + q31_t * pOut, + q31_t * pErr, + uint32_t blockSize); + + + /** + * @brief Initialization function for Q31 LMS filter. + * @param[in] S points to an instance of the Q31 LMS filter structure. + * @param[in] numTaps number of filter coefficients. + * @param[in] pCoeffs points to coefficient buffer. + * @param[in] pState points to state buffer. + * @param[in] mu step size that controls filter coefficient updates. + * @param[in] blockSize number of samples to process. + * @param[in] postShift bit shift applied to coefficients. + */ + void arm_lms_init_q31( + arm_lms_instance_q31 * S, + uint16_t numTaps, + q31_t * pCoeffs, + q31_t * pState, + q31_t mu, + uint32_t blockSize, + uint32_t postShift); + + + /** + * @brief Instance structure for the floating-point normalized LMS filter. + */ + typedef struct + { + uint16_t numTaps; /**< number of coefficients in the filter. */ + float32_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ + float32_t mu; /**< step size that control filter coefficient updates. */ + float32_t energy; /**< saves previous frame energy. */ + float32_t x0; /**< saves previous input sample. */ + } arm_lms_norm_instance_f32; + + + /** + * @brief Processing function for floating-point normalized LMS filter. + * @param[in] S points to an instance of the floating-point normalized LMS filter structure. + * @param[in] pSrc points to the block of input data. + * @param[in] pRef points to the block of reference data. + * @param[out] pOut points to the block of output data. + * @param[out] pErr points to the block of error data. + * @param[in] blockSize number of samples to process. + */ + void arm_lms_norm_f32( + arm_lms_norm_instance_f32 * S, + const float32_t * pSrc, + float32_t * pRef, + float32_t * pOut, + float32_t * pErr, + uint32_t blockSize); + + + /** + * @brief Initialization function for floating-point normalized LMS filter. + * @param[in] S points to an instance of the floating-point LMS filter structure. + * @param[in] numTaps number of filter coefficients. + * @param[in] pCoeffs points to coefficient buffer. + * @param[in] pState points to state buffer. + * @param[in] mu step size that controls filter coefficient updates. + * @param[in] blockSize number of samples to process. + */ + void arm_lms_norm_init_f32( + arm_lms_norm_instance_f32 * S, + uint16_t numTaps, + float32_t * pCoeffs, + float32_t * pState, + float32_t mu, + uint32_t blockSize); + + + /** + * @brief Instance structure for the Q31 normalized LMS filter. + */ + typedef struct + { + uint16_t numTaps; /**< number of coefficients in the filter. */ + q31_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ + q31_t mu; /**< step size that controls filter coefficient updates. */ + uint8_t postShift; /**< bit shift applied to coefficients. */ + const q31_t *recipTable; /**< points to the reciprocal initial value table. */ + q31_t energy; /**< saves previous frame energy. */ + q31_t x0; /**< saves previous input sample. */ + } arm_lms_norm_instance_q31; + + + /** + * @brief Processing function for Q31 normalized LMS filter. + * @param[in] S points to an instance of the Q31 normalized LMS filter structure. + * @param[in] pSrc points to the block of input data. + * @param[in] pRef points to the block of reference data. + * @param[out] pOut points to the block of output data. + * @param[out] pErr points to the block of error data. + * @param[in] blockSize number of samples to process. + */ + void arm_lms_norm_q31( + arm_lms_norm_instance_q31 * S, + const q31_t * pSrc, + q31_t * pRef, + q31_t * pOut, + q31_t * pErr, + uint32_t blockSize); + + + /** + * @brief Initialization function for Q31 normalized LMS filter. + * @param[in] S points to an instance of the Q31 normalized LMS filter structure. + * @param[in] numTaps number of filter coefficients. + * @param[in] pCoeffs points to coefficient buffer. + * @param[in] pState points to state buffer. + * @param[in] mu step size that controls filter coefficient updates. + * @param[in] blockSize number of samples to process. + * @param[in] postShift bit shift applied to coefficients. + */ + void arm_lms_norm_init_q31( + arm_lms_norm_instance_q31 * S, + uint16_t numTaps, + q31_t * pCoeffs, + q31_t * pState, + q31_t mu, + uint32_t blockSize, + uint8_t postShift); + + + /** + * @brief Instance structure for the Q15 normalized LMS filter. + */ + typedef struct + { + uint16_t numTaps; /**< Number of coefficients in the filter. */ + q15_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ + q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ + q15_t mu; /**< step size that controls filter coefficient updates. */ + uint8_t postShift; /**< bit shift applied to coefficients. */ + const q15_t *recipTable; /**< Points to the reciprocal initial value table. */ + q15_t energy; /**< saves previous frame energy. */ + q15_t x0; /**< saves previous input sample. */ + } arm_lms_norm_instance_q15; + + + /** + * @brief Processing function for Q15 normalized LMS filter. + * @param[in] S points to an instance of the Q15 normalized LMS filter structure. + * @param[in] pSrc points to the block of input data. + * @param[in] pRef points to the block of reference data. + * @param[out] pOut points to the block of output data. + * @param[out] pErr points to the block of error data. + * @param[in] blockSize number of samples to process. + */ + void arm_lms_norm_q15( + arm_lms_norm_instance_q15 * S, + const q15_t * pSrc, + q15_t * pRef, + q15_t * pOut, + q15_t * pErr, + uint32_t blockSize); + + + /** + * @brief Initialization function for Q15 normalized LMS filter. + * @param[in] S points to an instance of the Q15 normalized LMS filter structure. + * @param[in] numTaps number of filter coefficients. + * @param[in] pCoeffs points to coefficient buffer. + * @param[in] pState points to state buffer. + * @param[in] mu step size that controls filter coefficient updates. + * @param[in] blockSize number of samples to process. + * @param[in] postShift bit shift applied to coefficients. + */ + void arm_lms_norm_init_q15( + arm_lms_norm_instance_q15 * S, + uint16_t numTaps, + q15_t * pCoeffs, + q15_t * pState, + q15_t mu, + uint32_t blockSize, + uint8_t postShift); + + + /** + * @brief Correlation of floating-point sequences. + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. + */ + void arm_correlate_f32( + const float32_t * pSrcA, + uint32_t srcALen, + const float32_t * pSrcB, + uint32_t srcBLen, + float32_t * pDst); + + +/** + @brief Correlation of Q15 sequences + @param[in] pSrcA points to the first input sequence + @param[in] srcALen length of the first input sequence + @param[in] pSrcB points to the second input sequence + @param[in] srcBLen length of the second input sequence + @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. + @param[in] pScratch points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. +*/ +void arm_correlate_opt_q15( + const q15_t * pSrcA, + uint32_t srcALen, + const q15_t * pSrcB, + uint32_t srcBLen, + q15_t * pDst, + q15_t * pScratch); + + +/** + @brief Correlation of Q15 sequences. + @param[in] pSrcA points to the first input sequence + @param[in] srcALen length of the first input sequence + @param[in] pSrcB points to the second input sequence + @param[in] srcBLen length of the second input sequence + @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. + */ + void arm_correlate_q15( + const q15_t * pSrcA, + uint32_t srcALen, + const q15_t * pSrcB, + uint32_t srcBLen, + q15_t * pDst); + + +/** + @brief Correlation of Q15 sequences (fast version). + @param[in] pSrcA points to the first input sequence + @param[in] srcALen length of the first input sequence + @param[in] pSrcB points to the second input sequence + @param[in] srcBLen length of the second input sequence + @param[out] pDst points to the location where the output result is written. Length 2 * max(srcALen, srcBLen) - 1. + @return none + */ +void arm_correlate_fast_q15( + const q15_t * pSrcA, + uint32_t srcALen, + const q15_t * pSrcB, + uint32_t srcBLen, + q15_t * pDst); + + +/** + @brief Correlation of Q15 sequences (fast version). + @param[in] pSrcA points to the first input sequence. + @param[in] srcALen length of the first input sequence. + @param[in] pSrcB points to the second input sequence. + @param[in] srcBLen length of the second input sequence. + @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. + @param[in] pScratch points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. + */ +void arm_correlate_fast_opt_q15( + const q15_t * pSrcA, + uint32_t srcALen, + const q15_t * pSrcB, + uint32_t srcBLen, + q15_t * pDst, + q15_t * pScratch); + + + /** + * @brief Correlation of Q31 sequences. + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. + */ + void arm_correlate_q31( + const q31_t * pSrcA, + uint32_t srcALen, + const q31_t * pSrcB, + uint32_t srcBLen, + q31_t * pDst); + + +/** + @brief Correlation of Q31 sequences (fast version). + @param[in] pSrcA points to the first input sequence + @param[in] srcALen length of the first input sequence + @param[in] pSrcB points to the second input sequence + @param[in] srcBLen length of the second input sequence + @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. + */ +void arm_correlate_fast_q31( + const q31_t * pSrcA, + uint32_t srcALen, + const q31_t * pSrcB, + uint32_t srcBLen, + q31_t * pDst); + + + /** + * @brief Correlation of Q7 sequences. + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. + * @param[in] pScratch1 points to scratch buffer(of type q15_t) of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. + * @param[in] pScratch2 points to scratch buffer (of type q15_t) of size min(srcALen, srcBLen). + */ + void arm_correlate_opt_q7( + const q7_t * pSrcA, + uint32_t srcALen, + const q7_t * pSrcB, + uint32_t srcBLen, + q7_t * pDst, + q15_t * pScratch1, + q15_t * pScratch2); + + + /** + * @brief Correlation of Q7 sequences. + * @param[in] pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. + */ + void arm_correlate_q7( + const q7_t * pSrcA, + uint32_t srcALen, + const q7_t * pSrcB, + uint32_t srcBLen, + q7_t * pDst); + + + /** + * @brief Instance structure for the floating-point sparse FIR filter. + */ + typedef struct + { + uint16_t numTaps; /**< number of coefficients in the filter. */ + uint16_t stateIndex; /**< state buffer index. Points to the oldest sample in the state buffer. */ + float32_t *pState; /**< points to the state buffer array. The array is of length maxDelay+blockSize-1. */ + const float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ + uint16_t maxDelay; /**< maximum offset specified by the pTapDelay array. */ + int32_t *pTapDelay; /**< points to the array of delay values. The array is of length numTaps. */ + } arm_fir_sparse_instance_f32; + + /** + * @brief Instance structure for the Q31 sparse FIR filter. + */ + typedef struct + { + uint16_t numTaps; /**< number of coefficients in the filter. */ + uint16_t stateIndex; /**< state buffer index. Points to the oldest sample in the state buffer. */ + q31_t *pState; /**< points to the state buffer array. The array is of length maxDelay+blockSize-1. */ + const q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ + uint16_t maxDelay; /**< maximum offset specified by the pTapDelay array. */ + int32_t *pTapDelay; /**< points to the array of delay values. The array is of length numTaps. */ + } arm_fir_sparse_instance_q31; + + /** + * @brief Instance structure for the Q15 sparse FIR filter. + */ + typedef struct + { + uint16_t numTaps; /**< number of coefficients in the filter. */ + uint16_t stateIndex; /**< state buffer index. Points to the oldest sample in the state buffer. */ + q15_t *pState; /**< points to the state buffer array. The array is of length maxDelay+blockSize-1. */ + const q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ + uint16_t maxDelay; /**< maximum offset specified by the pTapDelay array. */ + int32_t *pTapDelay; /**< points to the array of delay values. The array is of length numTaps. */ + } arm_fir_sparse_instance_q15; + + /** + * @brief Instance structure for the Q7 sparse FIR filter. + */ + typedef struct + { + uint16_t numTaps; /**< number of coefficients in the filter. */ + uint16_t stateIndex; /**< state buffer index. Points to the oldest sample in the state buffer. */ + q7_t *pState; /**< points to the state buffer array. The array is of length maxDelay+blockSize-1. */ + const q7_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ + uint16_t maxDelay; /**< maximum offset specified by the pTapDelay array. */ + int32_t *pTapDelay; /**< points to the array of delay values. The array is of length numTaps. */ + } arm_fir_sparse_instance_q7; + + + /** + * @brief Processing function for the floating-point sparse FIR filter. + * @param[in] S points to an instance of the floating-point sparse FIR structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data + * @param[in] pScratchIn points to a temporary buffer of size blockSize. + * @param[in] blockSize number of input samples to process per call. + */ + void arm_fir_sparse_f32( + arm_fir_sparse_instance_f32 * S, + const float32_t * pSrc, + float32_t * pDst, + float32_t * pScratchIn, + uint32_t blockSize); + + + /** + * @brief Initialization function for the floating-point sparse FIR filter. + * @param[in,out] S points to an instance of the floating-point sparse FIR structure. + * @param[in] numTaps number of nonzero coefficients in the filter. + * @param[in] pCoeffs points to the array of filter coefficients. + * @param[in] pState points to the state buffer. + * @param[in] pTapDelay points to the array of offset times. + * @param[in] maxDelay maximum offset time supported. + * @param[in] blockSize number of samples that will be processed per block. + */ + void arm_fir_sparse_init_f32( + arm_fir_sparse_instance_f32 * S, + uint16_t numTaps, + const float32_t * pCoeffs, + float32_t * pState, + int32_t * pTapDelay, + uint16_t maxDelay, + uint32_t blockSize); + + + /** + * @brief Processing function for the Q31 sparse FIR filter. + * @param[in] S points to an instance of the Q31 sparse FIR structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data + * @param[in] pScratchIn points to a temporary buffer of size blockSize. + * @param[in] blockSize number of input samples to process per call. + */ + void arm_fir_sparse_q31( + arm_fir_sparse_instance_q31 * S, + const q31_t * pSrc, + q31_t * pDst, + q31_t * pScratchIn, + uint32_t blockSize); + + + /** + * @brief Initialization function for the Q31 sparse FIR filter. + * @param[in,out] S points to an instance of the Q31 sparse FIR structure. + * @param[in] numTaps number of nonzero coefficients in the filter. + * @param[in] pCoeffs points to the array of filter coefficients. + * @param[in] pState points to the state buffer. + * @param[in] pTapDelay points to the array of offset times. + * @param[in] maxDelay maximum offset time supported. + * @param[in] blockSize number of samples that will be processed per block. + */ + void arm_fir_sparse_init_q31( + arm_fir_sparse_instance_q31 * S, + uint16_t numTaps, + const q31_t * pCoeffs, + q31_t * pState, + int32_t * pTapDelay, + uint16_t maxDelay, + uint32_t blockSize); + + + /** + * @brief Processing function for the Q15 sparse FIR filter. + * @param[in] S points to an instance of the Q15 sparse FIR structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data + * @param[in] pScratchIn points to a temporary buffer of size blockSize. + * @param[in] pScratchOut points to a temporary buffer of size blockSize. + * @param[in] blockSize number of input samples to process per call. + */ + void arm_fir_sparse_q15( + arm_fir_sparse_instance_q15 * S, + const q15_t * pSrc, + q15_t * pDst, + q15_t * pScratchIn, + q31_t * pScratchOut, + uint32_t blockSize); + + + /** + * @brief Initialization function for the Q15 sparse FIR filter. + * @param[in,out] S points to an instance of the Q15 sparse FIR structure. + * @param[in] numTaps number of nonzero coefficients in the filter. + * @param[in] pCoeffs points to the array of filter coefficients. + * @param[in] pState points to the state buffer. + * @param[in] pTapDelay points to the array of offset times. + * @param[in] maxDelay maximum offset time supported. + * @param[in] blockSize number of samples that will be processed per block. + */ + void arm_fir_sparse_init_q15( + arm_fir_sparse_instance_q15 * S, + uint16_t numTaps, + const q15_t * pCoeffs, + q15_t * pState, + int32_t * pTapDelay, + uint16_t maxDelay, + uint32_t blockSize); + + + /** + * @brief Processing function for the Q7 sparse FIR filter. + * @param[in] S points to an instance of the Q7 sparse FIR structure. + * @param[in] pSrc points to the block of input data. + * @param[out] pDst points to the block of output data + * @param[in] pScratchIn points to a temporary buffer of size blockSize. + * @param[in] pScratchOut points to a temporary buffer of size blockSize. + * @param[in] blockSize number of input samples to process per call. + */ + void arm_fir_sparse_q7( + arm_fir_sparse_instance_q7 * S, + const q7_t * pSrc, + q7_t * pDst, + q7_t * pScratchIn, + q31_t * pScratchOut, + uint32_t blockSize); + + + /** + * @brief Initialization function for the Q7 sparse FIR filter. + * @param[in,out] S points to an instance of the Q7 sparse FIR structure. + * @param[in] numTaps number of nonzero coefficients in the filter. + * @param[in] pCoeffs points to the array of filter coefficients. + * @param[in] pState points to the state buffer. + * @param[in] pTapDelay points to the array of offset times. + * @param[in] maxDelay maximum offset time supported. + * @param[in] blockSize number of samples that will be processed per block. + */ + void arm_fir_sparse_init_q7( + arm_fir_sparse_instance_q7 * S, + uint16_t numTaps, + const q7_t * pCoeffs, + q7_t * pState, + int32_t * pTapDelay, + uint16_t maxDelay, + uint32_t blockSize); + + + /** + * @brief Floating-point sin_cos function. + * @param[in] theta input value in degrees + * @param[out] pSinVal points to the processed sine output. + * @param[out] pCosVal points to the processed cos output. + */ + void arm_sin_cos_f32( + float32_t theta, + float32_t * pSinVal, + float32_t * pCosVal); + + + /** + * @brief Q31 sin_cos function. + * @param[in] theta scaled input value in degrees + * @param[out] pSinVal points to the processed sine output. + * @param[out] pCosVal points to the processed cosine output. + */ + void arm_sin_cos_q31( + q31_t theta, + q31_t * pSinVal, + q31_t * pCosVal); + + + /** + * @brief Floating-point complex conjugate. + * @param[in] pSrc points to the input vector + * @param[out] pDst points to the output vector + * @param[in] numSamples number of complex samples in each vector + */ + void arm_cmplx_conj_f32( + const float32_t * pSrc, + float32_t * pDst, + uint32_t numSamples); + + /** + * @brief Q31 complex conjugate. + * @param[in] pSrc points to the input vector + * @param[out] pDst points to the output vector + * @param[in] numSamples number of complex samples in each vector + */ + void arm_cmplx_conj_q31( + const q31_t * pSrc, + q31_t * pDst, + uint32_t numSamples); + + + /** + * @brief Q15 complex conjugate. + * @param[in] pSrc points to the input vector + * @param[out] pDst points to the output vector + * @param[in] numSamples number of complex samples in each vector + */ + void arm_cmplx_conj_q15( + const q15_t * pSrc, + q15_t * pDst, + uint32_t numSamples); + + + /** + * @brief Floating-point complex magnitude squared + * @param[in] pSrc points to the complex input vector + * @param[out] pDst points to the real output vector + * @param[in] numSamples number of complex samples in the input vector + */ + void arm_cmplx_mag_squared_f32( + const float32_t * pSrc, + float32_t * pDst, + uint32_t numSamples); + + + /** + * @brief Q31 complex magnitude squared + * @param[in] pSrc points to the complex input vector + * @param[out] pDst points to the real output vector + * @param[in] numSamples number of complex samples in the input vector + */ + void arm_cmplx_mag_squared_q31( + const q31_t * pSrc, + q31_t * pDst, + uint32_t numSamples); + + + /** + * @brief Q15 complex magnitude squared + * @param[in] pSrc points to the complex input vector + * @param[out] pDst points to the real output vector + * @param[in] numSamples number of complex samples in the input vector + */ + void arm_cmplx_mag_squared_q15( + const q15_t * pSrc, + q15_t * pDst, + uint32_t numSamples); + + + /** + * @ingroup groupController + */ + + /** + * @defgroup PID PID Motor Control + * + * A Proportional Integral Derivative (PID) controller is a generic feedback control + * loop mechanism widely used in industrial control systems. + * A PID controller is the most commonly used type of feedback controller. + * + * This set of functions implements (PID) controllers + * for Q15, Q31, and floating-point data types. The functions operate on a single sample + * of data and each call to the function returns a single processed value. + * S points to an instance of the PID control data structure. in + * is the input sample value. The functions return the output value. + * + * \par Algorithm: + *
+   *    y[n] = y[n-1] + A0 * x[n] + A1 * x[n-1] + A2 * x[n-2]
+   *    A0 = Kp + Ki + Kd
+   *    A1 = (-Kp ) - (2 * Kd )
+   *    A2 = Kd
+   * 
+ * + * \par + * where \c Kp is proportional constant, \c Ki is Integral constant and \c Kd is Derivative constant + * + * \par + * \image html PID.gif "Proportional Integral Derivative Controller" + * + * \par + * The PID controller calculates an "error" value as the difference between + * the measured output and the reference input. + * The controller attempts to minimize the error by adjusting the process control inputs. + * The proportional value determines the reaction to the current error, + * the integral value determines the reaction based on the sum of recent errors, + * and the derivative value determines the reaction based on the rate at which the error has been changing. + * + * \par Instance Structure + * The Gains A0, A1, A2 and state variables for a PID controller are stored together in an instance data structure. + * A separate instance structure must be defined for each PID Controller. + * There are separate instance structure declarations for each of the 3 supported data types. + * + * \par Reset Functions + * There is also an associated reset function for each data type which clears the state array. + * + * \par Initialization Functions + * There is also an associated initialization function for each data type. + * The initialization function performs the following operations: + * - Initializes the Gains A0, A1, A2 from Kp,Ki, Kd gains. + * - Zeros out the values in the state buffer. + * + * \par + * Instance structure cannot be placed into a const data section and it is recommended to use the initialization function. + * + * \par Fixed-Point Behavior + * Care must be taken when using the fixed-point versions of the PID Controller functions. + * In particular, the overflow and saturation behavior of the accumulator used in each function must be considered. + * Refer to the function specific documentation below for usage guidelines. + */ + + /** + * @addtogroup PID + * @{ + */ + + /** + * @brief Process function for the floating-point PID Control. + * @param[in,out] S is an instance of the floating-point PID Control structure + * @param[in] in input sample to process + * @return processed output sample. + */ + __STATIC_FORCEINLINE float32_t arm_pid_f32( + arm_pid_instance_f32 * S, + float32_t in) + { + float32_t out; + + /* y[n] = y[n-1] + A0 * x[n] + A1 * x[n-1] + A2 * x[n-2] */ + out = (S->A0 * in) + + (S->A1 * S->state[0]) + (S->A2 * S->state[1]) + (S->state[2]); + + /* Update state */ + S->state[1] = S->state[0]; + S->state[0] = in; + S->state[2] = out; + + /* return to application */ + return (out); + + } + +/** + @brief Process function for the Q31 PID Control. + @param[in,out] S points to an instance of the Q31 PID Control structure + @param[in] in input sample to process + @return processed output sample. + + \par Scaling and Overflow Behavior + The function is implemented using an internal 64-bit accumulator. + The accumulator has a 2.62 format and maintains full precision of the intermediate multiplication results but provides only a single guard bit. + Thus, if the accumulator result overflows it wraps around rather than clip. + In order to avoid overflows completely the input signal must be scaled down by 2 bits as there are four additions. + After all multiply-accumulates are performed, the 2.62 accumulator is truncated to 1.32 format and then saturated to 1.31 format. + */ +__STATIC_FORCEINLINE q31_t arm_pid_q31( + arm_pid_instance_q31 * S, + q31_t in) + { + q63_t acc; + q31_t out; + + /* acc = A0 * x[n] */ + acc = (q63_t) S->A0 * in; + + /* acc += A1 * x[n-1] */ + acc += (q63_t) S->A1 * S->state[0]; + + /* acc += A2 * x[n-2] */ + acc += (q63_t) S->A2 * S->state[1]; + + /* convert output to 1.31 format to add y[n-1] */ + out = (q31_t) (acc >> 31U); + + /* out += y[n-1] */ + out += S->state[2]; + + /* Update state */ + S->state[1] = S->state[0]; + S->state[0] = in; + S->state[2] = out; + + /* return to application */ + return (out); + } + + +/** + @brief Process function for the Q15 PID Control. + @param[in,out] S points to an instance of the Q15 PID Control structure + @param[in] in input sample to process + @return processed output sample. + + \par Scaling and Overflow Behavior + The function is implemented using a 64-bit internal accumulator. + Both Gains and state variables are represented in 1.15 format and multiplications yield a 2.30 result. + The 2.30 intermediate results are accumulated in a 64-bit accumulator in 34.30 format. + There is no risk of internal overflow with this approach and the full precision of intermediate multiplications is preserved. + After all additions have been performed, the accumulator is truncated to 34.15 format by discarding low 15 bits. + Lastly, the accumulator is saturated to yield a result in 1.15 format. + */ +__STATIC_FORCEINLINE q15_t arm_pid_q15( + arm_pid_instance_q15 * S, + q15_t in) + { + q63_t acc; + q15_t out; + +#if defined (ARM_MATH_DSP) + /* Implementation of PID controller */ + + /* acc = A0 * x[n] */ + acc = (q31_t) __SMUAD((uint32_t)S->A0, (uint32_t)in); + + /* acc += A1 * x[n-1] + A2 * x[n-2] */ + acc = (q63_t)__SMLALD((uint32_t)S->A1, (uint32_t)read_q15x2 (S->state), (uint64_t)acc); +#else + /* acc = A0 * x[n] */ + acc = ((q31_t) S->A0) * in; + + /* acc += A1 * x[n-1] + A2 * x[n-2] */ + acc += (q31_t) S->A1 * S->state[0]; + acc += (q31_t) S->A2 * S->state[1]; +#endif + + /* acc += y[n-1] */ + acc += (q31_t) S->state[2] << 15; + + /* saturate the output */ + out = (q15_t) (__SSAT((q31_t)(acc >> 15), 16)); + + /* Update state */ + S->state[1] = S->state[0]; + S->state[0] = in; + S->state[2] = out; + + /* return to application */ + return (out); + } + + /** + * @} end of PID group + */ + + + /** + * @brief Floating-point matrix inverse. + * @param[in] src points to the instance of the input floating-point matrix structure. + * @param[out] dst points to the instance of the output floating-point matrix structure. + * @return The function returns ARM_MATH_SIZE_MISMATCH, if the dimensions do not match. + * If the input matrix is singular (does not have an inverse), then the algorithm terminates and returns error status ARM_MATH_SINGULAR. + */ + arm_status arm_mat_inverse_f32( + const arm_matrix_instance_f32 * src, + arm_matrix_instance_f32 * dst); + + + /** + * @brief Floating-point matrix inverse. + * @param[in] src points to the instance of the input floating-point matrix structure. + * @param[out] dst points to the instance of the output floating-point matrix structure. + * @return The function returns ARM_MATH_SIZE_MISMATCH, if the dimensions do not match. + * If the input matrix is singular (does not have an inverse), then the algorithm terminates and returns error status ARM_MATH_SINGULAR. + */ + arm_status arm_mat_inverse_f64( + const arm_matrix_instance_f64 * src, + arm_matrix_instance_f64 * dst); + + + + /** + * @ingroup groupController + */ + + /** + * @defgroup clarke Vector Clarke Transform + * Forward Clarke transform converts the instantaneous stator phases into a two-coordinate time invariant vector. + * Generally the Clarke transform uses three-phase currents Ia, Ib and Ic to calculate currents + * in the two-phase orthogonal stator axis Ialpha and Ibeta. + * When Ialpha is superposed with Ia as shown in the figure below + * \image html clarke.gif Stator current space vector and its components in (a,b). + * and Ia + Ib + Ic = 0, in this condition Ialpha and Ibeta + * can be calculated using only Ia and Ib. + * + * The function operates on a single sample of data and each call to the function returns the processed output. + * The library provides separate functions for Q31 and floating-point data types. + * \par Algorithm + * \image html clarkeFormula.gif + * where Ia and Ib are the instantaneous stator phases and + * pIalpha and pIbeta are the two coordinates of time invariant vector. + * \par Fixed-Point Behavior + * Care must be taken when using the Q31 version of the Clarke transform. + * In particular, the overflow and saturation behavior of the accumulator used must be considered. + * Refer to the function specific documentation below for usage guidelines. + */ + + /** + * @addtogroup clarke + * @{ + */ + + /** + * + * @brief Floating-point Clarke transform + * @param[in] Ia input three-phase coordinate a + * @param[in] Ib input three-phase coordinate b + * @param[out] pIalpha points to output two-phase orthogonal vector axis alpha + * @param[out] pIbeta points to output two-phase orthogonal vector axis beta + * @return none + */ + __STATIC_FORCEINLINE void arm_clarke_f32( + float32_t Ia, + float32_t Ib, + float32_t * pIalpha, + float32_t * pIbeta) + { + /* Calculate pIalpha using the equation, pIalpha = Ia */ + *pIalpha = Ia; + + /* Calculate pIbeta using the equation, pIbeta = (1/sqrt(3)) * Ia + (2/sqrt(3)) * Ib */ + *pIbeta = ((float32_t) 0.57735026919 * Ia + (float32_t) 1.15470053838 * Ib); + } + + +/** + @brief Clarke transform for Q31 version + @param[in] Ia input three-phase coordinate a + @param[in] Ib input three-phase coordinate b + @param[out] pIalpha points to output two-phase orthogonal vector axis alpha + @param[out] pIbeta points to output two-phase orthogonal vector axis beta + @return none + + \par Scaling and Overflow Behavior + The function is implemented using an internal 32-bit accumulator. + The accumulator maintains 1.31 format by truncating lower 31 bits of the intermediate multiplication in 2.62 format. + There is saturation on the addition, hence there is no risk of overflow. + */ +__STATIC_FORCEINLINE void arm_clarke_q31( + q31_t Ia, + q31_t Ib, + q31_t * pIalpha, + q31_t * pIbeta) + { + q31_t product1, product2; /* Temporary variables used to store intermediate results */ + + /* Calculating pIalpha from Ia by equation pIalpha = Ia */ + *pIalpha = Ia; + + /* Intermediate product is calculated by (1/(sqrt(3)) * Ia) */ + product1 = (q31_t) (((q63_t) Ia * 0x24F34E8B) >> 30); + + /* Intermediate product is calculated by (2/sqrt(3) * Ib) */ + product2 = (q31_t) (((q63_t) Ib * 0x49E69D16) >> 30); + + /* pIbeta is calculated by adding the intermediate products */ + *pIbeta = __QADD(product1, product2); + } + + /** + * @} end of clarke group + */ + + + /** + * @ingroup groupController + */ + + /** + * @defgroup inv_clarke Vector Inverse Clarke Transform + * Inverse Clarke transform converts the two-coordinate time invariant vector into instantaneous stator phases. + * + * The function operates on a single sample of data and each call to the function returns the processed output. + * The library provides separate functions for Q31 and floating-point data types. + * \par Algorithm + * \image html clarkeInvFormula.gif + * where pIa and pIb are the instantaneous stator phases and + * Ialpha and Ibeta are the two coordinates of time invariant vector. + * \par Fixed-Point Behavior + * Care must be taken when using the Q31 version of the Clarke transform. + * In particular, the overflow and saturation behavior of the accumulator used must be considered. + * Refer to the function specific documentation below for usage guidelines. + */ + + /** + * @addtogroup inv_clarke + * @{ + */ + + /** + * @brief Floating-point Inverse Clarke transform + * @param[in] Ialpha input two-phase orthogonal vector axis alpha + * @param[in] Ibeta input two-phase orthogonal vector axis beta + * @param[out] pIa points to output three-phase coordinate a + * @param[out] pIb points to output three-phase coordinate b + * @return none + */ + __STATIC_FORCEINLINE void arm_inv_clarke_f32( + float32_t Ialpha, + float32_t Ibeta, + float32_t * pIa, + float32_t * pIb) + { + /* Calculating pIa from Ialpha by equation pIa = Ialpha */ + *pIa = Ialpha; + + /* Calculating pIb from Ialpha and Ibeta by equation pIb = -(1/2) * Ialpha + (sqrt(3)/2) * Ibeta */ + *pIb = -0.5f * Ialpha + 0.8660254039f * Ibeta; + } + + +/** + @brief Inverse Clarke transform for Q31 version + @param[in] Ialpha input two-phase orthogonal vector axis alpha + @param[in] Ibeta input two-phase orthogonal vector axis beta + @param[out] pIa points to output three-phase coordinate a + @param[out] pIb points to output three-phase coordinate b + @return none + + \par Scaling and Overflow Behavior + The function is implemented using an internal 32-bit accumulator. + The accumulator maintains 1.31 format by truncating lower 31 bits of the intermediate multiplication in 2.62 format. + There is saturation on the subtraction, hence there is no risk of overflow. + */ +__STATIC_FORCEINLINE void arm_inv_clarke_q31( + q31_t Ialpha, + q31_t Ibeta, + q31_t * pIa, + q31_t * pIb) + { + q31_t product1, product2; /* Temporary variables used to store intermediate results */ + + /* Calculating pIa from Ialpha by equation pIa = Ialpha */ + *pIa = Ialpha; + + /* Intermediate product is calculated by (1/(2*sqrt(3)) * Ia) */ + product1 = (q31_t) (((q63_t) (Ialpha) * (0x40000000)) >> 31); + + /* Intermediate product is calculated by (1/sqrt(3) * pIb) */ + product2 = (q31_t) (((q63_t) (Ibeta) * (0x6ED9EBA1)) >> 31); + + /* pIb is calculated by subtracting the products */ + *pIb = __QSUB(product2, product1); + } + + /** + * @} end of inv_clarke group + */ + + + + /** + * @ingroup groupController + */ + + /** + * @defgroup park Vector Park Transform + * + * Forward Park transform converts the input two-coordinate vector to flux and torque components. + * The Park transform can be used to realize the transformation of the Ialpha and the Ibeta currents + * from the stationary to the moving reference frame and control the spatial relationship between + * the stator vector current and rotor flux vector. + * If we consider the d axis aligned with the rotor flux, the diagram below shows the + * current vector and the relationship from the two reference frames: + * \image html park.gif "Stator current space vector and its component in (a,b) and in the d,q rotating reference frame" + * + * The function operates on a single sample of data and each call to the function returns the processed output. + * The library provides separate functions for Q31 and floating-point data types. + * \par Algorithm + * \image html parkFormula.gif + * where Ialpha and Ibeta are the stator vector components, + * pId and pIq are rotor vector components and cosVal and sinVal are the + * cosine and sine values of theta (rotor flux position). + * \par Fixed-Point Behavior + * Care must be taken when using the Q31 version of the Park transform. + * In particular, the overflow and saturation behavior of the accumulator used must be considered. + * Refer to the function specific documentation below for usage guidelines. + */ + + /** + * @addtogroup park + * @{ + */ + + /** + * @brief Floating-point Park transform + * @param[in] Ialpha input two-phase vector coordinate alpha + * @param[in] Ibeta input two-phase vector coordinate beta + * @param[out] pId points to output rotor reference frame d + * @param[out] pIq points to output rotor reference frame q + * @param[in] sinVal sine value of rotation angle theta + * @param[in] cosVal cosine value of rotation angle theta + * @return none + * + * The function implements the forward Park transform. + * + */ + __STATIC_FORCEINLINE void arm_park_f32( + float32_t Ialpha, + float32_t Ibeta, + float32_t * pId, + float32_t * pIq, + float32_t sinVal, + float32_t cosVal) + { + /* Calculate pId using the equation, pId = Ialpha * cosVal + Ibeta * sinVal */ + *pId = Ialpha * cosVal + Ibeta * sinVal; + + /* Calculate pIq using the equation, pIq = - Ialpha * sinVal + Ibeta * cosVal */ + *pIq = -Ialpha * sinVal + Ibeta * cosVal; + } + + +/** + @brief Park transform for Q31 version + @param[in] Ialpha input two-phase vector coordinate alpha + @param[in] Ibeta input two-phase vector coordinate beta + @param[out] pId points to output rotor reference frame d + @param[out] pIq points to output rotor reference frame q + @param[in] sinVal sine value of rotation angle theta + @param[in] cosVal cosine value of rotation angle theta + @return none + + \par Scaling and Overflow Behavior + The function is implemented using an internal 32-bit accumulator. + The accumulator maintains 1.31 format by truncating lower 31 bits of the intermediate multiplication in 2.62 format. + There is saturation on the addition and subtraction, hence there is no risk of overflow. + */ +__STATIC_FORCEINLINE void arm_park_q31( + q31_t Ialpha, + q31_t Ibeta, + q31_t * pId, + q31_t * pIq, + q31_t sinVal, + q31_t cosVal) + { + q31_t product1, product2; /* Temporary variables used to store intermediate results */ + q31_t product3, product4; /* Temporary variables used to store intermediate results */ + + /* Intermediate product is calculated by (Ialpha * cosVal) */ + product1 = (q31_t) (((q63_t) (Ialpha) * (cosVal)) >> 31); + + /* Intermediate product is calculated by (Ibeta * sinVal) */ + product2 = (q31_t) (((q63_t) (Ibeta) * (sinVal)) >> 31); + + + /* Intermediate product is calculated by (Ialpha * sinVal) */ + product3 = (q31_t) (((q63_t) (Ialpha) * (sinVal)) >> 31); + + /* Intermediate product is calculated by (Ibeta * cosVal) */ + product4 = (q31_t) (((q63_t) (Ibeta) * (cosVal)) >> 31); + + /* Calculate pId by adding the two intermediate products 1 and 2 */ + *pId = __QADD(product1, product2); + + /* Calculate pIq by subtracting the two intermediate products 3 from 4 */ + *pIq = __QSUB(product4, product3); + } + + /** + * @} end of park group + */ + + + /** + * @ingroup groupController + */ + + /** + * @defgroup inv_park Vector Inverse Park transform + * Inverse Park transform converts the input flux and torque components to two-coordinate vector. + * + * The function operates on a single sample of data and each call to the function returns the processed output. + * The library provides separate functions for Q31 and floating-point data types. + * \par Algorithm + * \image html parkInvFormula.gif + * where pIalpha and pIbeta are the stator vector components, + * Id and Iq are rotor vector components and cosVal and sinVal are the + * cosine and sine values of theta (rotor flux position). + * \par Fixed-Point Behavior + * Care must be taken when using the Q31 version of the Park transform. + * In particular, the overflow and saturation behavior of the accumulator used must be considered. + * Refer to the function specific documentation below for usage guidelines. + */ + + /** + * @addtogroup inv_park + * @{ + */ + + /** + * @brief Floating-point Inverse Park transform + * @param[in] Id input coordinate of rotor reference frame d + * @param[in] Iq input coordinate of rotor reference frame q + * @param[out] pIalpha points to output two-phase orthogonal vector axis alpha + * @param[out] pIbeta points to output two-phase orthogonal vector axis beta + * @param[in] sinVal sine value of rotation angle theta + * @param[in] cosVal cosine value of rotation angle theta + * @return none + */ + __STATIC_FORCEINLINE void arm_inv_park_f32( + float32_t Id, + float32_t Iq, + float32_t * pIalpha, + float32_t * pIbeta, + float32_t sinVal, + float32_t cosVal) + { + /* Calculate pIalpha using the equation, pIalpha = Id * cosVal - Iq * sinVal */ + *pIalpha = Id * cosVal - Iq * sinVal; + + /* Calculate pIbeta using the equation, pIbeta = Id * sinVal + Iq * cosVal */ + *pIbeta = Id * sinVal + Iq * cosVal; + } + + +/** + @brief Inverse Park transform for Q31 version + @param[in] Id input coordinate of rotor reference frame d + @param[in] Iq input coordinate of rotor reference frame q + @param[out] pIalpha points to output two-phase orthogonal vector axis alpha + @param[out] pIbeta points to output two-phase orthogonal vector axis beta + @param[in] sinVal sine value of rotation angle theta + @param[in] cosVal cosine value of rotation angle theta + @return none + + @par Scaling and Overflow Behavior + The function is implemented using an internal 32-bit accumulator. + The accumulator maintains 1.31 format by truncating lower 31 bits of the intermediate multiplication in 2.62 format. + There is saturation on the addition, hence there is no risk of overflow. + */ +__STATIC_FORCEINLINE void arm_inv_park_q31( + q31_t Id, + q31_t Iq, + q31_t * pIalpha, + q31_t * pIbeta, + q31_t sinVal, + q31_t cosVal) + { + q31_t product1, product2; /* Temporary variables used to store intermediate results */ + q31_t product3, product4; /* Temporary variables used to store intermediate results */ + + /* Intermediate product is calculated by (Id * cosVal) */ + product1 = (q31_t) (((q63_t) (Id) * (cosVal)) >> 31); + + /* Intermediate product is calculated by (Iq * sinVal) */ + product2 = (q31_t) (((q63_t) (Iq) * (sinVal)) >> 31); + + + /* Intermediate product is calculated by (Id * sinVal) */ + product3 = (q31_t) (((q63_t) (Id) * (sinVal)) >> 31); + + /* Intermediate product is calculated by (Iq * cosVal) */ + product4 = (q31_t) (((q63_t) (Iq) * (cosVal)) >> 31); + + /* Calculate pIalpha by using the two intermediate products 1 and 2 */ + *pIalpha = __QSUB(product1, product2); + + /* Calculate pIbeta by using the two intermediate products 3 and 4 */ + *pIbeta = __QADD(product4, product3); + } + + /** + * @} end of Inverse park group + */ + + + /** + * @ingroup groupInterpolation + */ + + /** + * @defgroup LinearInterpolate Linear Interpolation + * + * Linear interpolation is a method of curve fitting using linear polynomials. + * Linear interpolation works by effectively drawing a straight line between two neighboring samples and returning the appropriate point along that line + * + * \par + * \image html LinearInterp.gif "Linear interpolation" + * + * \par + * A Linear Interpolate function calculates an output value(y), for the input(x) + * using linear interpolation of the input values x0, x1( nearest input values) and the output values y0 and y1(nearest output values) + * + * \par Algorithm: + *
+   *       y = y0 + (x - x0) * ((y1 - y0)/(x1-x0))
+   *       where x0, x1 are nearest values of input x
+   *             y0, y1 are nearest values to output y
+   * 
+ * + * \par + * This set of functions implements Linear interpolation process + * for Q7, Q15, Q31, and floating-point data types. The functions operate on a single + * sample of data and each call to the function returns a single processed value. + * S points to an instance of the Linear Interpolate function data structure. + * x is the input sample value. The functions returns the output value. + * + * \par + * if x is outside of the table boundary, Linear interpolation returns first value of the table + * if x is below input range and returns last value of table if x is above range. + */ + + /** + * @addtogroup LinearInterpolate + * @{ + */ + + /** + * @brief Process function for the floating-point Linear Interpolation Function. + * @param[in,out] S is an instance of the floating-point Linear Interpolation structure + * @param[in] x input sample to process + * @return y processed output sample. + * + */ + __STATIC_FORCEINLINE float32_t arm_linear_interp_f32( + arm_linear_interp_instance_f32 * S, + float32_t x) + { + float32_t y; + float32_t x0, x1; /* Nearest input values */ + float32_t y0, y1; /* Nearest output values */ + float32_t xSpacing = S->xSpacing; /* spacing between input values */ + int32_t i; /* Index variable */ + float32_t *pYData = S->pYData; /* pointer to output table */ + + /* Calculation of index */ + i = (int32_t) ((x - S->x1) / xSpacing); + + if (i < 0) + { + /* Iniatilize output for below specified range as least output value of table */ + y = pYData[0]; + } + else if ((uint32_t)i >= (S->nValues - 1)) + { + /* Iniatilize output for above specified range as last output value of table */ + y = pYData[S->nValues - 1]; + } + else + { + /* Calculation of nearest input values */ + x0 = S->x1 + i * xSpacing; + x1 = S->x1 + (i + 1) * xSpacing; + + /* Read of nearest output values */ + y0 = pYData[i]; + y1 = pYData[i + 1]; + + /* Calculation of output */ + y = y0 + (x - x0) * ((y1 - y0) / (x1 - x0)); + + } + + /* returns output value */ + return (y); + } + + + /** + * + * @brief Process function for the Q31 Linear Interpolation Function. + * @param[in] pYData pointer to Q31 Linear Interpolation table + * @param[in] x input sample to process + * @param[in] nValues number of table values + * @return y processed output sample. + * + * \par + * Input sample x is in 12.20 format which contains 12 bits for table index and 20 bits for fractional part. + * This function can support maximum of table size 2^12. + * + */ + __STATIC_FORCEINLINE q31_t arm_linear_interp_q31( + q31_t * pYData, + q31_t x, + uint32_t nValues) + { + q31_t y; /* output */ + q31_t y0, y1; /* Nearest output values */ + q31_t fract; /* fractional part */ + int32_t index; /* Index to read nearest output values */ + + /* Input is in 12.20 format */ + /* 12 bits for the table index */ + /* Index value calculation */ + index = ((x & (q31_t)0xFFF00000) >> 20); + + if (index >= (int32_t)(nValues - 1)) + { + return (pYData[nValues - 1]); + } + else if (index < 0) + { + return (pYData[0]); + } + else + { + /* 20 bits for the fractional part */ + /* shift left by 11 to keep fract in 1.31 format */ + fract = (x & 0x000FFFFF) << 11; + + /* Read two nearest output values from the index in 1.31(q31) format */ + y0 = pYData[index]; + y1 = pYData[index + 1]; + + /* Calculation of y0 * (1-fract) and y is in 2.30 format */ + y = ((q31_t) ((q63_t) y0 * (0x7FFFFFFF - fract) >> 32)); + + /* Calculation of y0 * (1-fract) + y1 *fract and y is in 2.30 format */ + y += ((q31_t) (((q63_t) y1 * fract) >> 32)); + + /* Convert y to 1.31 format */ + return (y << 1U); + } + } + + + /** + * + * @brief Process function for the Q15 Linear Interpolation Function. + * @param[in] pYData pointer to Q15 Linear Interpolation table + * @param[in] x input sample to process + * @param[in] nValues number of table values + * @return y processed output sample. + * + * \par + * Input sample x is in 12.20 format which contains 12 bits for table index and 20 bits for fractional part. + * This function can support maximum of table size 2^12. + * + */ + __STATIC_FORCEINLINE q15_t arm_linear_interp_q15( + q15_t * pYData, + q31_t x, + uint32_t nValues) + { + q63_t y; /* output */ + q15_t y0, y1; /* Nearest output values */ + q31_t fract; /* fractional part */ + int32_t index; /* Index to read nearest output values */ + + /* Input is in 12.20 format */ + /* 12 bits for the table index */ + /* Index value calculation */ + index = ((x & (int32_t)0xFFF00000) >> 20); + + if (index >= (int32_t)(nValues - 1)) + { + return (pYData[nValues - 1]); + } + else if (index < 0) + { + return (pYData[0]); + } + else + { + /* 20 bits for the fractional part */ + /* fract is in 12.20 format */ + fract = (x & 0x000FFFFF); + + /* Read two nearest output values from the index */ + y0 = pYData[index]; + y1 = pYData[index + 1]; + + /* Calculation of y0 * (1-fract) and y is in 13.35 format */ + y = ((q63_t) y0 * (0xFFFFF - fract)); + + /* Calculation of (y0 * (1-fract) + y1 * fract) and y is in 13.35 format */ + y += ((q63_t) y1 * (fract)); + + /* convert y to 1.15 format */ + return (q15_t) (y >> 20); + } + } + + + /** + * + * @brief Process function for the Q7 Linear Interpolation Function. + * @param[in] pYData pointer to Q7 Linear Interpolation table + * @param[in] x input sample to process + * @param[in] nValues number of table values + * @return y processed output sample. + * + * \par + * Input sample x is in 12.20 format which contains 12 bits for table index and 20 bits for fractional part. + * This function can support maximum of table size 2^12. + */ + __STATIC_FORCEINLINE q7_t arm_linear_interp_q7( + q7_t * pYData, + q31_t x, + uint32_t nValues) + { + q31_t y; /* output */ + q7_t y0, y1; /* Nearest output values */ + q31_t fract; /* fractional part */ + uint32_t index; /* Index to read nearest output values */ + + /* Input is in 12.20 format */ + /* 12 bits for the table index */ + /* Index value calculation */ + if (x < 0) + { + return (pYData[0]); + } + index = (x >> 20) & 0xfff; + + if (index >= (nValues - 1)) + { + return (pYData[nValues - 1]); + } + else + { + /* 20 bits for the fractional part */ + /* fract is in 12.20 format */ + fract = (x & 0x000FFFFF); + + /* Read two nearest output values from the index and are in 1.7(q7) format */ + y0 = pYData[index]; + y1 = pYData[index + 1]; + + /* Calculation of y0 * (1-fract ) and y is in 13.27(q27) format */ + y = ((y0 * (0xFFFFF - fract))); + + /* Calculation of y1 * fract + y0 * (1-fract) and y is in 13.27(q27) format */ + y += (y1 * fract); + + /* convert y to 1.7(q7) format */ + return (q7_t) (y >> 20); + } + } + + /** + * @} end of LinearInterpolate group + */ + + /** + * @brief Fast approximation to the trigonometric sine function for floating-point data. + * @param[in] x input value in radians. + * @return sin(x). + */ + float32_t arm_sin_f32( + float32_t x); + + + /** + * @brief Fast approximation to the trigonometric sine function for Q31 data. + * @param[in] x Scaled input value in radians. + * @return sin(x). + */ + q31_t arm_sin_q31( + q31_t x); + + + /** + * @brief Fast approximation to the trigonometric sine function for Q15 data. + * @param[in] x Scaled input value in radians. + * @return sin(x). + */ + q15_t arm_sin_q15( + q15_t x); + + + /** + * @brief Fast approximation to the trigonometric cosine function for floating-point data. + * @param[in] x input value in radians. + * @return cos(x). + */ + float32_t arm_cos_f32( + float32_t x); + + + /** + * @brief Fast approximation to the trigonometric cosine function for Q31 data. + * @param[in] x Scaled input value in radians. + * @return cos(x). + */ + q31_t arm_cos_q31( + q31_t x); + + + /** + * @brief Fast approximation to the trigonometric cosine function for Q15 data. + * @param[in] x Scaled input value in radians. + * @return cos(x). + */ + q15_t arm_cos_q15( + q15_t x); + + +/** + @brief Floating-point vector of log values. + @param[in] pSrc points to the input vector + @param[out] pDst points to the output vector + @param[in] blockSize number of samples in each vector + @return none + */ + void arm_vlog_f32( + const float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + +/** + @brief Floating-point vector of exp values. + @param[in] pSrc points to the input vector + @param[out] pDst points to the output vector + @param[in] blockSize number of samples in each vector + @return none + */ + void arm_vexp_f32( + const float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + /** + * @ingroup groupFastMath + */ + + + /** + * @defgroup SQRT Square Root + * + * Computes the square root of a number. + * There are separate functions for Q15, Q31, and floating-point data types. + * The square root function is computed using the Newton-Raphson algorithm. + * This is an iterative algorithm of the form: + *
+   *      x1 = x0 - f(x0)/f'(x0)
+   * 
+ * where x1 is the current estimate, + * x0 is the previous estimate, and + * f'(x0) is the derivative of f() evaluated at x0. + * For the square root function, the algorithm reduces to: + *
+   *     x0 = in/2                         [initial guess]
+   *     x1 = 1/2 * ( x0 + in / x0)        [each iteration]
+   * 
+ */ + + + /** + * @addtogroup SQRT + * @{ + */ + +/** + @brief Floating-point square root function. + @param[in] in input value + @param[out] pOut square root of input value + @return execution status + - \ref ARM_MATH_SUCCESS : input value is positive + - \ref ARM_MATH_ARGUMENT_ERROR : input value is negative; *pOut is set to 0 + */ +__STATIC_FORCEINLINE arm_status arm_sqrt_f32( + float32_t in, + float32_t * pOut) + { + if (in >= 0.0f) + { +#if defined ( __CC_ARM ) + #if defined __TARGET_FPU_VFP + *pOut = __sqrtf(in); + #else + *pOut = sqrtf(in); + #endif + +#elif defined ( __ICCARM__ ) + #if defined __ARMVFP__ + __ASM("VSQRT.F32 %0,%1" : "=t"(*pOut) : "t"(in)); + #else + *pOut = sqrtf(in); + #endif + +#else + *pOut = sqrtf(in); +#endif + + return (ARM_MATH_SUCCESS); + } + else + { + *pOut = 0.0f; + return (ARM_MATH_ARGUMENT_ERROR); + } + } + + +/** + @brief Q31 square root function. + @param[in] in input value. The range of the input value is [0 +1) or 0x00000000 to 0x7FFFFFFF + @param[out] pOut points to square root of input value + @return execution status + - \ref ARM_MATH_SUCCESS : input value is positive + - \ref ARM_MATH_ARGUMENT_ERROR : input value is negative; *pOut is set to 0 + */ +arm_status arm_sqrt_q31( + q31_t in, + q31_t * pOut); + + +/** + @brief Q15 square root function. + @param[in] in input value. The range of the input value is [0 +1) or 0x0000 to 0x7FFF + @param[out] pOut points to square root of input value + @return execution status + - \ref ARM_MATH_SUCCESS : input value is positive + - \ref ARM_MATH_ARGUMENT_ERROR : input value is negative; *pOut is set to 0 + */ +arm_status arm_sqrt_q15( + q15_t in, + q15_t * pOut); + + /** + * @brief Vector Floating-point square root function. + * @param[in] pIn input vector. + * @param[out] pOut vector of square roots of input elements. + * @param[in] len length of input vector. + * @return The function returns ARM_MATH_SUCCESS if input value is positive value or ARM_MATH_ARGUMENT_ERROR if + * in is negative value and returns zero output for negative values. + */ + void arm_vsqrt_f32( + float32_t * pIn, + float32_t * pOut, + uint16_t len); + + void arm_vsqrt_q31( + q31_t * pIn, + q31_t * pOut, + uint16_t len); + + void arm_vsqrt_q15( + q15_t * pIn, + q15_t * pOut, + uint16_t len); + + /** + * @} end of SQRT group + */ + + + /** + * @brief floating-point Circular write function. + */ + __STATIC_FORCEINLINE void arm_circularWrite_f32( + int32_t * circBuffer, + int32_t L, + uint16_t * writeOffset, + int32_t bufferInc, + const int32_t * src, + int32_t srcInc, + uint32_t blockSize) + { + uint32_t i = 0U; + int32_t wOffset; + + /* Copy the value of Index pointer that points + * to the current location where the input samples to be copied */ + wOffset = *writeOffset; + + /* Loop over the blockSize */ + i = blockSize; + + while (i > 0U) + { + /* copy the input sample to the circular buffer */ + circBuffer[wOffset] = *src; + + /* Update the input pointer */ + src += srcInc; + + /* Circularly update wOffset. Watch out for positive and negative value */ + wOffset += bufferInc; + if (wOffset >= L) + wOffset -= L; + + /* Decrement the loop counter */ + i--; + } + + /* Update the index pointer */ + *writeOffset = (uint16_t)wOffset; + } + + + + /** + * @brief floating-point Circular Read function. + */ + __STATIC_FORCEINLINE void arm_circularRead_f32( + int32_t * circBuffer, + int32_t L, + int32_t * readOffset, + int32_t bufferInc, + int32_t * dst, + int32_t * dst_base, + int32_t dst_length, + int32_t dstInc, + uint32_t blockSize) + { + uint32_t i = 0U; + int32_t rOffset; + int32_t* dst_end; + + /* Copy the value of Index pointer that points + * to the current location from where the input samples to be read */ + rOffset = *readOffset; + dst_end = dst_base + dst_length; + + /* Loop over the blockSize */ + i = blockSize; + + while (i > 0U) + { + /* copy the sample from the circular buffer to the destination buffer */ + *dst = circBuffer[rOffset]; + + /* Update the input pointer */ + dst += dstInc; + + if (dst == dst_end) + { + dst = dst_base; + } + + /* Circularly update rOffset. Watch out for positive and negative value */ + rOffset += bufferInc; + + if (rOffset >= L) + { + rOffset -= L; + } + + /* Decrement the loop counter */ + i--; + } + + /* Update the index pointer */ + *readOffset = rOffset; + } + + + /** + * @brief Q15 Circular write function. + */ + __STATIC_FORCEINLINE void arm_circularWrite_q15( + q15_t * circBuffer, + int32_t L, + uint16_t * writeOffset, + int32_t bufferInc, + const q15_t * src, + int32_t srcInc, + uint32_t blockSize) + { + uint32_t i = 0U; + int32_t wOffset; + + /* Copy the value of Index pointer that points + * to the current location where the input samples to be copied */ + wOffset = *writeOffset; + + /* Loop over the blockSize */ + i = blockSize; + + while (i > 0U) + { + /* copy the input sample to the circular buffer */ + circBuffer[wOffset] = *src; + + /* Update the input pointer */ + src += srcInc; + + /* Circularly update wOffset. Watch out for positive and negative value */ + wOffset += bufferInc; + if (wOffset >= L) + wOffset -= L; + + /* Decrement the loop counter */ + i--; + } + + /* Update the index pointer */ + *writeOffset = (uint16_t)wOffset; + } + + + /** + * @brief Q15 Circular Read function. + */ + __STATIC_FORCEINLINE void arm_circularRead_q15( + q15_t * circBuffer, + int32_t L, + int32_t * readOffset, + int32_t bufferInc, + q15_t * dst, + q15_t * dst_base, + int32_t dst_length, + int32_t dstInc, + uint32_t blockSize) + { + uint32_t i = 0; + int32_t rOffset; + q15_t* dst_end; + + /* Copy the value of Index pointer that points + * to the current location from where the input samples to be read */ + rOffset = *readOffset; + + dst_end = dst_base + dst_length; + + /* Loop over the blockSize */ + i = blockSize; + + while (i > 0U) + { + /* copy the sample from the circular buffer to the destination buffer */ + *dst = circBuffer[rOffset]; + + /* Update the input pointer */ + dst += dstInc; + + if (dst == dst_end) + { + dst = dst_base; + } + + /* Circularly update wOffset. Watch out for positive and negative value */ + rOffset += bufferInc; + + if (rOffset >= L) + { + rOffset -= L; + } + + /* Decrement the loop counter */ + i--; + } + + /* Update the index pointer */ + *readOffset = rOffset; + } + + + /** + * @brief Q7 Circular write function. + */ + __STATIC_FORCEINLINE void arm_circularWrite_q7( + q7_t * circBuffer, + int32_t L, + uint16_t * writeOffset, + int32_t bufferInc, + const q7_t * src, + int32_t srcInc, + uint32_t blockSize) + { + uint32_t i = 0U; + int32_t wOffset; + + /* Copy the value of Index pointer that points + * to the current location where the input samples to be copied */ + wOffset = *writeOffset; + + /* Loop over the blockSize */ + i = blockSize; + + while (i > 0U) + { + /* copy the input sample to the circular buffer */ + circBuffer[wOffset] = *src; + + /* Update the input pointer */ + src += srcInc; + + /* Circularly update wOffset. Watch out for positive and negative value */ + wOffset += bufferInc; + if (wOffset >= L) + wOffset -= L; + + /* Decrement the loop counter */ + i--; + } + + /* Update the index pointer */ + *writeOffset = (uint16_t)wOffset; + } + + + /** + * @brief Q7 Circular Read function. + */ + __STATIC_FORCEINLINE void arm_circularRead_q7( + q7_t * circBuffer, + int32_t L, + int32_t * readOffset, + int32_t bufferInc, + q7_t * dst, + q7_t * dst_base, + int32_t dst_length, + int32_t dstInc, + uint32_t blockSize) + { + uint32_t i = 0; + int32_t rOffset; + q7_t* dst_end; + + /* Copy the value of Index pointer that points + * to the current location from where the input samples to be read */ + rOffset = *readOffset; + + dst_end = dst_base + dst_length; + + /* Loop over the blockSize */ + i = blockSize; + + while (i > 0U) + { + /* copy the sample from the circular buffer to the destination buffer */ + *dst = circBuffer[rOffset]; + + /* Update the input pointer */ + dst += dstInc; + + if (dst == dst_end) + { + dst = dst_base; + } + + /* Circularly update rOffset. Watch out for positive and negative value */ + rOffset += bufferInc; + + if (rOffset >= L) + { + rOffset -= L; + } + + /* Decrement the loop counter */ + i--; + } + + /* Update the index pointer */ + *readOffset = rOffset; + } + + + /** + * @brief Sum of the squares of the elements of a Q31 vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output value. + */ + void arm_power_q31( + const q31_t * pSrc, + uint32_t blockSize, + q63_t * pResult); + + + /** + * @brief Sum of the squares of the elements of a floating-point vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output value. + */ + void arm_power_f32( + const float32_t * pSrc, + uint32_t blockSize, + float32_t * pResult); + + + /** + * @brief Sum of the squares of the elements of a Q15 vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output value. + */ + void arm_power_q15( + const q15_t * pSrc, + uint32_t blockSize, + q63_t * pResult); + + + /** + * @brief Sum of the squares of the elements of a Q7 vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output value. + */ + void arm_power_q7( + const q7_t * pSrc, + uint32_t blockSize, + q31_t * pResult); + + + /** + * @brief Mean value of a Q7 vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output value. + */ + void arm_mean_q7( + const q7_t * pSrc, + uint32_t blockSize, + q7_t * pResult); + + + /** + * @brief Mean value of a Q15 vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output value. + */ + void arm_mean_q15( + const q15_t * pSrc, + uint32_t blockSize, + q15_t * pResult); + + + /** + * @brief Mean value of a Q31 vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output value. + */ + void arm_mean_q31( + const q31_t * pSrc, + uint32_t blockSize, + q31_t * pResult); + + + /** + * @brief Mean value of a floating-point vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output value. + */ + void arm_mean_f32( + const float32_t * pSrc, + uint32_t blockSize, + float32_t * pResult); + + + /** + * @brief Variance of the elements of a floating-point vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output value. + */ + void arm_var_f32( + const float32_t * pSrc, + uint32_t blockSize, + float32_t * pResult); + + + /** + * @brief Variance of the elements of a Q31 vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output value. + */ + void arm_var_q31( + const q31_t * pSrc, + uint32_t blockSize, + q31_t * pResult); + + + /** + * @brief Variance of the elements of a Q15 vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output value. + */ + void arm_var_q15( + const q15_t * pSrc, + uint32_t blockSize, + q15_t * pResult); + + + /** + * @brief Root Mean Square of the elements of a floating-point vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output value. + */ + void arm_rms_f32( + const float32_t * pSrc, + uint32_t blockSize, + float32_t * pResult); + + + /** + * @brief Root Mean Square of the elements of a Q31 vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output value. + */ + void arm_rms_q31( + const q31_t * pSrc, + uint32_t blockSize, + q31_t * pResult); + + + /** + * @brief Root Mean Square of the elements of a Q15 vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output value. + */ + void arm_rms_q15( + const q15_t * pSrc, + uint32_t blockSize, + q15_t * pResult); + + + /** + * @brief Standard deviation of the elements of a floating-point vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output value. + */ + void arm_std_f32( + const float32_t * pSrc, + uint32_t blockSize, + float32_t * pResult); + + + /** + * @brief Standard deviation of the elements of a Q31 vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output value. + */ + void arm_std_q31( + const q31_t * pSrc, + uint32_t blockSize, + q31_t * pResult); + + + /** + * @brief Standard deviation of the elements of a Q15 vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output value. + */ + void arm_std_q15( + const q15_t * pSrc, + uint32_t blockSize, + q15_t * pResult); + + + /** + * @brief Floating-point complex magnitude + * @param[in] pSrc points to the complex input vector + * @param[out] pDst points to the real output vector + * @param[in] numSamples number of complex samples in the input vector + */ + void arm_cmplx_mag_f32( + const float32_t * pSrc, + float32_t * pDst, + uint32_t numSamples); + + + /** + * @brief Q31 complex magnitude + * @param[in] pSrc points to the complex input vector + * @param[out] pDst points to the real output vector + * @param[in] numSamples number of complex samples in the input vector + */ + void arm_cmplx_mag_q31( + const q31_t * pSrc, + q31_t * pDst, + uint32_t numSamples); + + + /** + * @brief Q15 complex magnitude + * @param[in] pSrc points to the complex input vector + * @param[out] pDst points to the real output vector + * @param[in] numSamples number of complex samples in the input vector + */ + void arm_cmplx_mag_q15( + const q15_t * pSrc, + q15_t * pDst, + uint32_t numSamples); + + + /** + * @brief Q15 complex dot product + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[in] numSamples number of complex samples in each vector + * @param[out] realResult real part of the result returned here + * @param[out] imagResult imaginary part of the result returned here + */ + void arm_cmplx_dot_prod_q15( + const q15_t * pSrcA, + const q15_t * pSrcB, + uint32_t numSamples, + q31_t * realResult, + q31_t * imagResult); + + + /** + * @brief Q31 complex dot product + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[in] numSamples number of complex samples in each vector + * @param[out] realResult real part of the result returned here + * @param[out] imagResult imaginary part of the result returned here + */ + void arm_cmplx_dot_prod_q31( + const q31_t * pSrcA, + const q31_t * pSrcB, + uint32_t numSamples, + q63_t * realResult, + q63_t * imagResult); + + + /** + * @brief Floating-point complex dot product + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[in] numSamples number of complex samples in each vector + * @param[out] realResult real part of the result returned here + * @param[out] imagResult imaginary part of the result returned here + */ + void arm_cmplx_dot_prod_f32( + const float32_t * pSrcA, + const float32_t * pSrcB, + uint32_t numSamples, + float32_t * realResult, + float32_t * imagResult); + + + /** + * @brief Q15 complex-by-real multiplication + * @param[in] pSrcCmplx points to the complex input vector + * @param[in] pSrcReal points to the real input vector + * @param[out] pCmplxDst points to the complex output vector + * @param[in] numSamples number of samples in each vector + */ + void arm_cmplx_mult_real_q15( + const q15_t * pSrcCmplx, + const q15_t * pSrcReal, + q15_t * pCmplxDst, + uint32_t numSamples); + + + /** + * @brief Q31 complex-by-real multiplication + * @param[in] pSrcCmplx points to the complex input vector + * @param[in] pSrcReal points to the real input vector + * @param[out] pCmplxDst points to the complex output vector + * @param[in] numSamples number of samples in each vector + */ + void arm_cmplx_mult_real_q31( + const q31_t * pSrcCmplx, + const q31_t * pSrcReal, + q31_t * pCmplxDst, + uint32_t numSamples); + + + /** + * @brief Floating-point complex-by-real multiplication + * @param[in] pSrcCmplx points to the complex input vector + * @param[in] pSrcReal points to the real input vector + * @param[out] pCmplxDst points to the complex output vector + * @param[in] numSamples number of samples in each vector + */ + void arm_cmplx_mult_real_f32( + const float32_t * pSrcCmplx, + const float32_t * pSrcReal, + float32_t * pCmplxDst, + uint32_t numSamples); + + + /** + * @brief Minimum value of a Q7 vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] result is output pointer + * @param[in] index is the array index of the minimum value in the input buffer. + */ + void arm_min_q7( + const q7_t * pSrc, + uint32_t blockSize, + q7_t * result, + uint32_t * index); + + + /** + * @brief Minimum value of a Q15 vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output pointer + * @param[in] pIndex is the array index of the minimum value in the input buffer. + */ + void arm_min_q15( + const q15_t * pSrc, + uint32_t blockSize, + q15_t * pResult, + uint32_t * pIndex); + + + /** + * @brief Minimum value of a Q31 vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output pointer + * @param[out] pIndex is the array index of the minimum value in the input buffer. + */ + void arm_min_q31( + const q31_t * pSrc, + uint32_t blockSize, + q31_t * pResult, + uint32_t * pIndex); + + + /** + * @brief Minimum value of a floating-point vector. + * @param[in] pSrc is input pointer + * @param[in] blockSize is the number of samples to process + * @param[out] pResult is output pointer + * @param[out] pIndex is the array index of the minimum value in the input buffer. + */ + void arm_min_f32( + const float32_t * pSrc, + uint32_t blockSize, + float32_t * pResult, + uint32_t * pIndex); + + +/** + * @brief Maximum value of a Q7 vector. + * @param[in] pSrc points to the input buffer + * @param[in] blockSize length of the input vector + * @param[out] pResult maximum value returned here + * @param[out] pIndex index of maximum value returned here + */ + void arm_max_q7( + const q7_t * pSrc, + uint32_t blockSize, + q7_t * pResult, + uint32_t * pIndex); + + +/** + * @brief Maximum value of a Q15 vector. + * @param[in] pSrc points to the input buffer + * @param[in] blockSize length of the input vector + * @param[out] pResult maximum value returned here + * @param[out] pIndex index of maximum value returned here + */ + void arm_max_q15( + const q15_t * pSrc, + uint32_t blockSize, + q15_t * pResult, + uint32_t * pIndex); + + +/** + * @brief Maximum value of a Q31 vector. + * @param[in] pSrc points to the input buffer + * @param[in] blockSize length of the input vector + * @param[out] pResult maximum value returned here + * @param[out] pIndex index of maximum value returned here + */ + void arm_max_q31( + const q31_t * pSrc, + uint32_t blockSize, + q31_t * pResult, + uint32_t * pIndex); + + +/** + * @brief Maximum value of a floating-point vector. + * @param[in] pSrc points to the input buffer + * @param[in] blockSize length of the input vector + * @param[out] pResult maximum value returned here + * @param[out] pIndex index of maximum value returned here + */ + void arm_max_f32( + const float32_t * pSrc, + uint32_t blockSize, + float32_t * pResult, + uint32_t * pIndex); + + /** + @brief Maximum value of a floating-point vector. + @param[in] pSrc points to the input vector + @param[in] blockSize number of samples in input vector + @param[out] pResult maximum value returned here + @return none + */ + void arm_max_no_idx_f32( + const float32_t *pSrc, + uint32_t blockSize, + float32_t *pResult); + + /** + * @brief Q15 complex-by-complex multiplication + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[out] pDst points to the output vector + * @param[in] numSamples number of complex samples in each vector + */ + void arm_cmplx_mult_cmplx_q15( + const q15_t * pSrcA, + const q15_t * pSrcB, + q15_t * pDst, + uint32_t numSamples); + + + /** + * @brief Q31 complex-by-complex multiplication + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[out] pDst points to the output vector + * @param[in] numSamples number of complex samples in each vector + */ + void arm_cmplx_mult_cmplx_q31( + const q31_t * pSrcA, + const q31_t * pSrcB, + q31_t * pDst, + uint32_t numSamples); + + + /** + * @brief Floating-point complex-by-complex multiplication + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[out] pDst points to the output vector + * @param[in] numSamples number of complex samples in each vector + */ + void arm_cmplx_mult_cmplx_f32( + const float32_t * pSrcA, + const float32_t * pSrcB, + float32_t * pDst, + uint32_t numSamples); + + + /** + * @brief Converts the elements of the floating-point vector to Q31 vector. + * @param[in] pSrc points to the floating-point input vector + * @param[out] pDst points to the Q31 output vector + * @param[in] blockSize length of the input vector + */ + void arm_float_to_q31( + const float32_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + + /** + * @brief Converts the elements of the floating-point vector to Q15 vector. + * @param[in] pSrc points to the floating-point input vector + * @param[out] pDst points to the Q15 output vector + * @param[in] blockSize length of the input vector + */ + void arm_float_to_q15( + const float32_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + + /** + * @brief Converts the elements of the floating-point vector to Q7 vector. + * @param[in] pSrc points to the floating-point input vector + * @param[out] pDst points to the Q7 output vector + * @param[in] blockSize length of the input vector + */ + void arm_float_to_q7( + const float32_t * pSrc, + q7_t * pDst, + uint32_t blockSize); + + + /** + * @brief Converts the elements of the Q31 vector to floating-point vector. + * @param[in] pSrc is input pointer + * @param[out] pDst is output pointer + * @param[in] blockSize is the number of samples to process + */ + void arm_q31_to_float( + const q31_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @brief Converts the elements of the Q31 vector to Q15 vector. + * @param[in] pSrc is input pointer + * @param[out] pDst is output pointer + * @param[in] blockSize is the number of samples to process + */ + void arm_q31_to_q15( + const q31_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + + + /** + * @brief Converts the elements of the Q31 vector to Q7 vector. + * @param[in] pSrc is input pointer + * @param[out] pDst is output pointer + * @param[in] blockSize is the number of samples to process + */ + void arm_q31_to_q7( + const q31_t * pSrc, + q7_t * pDst, + uint32_t blockSize); + + + /** + * @brief Converts the elements of the Q15 vector to floating-point vector. + * @param[in] pSrc is input pointer + * @param[out] pDst is output pointer + * @param[in] blockSize is the number of samples to process + */ + void arm_q15_to_float( + const q15_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @brief Converts the elements of the Q15 vector to Q31 vector. + * @param[in] pSrc is input pointer + * @param[out] pDst is output pointer + * @param[in] blockSize is the number of samples to process + */ + void arm_q15_to_q31( + const q15_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + + /** + * @brief Converts the elements of the Q15 vector to Q7 vector. + * @param[in] pSrc is input pointer + * @param[out] pDst is output pointer + * @param[in] blockSize is the number of samples to process + */ + void arm_q15_to_q7( + const q15_t * pSrc, + q7_t * pDst, + uint32_t blockSize); + + + /** + * @brief Converts the elements of the Q7 vector to floating-point vector. + * @param[in] pSrc is input pointer + * @param[out] pDst is output pointer + * @param[in] blockSize is the number of samples to process + */ + void arm_q7_to_float( + const q7_t * pSrc, + float32_t * pDst, + uint32_t blockSize); + + + /** + * @brief Converts the elements of the Q7 vector to Q31 vector. + * @param[in] pSrc input pointer + * @param[out] pDst output pointer + * @param[in] blockSize number of samples to process + */ + void arm_q7_to_q31( + const q7_t * pSrc, + q31_t * pDst, + uint32_t blockSize); + + + /** + * @brief Converts the elements of the Q7 vector to Q15 vector. + * @param[in] pSrc input pointer + * @param[out] pDst output pointer + * @param[in] blockSize number of samples to process + */ + void arm_q7_to_q15( + const q7_t * pSrc, + q15_t * pDst, + uint32_t blockSize); + +/** + * @brief Struct for specifying SVM Kernel + */ +typedef enum +{ + ARM_ML_KERNEL_LINEAR = 0, + /**< Linear kernel */ + ARM_ML_KERNEL_POLYNOMIAL = 1, + /**< Polynomial kernel */ + ARM_ML_KERNEL_RBF = 2, + /**< Radial Basis Function kernel */ + ARM_ML_KERNEL_SIGMOID = 3 + /**< Sigmoid kernel */ +} arm_ml_kernel_type; + + +/** + * @brief Instance structure for linear SVM prediction function. + */ +typedef struct +{ + uint32_t nbOfSupportVectors; /**< Number of support vectors */ + uint32_t vectorDimension; /**< Dimension of vector space */ + float32_t intercept; /**< Intercept */ + const float32_t *dualCoefficients; /**< Dual coefficients */ + const float32_t *supportVectors; /**< Support vectors */ + const int32_t *classes; /**< The two SVM classes */ +} arm_svm_linear_instance_f32; + + +/** + * @brief Instance structure for polynomial SVM prediction function. + */ +typedef struct +{ + uint32_t nbOfSupportVectors; /**< Number of support vectors */ + uint32_t vectorDimension; /**< Dimension of vector space */ + float32_t intercept; /**< Intercept */ + const float32_t *dualCoefficients; /**< Dual coefficients */ + const float32_t *supportVectors; /**< Support vectors */ + const int32_t *classes; /**< The two SVM classes */ + int32_t degree; /**< Polynomial degree */ + float32_t coef0; /**< Polynomial constant */ + float32_t gamma; /**< Gamma factor */ +} arm_svm_polynomial_instance_f32; + +/** + * @brief Instance structure for rbf SVM prediction function. + */ +typedef struct +{ + uint32_t nbOfSupportVectors; /**< Number of support vectors */ + uint32_t vectorDimension; /**< Dimension of vector space */ + float32_t intercept; /**< Intercept */ + const float32_t *dualCoefficients; /**< Dual coefficients */ + const float32_t *supportVectors; /**< Support vectors */ + const int32_t *classes; /**< The two SVM classes */ + float32_t gamma; /**< Gamma factor */ +} arm_svm_rbf_instance_f32; + +/** + * @brief Instance structure for sigmoid SVM prediction function. + */ +typedef struct +{ + uint32_t nbOfSupportVectors; /**< Number of support vectors */ + uint32_t vectorDimension; /**< Dimension of vector space */ + float32_t intercept; /**< Intercept */ + const float32_t *dualCoefficients; /**< Dual coefficients */ + const float32_t *supportVectors; /**< Support vectors */ + const int32_t *classes; /**< The two SVM classes */ + float32_t coef0; /**< Independant constant */ + float32_t gamma; /**< Gamma factor */ +} arm_svm_sigmoid_instance_f32; + +/** + * @brief SVM linear instance init function + * @param[in] S Parameters for SVM functions + * @param[in] nbOfSupportVectors Number of support vectors + * @param[in] vectorDimension Dimension of vector space + * @param[in] intercept Intercept + * @param[in] dualCoefficients Array of dual coefficients + * @param[in] supportVectors Array of support vectors + * @param[in] classes Array of 2 classes ID + * @return none. + * + */ + + +void arm_svm_linear_init_f32(arm_svm_linear_instance_f32 *S, + uint32_t nbOfSupportVectors, + uint32_t vectorDimension, + float32_t intercept, + const float32_t *dualCoefficients, + const float32_t *supportVectors, + const int32_t *classes); + +/** + * @brief SVM linear prediction + * @param[in] S Pointer to an instance of the linear SVM structure. + * @param[in] in Pointer to input vector + * @param[out] pResult Decision value + * @return none. + * + */ + +void arm_svm_linear_predict_f32(const arm_svm_linear_instance_f32 *S, + const float32_t * in, + int32_t * pResult); + + +/** + * @brief SVM polynomial instance init function + * @param[in] S points to an instance of the polynomial SVM structure. + * @param[in] nbOfSupportVectors Number of support vectors + * @param[in] vectorDimension Dimension of vector space + * @param[in] intercept Intercept + * @param[in] dualCoefficients Array of dual coefficients + * @param[in] supportVectors Array of support vectors + * @param[in] classes Array of 2 classes ID + * @param[in] degree Polynomial degree + * @param[in] coef0 coeff0 (scikit-learn terminology) + * @param[in] gamma gamma (scikit-learn terminology) + * @return none. + * + */ + + +void arm_svm_polynomial_init_f32(arm_svm_polynomial_instance_f32 *S, + uint32_t nbOfSupportVectors, + uint32_t vectorDimension, + float32_t intercept, + const float32_t *dualCoefficients, + const float32_t *supportVectors, + const int32_t *classes, + int32_t degree, + float32_t coef0, + float32_t gamma + ); + +/** + * @brief SVM polynomial prediction + * @param[in] S Pointer to an instance of the polynomial SVM structure. + * @param[in] in Pointer to input vector + * @param[out] pResult Decision value + * @return none. + * + */ +void arm_svm_polynomial_predict_f32(const arm_svm_polynomial_instance_f32 *S, + const float32_t * in, + int32_t * pResult); + + +/** + * @brief SVM radial basis function instance init function + * @param[in] S points to an instance of the polynomial SVM structure. + * @param[in] nbOfSupportVectors Number of support vectors + * @param[in] vectorDimension Dimension of vector space + * @param[in] intercept Intercept + * @param[in] dualCoefficients Array of dual coefficients + * @param[in] supportVectors Array of support vectors + * @param[in] classes Array of 2 classes ID + * @param[in] gamma gamma (scikit-learn terminology) + * @return none. + * + */ + +void arm_svm_rbf_init_f32(arm_svm_rbf_instance_f32 *S, + uint32_t nbOfSupportVectors, + uint32_t vectorDimension, + float32_t intercept, + const float32_t *dualCoefficients, + const float32_t *supportVectors, + const int32_t *classes, + float32_t gamma + ); + +/** + * @brief SVM rbf prediction + * @param[in] S Pointer to an instance of the rbf SVM structure. + * @param[in] in Pointer to input vector + * @param[out] pResult decision value + * @return none. + * + */ +void arm_svm_rbf_predict_f32(const arm_svm_rbf_instance_f32 *S, + const float32_t * in, + int32_t * pResult); + +/** + * @brief SVM sigmoid instance init function + * @param[in] S points to an instance of the rbf SVM structure. + * @param[in] nbOfSupportVectors Number of support vectors + * @param[in] vectorDimension Dimension of vector space + * @param[in] intercept Intercept + * @param[in] dualCoefficients Array of dual coefficients + * @param[in] supportVectors Array of support vectors + * @param[in] classes Array of 2 classes ID + * @param[in] coef0 coeff0 (scikit-learn terminology) + * @param[in] gamma gamma (scikit-learn terminology) + * @return none. + * + */ + +void arm_svm_sigmoid_init_f32(arm_svm_sigmoid_instance_f32 *S, + uint32_t nbOfSupportVectors, + uint32_t vectorDimension, + float32_t intercept, + const float32_t *dualCoefficients, + const float32_t *supportVectors, + const int32_t *classes, + float32_t coef0, + float32_t gamma + ); + +/** + * @brief SVM sigmoid prediction + * @param[in] S Pointer to an instance of the rbf SVM structure. + * @param[in] in Pointer to input vector + * @param[out] pResult Decision value + * @return none. + * + */ +void arm_svm_sigmoid_predict_f32(const arm_svm_sigmoid_instance_f32 *S, + const float32_t * in, + int32_t * pResult); + + + +/** + * @brief Instance structure for Naive Gaussian Bayesian estimator. + */ +typedef struct +{ + uint32_t vectorDimension; /**< Dimension of vector space */ + uint32_t numberOfClasses; /**< Number of different classes */ + const float32_t *theta; /**< Mean values for the Gaussians */ + const float32_t *sigma; /**< Variances for the Gaussians */ + const float32_t *classPriors; /**< Class prior probabilities */ + float32_t epsilon; /**< Additive value to variances */ +} arm_gaussian_naive_bayes_instance_f32; + +/** + * @brief Naive Gaussian Bayesian Estimator + * + * @param[in] S points to a naive bayes instance structure + * @param[in] in points to the elements of the input vector. + * @param[in] pBuffer points to a buffer of length numberOfClasses + * @return The predicted class + * + */ + + +uint32_t arm_gaussian_naive_bayes_predict_f32(const arm_gaussian_naive_bayes_instance_f32 *S, + const float32_t * in, + float32_t *pBuffer); + +/** + * @brief Computation of the LogSumExp + * + * In probabilistic computations, the dynamic of the probability values can be very + * wide because they come from gaussian functions. + * To avoid underflow and overflow issues, the values are represented by their log. + * In this representation, multiplying the original exp values is easy : their logs are added. + * But adding the original exp values is requiring some special handling and it is the + * goal of the LogSumExp function. + * + * If the values are x1...xn, the function is computing: + * + * ln(exp(x1) + ... + exp(xn)) and the computation is done in such a way that + * rounding issues are minimised. + * + * The max xm of the values is extracted and the function is computing: + * xm + ln(exp(x1 - xm) + ... + exp(xn - xm)) + * + * @param[in] *in Pointer to an array of input values. + * @param[in] blockSize Number of samples in the input array. + * @return LogSumExp + * + */ + + +float32_t arm_logsumexp_f32(const float32_t *in, uint32_t blockSize); + +/** + * @brief Dot product with log arithmetic + * + * Vectors are containing the log of the samples + * + * @param[in] pSrcA points to the first input vector + * @param[in] pSrcB points to the second input vector + * @param[in] blockSize number of samples in each vector + * @param[in] pTmpBuffer temporary buffer of length blockSize + * @return The log of the dot product . + * + */ + + +float32_t arm_logsumexp_dot_prod_f32(const float32_t * pSrcA, + const float32_t * pSrcB, + uint32_t blockSize, + float32_t *pTmpBuffer); + +/** + * @brief Entropy + * + * @param[in] pSrcA Array of input values. + * @param[in] blockSize Number of samples in the input array. + * @return Entropy -Sum(p ln p) + * + */ + + +float32_t arm_entropy_f32(const float32_t * pSrcA,uint32_t blockSize); + + +/** + * @brief Entropy + * + * @param[in] pSrcA Array of input values. + * @param[in] blockSize Number of samples in the input array. + * @return Entropy -Sum(p ln p) + * + */ + + +float64_t arm_entropy_f64(const float64_t * pSrcA, uint32_t blockSize); + + +/** + * @brief Kullback-Leibler + * + * @param[in] pSrcA Pointer to an array of input values for probability distribution A. + * @param[in] pSrcB Pointer to an array of input values for probability distribution B. + * @param[in] blockSize Number of samples in the input array. + * @return Kullback-Leibler Divergence D(A || B) + * + */ +float32_t arm_kullback_leibler_f32(const float32_t * pSrcA + ,const float32_t * pSrcB + ,uint32_t blockSize); + + +/** + * @brief Kullback-Leibler + * + * @param[in] pSrcA Pointer to an array of input values for probability distribution A. + * @param[in] pSrcB Pointer to an array of input values for probability distribution B. + * @param[in] blockSize Number of samples in the input array. + * @return Kullback-Leibler Divergence D(A || B) + * + */ +float64_t arm_kullback_leibler_f64(const float64_t * pSrcA, + const float64_t * pSrcB, + uint32_t blockSize); + + +/** + * @brief Weighted sum + * + * + * @param[in] *in Array of input values. + * @param[in] *weigths Weights + * @param[in] blockSize Number of samples in the input array. + * @return Weighted sum + * + */ +float32_t arm_weighted_sum_f32(const float32_t *in + , const float32_t *weigths + , uint32_t blockSize); + + +/** + * @brief Barycenter + * + * + * @param[in] in List of vectors + * @param[in] weights Weights of the vectors + * @param[out] out Barycenter + * @param[in] nbVectors Number of vectors + * @param[in] vecDim Dimension of space (vector dimension) + * @return None + * + */ +void arm_barycenter_f32(const float32_t *in + , const float32_t *weights + , float32_t *out + , uint32_t nbVectors + , uint32_t vecDim); + +/** + * @brief Euclidean distance between two vectors + * @param[in] pA First vector + * @param[in] pB Second vector + * @param[in] blockSize vector length + * @return distance + * + */ + +float32_t arm_euclidean_distance_f32(const float32_t *pA,const float32_t *pB, uint32_t blockSize); + +/** + * @brief Bray-Curtis distance between two vectors + * @param[in] pA First vector + * @param[in] pB Second vector + * @param[in] blockSize vector length + * @return distance + * + */ +float32_t arm_braycurtis_distance_f32(const float32_t *pA,const float32_t *pB, uint32_t blockSize); + +/** + * @brief Canberra distance between two vectors + * + * This function may divide by zero when samples pA[i] and pB[i] are both zero. + * The result of the computation will be correct. So the division per zero may be + * ignored. + * + * @param[in] pA First vector + * @param[in] pB Second vector + * @param[in] blockSize vector length + * @return distance + * + */ +float32_t arm_canberra_distance_f32(const float32_t *pA,const float32_t *pB, uint32_t blockSize); + + +/** + * @brief Chebyshev distance between two vectors + * @param[in] pA First vector + * @param[in] pB Second vector + * @param[in] blockSize vector length + * @return distance + * + */ +float32_t arm_chebyshev_distance_f32(const float32_t *pA,const float32_t *pB, uint32_t blockSize); + + +/** + * @brief Cityblock (Manhattan) distance between two vectors + * @param[in] pA First vector + * @param[in] pB Second vector + * @param[in] blockSize vector length + * @return distance + * + */ +float32_t arm_cityblock_distance_f32(const float32_t *pA,const float32_t *pB, uint32_t blockSize); + +/** + * @brief Correlation distance between two vectors + * + * The input vectors are modified in place ! + * + * @param[in] pA First vector + * @param[in] pB Second vector + * @param[in] blockSize vector length + * @return distance + * + */ +float32_t arm_correlation_distance_f32(float32_t *pA,float32_t *pB, uint32_t blockSize); + +/** + * @brief Cosine distance between two vectors + * + * @param[in] pA First vector + * @param[in] pB Second vector + * @param[in] blockSize vector length + * @return distance + * + */ + +float32_t arm_cosine_distance_f32(const float32_t *pA,const float32_t *pB, uint32_t blockSize); + +/** + * @brief Jensen-Shannon distance between two vectors + * + * This function is assuming that elements of second vector are > 0 + * and 0 only when the corresponding element of first vector is 0. + * Otherwise the result of the computation does not make sense + * and for speed reasons, the cases returning NaN or Infinity are not + * managed. + * + * When the function is computing x log (x / y) with x 0 and y 0, + * it will compute the right value (0) but a division per zero will occur + * and shoudl be ignored in client code. + * + * @param[in] pA First vector + * @param[in] pB Second vector + * @param[in] blockSize vector length + * @return distance + * + */ + +float32_t arm_jensenshannon_distance_f32(const float32_t *pA,const float32_t *pB,uint32_t blockSize); + +/** + * @brief Minkowski distance between two vectors + * + * @param[in] pA First vector + * @param[in] pB Second vector + * @param[in] n Norm order (>= 2) + * @param[in] blockSize vector length + * @return distance + * + */ + + + +float32_t arm_minkowski_distance_f32(const float32_t *pA,const float32_t *pB, int32_t order, uint32_t blockSize); + +/** + * @brief Dice distance between two vectors + * + * @param[in] pA First vector of packed booleans + * @param[in] pB Second vector of packed booleans + * @param[in] order Distance order + * @param[in] blockSize Number of samples + * @return distance + * + */ + + +float32_t arm_dice_distance(const uint32_t *pA, const uint32_t *pB, uint32_t numberOfBools); + +/** + * @brief Hamming distance between two vectors + * + * @param[in] pA First vector of packed booleans + * @param[in] pB Second vector of packed booleans + * @param[in] numberOfBools Number of booleans + * @return distance + * + */ + +float32_t arm_hamming_distance(const uint32_t *pA, const uint32_t *pB, uint32_t numberOfBools); + +/** + * @brief Jaccard distance between two vectors + * + * @param[in] pA First vector of packed booleans + * @param[in] pB Second vector of packed booleans + * @param[in] numberOfBools Number of booleans + * @return distance + * + */ + +float32_t arm_jaccard_distance(const uint32_t *pA, const uint32_t *pB, uint32_t numberOfBools); + +/** + * @brief Kulsinski distance between two vectors + * + * @param[in] pA First vector of packed booleans + * @param[in] pB Second vector of packed booleans + * @param[in] numberOfBools Number of booleans + * @return distance + * + */ + +float32_t arm_kulsinski_distance(const uint32_t *pA, const uint32_t *pB, uint32_t numberOfBools); + +/** + * @brief Roger Stanimoto distance between two vectors + * + * @param[in] pA First vector of packed booleans + * @param[in] pB Second vector of packed booleans + * @param[in] numberOfBools Number of booleans + * @return distance + * + */ + +float32_t arm_rogerstanimoto_distance(const uint32_t *pA, const uint32_t *pB, uint32_t numberOfBools); + +/** + * @brief Russell-Rao distance between two vectors + * + * @param[in] pA First vector of packed booleans + * @param[in] pB Second vector of packed booleans + * @param[in] numberOfBools Number of booleans + * @return distance + * + */ + +float32_t arm_russellrao_distance(const uint32_t *pA, const uint32_t *pB, uint32_t numberOfBools); + +/** + * @brief Sokal-Michener distance between two vectors + * + * @param[in] pA First vector of packed booleans + * @param[in] pB Second vector of packed booleans + * @param[in] numberOfBools Number of booleans + * @return distance + * + */ + +float32_t arm_sokalmichener_distance(const uint32_t *pA, const uint32_t *pB, uint32_t numberOfBools); + +/** + * @brief Sokal-Sneath distance between two vectors + * + * @param[in] pA First vector of packed booleans + * @param[in] pB Second vector of packed booleans + * @param[in] numberOfBools Number of booleans + * @return distance + * + */ + +float32_t arm_sokalsneath_distance(const uint32_t *pA, const uint32_t *pB, uint32_t numberOfBools); + +/** + * @brief Yule distance between two vectors + * + * @param[in] pA First vector of packed booleans + * @param[in] pB Second vector of packed booleans + * @param[in] numberOfBools Number of booleans + * @return distance + * + */ + +float32_t arm_yule_distance(const uint32_t *pA, const uint32_t *pB, uint32_t numberOfBools); + + + /** + * @ingroup groupInterpolation + */ + + /** + * @defgroup BilinearInterpolate Bilinear Interpolation + * + * Bilinear interpolation is an extension of linear interpolation applied to a two dimensional grid. + * The underlying function f(x, y) is sampled on a regular grid and the interpolation process + * determines values between the grid points. + * Bilinear interpolation is equivalent to two step linear interpolation, first in the x-dimension and then in the y-dimension. + * Bilinear interpolation is often used in image processing to rescale images. + * The CMSIS DSP library provides bilinear interpolation functions for Q7, Q15, Q31, and floating-point data types. + * + * Algorithm + * \par + * The instance structure used by the bilinear interpolation functions describes a two dimensional data table. + * For floating-point, the instance structure is defined as: + *
+   *   typedef struct
+   *   {
+   *     uint16_t numRows;
+   *     uint16_t numCols;
+   *     float32_t *pData;
+   * } arm_bilinear_interp_instance_f32;
+   * 
+ * + * \par + * where numRows specifies the number of rows in the table; + * numCols specifies the number of columns in the table; + * and pData points to an array of size numRows*numCols values. + * The data table pTable is organized in row order and the supplied data values fall on integer indexes. + * That is, table element (x,y) is located at pTable[x + y*numCols] where x and y are integers. + * + * \par + * Let (x, y) specify the desired interpolation point. Then define: + *
+   *     XF = floor(x)
+   *     YF = floor(y)
+   * 
+ * \par + * The interpolated output point is computed as: + *
+   *  f(x, y) = f(XF, YF) * (1-(x-XF)) * (1-(y-YF))
+   *           + f(XF+1, YF) * (x-XF)*(1-(y-YF))
+   *           + f(XF, YF+1) * (1-(x-XF))*(y-YF)
+   *           + f(XF+1, YF+1) * (x-XF)*(y-YF)
+   * 
+ * Note that the coordinates (x, y) contain integer and fractional components. + * The integer components specify which portion of the table to use while the + * fractional components control the interpolation processor. + * + * \par + * if (x,y) are outside of the table boundary, Bilinear interpolation returns zero output. + */ + + + /** + * @addtogroup BilinearInterpolate + * @{ + */ + + /** + * @brief Floating-point bilinear interpolation. + * @param[in,out] S points to an instance of the interpolation structure. + * @param[in] X interpolation coordinate. + * @param[in] Y interpolation coordinate. + * @return out interpolated value. + */ + __STATIC_FORCEINLINE float32_t arm_bilinear_interp_f32( + const arm_bilinear_interp_instance_f32 * S, + float32_t X, + float32_t Y) + { + float32_t out; + float32_t f00, f01, f10, f11; + float32_t *pData = S->pData; + int32_t xIndex, yIndex, index; + float32_t xdiff, ydiff; + float32_t b1, b2, b3, b4; + + xIndex = (int32_t) X; + yIndex = (int32_t) Y; + + /* Care taken for table outside boundary */ + /* Returns zero output when values are outside table boundary */ + if (xIndex < 0 || xIndex > (S->numCols - 2) || yIndex < 0 || yIndex > (S->numRows - 2)) + { + return (0); + } + + /* Calculation of index for two nearest points in X-direction */ + index = (xIndex ) + (yIndex ) * S->numCols; + + + /* Read two nearest points in X-direction */ + f00 = pData[index]; + f01 = pData[index + 1]; + + /* Calculation of index for two nearest points in Y-direction */ + index = (xIndex ) + (yIndex+1) * S->numCols; + + + /* Read two nearest points in Y-direction */ + f10 = pData[index]; + f11 = pData[index + 1]; + + /* Calculation of intermediate values */ + b1 = f00; + b2 = f01 - f00; + b3 = f10 - f00; + b4 = f00 - f01 - f10 + f11; + + /* Calculation of fractional part in X */ + xdiff = X - xIndex; + + /* Calculation of fractional part in Y */ + ydiff = Y - yIndex; + + /* Calculation of bi-linear interpolated output */ + out = b1 + b2 * xdiff + b3 * ydiff + b4 * xdiff * ydiff; + + /* return to application */ + return (out); + } + + + /** + * @brief Q31 bilinear interpolation. + * @param[in,out] S points to an instance of the interpolation structure. + * @param[in] X interpolation coordinate in 12.20 format. + * @param[in] Y interpolation coordinate in 12.20 format. + * @return out interpolated value. + */ + __STATIC_FORCEINLINE q31_t arm_bilinear_interp_q31( + arm_bilinear_interp_instance_q31 * S, + q31_t X, + q31_t Y) + { + q31_t out; /* Temporary output */ + q31_t acc = 0; /* output */ + q31_t xfract, yfract; /* X, Y fractional parts */ + q31_t x1, x2, y1, y2; /* Nearest output values */ + int32_t rI, cI; /* Row and column indices */ + q31_t *pYData = S->pData; /* pointer to output table values */ + uint32_t nCols = S->numCols; /* num of rows */ + + /* Input is in 12.20 format */ + /* 12 bits for the table index */ + /* Index value calculation */ + rI = ((X & (q31_t)0xFFF00000) >> 20); + + /* Input is in 12.20 format */ + /* 12 bits for the table index */ + /* Index value calculation */ + cI = ((Y & (q31_t)0xFFF00000) >> 20); + + /* Care taken for table outside boundary */ + /* Returns zero output when values are outside table boundary */ + if (rI < 0 || rI > (S->numCols - 2) || cI < 0 || cI > (S->numRows - 2)) + { + return (0); + } + + /* 20 bits for the fractional part */ + /* shift left xfract by 11 to keep 1.31 format */ + xfract = (X & 0x000FFFFF) << 11U; + + /* Read two nearest output values from the index */ + x1 = pYData[(rI) + (int32_t)nCols * (cI) ]; + x2 = pYData[(rI) + (int32_t)nCols * (cI) + 1]; + + /* 20 bits for the fractional part */ + /* shift left yfract by 11 to keep 1.31 format */ + yfract = (Y & 0x000FFFFF) << 11U; + + /* Read two nearest output values from the index */ + y1 = pYData[(rI) + (int32_t)nCols * (cI + 1) ]; + y2 = pYData[(rI) + (int32_t)nCols * (cI + 1) + 1]; + + /* Calculation of x1 * (1-xfract ) * (1-yfract) and acc is in 3.29(q29) format */ + out = ((q31_t) (((q63_t) x1 * (0x7FFFFFFF - xfract)) >> 32)); + acc = ((q31_t) (((q63_t) out * (0x7FFFFFFF - yfract)) >> 32)); + + /* x2 * (xfract) * (1-yfract) in 3.29(q29) and adding to acc */ + out = ((q31_t) ((q63_t) x2 * (0x7FFFFFFF - yfract) >> 32)); + acc += ((q31_t) ((q63_t) out * (xfract) >> 32)); + + /* y1 * (1 - xfract) * (yfract) in 3.29(q29) and adding to acc */ + out = ((q31_t) ((q63_t) y1 * (0x7FFFFFFF - xfract) >> 32)); + acc += ((q31_t) ((q63_t) out * (yfract) >> 32)); + + /* y2 * (xfract) * (yfract) in 3.29(q29) and adding to acc */ + out = ((q31_t) ((q63_t) y2 * (xfract) >> 32)); + acc += ((q31_t) ((q63_t) out * (yfract) >> 32)); + + /* Convert acc to 1.31(q31) format */ + return ((q31_t)(acc << 2)); + } + + + /** + * @brief Q15 bilinear interpolation. + * @param[in,out] S points to an instance of the interpolation structure. + * @param[in] X interpolation coordinate in 12.20 format. + * @param[in] Y interpolation coordinate in 12.20 format. + * @return out interpolated value. + */ + __STATIC_FORCEINLINE q15_t arm_bilinear_interp_q15( + arm_bilinear_interp_instance_q15 * S, + q31_t X, + q31_t Y) + { + q63_t acc = 0; /* output */ + q31_t out; /* Temporary output */ + q15_t x1, x2, y1, y2; /* Nearest output values */ + q31_t xfract, yfract; /* X, Y fractional parts */ + int32_t rI, cI; /* Row and column indices */ + q15_t *pYData = S->pData; /* pointer to output table values */ + uint32_t nCols = S->numCols; /* num of rows */ + + /* Input is in 12.20 format */ + /* 12 bits for the table index */ + /* Index value calculation */ + rI = ((X & (q31_t)0xFFF00000) >> 20); + + /* Input is in 12.20 format */ + /* 12 bits for the table index */ + /* Index value calculation */ + cI = ((Y & (q31_t)0xFFF00000) >> 20); + + /* Care taken for table outside boundary */ + /* Returns zero output when values are outside table boundary */ + if (rI < 0 || rI > (S->numCols - 2) || cI < 0 || cI > (S->numRows - 2)) + { + return (0); + } + + /* 20 bits for the fractional part */ + /* xfract should be in 12.20 format */ + xfract = (X & 0x000FFFFF); + + /* Read two nearest output values from the index */ + x1 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI) ]; + x2 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI) + 1]; + + /* 20 bits for the fractional part */ + /* yfract should be in 12.20 format */ + yfract = (Y & 0x000FFFFF); + + /* Read two nearest output values from the index */ + y1 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI + 1) ]; + y2 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI + 1) + 1]; + + /* Calculation of x1 * (1-xfract ) * (1-yfract) and acc is in 13.51 format */ + + /* x1 is in 1.15(q15), xfract in 12.20 format and out is in 13.35 format */ + /* convert 13.35 to 13.31 by right shifting and out is in 1.31 */ + out = (q31_t) (((q63_t) x1 * (0x0FFFFF - xfract)) >> 4U); + acc = ((q63_t) out * (0x0FFFFF - yfract)); + + /* x2 * (xfract) * (1-yfract) in 1.51 and adding to acc */ + out = (q31_t) (((q63_t) x2 * (0x0FFFFF - yfract)) >> 4U); + acc += ((q63_t) out * (xfract)); + + /* y1 * (1 - xfract) * (yfract) in 1.51 and adding to acc */ + out = (q31_t) (((q63_t) y1 * (0x0FFFFF - xfract)) >> 4U); + acc += ((q63_t) out * (yfract)); + + /* y2 * (xfract) * (yfract) in 1.51 and adding to acc */ + out = (q31_t) (((q63_t) y2 * (xfract)) >> 4U); + acc += ((q63_t) out * (yfract)); + + /* acc is in 13.51 format and down shift acc by 36 times */ + /* Convert out to 1.15 format */ + return ((q15_t)(acc >> 36)); + } + + + /** + * @brief Q7 bilinear interpolation. + * @param[in,out] S points to an instance of the interpolation structure. + * @param[in] X interpolation coordinate in 12.20 format. + * @param[in] Y interpolation coordinate in 12.20 format. + * @return out interpolated value. + */ + __STATIC_FORCEINLINE q7_t arm_bilinear_interp_q7( + arm_bilinear_interp_instance_q7 * S, + q31_t X, + q31_t Y) + { + q63_t acc = 0; /* output */ + q31_t out; /* Temporary output */ + q31_t xfract, yfract; /* X, Y fractional parts */ + q7_t x1, x2, y1, y2; /* Nearest output values */ + int32_t rI, cI; /* Row and column indices */ + q7_t *pYData = S->pData; /* pointer to output table values */ + uint32_t nCols = S->numCols; /* num of rows */ + + /* Input is in 12.20 format */ + /* 12 bits for the table index */ + /* Index value calculation */ + rI = ((X & (q31_t)0xFFF00000) >> 20); + + /* Input is in 12.20 format */ + /* 12 bits for the table index */ + /* Index value calculation */ + cI = ((Y & (q31_t)0xFFF00000) >> 20); + + /* Care taken for table outside boundary */ + /* Returns zero output when values are outside table boundary */ + if (rI < 0 || rI > (S->numCols - 2) || cI < 0 || cI > (S->numRows - 2)) + { + return (0); + } + + /* 20 bits for the fractional part */ + /* xfract should be in 12.20 format */ + xfract = (X & (q31_t)0x000FFFFF); + + /* Read two nearest output values from the index */ + x1 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI) ]; + x2 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI) + 1]; + + /* 20 bits for the fractional part */ + /* yfract should be in 12.20 format */ + yfract = (Y & (q31_t)0x000FFFFF); + + /* Read two nearest output values from the index */ + y1 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI + 1) ]; + y2 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI + 1) + 1]; + + /* Calculation of x1 * (1-xfract ) * (1-yfract) and acc is in 16.47 format */ + out = ((x1 * (0xFFFFF - xfract))); + acc = (((q63_t) out * (0xFFFFF - yfract))); + + /* x2 * (xfract) * (1-yfract) in 2.22 and adding to acc */ + out = ((x2 * (0xFFFFF - yfract))); + acc += (((q63_t) out * (xfract))); + + /* y1 * (1 - xfract) * (yfract) in 2.22 and adding to acc */ + out = ((y1 * (0xFFFFF - xfract))); + acc += (((q63_t) out * (yfract))); + + /* y2 * (xfract) * (yfract) in 2.22 and adding to acc */ + out = ((y2 * (yfract))); + acc += (((q63_t) out * (xfract))); + + /* acc in 16.47 format and down shift by 40 to convert to 1.7 format */ + return ((q7_t)(acc >> 40)); + } + + /** + * @} end of BilinearInterpolate group + */ + + +/* SMMLAR */ +#define multAcc_32x32_keep32_R(a, x, y) \ + a = (q31_t) (((((q63_t) a) << 32) + ((q63_t) x * y) + 0x80000000LL ) >> 32) + +/* SMMLSR */ +#define multSub_32x32_keep32_R(a, x, y) \ + a = (q31_t) (((((q63_t) a) << 32) - ((q63_t) x * y) + 0x80000000LL ) >> 32) + +/* SMMULR */ +#define mult_32x32_keep32_R(a, x, y) \ + a = (q31_t) (((q63_t) x * y + 0x80000000LL ) >> 32) + +/* SMMLA */ +#define multAcc_32x32_keep32(a, x, y) \ + a += (q31_t) (((q63_t) x * y) >> 32) + +/* SMMLS */ +#define multSub_32x32_keep32(a, x, y) \ + a -= (q31_t) (((q63_t) x * y) >> 32) + +/* SMMUL */ +#define mult_32x32_keep32(a, x, y) \ + a = (q31_t) (((q63_t) x * y ) >> 32) + + +#if defined ( __CC_ARM ) + /* Enter low optimization region - place directly above function definition */ + #if defined( __ARM_ARCH_7EM__ ) + #define LOW_OPTIMIZATION_ENTER \ + _Pragma ("push") \ + _Pragma ("O1") + #else + #define LOW_OPTIMIZATION_ENTER + #endif + + /* Exit low optimization region - place directly after end of function definition */ + #if defined ( __ARM_ARCH_7EM__ ) + #define LOW_OPTIMIZATION_EXIT \ + _Pragma ("pop") + #else + #define LOW_OPTIMIZATION_EXIT + #endif + + /* Enter low optimization region - place directly above function definition */ + #define IAR_ONLY_LOW_OPTIMIZATION_ENTER + + /* Exit low optimization region - place directly after end of function definition */ + #define IAR_ONLY_LOW_OPTIMIZATION_EXIT + +#elif defined (__ARMCC_VERSION ) && ( __ARMCC_VERSION >= 6010050 ) + #define LOW_OPTIMIZATION_ENTER + #define LOW_OPTIMIZATION_EXIT + #define IAR_ONLY_LOW_OPTIMIZATION_ENTER + #define IAR_ONLY_LOW_OPTIMIZATION_EXIT + +#elif defined ( __GNUC__ ) + #define LOW_OPTIMIZATION_ENTER \ + __attribute__(( optimize("-O1") )) + #define LOW_OPTIMIZATION_EXIT + #define IAR_ONLY_LOW_OPTIMIZATION_ENTER + #define IAR_ONLY_LOW_OPTIMIZATION_EXIT + +#elif defined ( __ICCARM__ ) + /* Enter low optimization region - place directly above function definition */ + #if defined ( __ARM_ARCH_7EM__ ) + #define LOW_OPTIMIZATION_ENTER \ + _Pragma ("optimize=low") + #else + #define LOW_OPTIMIZATION_ENTER + #endif + + /* Exit low optimization region - place directly after end of function definition */ + #define LOW_OPTIMIZATION_EXIT + + /* Enter low optimization region - place directly above function definition */ + #if defined ( __ARM_ARCH_7EM__ ) + #define IAR_ONLY_LOW_OPTIMIZATION_ENTER \ + _Pragma ("optimize=low") + #else + #define IAR_ONLY_LOW_OPTIMIZATION_ENTER + #endif + + /* Exit low optimization region - place directly after end of function definition */ + #define IAR_ONLY_LOW_OPTIMIZATION_EXIT + +#elif defined ( __TI_ARM__ ) + #define LOW_OPTIMIZATION_ENTER + #define LOW_OPTIMIZATION_EXIT + #define IAR_ONLY_LOW_OPTIMIZATION_ENTER + #define IAR_ONLY_LOW_OPTIMIZATION_EXIT + +#elif defined ( __CSMC__ ) + #define LOW_OPTIMIZATION_ENTER + #define LOW_OPTIMIZATION_EXIT + #define IAR_ONLY_LOW_OPTIMIZATION_ENTER + #define IAR_ONLY_LOW_OPTIMIZATION_EXIT + +#elif defined ( __TASKING__ ) + #define LOW_OPTIMIZATION_ENTER + #define LOW_OPTIMIZATION_EXIT + #define IAR_ONLY_LOW_OPTIMIZATION_ENTER + #define IAR_ONLY_LOW_OPTIMIZATION_EXIT + +#elif defined ( _MSC_VER ) || defined(__GNUC_PYTHON__) + #define LOW_OPTIMIZATION_ENTER + #define LOW_OPTIMIZATION_EXIT + #define IAR_ONLY_LOW_OPTIMIZATION_ENTER + #define IAR_ONLY_LOW_OPTIMIZATION_EXIT +#endif + + + +/* Compiler specific diagnostic adjustment */ +#if defined ( __CC_ARM ) + +#elif defined ( __ARMCC_VERSION ) && ( __ARMCC_VERSION >= 6010050 ) + +#elif defined ( __GNUC__ ) +#pragma GCC diagnostic pop + +#elif defined ( __ICCARM__ ) + +#elif defined ( __TI_ARM__ ) + +#elif defined ( __CSMC__ ) + +#elif defined ( __TASKING__ ) + +#elif defined ( _MSC_VER ) + +#else + #error Unknown compiler +#endif + +#ifdef __cplusplus +} +#endif + + +#endif /* _ARM_MATH_H */ + +/** + * + * End of file. + */ diff --git a/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_mve_tables.h b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_mve_tables.h new file mode 100644 index 0000000000..4d2c135ac6 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_mve_tables.h @@ -0,0 +1,235 @@ +/* ---------------------------------------------------------------------- + * Project: CMSIS DSP Library + * Title: arm_mve_tables.h + * Description: common tables like fft twiddle factors, Bitreverse, reciprocal etc + * used for MVE implementation only + * + * $Date: 08. January 2020 + * $Revision: V1.7.0 + * + * Target Processor: Cortex-M cores + * -------------------------------------------------------------------- */ +/* + * Copyright (C) 2010-2020 ARM Limited or its affiliates. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * 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 + * + * www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an AS IS BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + + #ifndef _ARM_MVE_TABLES_H + #define _ARM_MVE_TABLES_H + + #include "arm_math.h" + + + + + + +#if defined(ARM_MATH_MVEF) && !defined(ARM_MATH_AUTOVECTORIZE) + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_FFT_ALLOW_TABLES) + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F32_16) || defined(ARM_TABLE_TWIDDLECOEF_F32_32) + +extern uint32_t rearranged_twiddle_tab_stride1_arr_16_f32[2]; +extern uint32_t rearranged_twiddle_tab_stride2_arr_16_f32[2]; +extern uint32_t rearranged_twiddle_tab_stride3_arr_16_f32[2]; +extern float32_t rearranged_twiddle_stride1_16_f32[8]; +extern float32_t rearranged_twiddle_stride2_16_f32[8]; +extern float32_t rearranged_twiddle_stride3_16_f32[8]; +#endif + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F32_64) || defined(ARM_TABLE_TWIDDLECOEF_F32_128) + +extern uint32_t rearranged_twiddle_tab_stride1_arr_64_f32[3]; +extern uint32_t rearranged_twiddle_tab_stride2_arr_64_f32[3]; +extern uint32_t rearranged_twiddle_tab_stride3_arr_64_f32[3]; +extern float32_t rearranged_twiddle_stride1_64_f32[40]; +extern float32_t rearranged_twiddle_stride2_64_f32[40]; +extern float32_t rearranged_twiddle_stride3_64_f32[40]; +#endif + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F32_256) || defined(ARM_TABLE_TWIDDLECOEF_F32_512) + +extern uint32_t rearranged_twiddle_tab_stride1_arr_256_f32[4]; +extern uint32_t rearranged_twiddle_tab_stride2_arr_256_f32[4]; +extern uint32_t rearranged_twiddle_tab_stride3_arr_256_f32[4]; +extern float32_t rearranged_twiddle_stride1_256_f32[168]; +extern float32_t rearranged_twiddle_stride2_256_f32[168]; +extern float32_t rearranged_twiddle_stride3_256_f32[168]; +#endif + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F32_1024) || defined(ARM_TABLE_TWIDDLECOEF_F32_2048) + +extern uint32_t rearranged_twiddle_tab_stride1_arr_1024_f32[5]; +extern uint32_t rearranged_twiddle_tab_stride2_arr_1024_f32[5]; +extern uint32_t rearranged_twiddle_tab_stride3_arr_1024_f32[5]; +extern float32_t rearranged_twiddle_stride1_1024_f32[680]; +extern float32_t rearranged_twiddle_stride2_1024_f32[680]; +extern float32_t rearranged_twiddle_stride3_1024_f32[680]; +#endif + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_F32_4096) || defined(ARM_TABLE_TWIDDLECOEF_F32_8192) + +extern uint32_t rearranged_twiddle_tab_stride1_arr_4096_f32[6]; +extern uint32_t rearranged_twiddle_tab_stride2_arr_4096_f32[6]; +extern uint32_t rearranged_twiddle_tab_stride3_arr_4096_f32[6]; +extern float32_t rearranged_twiddle_stride1_4096_f32[2728]; +extern float32_t rearranged_twiddle_stride2_4096_f32[2728]; +extern float32_t rearranged_twiddle_stride3_4096_f32[2728]; +#endif + + +#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_FFT_ALLOW_TABLES) */ + +#endif /* defined(ARM_MATH_MVEF) && !defined(ARM_MATH_AUTOVECTORIZE) */ + + + +#if defined(ARM_MATH_MVEI) + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_FFT_ALLOW_TABLES) + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q31_16) || defined(ARM_TABLE_TWIDDLECOEF_Q31_32) + +extern uint32_t rearranged_twiddle_tab_stride1_arr_16_q31[2]; +extern uint32_t rearranged_twiddle_tab_stride2_arr_16_q31[2]; +extern uint32_t rearranged_twiddle_tab_stride3_arr_16_q31[2]; +extern q31_t rearranged_twiddle_stride1_16_q31[8]; +extern q31_t rearranged_twiddle_stride2_16_q31[8]; +extern q31_t rearranged_twiddle_stride3_16_q31[8]; +#endif + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q31_64) || defined(ARM_TABLE_TWIDDLECOEF_Q31_128) + +extern uint32_t rearranged_twiddle_tab_stride1_arr_64_q31[3]; +extern uint32_t rearranged_twiddle_tab_stride2_arr_64_q31[3]; +extern uint32_t rearranged_twiddle_tab_stride3_arr_64_q31[3]; +extern q31_t rearranged_twiddle_stride1_64_q31[40]; +extern q31_t rearranged_twiddle_stride2_64_q31[40]; +extern q31_t rearranged_twiddle_stride3_64_q31[40]; +#endif + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q31_256) || defined(ARM_TABLE_TWIDDLECOEF_Q31_512) + +extern uint32_t rearranged_twiddle_tab_stride1_arr_256_q31[4]; +extern uint32_t rearranged_twiddle_tab_stride2_arr_256_q31[4]; +extern uint32_t rearranged_twiddle_tab_stride3_arr_256_q31[4]; +extern q31_t rearranged_twiddle_stride1_256_q31[168]; +extern q31_t rearranged_twiddle_stride2_256_q31[168]; +extern q31_t rearranged_twiddle_stride3_256_q31[168]; +#endif + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q31_1024) || defined(ARM_TABLE_TWIDDLECOEF_Q31_2048) + +extern uint32_t rearranged_twiddle_tab_stride1_arr_1024_q31[5]; +extern uint32_t rearranged_twiddle_tab_stride2_arr_1024_q31[5]; +extern uint32_t rearranged_twiddle_tab_stride3_arr_1024_q31[5]; +extern q31_t rearranged_twiddle_stride1_1024_q31[680]; +extern q31_t rearranged_twiddle_stride2_1024_q31[680]; +extern q31_t rearranged_twiddle_stride3_1024_q31[680]; +#endif + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q31_4096) || defined(ARM_TABLE_TWIDDLECOEF_Q31_8192) + +extern uint32_t rearranged_twiddle_tab_stride1_arr_4096_q31[6]; +extern uint32_t rearranged_twiddle_tab_stride2_arr_4096_q31[6]; +extern uint32_t rearranged_twiddle_tab_stride3_arr_4096_q31[6]; +extern q31_t rearranged_twiddle_stride1_4096_q31[2728]; +extern q31_t rearranged_twiddle_stride2_4096_q31[2728]; +extern q31_t rearranged_twiddle_stride3_4096_q31[2728]; +#endif + + +#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_FFT_ALLOW_TABLES) */ + +#endif /* defined(ARM_MATH_MVEI) */ + + + +#if defined(ARM_MATH_MVEI) + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_FFT_ALLOW_TABLES) + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q15_16) || defined(ARM_TABLE_TWIDDLECOEF_Q15_32) + +extern uint32_t rearranged_twiddle_tab_stride1_arr_16_q15[2]; +extern uint32_t rearranged_twiddle_tab_stride2_arr_16_q15[2]; +extern uint32_t rearranged_twiddle_tab_stride3_arr_16_q15[2]; +extern q15_t rearranged_twiddle_stride1_16_q15[8]; +extern q15_t rearranged_twiddle_stride2_16_q15[8]; +extern q15_t rearranged_twiddle_stride3_16_q15[8]; +#endif + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q15_64) || defined(ARM_TABLE_TWIDDLECOEF_Q15_128) + +extern uint32_t rearranged_twiddle_tab_stride1_arr_64_q15[3]; +extern uint32_t rearranged_twiddle_tab_stride2_arr_64_q15[3]; +extern uint32_t rearranged_twiddle_tab_stride3_arr_64_q15[3]; +extern q15_t rearranged_twiddle_stride1_64_q15[40]; +extern q15_t rearranged_twiddle_stride2_64_q15[40]; +extern q15_t rearranged_twiddle_stride3_64_q15[40]; +#endif + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q15_256) || defined(ARM_TABLE_TWIDDLECOEF_Q15_512) + +extern uint32_t rearranged_twiddle_tab_stride1_arr_256_q15[4]; +extern uint32_t rearranged_twiddle_tab_stride2_arr_256_q15[4]; +extern uint32_t rearranged_twiddle_tab_stride3_arr_256_q15[4]; +extern q15_t rearranged_twiddle_stride1_256_q15[168]; +extern q15_t rearranged_twiddle_stride2_256_q15[168]; +extern q15_t rearranged_twiddle_stride3_256_q15[168]; +#endif + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q15_1024) || defined(ARM_TABLE_TWIDDLECOEF_Q15_2048) + +extern uint32_t rearranged_twiddle_tab_stride1_arr_1024_q15[5]; +extern uint32_t rearranged_twiddle_tab_stride2_arr_1024_q15[5]; +extern uint32_t rearranged_twiddle_tab_stride3_arr_1024_q15[5]; +extern q15_t rearranged_twiddle_stride1_1024_q15[680]; +extern q15_t rearranged_twiddle_stride2_1024_q15[680]; +extern q15_t rearranged_twiddle_stride3_1024_q15[680]; +#endif + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_ALL_FFT_TABLES) || defined(ARM_TABLE_TWIDDLECOEF_Q15_4096) || defined(ARM_TABLE_TWIDDLECOEF_Q15_8192) + +extern uint32_t rearranged_twiddle_tab_stride1_arr_4096_q15[6]; +extern uint32_t rearranged_twiddle_tab_stride2_arr_4096_q15[6]; +extern uint32_t rearranged_twiddle_tab_stride3_arr_4096_q15[6]; +extern q15_t rearranged_twiddle_stride1_4096_q15[2728]; +extern q15_t rearranged_twiddle_stride2_4096_q15[2728]; +extern q15_t rearranged_twiddle_stride3_4096_q15[2728]; +#endif + + +#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_FFT_ALLOW_TABLES) */ + +#endif /* defined(ARM_MATH_MVEI) */ + + + +#if defined(ARM_MATH_MVEI) + +#if !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_FFT_ALLOW_TABLES) + + +#endif /* !defined(ARM_DSP_CONFIG_TABLES) || defined(ARM_FFT_ALLOW_TABLES) */ + +#endif /* defined(ARM_MATH_MVEI) */ + + + +#endif /*_ARM_MVE_TABLES_H*/ + diff --git a/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_vec_math.h b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_vec_math.h new file mode 100644 index 0000000000..0ce9464bcb --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/arm_vec_math.h @@ -0,0 +1,372 @@ +/****************************************************************************** + * @file arm_vec_math.h + * @brief Public header file for CMSIS DSP Library + * @version V1.7.0 + * @date 15. October 2019 + ******************************************************************************/ +/* + * Copyright (c) 2010-2019 Arm Limited or its affiliates. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * 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 + * + * www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an AS IS BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef _ARM_VEC_MATH_H +#define _ARM_VEC_MATH_H + +#include "arm_math.h" +#include "arm_common_tables.h" +#include "arm_helium_utils.h" + +#ifdef __cplusplus +extern "C" +{ +#endif + +#if (defined(ARM_MATH_MVEF) || defined(ARM_MATH_HELIUM)) && !defined(ARM_MATH_AUTOVECTORIZE) + +#define INV_NEWTON_INIT_F32 0x7EF127EA + +static const float32_t __logf_rng_f32=0.693147180f; + + +/* fast inverse approximation (3x newton) */ +__STATIC_INLINE f32x4_t vrecip_medprec_f32( + f32x4_t x) +{ + q31x4_t m; + f32x4_t b; + any32x4_t xinv; + f32x4_t ax = vabsq(x); + + xinv.f = ax; + m = 0x3F800000 - (xinv.i & 0x7F800000); + xinv.i = xinv.i + m; + xinv.f = 1.41176471f - 0.47058824f * xinv.f; + xinv.i = xinv.i + m; + + b = 2.0f - xinv.f * ax; + xinv.f = xinv.f * b; + + b = 2.0f - xinv.f * ax; + xinv.f = xinv.f * b; + + b = 2.0f - xinv.f * ax; + xinv.f = xinv.f * b; + + xinv.f = vdupq_m(xinv.f, INFINITY, vcmpeqq(x, 0.0f)); + /* + * restore sign + */ + xinv.f = vnegq_m(xinv.f, xinv.f, vcmpltq(x, 0.0f)); + + return xinv.f; +} + +/* fast inverse approximation (4x newton) */ +__STATIC_INLINE f32x4_t vrecip_hiprec_f32( + f32x4_t x) +{ + q31x4_t m; + f32x4_t b; + any32x4_t xinv; + f32x4_t ax = vabsq(x); + + xinv.f = ax; + + m = 0x3F800000 - (xinv.i & 0x7F800000); + xinv.i = xinv.i + m; + xinv.f = 1.41176471f - 0.47058824f * xinv.f; + xinv.i = xinv.i + m; + + b = 2.0f - xinv.f * ax; + xinv.f = xinv.f * b; + + b = 2.0f - xinv.f * ax; + xinv.f = xinv.f * b; + + b = 2.0f - xinv.f * ax; + xinv.f = xinv.f * b; + + b = 2.0f - xinv.f * ax; + xinv.f = xinv.f * b; + + xinv.f = vdupq_m(xinv.f, INFINITY, vcmpeqq(x, 0.0f)); + /* + * restore sign + */ + xinv.f = vnegq_m(xinv.f, xinv.f, vcmpltq(x, 0.0f)); + + return xinv.f; +} + +__STATIC_INLINE f32x4_t vdiv_f32( + f32x4_t num, f32x4_t den) +{ + return vmulq(num, vrecip_hiprec_f32(den)); +} + +/** + @brief Single-precision taylor dev. + @param[in] x f32 quad vector input + @param[in] coeffs f32 quad vector coeffs + @return destination f32 quad vector + */ + +__STATIC_INLINE f32x4_t vtaylor_polyq_f32( + f32x4_t x, + const float32_t * coeffs) +{ + f32x4_t A = vfmasq(vdupq_n_f32(coeffs[4]), x, coeffs[0]); + f32x4_t B = vfmasq(vdupq_n_f32(coeffs[6]), x, coeffs[2]); + f32x4_t C = vfmasq(vdupq_n_f32(coeffs[5]), x, coeffs[1]); + f32x4_t D = vfmasq(vdupq_n_f32(coeffs[7]), x, coeffs[3]); + f32x4_t x2 = vmulq(x, x); + f32x4_t x4 = vmulq(x2, x2); + f32x4_t res = vfmaq(vfmaq_f32(A, B, x2), vfmaq_f32(C, D, x2), x4); + + return res; +} + +__STATIC_INLINE f32x4_t vmant_exp_f32( + f32x4_t x, + int32x4_t * e) +{ + any32x4_t r; + int32x4_t n; + + r.f = x; + n = r.i >> 23; + n = n - 127; + r.i = r.i - (n << 23); + + *e = n; + return r.f; +} + + +__STATIC_INLINE f32x4_t vlogq_f32(f32x4_t vecIn) +{ + q31x4_t vecExpUnBiased; + f32x4_t vecTmpFlt0, vecTmpFlt1; + f32x4_t vecAcc0, vecAcc1, vecAcc2, vecAcc3; + f32x4_t vecExpUnBiasedFlt; + + /* + * extract exponent + */ + vecTmpFlt1 = vmant_exp_f32(vecIn, &vecExpUnBiased); + + vecTmpFlt0 = vecTmpFlt1 * vecTmpFlt1; + /* + * a = (__logf_lut_f32[4] * r.f) + (__logf_lut_f32[0]); + */ + vecAcc0 = vdupq_n_f32(__logf_lut_f32[0]); + vecAcc0 = vfmaq(vecAcc0, vecTmpFlt1, __logf_lut_f32[4]); + /* + * b = (__logf_lut_f32[6] * r.f) + (__logf_lut_f32[2]); + */ + vecAcc1 = vdupq_n_f32(__logf_lut_f32[2]); + vecAcc1 = vfmaq(vecAcc1, vecTmpFlt1, __logf_lut_f32[6]); + /* + * c = (__logf_lut_f32[5] * r.f) + (__logf_lut_f32[1]); + */ + vecAcc2 = vdupq_n_f32(__logf_lut_f32[1]); + vecAcc2 = vfmaq(vecAcc2, vecTmpFlt1, __logf_lut_f32[5]); + /* + * d = (__logf_lut_f32[7] * r.f) + (__logf_lut_f32[3]); + */ + vecAcc3 = vdupq_n_f32(__logf_lut_f32[3]); + vecAcc3 = vfmaq(vecAcc3, vecTmpFlt1, __logf_lut_f32[7]); + /* + * a = a + b * xx; + */ + vecAcc0 = vfmaq(vecAcc0, vecAcc1, vecTmpFlt0); + /* + * c = c + d * xx; + */ + vecAcc2 = vfmaq(vecAcc2, vecAcc3, vecTmpFlt0); + /* + * xx = xx * xx; + */ + vecTmpFlt0 = vecTmpFlt0 * vecTmpFlt0; + vecExpUnBiasedFlt = vcvtq_f32_s32(vecExpUnBiased); + /* + * r.f = a + c * xx; + */ + vecAcc0 = vfmaq(vecAcc0, vecAcc2, vecTmpFlt0); + /* + * add exponent + * r.f = r.f + ((float32_t) m) * __logf_rng_f32; + */ + vecAcc0 = vfmaq(vecAcc0, vecExpUnBiasedFlt, __logf_rng_f32); + // set log0 down to -inf + vecAcc0 = vdupq_m(vecAcc0, -INFINITY, vcmpeqq(vecIn, 0.0f)); + return vecAcc0; +} + +__STATIC_INLINE f32x4_t vexpq_f32( + f32x4_t x) +{ + // Perform range reduction [-log(2),log(2)] + int32x4_t m = vcvtq_s32_f32(vmulq_n_f32(x, 1.4426950408f)); + f32x4_t val = vfmsq_f32(x, vcvtq_f32_s32(m), vdupq_n_f32(0.6931471805f)); + + // Polynomial Approximation + f32x4_t poly = vtaylor_polyq_f32(val, exp_tab); + + // Reconstruct + poly = (f32x4_t) (vqaddq_s32((q31x4_t) (poly), vqshlq_n_s32(m, 23))); + + poly = vdupq_m(poly, 0.0f, vcmpltq_n_s32(m, -126)); + return poly; +} + +__STATIC_INLINE f32x4_t arm_vec_exponent_f32(f32x4_t x, int32_t nb) +{ + f32x4_t r = x; + nb--; + while (nb > 0) { + r = vmulq(r, x); + nb--; + } + return (r); +} + +__STATIC_INLINE f32x4_t vrecip_f32(f32x4_t vecIn) +{ + f32x4_t vecSx, vecW, vecTmp; + any32x4_t v; + + vecSx = vabsq(vecIn); + + v.f = vecIn; + v.i = vsubq(vdupq_n_s32(INV_NEWTON_INIT_F32), v.i); + + vecW = vmulq(vecSx, v.f); + + // v.f = v.f * (8 + w * (-28 + w * (56 + w * (-70 + w *(56 + w * (-28 + w * (8 - w))))))); + vecTmp = vsubq(vdupq_n_f32(8.0f), vecW); + vecTmp = vfmasq(vecW, vecTmp, -28.0f); + vecTmp = vfmasq(vecW, vecTmp, 56.0f); + vecTmp = vfmasq(vecW, vecTmp, -70.0f); + vecTmp = vfmasq(vecW, vecTmp, 56.0f); + vecTmp = vfmasq(vecW, vecTmp, -28.0f); + vecTmp = vfmasq(vecW, vecTmp, 8.0f); + v.f = vmulq(v.f, vecTmp); + + v.f = vdupq_m(v.f, INFINITY, vcmpeqq(vecIn, 0.0f)); + /* + * restore sign + */ + v.f = vnegq_m(v.f, v.f, vcmpltq(vecIn, 0.0f)); + return v.f; +} + +__STATIC_INLINE f32x4_t vtanhq_f32( + f32x4_t val) +{ + f32x4_t x = + vminnmq_f32(vmaxnmq_f32(val, vdupq_n_f32(-10.f)), vdupq_n_f32(10.0f)); + f32x4_t exp2x = vexpq_f32(vmulq_n_f32(x, 2.f)); + f32x4_t num = vsubq_n_f32(exp2x, 1.f); + f32x4_t den = vaddq_n_f32(exp2x, 1.f); + f32x4_t tanh = vmulq_f32(num, vrecip_f32(den)); + return tanh; +} + +__STATIC_INLINE f32x4_t vpowq_f32( + f32x4_t val, + f32x4_t n) +{ + return vexpq_f32(vmulq_f32(n, vlogq_f32(val))); +} + +#endif /* (defined(ARM_MATH_MVEF) || defined(ARM_MATH_HELIUM)) && !defined(ARM_MATH_AUTOVECTORIZE)*/ + +#if (defined(ARM_MATH_MVEI) || defined(ARM_MATH_HELIUM)) +#endif /* (defined(ARM_MATH_MVEI) || defined(ARM_MATH_HELIUM)) */ + +#if (defined(ARM_MATH_NEON) || defined(ARM_MATH_NEON_EXPERIMENTAL)) && !defined(ARM_MATH_AUTOVECTORIZE) + +#include "NEMath.h" +/** + * @brief Vectorized integer exponentiation + * @param[in] x value + * @param[in] nb integer exponent >= 1 + * @return x^nb + * + */ +__STATIC_INLINE float32x4_t arm_vec_exponent_f32(float32x4_t x, int32_t nb) +{ + float32x4_t r = x; + nb --; + while(nb > 0) + { + r = vmulq_f32(r , x); + nb--; + } + return(r); +} + + +__STATIC_INLINE float32x4_t __arm_vec_sqrt_f32_neon(float32x4_t x) +{ + float32x4_t x1 = vmaxq_f32(x, vdupq_n_f32(FLT_MIN)); + float32x4_t e = vrsqrteq_f32(x1); + e = vmulq_f32(vrsqrtsq_f32(vmulq_f32(x1, e), e), e); + e = vmulq_f32(vrsqrtsq_f32(vmulq_f32(x1, e), e), e); + return vmulq_f32(x, e); +} + +__STATIC_INLINE int16x8_t __arm_vec_sqrt_q15_neon(int16x8_t vec) +{ + float32x4_t tempF; + int32x4_t tempHI,tempLO; + + tempLO = vmovl_s16(vget_low_s16(vec)); + tempF = vcvtq_n_f32_s32(tempLO,15); + tempF = __arm_vec_sqrt_f32_neon(tempF); + tempLO = vcvtq_n_s32_f32(tempF,15); + + tempHI = vmovl_s16(vget_high_s16(vec)); + tempF = vcvtq_n_f32_s32(tempHI,15); + tempF = __arm_vec_sqrt_f32_neon(tempF); + tempHI = vcvtq_n_s32_f32(tempF,15); + + return(vcombine_s16(vqmovn_s32(tempLO),vqmovn_s32(tempHI))); +} + +__STATIC_INLINE int32x4_t __arm_vec_sqrt_q31_neon(int32x4_t vec) +{ + float32x4_t temp; + + temp = vcvtq_n_f32_s32(vec,31); + temp = __arm_vec_sqrt_f32_neon(temp); + return(vcvtq_n_s32_f32(temp,31)); +} + +#endif /* (defined(ARM_MATH_NEON) || defined(ARM_MATH_NEON_EXPERIMENTAL)) && !defined(ARM_MATH_AUTOVECTORIZE) */ + +#ifdef __cplusplus +} +#endif + + +#endif /* _ARM_VEC_MATH_H */ + +/** + * + * End of file. + */ diff --git a/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_armcc.h b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_armcc.h new file mode 100644 index 0000000000..fe49915d96 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_armcc.h @@ -0,0 +1,885 @@ +/****************************************************************************** + * @file cmsis_armcc.h + * @brief CMSIS compiler ARMCC (Arm Compiler 5) header file + * @version V5.2.1 + * @date 26. March 2020 + ******************************************************************************/ +/* + * Copyright (c) 2009-2020 Arm Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * 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 + * + * www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an AS IS BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef __CMSIS_ARMCC_H +#define __CMSIS_ARMCC_H + + +#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 400677) + #error "Please use Arm Compiler Toolchain V4.0.677 or later!" +#endif + +/* CMSIS compiler control architecture macros */ +#if ((defined (__TARGET_ARCH_6_M ) && (__TARGET_ARCH_6_M == 1)) || \ + (defined (__TARGET_ARCH_6S_M ) && (__TARGET_ARCH_6S_M == 1)) ) + #define __ARM_ARCH_6M__ 1 +#endif + +#if (defined (__TARGET_ARCH_7_M ) && (__TARGET_ARCH_7_M == 1)) + #define __ARM_ARCH_7M__ 1 +#endif + +#if (defined (__TARGET_ARCH_7E_M) && (__TARGET_ARCH_7E_M == 1)) + #define __ARM_ARCH_7EM__ 1 +#endif + + /* __ARM_ARCH_8M_BASE__ not applicable */ + /* __ARM_ARCH_8M_MAIN__ not applicable */ + /* __ARM_ARCH_8_1M_MAIN__ not applicable */ + +/* CMSIS compiler control DSP macros */ +#if ((defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) + #define __ARM_FEATURE_DSP 1 +#endif + +/* CMSIS compiler specific defines */ +#ifndef __ASM + #define __ASM __asm +#endif +#ifndef __INLINE + #define __INLINE __inline +#endif +#ifndef __STATIC_INLINE + #define __STATIC_INLINE static __inline +#endif +#ifndef __STATIC_FORCEINLINE + #define __STATIC_FORCEINLINE static __forceinline +#endif +#ifndef __NO_RETURN + #define __NO_RETURN __declspec(noreturn) +#endif +#ifndef __USED + #define __USED __attribute__((used)) +#endif +#ifndef __WEAK + #define __WEAK __attribute__((weak)) +#endif +#ifndef __PACKED + #define __PACKED __attribute__((packed)) +#endif +#ifndef __PACKED_STRUCT + #define __PACKED_STRUCT __packed struct +#endif +#ifndef __PACKED_UNION + #define __PACKED_UNION __packed union +#endif +#ifndef __UNALIGNED_UINT32 /* deprecated */ + #define __UNALIGNED_UINT32(x) (*((__packed uint32_t *)(x))) +#endif +#ifndef __UNALIGNED_UINT16_WRITE + #define __UNALIGNED_UINT16_WRITE(addr, val) ((*((__packed uint16_t *)(addr))) = (val)) +#endif +#ifndef __UNALIGNED_UINT16_READ + #define __UNALIGNED_UINT16_READ(addr) (*((const __packed uint16_t *)(addr))) +#endif +#ifndef __UNALIGNED_UINT32_WRITE + #define __UNALIGNED_UINT32_WRITE(addr, val) ((*((__packed uint32_t *)(addr))) = (val)) +#endif +#ifndef __UNALIGNED_UINT32_READ + #define __UNALIGNED_UINT32_READ(addr) (*((const __packed uint32_t *)(addr))) +#endif +#ifndef __ALIGNED + #define __ALIGNED(x) __attribute__((aligned(x))) +#endif +#ifndef __RESTRICT + #define __RESTRICT __restrict +#endif +#ifndef __COMPILER_BARRIER + #define __COMPILER_BARRIER() __memory_changed() +#endif + +/* ######################### Startup and Lowlevel Init ######################## */ + +#ifndef __PROGRAM_START +#define __PROGRAM_START __main +#endif + +#ifndef __INITIAL_SP +#define __INITIAL_SP Image$$ARM_LIB_STACK$$ZI$$Limit +#endif + +#ifndef __STACK_LIMIT +#define __STACK_LIMIT Image$$ARM_LIB_STACK$$ZI$$Base +#endif + +#ifndef __VECTOR_TABLE +#define __VECTOR_TABLE __Vectors +#endif + +#ifndef __VECTOR_TABLE_ATTRIBUTE +#define __VECTOR_TABLE_ATTRIBUTE __attribute__((used, section("RESET"))) +#endif + +/* ########################### Core Function Access ########################### */ +/** \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions + @{ + */ + +/** + \brief Enable IRQ Interrupts + \details Enables IRQ interrupts by clearing the I-bit in the CPSR. + Can only be executed in Privileged modes. + */ +/* intrinsic void __enable_irq(); */ + + +/** + \brief Disable IRQ Interrupts + \details Disables IRQ interrupts by setting the I-bit in the CPSR. + Can only be executed in Privileged modes. + */ +/* intrinsic void __disable_irq(); */ + +/** + \brief Get Control Register + \details 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 + \details 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 + \details 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 + \details 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 + \details 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 + \details 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 + \details 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 + \details 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 + \details 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 + \details 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 + \details 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 ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) + +/** + \brief Enable FIQ + \details 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 + \details 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 + \details 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 + \details 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 & 0xFFU); +} + + +/** + \brief Set Base Priority with condition + \details Assigns the given value to the Base Priority register only if BASEPRI masking is disabled, + or the new value increases the BASEPRI priority level. + \param [in] basePri Base Priority value to set + */ +__STATIC_INLINE void __set_BASEPRI_MAX(uint32_t basePri) +{ + register uint32_t __regBasePriMax __ASM("basepri_max"); + __regBasePriMax = (basePri & 0xFFU); +} + + +/** + \brief Get Fault Mask + \details 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 + \details 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)1U); +} + +#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) */ + + +/** + \brief Get FPSCR + \details 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 ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ + (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) + register uint32_t __regfpscr __ASM("fpscr"); + return(__regfpscr); +#else + return(0U); +#endif +} + + +/** + \brief Set FPSCR + \details 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 ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ + (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) + register uint32_t __regfpscr __ASM("fpscr"); + __regfpscr = (fpscr); +#else + (void)fpscr; +#endif +} + + +/*@} end of CMSIS_Core_RegAccFunctions */ + + +/* ########################## Core Instruction Access ######################### */ +/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface + Access to dedicated instructions + @{ +*/ + +/** + \brief No Operation + \details No Operation does nothing. This instruction can be used for code alignment purposes. + */ +#define __NOP __nop + + +/** + \brief Wait For Interrupt + \details 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 + \details 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 + \details Send Event is a hint instruction. It causes an event to be signaled to the CPU. + */ +#define __SEV __sev + + +/** + \brief Instruction Synchronization Barrier + \details 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 + \details 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 + \details 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) + \details Reverses the byte order in unsigned integer value. For example, 0x12345678 becomes 0x78563412. + \param [in] value Value to reverse + \return Reversed value + */ +#define __REV __rev + + +/** + \brief Reverse byte order (16 bit) + \details Reverses the byte order within each halfword of a word. For example, 0x12345678 becomes 0x34127856. + \param [in] value Value to reverse + \return Reversed value + */ +#ifndef __NO_EMBEDDED_ASM +__attribute__((section(".rev16_text"))) __STATIC_INLINE __ASM uint32_t __REV16(uint32_t value) +{ + rev16 r0, r0 + bx lr +} +#endif + + +/** + \brief Reverse byte order (16 bit) + \details Reverses the byte order in a 16-bit value and returns the signed 16-bit result. For example, 0x0080 becomes 0x8000. + \param [in] value Value to reverse + \return Reversed value + */ +#ifndef __NO_EMBEDDED_ASM +__attribute__((section(".revsh_text"))) __STATIC_INLINE __ASM int16_t __REVSH(int16_t value) +{ + revsh r0, r0 + bx lr +} +#endif + + +/** + \brief Rotate Right in unsigned value (32 bit) + \details Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits. + \param [in] op1 Value to rotate + \param [in] op2 Number of Bits to rotate + \return Rotated value + */ +#define __ROR __ror + + +/** + \brief Breakpoint + \details Causes the processor to enter Debug state. + Debug tools can use this to investigate system state when the instruction at a particular address is reached. + \param [in] value is ignored by the processor. + If required, a debugger can use it to store additional information about the breakpoint. + */ +#define __BKPT(value) __breakpoint(value) + + +/** + \brief Reverse bit order of value + \details Reverses the bit order of the given value. + \param [in] value Value to reverse + \return Reversed value + */ +#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) + #define __RBIT __rbit +#else +__attribute__((always_inline)) __STATIC_INLINE uint32_t __RBIT(uint32_t value) +{ + uint32_t result; + uint32_t s = (4U /*sizeof(v)*/ * 8U) - 1U; /* extra shift needed at end */ + + result = value; /* r will be reversed bits of v; first get LSB of v */ + for (value >>= 1U; value != 0U; value >>= 1U) + { + result <<= 1U; + result |= value & 1U; + s--; + } + result <<= s; /* shift when v's highest bits are zero */ + return result; +} +#endif + + +/** + \brief Count leading zeros + \details 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 + + +#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) + +/** + \brief LDR Exclusive (8 bit) + \details Executes a exclusive LDR instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020) + #define __LDREXB(ptr) ((uint8_t ) __ldrex(ptr)) +#else + #define __LDREXB(ptr) _Pragma("push") _Pragma("diag_suppress 3731") ((uint8_t ) __ldrex(ptr)) _Pragma("pop") +#endif + + +/** + \brief LDR Exclusive (16 bit) + \details Executes a exclusive LDR instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020) + #define __LDREXH(ptr) ((uint16_t) __ldrex(ptr)) +#else + #define __LDREXH(ptr) _Pragma("push") _Pragma("diag_suppress 3731") ((uint16_t) __ldrex(ptr)) _Pragma("pop") +#endif + + +/** + \brief LDR Exclusive (32 bit) + \details Executes a exclusive LDR instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020) + #define __LDREXW(ptr) ((uint32_t ) __ldrex(ptr)) +#else + #define __LDREXW(ptr) _Pragma("push") _Pragma("diag_suppress 3731") ((uint32_t ) __ldrex(ptr)) _Pragma("pop") +#endif + + +/** + \brief STR Exclusive (8 bit) + \details Executes a exclusive STR instruction for 8 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020) + #define __STREXB(value, ptr) __strex(value, ptr) +#else + #define __STREXB(value, ptr) _Pragma("push") _Pragma("diag_suppress 3731") __strex(value, ptr) _Pragma("pop") +#endif + + +/** + \brief STR Exclusive (16 bit) + \details Executes a exclusive STR instruction for 16 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020) + #define __STREXH(value, ptr) __strex(value, ptr) +#else + #define __STREXH(value, ptr) _Pragma("push") _Pragma("diag_suppress 3731") __strex(value, ptr) _Pragma("pop") +#endif + + +/** + \brief STR Exclusive (32 bit) + \details Executes a exclusive STR instruction for 32 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020) + #define __STREXW(value, ptr) __strex(value, ptr) +#else + #define __STREXW(value, ptr) _Pragma("push") _Pragma("diag_suppress 3731") __strex(value, ptr) _Pragma("pop") +#endif + + +/** + \brief Remove the exclusive lock + \details Removes the exclusive lock which is created by LDREX. + */ +#define __CLREX __clrex + + +/** + \brief Signed Saturate + \details 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 + \details 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 Rotate Right with Extend (32 bit) + \details Moves each bit of a bitstring right by one bit. + The carry input is shifted in at the left end of the bitstring. + \param [in] value Value to rotate + \return Rotated value + */ +#ifndef __NO_EMBEDDED_ASM +__attribute__((section(".rrx_text"))) __STATIC_INLINE __ASM uint32_t __RRX(uint32_t value) +{ + rrx r0, r0 + bx lr +} +#endif + + +/** + \brief LDRT Unprivileged (8 bit) + \details Executes a Unprivileged LDRT instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +#define __LDRBT(ptr) ((uint8_t ) __ldrt(ptr)) + + +/** + \brief LDRT Unprivileged (16 bit) + \details Executes a Unprivileged LDRT instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +#define __LDRHT(ptr) ((uint16_t) __ldrt(ptr)) + + +/** + \brief LDRT Unprivileged (32 bit) + \details Executes a Unprivileged LDRT instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +#define __LDRT(ptr) ((uint32_t ) __ldrt(ptr)) + + +/** + \brief STRT Unprivileged (8 bit) + \details Executes a Unprivileged STRT instruction for 8 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +#define __STRBT(value, ptr) __strt(value, ptr) + + +/** + \brief STRT Unprivileged (16 bit) + \details Executes a Unprivileged STRT instruction for 16 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +#define __STRHT(value, ptr) __strt(value, ptr) + + +/** + \brief STRT Unprivileged (32 bit) + \details Executes a Unprivileged STRT instruction for 32 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +#define __STRT(value, ptr) __strt(value, ptr) + +#else /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) */ + +/** + \brief Signed Saturate + \details Saturates a signed value. + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (1..32) + \return Saturated value + */ +__attribute__((always_inline)) __STATIC_INLINE int32_t __SSAT(int32_t val, uint32_t sat) +{ + if ((sat >= 1U) && (sat <= 32U)) + { + const int32_t max = (int32_t)((1U << (sat - 1U)) - 1U); + const int32_t min = -1 - max ; + if (val > max) + { + return max; + } + else if (val < min) + { + return min; + } + } + return val; +} + +/** + \brief Unsigned Saturate + \details Saturates an unsigned value. + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (0..31) + \return Saturated value + */ +__attribute__((always_inline)) __STATIC_INLINE uint32_t __USAT(int32_t val, uint32_t sat) +{ + if (sat <= 31U) + { + const uint32_t max = ((1U << sat) - 1U); + if (val > (int32_t)max) + { + return max; + } + else if (val < 0) + { + return 0U; + } + } + return (uint32_t)val; +} + +#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) */ + +/*@}*/ /* end of group CMSIS_Core_InstructionInterface */ + + +/* ################### Compiler specific Intrinsics ########################### */ +/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics + Access to dedicated SIMD instructions + @{ +*/ + +#if ((defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) + +#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) ) + +#define __SMMLA(ARG1,ARG2,ARG3) ( (int32_t)((((int64_t)(ARG1) * (ARG2)) + \ + ((int64_t)(ARG3) << 32U) ) >> 32U)) + +#define __SXTB16_RORn(ARG1, ARG2) __SXTB16(__ROR(ARG1, ARG2)) + +#endif /* ((defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) */ +/*@} end of group CMSIS_SIMD_intrinsics */ + + +#endif /* __CMSIS_ARMCC_H */ diff --git a/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_armclang.h b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_armclang.h new file mode 100644 index 0000000000..a8c22afe26 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_armclang.h @@ -0,0 +1,1467 @@ +/****************************************************************************** + * @file cmsis_armclang.h + * @brief CMSIS compiler armclang (Arm Compiler 6) header file + * @version V5.3.1 + * @date 26. March 2020 + ******************************************************************************/ +/* + * Copyright (c) 2009-2020 Arm Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * 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 + * + * 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. + */ + +/*lint -esym(9058, IRQn)*/ /* disable MISRA 2012 Rule 2.4 for IRQn */ + +#ifndef __CMSIS_ARMCLANG_H +#define __CMSIS_ARMCLANG_H + +#pragma clang system_header /* treat file as system include file */ + +#ifndef __ARM_COMPAT_H +#include /* Compatibility header for Arm Compiler 5 intrinsics */ +#endif + +/* CMSIS compiler specific defines */ +#ifndef __ASM + #define __ASM __asm +#endif +#ifndef __INLINE + #define __INLINE __inline +#endif +#ifndef __STATIC_INLINE + #define __STATIC_INLINE static __inline +#endif +#ifndef __STATIC_FORCEINLINE + #define __STATIC_FORCEINLINE __attribute__((always_inline)) static __inline +#endif +#ifndef __NO_RETURN + #define __NO_RETURN __attribute__((__noreturn__)) +#endif +#ifndef __USED + #define __USED __attribute__((used)) +#endif +#ifndef __WEAK + #define __WEAK __attribute__((weak)) +#endif +#ifndef __PACKED + #define __PACKED __attribute__((packed, aligned(1))) +#endif +#ifndef __PACKED_STRUCT + #define __PACKED_STRUCT struct __attribute__((packed, aligned(1))) +#endif +#ifndef __PACKED_UNION + #define __PACKED_UNION union __attribute__((packed, aligned(1))) +#endif +#ifndef __UNALIGNED_UINT32 /* deprecated */ + #pragma clang diagnostic push + #pragma clang diagnostic ignored "-Wpacked" +/*lint -esym(9058, T_UINT32)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT32 */ + struct __attribute__((packed)) T_UINT32 { uint32_t v; }; + #pragma clang diagnostic pop + #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) +#endif +#ifndef __UNALIGNED_UINT16_WRITE + #pragma clang diagnostic push + #pragma clang diagnostic ignored "-Wpacked" +/*lint -esym(9058, T_UINT16_WRITE)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT16_WRITE */ + __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; + #pragma clang diagnostic pop + #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) +#endif +#ifndef __UNALIGNED_UINT16_READ + #pragma clang diagnostic push + #pragma clang diagnostic ignored "-Wpacked" +/*lint -esym(9058, T_UINT16_READ)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT16_READ */ + __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; + #pragma clang diagnostic pop + #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) +#endif +#ifndef __UNALIGNED_UINT32_WRITE + #pragma clang diagnostic push + #pragma clang diagnostic ignored "-Wpacked" +/*lint -esym(9058, T_UINT32_WRITE)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT32_WRITE */ + __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; + #pragma clang diagnostic pop + #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) +#endif +#ifndef __UNALIGNED_UINT32_READ + #pragma clang diagnostic push + #pragma clang diagnostic ignored "-Wpacked" +/*lint -esym(9058, T_UINT32_READ)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT32_READ */ + __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; + #pragma clang diagnostic pop + #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) +#endif +#ifndef __ALIGNED + #define __ALIGNED(x) __attribute__((aligned(x))) +#endif +#ifndef __RESTRICT + #define __RESTRICT __restrict +#endif +#ifndef __COMPILER_BARRIER + #define __COMPILER_BARRIER() __ASM volatile("":::"memory") +#endif + +/* ######################### Startup and Lowlevel Init ######################## */ + +#ifndef __PROGRAM_START +#define __PROGRAM_START __main +#endif + +#ifndef __INITIAL_SP +#define __INITIAL_SP Image$$ARM_LIB_STACK$$ZI$$Limit +#endif + +#ifndef __STACK_LIMIT +#define __STACK_LIMIT Image$$ARM_LIB_STACK$$ZI$$Base +#endif + +#ifndef __VECTOR_TABLE +#define __VECTOR_TABLE __Vectors +#endif + +#ifndef __VECTOR_TABLE_ATTRIBUTE +#define __VECTOR_TABLE_ATTRIBUTE __attribute__((used, section("RESET"))) +#endif + +/* ########################### Core Function Access ########################### */ +/** \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions + @{ + */ + +/** + \brief Enable IRQ Interrupts + \details Enables IRQ interrupts by clearing the I-bit in the CPSR. + Can only be executed in Privileged modes. + */ +/* intrinsic void __enable_irq(); see arm_compat.h */ + + +/** + \brief Disable IRQ Interrupts + \details Disables IRQ interrupts by setting the I-bit in the CPSR. + Can only be executed in Privileged modes. + */ +/* intrinsic void __disable_irq(); see arm_compat.h */ + + +/** + \brief Get Control Register + \details Returns the content of the Control Register. + \return Control Register value + */ +__STATIC_FORCEINLINE uint32_t __get_CONTROL(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, control" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Control Register (non-secure) + \details Returns the content of the non-secure Control Register when in secure mode. + \return non-secure Control Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_CONTROL_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, control_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Control Register + \details Writes the given value to the Control Register. + \param [in] control Control Register value to set + */ +__STATIC_FORCEINLINE void __set_CONTROL(uint32_t control) +{ + __ASM volatile ("MSR control, %0" : : "r" (control) : "memory"); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Control Register (non-secure) + \details Writes the given value to the non-secure Control Register when in secure state. + \param [in] control Control Register value to set + */ +__STATIC_FORCEINLINE void __TZ_set_CONTROL_NS(uint32_t control) +{ + __ASM volatile ("MSR control_ns, %0" : : "r" (control) : "memory"); +} +#endif + + +/** + \brief Get IPSR Register + \details Returns the content of the IPSR Register. + \return IPSR Register value + */ +__STATIC_FORCEINLINE uint32_t __get_IPSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, ipsr" : "=r" (result) ); + return(result); +} + + +/** + \brief Get APSR Register + \details Returns the content of the APSR Register. + \return APSR Register value + */ +__STATIC_FORCEINLINE uint32_t __get_APSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, apsr" : "=r" (result) ); + return(result); +} + + +/** + \brief Get xPSR Register + \details Returns the content of the xPSR Register. + \return xPSR Register value + */ +__STATIC_FORCEINLINE uint32_t __get_xPSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, xpsr" : "=r" (result) ); + return(result); +} + + +/** + \brief Get Process Stack Pointer + \details Returns the current value of the Process Stack Pointer (PSP). + \return PSP Register value + */ +__STATIC_FORCEINLINE uint32_t __get_PSP(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, psp" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Process Stack Pointer (non-secure) + \details Returns the current value of the non-secure Process Stack Pointer (PSP) when in secure state. + \return PSP Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_PSP_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, psp_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Process Stack Pointer + \details Assigns the given value to the Process Stack Pointer (PSP). + \param [in] topOfProcStack Process Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __set_PSP(uint32_t topOfProcStack) +{ + __ASM volatile ("MSR psp, %0" : : "r" (topOfProcStack) : ); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Process Stack Pointer (non-secure) + \details Assigns the given value to the non-secure Process Stack Pointer (PSP) when in secure state. + \param [in] topOfProcStack Process Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __TZ_set_PSP_NS(uint32_t topOfProcStack) +{ + __ASM volatile ("MSR psp_ns, %0" : : "r" (topOfProcStack) : ); +} +#endif + + +/** + \brief Get Main Stack Pointer + \details Returns the current value of the Main Stack Pointer (MSP). + \return MSP Register value + */ +__STATIC_FORCEINLINE uint32_t __get_MSP(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, msp" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Main Stack Pointer (non-secure) + \details Returns the current value of the non-secure Main Stack Pointer (MSP) when in secure state. + \return MSP Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_MSP_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, msp_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Main Stack Pointer + \details Assigns the given value to the Main Stack Pointer (MSP). + \param [in] topOfMainStack Main Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __set_MSP(uint32_t topOfMainStack) +{ + __ASM volatile ("MSR msp, %0" : : "r" (topOfMainStack) : ); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Main Stack Pointer (non-secure) + \details Assigns the given value to the non-secure Main Stack Pointer (MSP) when in secure state. + \param [in] topOfMainStack Main Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __TZ_set_MSP_NS(uint32_t topOfMainStack) +{ + __ASM volatile ("MSR msp_ns, %0" : : "r" (topOfMainStack) : ); +} +#endif + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Stack Pointer (non-secure) + \details Returns the current value of the non-secure Stack Pointer (SP) when in secure state. + \return SP Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_SP_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, sp_ns" : "=r" (result) ); + return(result); +} + + +/** + \brief Set Stack Pointer (non-secure) + \details Assigns the given value to the non-secure Stack Pointer (SP) when in secure state. + \param [in] topOfStack Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __TZ_set_SP_NS(uint32_t topOfStack) +{ + __ASM volatile ("MSR sp_ns, %0" : : "r" (topOfStack) : ); +} +#endif + + +/** + \brief Get Priority Mask + \details Returns the current state of the priority mask bit from the Priority Mask Register. + \return Priority Mask value + */ +__STATIC_FORCEINLINE uint32_t __get_PRIMASK(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, primask" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Priority Mask (non-secure) + \details Returns the current state of the non-secure priority mask bit from the Priority Mask Register when in secure state. + \return Priority Mask value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_PRIMASK_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, primask_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Priority Mask + \details Assigns the given value to the Priority Mask Register. + \param [in] priMask Priority Mask + */ +__STATIC_FORCEINLINE void __set_PRIMASK(uint32_t priMask) +{ + __ASM volatile ("MSR primask, %0" : : "r" (priMask) : "memory"); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Priority Mask (non-secure) + \details Assigns the given value to the non-secure Priority Mask Register when in secure state. + \param [in] priMask Priority Mask + */ +__STATIC_FORCEINLINE void __TZ_set_PRIMASK_NS(uint32_t priMask) +{ + __ASM volatile ("MSR primask_ns, %0" : : "r" (priMask) : "memory"); +} +#endif + + +#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8_1M_MAIN__) && (__ARM_ARCH_8_1M_MAIN__ == 1)) ) +/** + \brief Enable FIQ + \details Enables FIQ interrupts by clearing the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +#define __enable_fault_irq __enable_fiq /* see arm_compat.h */ + + +/** + \brief Disable FIQ + \details Disables FIQ interrupts by setting the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +#define __disable_fault_irq __disable_fiq /* see arm_compat.h */ + + +/** + \brief Get Base Priority + \details Returns the current value of the Base Priority register. + \return Base Priority register value + */ +__STATIC_FORCEINLINE uint32_t __get_BASEPRI(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, basepri" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Base Priority (non-secure) + \details Returns the current value of the non-secure Base Priority register when in secure state. + \return Base Priority register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_BASEPRI_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, basepri_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Base Priority + \details Assigns the given value to the Base Priority register. + \param [in] basePri Base Priority value to set + */ +__STATIC_FORCEINLINE void __set_BASEPRI(uint32_t basePri) +{ + __ASM volatile ("MSR basepri, %0" : : "r" (basePri) : "memory"); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Base Priority (non-secure) + \details Assigns the given value to the non-secure Base Priority register when in secure state. + \param [in] basePri Base Priority value to set + */ +__STATIC_FORCEINLINE void __TZ_set_BASEPRI_NS(uint32_t basePri) +{ + __ASM volatile ("MSR basepri_ns, %0" : : "r" (basePri) : "memory"); +} +#endif + + +/** + \brief Set Base Priority with condition + \details Assigns the given value to the Base Priority register only if BASEPRI masking is disabled, + or the new value increases the BASEPRI priority level. + \param [in] basePri Base Priority value to set + */ +__STATIC_FORCEINLINE void __set_BASEPRI_MAX(uint32_t basePri) +{ + __ASM volatile ("MSR basepri_max, %0" : : "r" (basePri) : "memory"); +} + + +/** + \brief Get Fault Mask + \details Returns the current value of the Fault Mask register. + \return Fault Mask register value + */ +__STATIC_FORCEINLINE uint32_t __get_FAULTMASK(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, faultmask" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Fault Mask (non-secure) + \details Returns the current value of the non-secure Fault Mask register when in secure state. + \return Fault Mask register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_FAULTMASK_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, faultmask_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Fault Mask + \details Assigns the given value to the Fault Mask register. + \param [in] faultMask Fault Mask value to set + */ +__STATIC_FORCEINLINE void __set_FAULTMASK(uint32_t faultMask) +{ + __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) : "memory"); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Fault Mask (non-secure) + \details Assigns the given value to the non-secure Fault Mask register when in secure state. + \param [in] faultMask Fault Mask value to set + */ +__STATIC_FORCEINLINE void __TZ_set_FAULTMASK_NS(uint32_t faultMask) +{ + __ASM volatile ("MSR faultmask_ns, %0" : : "r" (faultMask) : "memory"); +} +#endif + +#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8_1M_MAIN__) && (__ARM_ARCH_8_1M_MAIN__ == 1)) ) */ + + +#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) || \ + (defined (__ARM_ARCH_8_1M_MAIN__) && (__ARM_ARCH_8_1M_MAIN__ == 1)) ) + +/** + \brief Get Process Stack Pointer Limit + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence zero is returned always in non-secure + mode. + + \details Returns the current value of the Process Stack Pointer Limit (PSPLIM). + \return PSPLIM Register value + */ +__STATIC_FORCEINLINE uint32_t __get_PSPLIM(void) +{ +#if (!((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8_1M_MAIN__ ) && (__ARM_ARCH_8_1M_MAIN__ == 1)) ) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + return 0U; +#else + uint32_t result; + __ASM volatile ("MRS %0, psplim" : "=r" (result) ); + return result; +#endif +} + +#if (defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Process Stack Pointer Limit (non-secure) + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence zero is returned always in non-secure + mode. + + \details Returns the current value of the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. + \return PSPLIM Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_PSPLIM_NS(void) +{ +#if (!((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8_1M_MAIN__ ) && (__ARM_ARCH_8_1M_MAIN__ == 1)) ) ) + // without main extensions, the non-secure PSPLIM is RAZ/WI + return 0U; +#else + uint32_t result; + __ASM volatile ("MRS %0, psplim_ns" : "=r" (result) ); + return result; +#endif +} +#endif + + +/** + \brief Set Process Stack Pointer Limit + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence the write is silently ignored in non-secure + mode. + + \details Assigns the given value to the Process Stack Pointer Limit (PSPLIM). + \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set + */ +__STATIC_FORCEINLINE void __set_PSPLIM(uint32_t ProcStackPtrLimit) +{ +#if (!((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8_1M_MAIN__ ) && (__ARM_ARCH_8_1M_MAIN__ == 1)) ) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + (void)ProcStackPtrLimit; +#else + __ASM volatile ("MSR psplim, %0" : : "r" (ProcStackPtrLimit)); +#endif +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Process Stack Pointer (non-secure) + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence the write is silently ignored in non-secure + mode. + + \details Assigns the given value to the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. + \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set + */ +__STATIC_FORCEINLINE void __TZ_set_PSPLIM_NS(uint32_t ProcStackPtrLimit) +{ +#if (!((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8_1M_MAIN__ ) && (__ARM_ARCH_8_1M_MAIN__ == 1)) ) ) + // without main extensions, the non-secure PSPLIM is RAZ/WI + (void)ProcStackPtrLimit; +#else + __ASM volatile ("MSR psplim_ns, %0\n" : : "r" (ProcStackPtrLimit)); +#endif +} +#endif + + +/** + \brief Get Main Stack Pointer Limit + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence zero is returned always. + + \details Returns the current value of the Main Stack Pointer Limit (MSPLIM). + \return MSPLIM Register value + */ +__STATIC_FORCEINLINE uint32_t __get_MSPLIM(void) +{ +#if (!((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8_1M_MAIN__ ) && (__ARM_ARCH_8_1M_MAIN__ == 1)) ) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + return 0U; +#else + uint32_t result; + __ASM volatile ("MRS %0, msplim" : "=r" (result) ); + return result; +#endif +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Main Stack Pointer Limit (non-secure) + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence zero is returned always. + + \details Returns the current value of the non-secure Main Stack Pointer Limit(MSPLIM) when in secure state. + \return MSPLIM Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_MSPLIM_NS(void) +{ +#if (!((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8_1M_MAIN__ ) && (__ARM_ARCH_8_1M_MAIN__ == 1)) ) ) + // without main extensions, the non-secure MSPLIM is RAZ/WI + return 0U; +#else + uint32_t result; + __ASM volatile ("MRS %0, msplim_ns" : "=r" (result) ); + return result; +#endif +} +#endif + + +/** + \brief Set Main Stack Pointer Limit + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence the write is silently ignored. + + \details Assigns the given value to the Main Stack Pointer Limit (MSPLIM). + \param [in] MainStackPtrLimit Main Stack Pointer Limit value to set + */ +__STATIC_FORCEINLINE void __set_MSPLIM(uint32_t MainStackPtrLimit) +{ +#if (!((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8_1M_MAIN__ ) && (__ARM_ARCH_8_1M_MAIN__ == 1)) ) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + (void)MainStackPtrLimit; +#else + __ASM volatile ("MSR msplim, %0" : : "r" (MainStackPtrLimit)); +#endif +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Main Stack Pointer Limit (non-secure) + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence the write is silently ignored. + + \details Assigns the given value to the non-secure Main Stack Pointer Limit (MSPLIM) when in secure state. + \param [in] MainStackPtrLimit Main Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __TZ_set_MSPLIM_NS(uint32_t MainStackPtrLimit) +{ +#if (!((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8_1M_MAIN__ ) && (__ARM_ARCH_8_1M_MAIN__ == 1)) ) ) + // without main extensions, the non-secure MSPLIM is RAZ/WI + (void)MainStackPtrLimit; +#else + __ASM volatile ("MSR msplim_ns, %0" : : "r" (MainStackPtrLimit)); +#endif +} +#endif + +#endif /* ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) || \ + (defined (__ARM_ARCH_8_1M_MAIN__) && (__ARM_ARCH_8_1M_MAIN__ == 1)) ) */ + +/** + \brief Get FPSCR + \details Returns the current value of the Floating Point Status/Control register. + \return Floating Point Status/Control register value + */ +#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ + (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) +#define __get_FPSCR (uint32_t)__builtin_arm_get_fpscr +#else +#define __get_FPSCR() ((uint32_t)0U) +#endif + +/** + \brief Set FPSCR + \details Assigns the given value to the Floating Point Status/Control register. + \param [in] fpscr Floating Point Status/Control value to set + */ +#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ + (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) +#define __set_FPSCR __builtin_arm_set_fpscr +#else +#define __set_FPSCR(x) ((void)(x)) +#endif + + +/*@} end of CMSIS_Core_RegAccFunctions */ + + +/* ########################## Core Instruction Access ######################### */ +/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface + Access to dedicated instructions + @{ +*/ + +/* Define macros for porting to both thumb1 and thumb2. + * For thumb1, use low register (r0-r7), specified by constraint "l" + * Otherwise, use general registers, specified by constraint "r" */ +#if defined (__thumb__) && !defined (__thumb2__) +#define __CMSIS_GCC_OUT_REG(r) "=l" (r) +#define __CMSIS_GCC_RW_REG(r) "+l" (r) +#define __CMSIS_GCC_USE_REG(r) "l" (r) +#else +#define __CMSIS_GCC_OUT_REG(r) "=r" (r) +#define __CMSIS_GCC_RW_REG(r) "+r" (r) +#define __CMSIS_GCC_USE_REG(r) "r" (r) +#endif + +/** + \brief No Operation + \details No Operation does nothing. This instruction can be used for code alignment purposes. + */ +#define __NOP __builtin_arm_nop + +/** + \brief Wait For Interrupt + \details Wait For Interrupt is a hint instruction that suspends execution until one of a number of events occurs. + */ +#define __WFI __builtin_arm_wfi + + +/** + \brief Wait For Event + \details 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 __builtin_arm_wfe + + +/** + \brief Send Event + \details Send Event is a hint instruction. It causes an event to be signaled to the CPU. + */ +#define __SEV __builtin_arm_sev + + +/** + \brief Instruction Synchronization Barrier + \details 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() __builtin_arm_isb(0xF) + +/** + \brief Data Synchronization Barrier + \details Acts as a special kind of Data Memory Barrier. + It completes when all explicit memory accesses before this instruction complete. + */ +#define __DSB() __builtin_arm_dsb(0xF) + + +/** + \brief Data Memory Barrier + \details Ensures the apparent order of the explicit memory operations before + and after the instruction, without ensuring their completion. + */ +#define __DMB() __builtin_arm_dmb(0xF) + + +/** + \brief Reverse byte order (32 bit) + \details Reverses the byte order in unsigned integer value. For example, 0x12345678 becomes 0x78563412. + \param [in] value Value to reverse + \return Reversed value + */ +#define __REV(value) __builtin_bswap32(value) + + +/** + \brief Reverse byte order (16 bit) + \details Reverses the byte order within each halfword of a word. For example, 0x12345678 becomes 0x34127856. + \param [in] value Value to reverse + \return Reversed value + */ +#define __REV16(value) __ROR(__REV(value), 16) + + +/** + \brief Reverse byte order (16 bit) + \details Reverses the byte order in a 16-bit value and returns the signed 16-bit result. For example, 0x0080 becomes 0x8000. + \param [in] value Value to reverse + \return Reversed value + */ +#define __REVSH(value) (int16_t)__builtin_bswap16(value) + + +/** + \brief Rotate Right in unsigned value (32 bit) + \details Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits. + \param [in] op1 Value to rotate + \param [in] op2 Number of Bits to rotate + \return Rotated value + */ +__STATIC_FORCEINLINE uint32_t __ROR(uint32_t op1, uint32_t op2) +{ + op2 %= 32U; + if (op2 == 0U) + { + return op1; + } + return (op1 >> op2) | (op1 << (32U - op2)); +} + + +/** + \brief Breakpoint + \details Causes the processor to enter Debug state. + Debug tools can use this to investigate system state when the instruction at a particular address is reached. + \param [in] value is ignored by the processor. + If required, a debugger can use it to store additional information about the breakpoint. + */ +#define __BKPT(value) __ASM volatile ("bkpt "#value) + + +/** + \brief Reverse bit order of value + \details Reverses the bit order of the given value. + \param [in] value Value to reverse + \return Reversed value + */ +#define __RBIT __builtin_arm_rbit + +/** + \brief Count leading zeros + \details 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 + */ +__STATIC_FORCEINLINE uint8_t __CLZ(uint32_t value) +{ + /* Even though __builtin_clz produces a CLZ instruction on ARM, formally + __builtin_clz(0) is undefined behaviour, so handle this case specially. + This guarantees ARM-compatible results if happening to compile on a non-ARM + target, and ensures the compiler doesn't decide to activate any + optimisations using the logic "value was passed to __builtin_clz, so it + is non-zero". + ARM Compiler 6.10 and possibly earlier will optimise this test away, leaving a + single CLZ instruction. + */ + if (value == 0U) + { + return 32U; + } + return __builtin_clz(value); +} + + +#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) || \ + (defined (__ARM_ARCH_8_1M_MAIN__) && (__ARM_ARCH_8_1M_MAIN__ == 1)) ) + +/** + \brief LDR Exclusive (8 bit) + \details Executes a exclusive LDR instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +#define __LDREXB (uint8_t)__builtin_arm_ldrex + + +/** + \brief LDR Exclusive (16 bit) + \details Executes a exclusive LDR instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +#define __LDREXH (uint16_t)__builtin_arm_ldrex + + +/** + \brief LDR Exclusive (32 bit) + \details Executes a exclusive LDR instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +#define __LDREXW (uint32_t)__builtin_arm_ldrex + + +/** + \brief STR Exclusive (8 bit) + \details Executes a exclusive STR instruction 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 (uint32_t)__builtin_arm_strex + + +/** + \brief STR Exclusive (16 bit) + \details Executes a exclusive STR instruction 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 (uint32_t)__builtin_arm_strex + + +/** + \brief STR Exclusive (32 bit) + \details Executes a exclusive STR instruction 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 (uint32_t)__builtin_arm_strex + + +/** + \brief Remove the exclusive lock + \details Removes the exclusive lock which is created by LDREX. + */ +#define __CLREX __builtin_arm_clrex + +#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) || \ + (defined (__ARM_ARCH_8_1M_MAIN__) && (__ARM_ARCH_8_1M_MAIN__ == 1)) ) */ + + +#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8_1M_MAIN__) && (__ARM_ARCH_8_1M_MAIN__ == 1)) ) + +/** + \brief Signed Saturate + \details 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 __builtin_arm_ssat + + +/** + \brief Unsigned Saturate + \details 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 __builtin_arm_usat + + +/** + \brief Rotate Right with Extend (32 bit) + \details Moves each bit of a bitstring right by one bit. + The carry input is shifted in at the left end of the bitstring. + \param [in] value Value to rotate + \return Rotated value + */ +__STATIC_FORCEINLINE uint32_t __RRX(uint32_t value) +{ + uint32_t result; + + __ASM volatile ("rrx %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); + return(result); +} + + +/** + \brief LDRT Unprivileged (8 bit) + \details Executes a Unprivileged LDRT instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +__STATIC_FORCEINLINE uint8_t __LDRBT(volatile uint8_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldrbt %0, %1" : "=r" (result) : "Q" (*ptr) ); + return ((uint8_t) result); /* Add explicit type cast here */ +} + + +/** + \brief LDRT Unprivileged (16 bit) + \details Executes a Unprivileged LDRT instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +__STATIC_FORCEINLINE uint16_t __LDRHT(volatile uint16_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldrht %0, %1" : "=r" (result) : "Q" (*ptr) ); + return ((uint16_t) result); /* Add explicit type cast here */ +} + + +/** + \brief LDRT Unprivileged (32 bit) + \details Executes a Unprivileged LDRT instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +__STATIC_FORCEINLINE uint32_t __LDRT(volatile uint32_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldrt %0, %1" : "=r" (result) : "Q" (*ptr) ); + return(result); +} + + +/** + \brief STRT Unprivileged (8 bit) + \details Executes a Unprivileged STRT instruction for 8 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STRBT(uint8_t value, volatile uint8_t *ptr) +{ + __ASM volatile ("strbt %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); +} + + +/** + \brief STRT Unprivileged (16 bit) + \details Executes a Unprivileged STRT instruction for 16 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STRHT(uint16_t value, volatile uint16_t *ptr) +{ + __ASM volatile ("strht %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); +} + + +/** + \brief STRT Unprivileged (32 bit) + \details Executes a Unprivileged STRT instruction for 32 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STRT(uint32_t value, volatile uint32_t *ptr) +{ + __ASM volatile ("strt %1, %0" : "=Q" (*ptr) : "r" (value) ); +} + +#else /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8_1M_MAIN__) && (__ARM_ARCH_8_1M_MAIN__ == 1)) ) */ + +/** + \brief Signed Saturate + \details Saturates a signed value. + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (1..32) + \return Saturated value + */ +__STATIC_FORCEINLINE int32_t __SSAT(int32_t val, uint32_t sat) +{ + if ((sat >= 1U) && (sat <= 32U)) + { + const int32_t max = (int32_t)((1U << (sat - 1U)) - 1U); + const int32_t min = -1 - max ; + if (val > max) + { + return max; + } + else if (val < min) + { + return min; + } + } + return val; +} + +/** + \brief Unsigned Saturate + \details Saturates an unsigned value. + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (0..31) + \return Saturated value + */ +__STATIC_FORCEINLINE uint32_t __USAT(int32_t val, uint32_t sat) +{ + if (sat <= 31U) + { + const uint32_t max = ((1U << sat) - 1U); + if (val > (int32_t)max) + { + return max; + } + else if (val < 0) + { + return 0U; + } + } + return (uint32_t)val; +} + +#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8_1M_MAIN__) && (__ARM_ARCH_8_1M_MAIN__ == 1)) ) */ + + +#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) || \ + (defined (__ARM_ARCH_8_1M_MAIN__) && (__ARM_ARCH_8_1M_MAIN__ == 1)) ) + +/** + \brief Load-Acquire (8 bit) + \details Executes a LDAB instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +__STATIC_FORCEINLINE uint8_t __LDAB(volatile uint8_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldab %0, %1" : "=r" (result) : "Q" (*ptr) : "memory" ); + return ((uint8_t) result); +} + + +/** + \brief Load-Acquire (16 bit) + \details Executes a LDAH instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +__STATIC_FORCEINLINE uint16_t __LDAH(volatile uint16_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldah %0, %1" : "=r" (result) : "Q" (*ptr) : "memory" ); + return ((uint16_t) result); +} + + +/** + \brief Load-Acquire (32 bit) + \details Executes a LDA instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +__STATIC_FORCEINLINE uint32_t __LDA(volatile uint32_t *ptr) +{ + uint32_t result; + + __ASM volatile ("lda %0, %1" : "=r" (result) : "Q" (*ptr) : "memory" ); + return(result); +} + + +/** + \brief Store-Release (8 bit) + \details Executes a STLB instruction for 8 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STLB(uint8_t value, volatile uint8_t *ptr) +{ + __ASM volatile ("stlb %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) : "memory" ); +} + + +/** + \brief Store-Release (16 bit) + \details Executes a STLH instruction for 16 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STLH(uint16_t value, volatile uint16_t *ptr) +{ + __ASM volatile ("stlh %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) : "memory" ); +} + + +/** + \brief Store-Release (32 bit) + \details Executes a STL instruction for 32 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STL(uint32_t value, volatile uint32_t *ptr) +{ + __ASM volatile ("stl %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) : "memory" ); +} + + +/** + \brief Load-Acquire Exclusive (8 bit) + \details Executes a LDAB exclusive instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +#define __LDAEXB (uint8_t)__builtin_arm_ldaex + + +/** + \brief Load-Acquire Exclusive (16 bit) + \details Executes a LDAH exclusive instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +#define __LDAEXH (uint16_t)__builtin_arm_ldaex + + +/** + \brief Load-Acquire Exclusive (32 bit) + \details Executes a LDA exclusive instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +#define __LDAEX (uint32_t)__builtin_arm_ldaex + + +/** + \brief Store-Release Exclusive (8 bit) + \details Executes a STLB exclusive instruction 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 __STLEXB (uint32_t)__builtin_arm_stlex + + +/** + \brief Store-Release Exclusive (16 bit) + \details Executes a STLH exclusive instruction 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 __STLEXH (uint32_t)__builtin_arm_stlex + + +/** + \brief Store-Release Exclusive (32 bit) + \details Executes a STL exclusive instruction 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 __STLEX (uint32_t)__builtin_arm_stlex + +#endif /* ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) || \ + (defined (__ARM_ARCH_8_1M_MAIN__) && (__ARM_ARCH_8_1M_MAIN__ == 1)) ) */ + +/*@}*/ /* end of group CMSIS_Core_InstructionInterface */ + + +/* ################### Compiler specific Intrinsics ########################### */ +/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics + Access to dedicated SIMD instructions + @{ +*/ + +#if (defined (__ARM_FEATURE_DSP) && (__ARM_FEATURE_DSP == 1)) + +#define __SADD8 __builtin_arm_sadd8 +#define __QADD8 __builtin_arm_qadd8 +#define __SHADD8 __builtin_arm_shadd8 +#define __UADD8 __builtin_arm_uadd8 +#define __UQADD8 __builtin_arm_uqadd8 +#define __UHADD8 __builtin_arm_uhadd8 +#define __SSUB8 __builtin_arm_ssub8 +#define __QSUB8 __builtin_arm_qsub8 +#define __SHSUB8 __builtin_arm_shsub8 +#define __USUB8 __builtin_arm_usub8 +#define __UQSUB8 __builtin_arm_uqsub8 +#define __UHSUB8 __builtin_arm_uhsub8 +#define __SADD16 __builtin_arm_sadd16 +#define __QADD16 __builtin_arm_qadd16 +#define __SHADD16 __builtin_arm_shadd16 +#define __UADD16 __builtin_arm_uadd16 +#define __UQADD16 __builtin_arm_uqadd16 +#define __UHADD16 __builtin_arm_uhadd16 +#define __SSUB16 __builtin_arm_ssub16 +#define __QSUB16 __builtin_arm_qsub16 +#define __SHSUB16 __builtin_arm_shsub16 +#define __USUB16 __builtin_arm_usub16 +#define __UQSUB16 __builtin_arm_uqsub16 +#define __UHSUB16 __builtin_arm_uhsub16 +#define __SASX __builtin_arm_sasx +#define __QASX __builtin_arm_qasx +#define __SHASX __builtin_arm_shasx +#define __UASX __builtin_arm_uasx +#define __UQASX __builtin_arm_uqasx +#define __UHASX __builtin_arm_uhasx +#define __SSAX __builtin_arm_ssax +#define __QSAX __builtin_arm_qsax +#define __SHSAX __builtin_arm_shsax +#define __USAX __builtin_arm_usax +#define __UQSAX __builtin_arm_uqsax +#define __UHSAX __builtin_arm_uhsax +#define __USAD8 __builtin_arm_usad8 +#define __USADA8 __builtin_arm_usada8 +#define __SSAT16 __builtin_arm_ssat16 +#define __USAT16 __builtin_arm_usat16 +#define __UXTB16 __builtin_arm_uxtb16 +#define __UXTAB16 __builtin_arm_uxtab16 +#define __SXTB16 __builtin_arm_sxtb16 +#define __SXTAB16 __builtin_arm_sxtab16 +#define __SMUAD __builtin_arm_smuad +#define __SMUADX __builtin_arm_smuadx +#define __SMLAD __builtin_arm_smlad +#define __SMLADX __builtin_arm_smladx +#define __SMLALD __builtin_arm_smlald +#define __SMLALDX __builtin_arm_smlaldx +#define __SMUSD __builtin_arm_smusd +#define __SMUSDX __builtin_arm_smusdx +#define __SMLSD __builtin_arm_smlsd +#define __SMLSDX __builtin_arm_smlsdx +#define __SMLSLD __builtin_arm_smlsld +#define __SMLSLDX __builtin_arm_smlsldx +#define __SEL __builtin_arm_sel +#define __QADD __builtin_arm_qadd +#define __QSUB __builtin_arm_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) ) + +#define __SXTB16_RORn(ARG1, ARG2) __SXTB16(__ROR(ARG1, ARG2)) + +__STATIC_FORCEINLINE int32_t __SMMLA (int32_t op1, int32_t op2, int32_t op3) +{ + int32_t result; + + __ASM volatile ("smmla %0, %1, %2, %3" : "=r" (result): "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +#endif /* (__ARM_FEATURE_DSP == 1) */ +/*@} end of group CMSIS_SIMD_intrinsics */ + + +#endif /* __CMSIS_ARMCLANG_H */ diff --git a/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_armclang_ltm.h b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_armclang_ltm.h new file mode 100644 index 0000000000..cdc0690747 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_armclang_ltm.h @@ -0,0 +1,1893 @@ +/****************************************************************************** + * @file cmsis_armclang_ltm.h + * @brief CMSIS compiler armclang (Arm Compiler 6) header file + * @version V1.3.0 + * @date 26. March 2020 + ******************************************************************************/ +/* + * Copyright (c) 2018-2020 Arm Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * 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 + * + * 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. + */ + +/*lint -esym(9058, IRQn)*/ /* disable MISRA 2012 Rule 2.4 for IRQn */ + +#ifndef __CMSIS_ARMCLANG_H +#define __CMSIS_ARMCLANG_H + +#pragma clang system_header /* treat file as system include file */ + +#ifndef __ARM_COMPAT_H +#include /* Compatibility header for Arm Compiler 5 intrinsics */ +#endif + +/* CMSIS compiler specific defines */ +#ifndef __ASM + #define __ASM __asm +#endif +#ifndef __INLINE + #define __INLINE __inline +#endif +#ifndef __STATIC_INLINE + #define __STATIC_INLINE static __inline +#endif +#ifndef __STATIC_FORCEINLINE + #define __STATIC_FORCEINLINE __attribute__((always_inline)) static __inline +#endif +#ifndef __NO_RETURN + #define __NO_RETURN __attribute__((__noreturn__)) +#endif +#ifndef __USED + #define __USED __attribute__((used)) +#endif +#ifndef __WEAK + #define __WEAK __attribute__((weak)) +#endif +#ifndef __PACKED + #define __PACKED __attribute__((packed, aligned(1))) +#endif +#ifndef __PACKED_STRUCT + #define __PACKED_STRUCT struct __attribute__((packed, aligned(1))) +#endif +#ifndef __PACKED_UNION + #define __PACKED_UNION union __attribute__((packed, aligned(1))) +#endif +#ifndef __UNALIGNED_UINT32 /* deprecated */ + #pragma clang diagnostic push + #pragma clang diagnostic ignored "-Wpacked" +/*lint -esym(9058, T_UINT32)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT32 */ + struct __attribute__((packed)) T_UINT32 { uint32_t v; }; + #pragma clang diagnostic pop + #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) +#endif +#ifndef __UNALIGNED_UINT16_WRITE + #pragma clang diagnostic push + #pragma clang diagnostic ignored "-Wpacked" +/*lint -esym(9058, T_UINT16_WRITE)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT16_WRITE */ + __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; + #pragma clang diagnostic pop + #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) +#endif +#ifndef __UNALIGNED_UINT16_READ + #pragma clang diagnostic push + #pragma clang diagnostic ignored "-Wpacked" +/*lint -esym(9058, T_UINT16_READ)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT16_READ */ + __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; + #pragma clang diagnostic pop + #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) +#endif +#ifndef __UNALIGNED_UINT32_WRITE + #pragma clang diagnostic push + #pragma clang diagnostic ignored "-Wpacked" +/*lint -esym(9058, T_UINT32_WRITE)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT32_WRITE */ + __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; + #pragma clang diagnostic pop + #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) +#endif +#ifndef __UNALIGNED_UINT32_READ + #pragma clang diagnostic push + #pragma clang diagnostic ignored "-Wpacked" +/*lint -esym(9058, T_UINT32_READ)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT32_READ */ + __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; + #pragma clang diagnostic pop + #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) +#endif +#ifndef __ALIGNED + #define __ALIGNED(x) __attribute__((aligned(x))) +#endif +#ifndef __RESTRICT + #define __RESTRICT __restrict +#endif +#ifndef __COMPILER_BARRIER + #define __COMPILER_BARRIER() __ASM volatile("":::"memory") +#endif + +/* ######################### Startup and Lowlevel Init ######################## */ + +#ifndef __PROGRAM_START +#define __PROGRAM_START __main +#endif + +#ifndef __INITIAL_SP +#define __INITIAL_SP Image$$ARM_LIB_STACK$$ZI$$Limit +#endif + +#ifndef __STACK_LIMIT +#define __STACK_LIMIT Image$$ARM_LIB_STACK$$ZI$$Base +#endif + +#ifndef __VECTOR_TABLE +#define __VECTOR_TABLE __Vectors +#endif + +#ifndef __VECTOR_TABLE_ATTRIBUTE +#define __VECTOR_TABLE_ATTRIBUTE __attribute__((used, section("RESET"))) +#endif + + +/* ########################### Core Function Access ########################### */ +/** \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions + @{ + */ + +/** + \brief Enable IRQ Interrupts + \details Enables IRQ interrupts by clearing the I-bit in the CPSR. + Can only be executed in Privileged modes. + */ +/* intrinsic void __enable_irq(); see arm_compat.h */ + + +/** + \brief Disable IRQ Interrupts + \details Disables IRQ interrupts by setting the I-bit in the CPSR. + Can only be executed in Privileged modes. + */ +/* intrinsic void __disable_irq(); see arm_compat.h */ + + +/** + \brief Get Control Register + \details Returns the content of the Control Register. + \return Control Register value + */ +__STATIC_FORCEINLINE uint32_t __get_CONTROL(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, control" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Control Register (non-secure) + \details Returns the content of the non-secure Control Register when in secure mode. + \return non-secure Control Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_CONTROL_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, control_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Control Register + \details Writes the given value to the Control Register. + \param [in] control Control Register value to set + */ +__STATIC_FORCEINLINE void __set_CONTROL(uint32_t control) +{ + __ASM volatile ("MSR control, %0" : : "r" (control) : "memory"); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Control Register (non-secure) + \details Writes the given value to the non-secure Control Register when in secure state. + \param [in] control Control Register value to set + */ +__STATIC_FORCEINLINE void __TZ_set_CONTROL_NS(uint32_t control) +{ + __ASM volatile ("MSR control_ns, %0" : : "r" (control) : "memory"); +} +#endif + + +/** + \brief Get IPSR Register + \details Returns the content of the IPSR Register. + \return IPSR Register value + */ +__STATIC_FORCEINLINE uint32_t __get_IPSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, ipsr" : "=r" (result) ); + return(result); +} + + +/** + \brief Get APSR Register + \details Returns the content of the APSR Register. + \return APSR Register value + */ +__STATIC_FORCEINLINE uint32_t __get_APSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, apsr" : "=r" (result) ); + return(result); +} + + +/** + \brief Get xPSR Register + \details Returns the content of the xPSR Register. + \return xPSR Register value + */ +__STATIC_FORCEINLINE uint32_t __get_xPSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, xpsr" : "=r" (result) ); + return(result); +} + + +/** + \brief Get Process Stack Pointer + \details Returns the current value of the Process Stack Pointer (PSP). + \return PSP Register value + */ +__STATIC_FORCEINLINE uint32_t __get_PSP(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, psp" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Process Stack Pointer (non-secure) + \details Returns the current value of the non-secure Process Stack Pointer (PSP) when in secure state. + \return PSP Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_PSP_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, psp_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Process Stack Pointer + \details Assigns the given value to the Process Stack Pointer (PSP). + \param [in] topOfProcStack Process Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __set_PSP(uint32_t topOfProcStack) +{ + __ASM volatile ("MSR psp, %0" : : "r" (topOfProcStack) : ); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Process Stack Pointer (non-secure) + \details Assigns the given value to the non-secure Process Stack Pointer (PSP) when in secure state. + \param [in] topOfProcStack Process Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __TZ_set_PSP_NS(uint32_t topOfProcStack) +{ + __ASM volatile ("MSR psp_ns, %0" : : "r" (topOfProcStack) : ); +} +#endif + + +/** + \brief Get Main Stack Pointer + \details Returns the current value of the Main Stack Pointer (MSP). + \return MSP Register value + */ +__STATIC_FORCEINLINE uint32_t __get_MSP(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, msp" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Main Stack Pointer (non-secure) + \details Returns the current value of the non-secure Main Stack Pointer (MSP) when in secure state. + \return MSP Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_MSP_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, msp_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Main Stack Pointer + \details Assigns the given value to the Main Stack Pointer (MSP). + \param [in] topOfMainStack Main Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __set_MSP(uint32_t topOfMainStack) +{ + __ASM volatile ("MSR msp, %0" : : "r" (topOfMainStack) : ); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Main Stack Pointer (non-secure) + \details Assigns the given value to the non-secure Main Stack Pointer (MSP) when in secure state. + \param [in] topOfMainStack Main Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __TZ_set_MSP_NS(uint32_t topOfMainStack) +{ + __ASM volatile ("MSR msp_ns, %0" : : "r" (topOfMainStack) : ); +} +#endif + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Stack Pointer (non-secure) + \details Returns the current value of the non-secure Stack Pointer (SP) when in secure state. + \return SP Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_SP_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, sp_ns" : "=r" (result) ); + return(result); +} + + +/** + \brief Set Stack Pointer (non-secure) + \details Assigns the given value to the non-secure Stack Pointer (SP) when in secure state. + \param [in] topOfStack Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __TZ_set_SP_NS(uint32_t topOfStack) +{ + __ASM volatile ("MSR sp_ns, %0" : : "r" (topOfStack) : ); +} +#endif + + +/** + \brief Get Priority Mask + \details Returns the current state of the priority mask bit from the Priority Mask Register. + \return Priority Mask value + */ +__STATIC_FORCEINLINE uint32_t __get_PRIMASK(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, primask" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Priority Mask (non-secure) + \details Returns the current state of the non-secure priority mask bit from the Priority Mask Register when in secure state. + \return Priority Mask value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_PRIMASK_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, primask_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Priority Mask + \details Assigns the given value to the Priority Mask Register. + \param [in] priMask Priority Mask + */ +__STATIC_FORCEINLINE void __set_PRIMASK(uint32_t priMask) +{ + __ASM volatile ("MSR primask, %0" : : "r" (priMask) : "memory"); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Priority Mask (non-secure) + \details Assigns the given value to the non-secure Priority Mask Register when in secure state. + \param [in] priMask Priority Mask + */ +__STATIC_FORCEINLINE void __TZ_set_PRIMASK_NS(uint32_t priMask) +{ + __ASM volatile ("MSR primask_ns, %0" : : "r" (priMask) : "memory"); +} +#endif + + +#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) +/** + \brief Enable FIQ + \details Enables FIQ interrupts by clearing the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +#define __enable_fault_irq __enable_fiq /* see arm_compat.h */ + + +/** + \brief Disable FIQ + \details Disables FIQ interrupts by setting the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +#define __disable_fault_irq __disable_fiq /* see arm_compat.h */ + + +/** + \brief Get Base Priority + \details Returns the current value of the Base Priority register. + \return Base Priority register value + */ +__STATIC_FORCEINLINE uint32_t __get_BASEPRI(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, basepri" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Base Priority (non-secure) + \details Returns the current value of the non-secure Base Priority register when in secure state. + \return Base Priority register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_BASEPRI_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, basepri_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Base Priority + \details Assigns the given value to the Base Priority register. + \param [in] basePri Base Priority value to set + */ +__STATIC_FORCEINLINE void __set_BASEPRI(uint32_t basePri) +{ + __ASM volatile ("MSR basepri, %0" : : "r" (basePri) : "memory"); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Base Priority (non-secure) + \details Assigns the given value to the non-secure Base Priority register when in secure state. + \param [in] basePri Base Priority value to set + */ +__STATIC_FORCEINLINE void __TZ_set_BASEPRI_NS(uint32_t basePri) +{ + __ASM volatile ("MSR basepri_ns, %0" : : "r" (basePri) : "memory"); +} +#endif + + +/** + \brief Set Base Priority with condition + \details Assigns the given value to the Base Priority register only if BASEPRI masking is disabled, + or the new value increases the BASEPRI priority level. + \param [in] basePri Base Priority value to set + */ +__STATIC_FORCEINLINE void __set_BASEPRI_MAX(uint32_t basePri) +{ + __ASM volatile ("MSR basepri_max, %0" : : "r" (basePri) : "memory"); +} + + +/** + \brief Get Fault Mask + \details Returns the current value of the Fault Mask register. + \return Fault Mask register value + */ +__STATIC_FORCEINLINE uint32_t __get_FAULTMASK(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, faultmask" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Fault Mask (non-secure) + \details Returns the current value of the non-secure Fault Mask register when in secure state. + \return Fault Mask register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_FAULTMASK_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, faultmask_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Fault Mask + \details Assigns the given value to the Fault Mask register. + \param [in] faultMask Fault Mask value to set + */ +__STATIC_FORCEINLINE void __set_FAULTMASK(uint32_t faultMask) +{ + __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) : "memory"); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Fault Mask (non-secure) + \details Assigns the given value to the non-secure Fault Mask register when in secure state. + \param [in] faultMask Fault Mask value to set + */ +__STATIC_FORCEINLINE void __TZ_set_FAULTMASK_NS(uint32_t faultMask) +{ + __ASM volatile ("MSR faultmask_ns, %0" : : "r" (faultMask) : "memory"); +} +#endif + +#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ + + +#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) + +/** + \brief Get Process Stack Pointer Limit + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence zero is returned always in non-secure + mode. + + \details Returns the current value of the Process Stack Pointer Limit (PSPLIM). + \return PSPLIM Register value + */ +__STATIC_FORCEINLINE uint32_t __get_PSPLIM(void) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + return 0U; +#else + uint32_t result; + __ASM volatile ("MRS %0, psplim" : "=r" (result) ); + return result; +#endif +} + +#if (defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Process Stack Pointer Limit (non-secure) + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence zero is returned always in non-secure + mode. + + \details Returns the current value of the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. + \return PSPLIM Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_PSPLIM_NS(void) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + return 0U; +#else + uint32_t result; + __ASM volatile ("MRS %0, psplim_ns" : "=r" (result) ); + return result; +#endif +} +#endif + + +/** + \brief Set Process Stack Pointer Limit + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence the write is silently ignored in non-secure + mode. + + \details Assigns the given value to the Process Stack Pointer Limit (PSPLIM). + \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set + */ +__STATIC_FORCEINLINE void __set_PSPLIM(uint32_t ProcStackPtrLimit) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + (void)ProcStackPtrLimit; +#else + __ASM volatile ("MSR psplim, %0" : : "r" (ProcStackPtrLimit)); +#endif +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Process Stack Pointer (non-secure) + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence the write is silently ignored in non-secure + mode. + + \details Assigns the given value to the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. + \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set + */ +__STATIC_FORCEINLINE void __TZ_set_PSPLIM_NS(uint32_t ProcStackPtrLimit) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + (void)ProcStackPtrLimit; +#else + __ASM volatile ("MSR psplim_ns, %0\n" : : "r" (ProcStackPtrLimit)); +#endif +} +#endif + + +/** + \brief Get Main Stack Pointer Limit + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence zero is returned always. + + \details Returns the current value of the Main Stack Pointer Limit (MSPLIM). + \return MSPLIM Register value + */ +__STATIC_FORCEINLINE uint32_t __get_MSPLIM(void) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + return 0U; +#else + uint32_t result; + __ASM volatile ("MRS %0, msplim" : "=r" (result) ); + return result; +#endif +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Main Stack Pointer Limit (non-secure) + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence zero is returned always. + + \details Returns the current value of the non-secure Main Stack Pointer Limit(MSPLIM) when in secure state. + \return MSPLIM Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_MSPLIM_NS(void) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + return 0U; +#else + uint32_t result; + __ASM volatile ("MRS %0, msplim_ns" : "=r" (result) ); + return result; +#endif +} +#endif + + +/** + \brief Set Main Stack Pointer Limit + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence the write is silently ignored. + + \details Assigns the given value to the Main Stack Pointer Limit (MSPLIM). + \param [in] MainStackPtrLimit Main Stack Pointer Limit value to set + */ +__STATIC_FORCEINLINE void __set_MSPLIM(uint32_t MainStackPtrLimit) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + (void)MainStackPtrLimit; +#else + __ASM volatile ("MSR msplim, %0" : : "r" (MainStackPtrLimit)); +#endif +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Main Stack Pointer Limit (non-secure) + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence the write is silently ignored. + + \details Assigns the given value to the non-secure Main Stack Pointer Limit (MSPLIM) when in secure state. + \param [in] MainStackPtrLimit Main Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __TZ_set_MSPLIM_NS(uint32_t MainStackPtrLimit) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + (void)MainStackPtrLimit; +#else + __ASM volatile ("MSR msplim_ns, %0" : : "r" (MainStackPtrLimit)); +#endif +} +#endif + +#endif /* ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ + +/** + \brief Get FPSCR + \details Returns the current value of the Floating Point Status/Control register. + \return Floating Point Status/Control register value + */ +#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ + (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) +#define __get_FPSCR (uint32_t)__builtin_arm_get_fpscr +#else +#define __get_FPSCR() ((uint32_t)0U) +#endif + +/** + \brief Set FPSCR + \details Assigns the given value to the Floating Point Status/Control register. + \param [in] fpscr Floating Point Status/Control value to set + */ +#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ + (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) +#define __set_FPSCR __builtin_arm_set_fpscr +#else +#define __set_FPSCR(x) ((void)(x)) +#endif + + +/*@} end of CMSIS_Core_RegAccFunctions */ + + +/* ########################## Core Instruction Access ######################### */ +/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface + Access to dedicated instructions + @{ +*/ + +/* Define macros for porting to both thumb1 and thumb2. + * For thumb1, use low register (r0-r7), specified by constraint "l" + * Otherwise, use general registers, specified by constraint "r" */ +#if defined (__thumb__) && !defined (__thumb2__) +#define __CMSIS_GCC_OUT_REG(r) "=l" (r) +#define __CMSIS_GCC_USE_REG(r) "l" (r) +#else +#define __CMSIS_GCC_OUT_REG(r) "=r" (r) +#define __CMSIS_GCC_USE_REG(r) "r" (r) +#endif + +/** + \brief No Operation + \details No Operation does nothing. This instruction can be used for code alignment purposes. + */ +#define __NOP __builtin_arm_nop + +/** + \brief Wait For Interrupt + \details Wait For Interrupt is a hint instruction that suspends execution until one of a number of events occurs. + */ +#define __WFI __builtin_arm_wfi + + +/** + \brief Wait For Event + \details 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 __builtin_arm_wfe + + +/** + \brief Send Event + \details Send Event is a hint instruction. It causes an event to be signaled to the CPU. + */ +#define __SEV __builtin_arm_sev + + +/** + \brief Instruction Synchronization Barrier + \details 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() __builtin_arm_isb(0xF) + +/** + \brief Data Synchronization Barrier + \details Acts as a special kind of Data Memory Barrier. + It completes when all explicit memory accesses before this instruction complete. + */ +#define __DSB() __builtin_arm_dsb(0xF) + + +/** + \brief Data Memory Barrier + \details Ensures the apparent order of the explicit memory operations before + and after the instruction, without ensuring their completion. + */ +#define __DMB() __builtin_arm_dmb(0xF) + + +/** + \brief Reverse byte order (32 bit) + \details Reverses the byte order in unsigned integer value. For example, 0x12345678 becomes 0x78563412. + \param [in] value Value to reverse + \return Reversed value + */ +#define __REV(value) __builtin_bswap32(value) + + +/** + \brief Reverse byte order (16 bit) + \details Reverses the byte order within each halfword of a word. For example, 0x12345678 becomes 0x34127856. + \param [in] value Value to reverse + \return Reversed value + */ +#define __REV16(value) __ROR(__REV(value), 16) + + +/** + \brief Reverse byte order (16 bit) + \details Reverses the byte order in a 16-bit value and returns the signed 16-bit result. For example, 0x0080 becomes 0x8000. + \param [in] value Value to reverse + \return Reversed value + */ +#define __REVSH(value) (int16_t)__builtin_bswap16(value) + + +/** + \brief Rotate Right in unsigned value (32 bit) + \details Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits. + \param [in] op1 Value to rotate + \param [in] op2 Number of Bits to rotate + \return Rotated value + */ +__STATIC_FORCEINLINE uint32_t __ROR(uint32_t op1, uint32_t op2) +{ + op2 %= 32U; + if (op2 == 0U) + { + return op1; + } + return (op1 >> op2) | (op1 << (32U - op2)); +} + + +/** + \brief Breakpoint + \details Causes the processor to enter Debug state. + Debug tools can use this to investigate system state when the instruction at a particular address is reached. + \param [in] value is ignored by the processor. + If required, a debugger can use it to store additional information about the breakpoint. + */ +#define __BKPT(value) __ASM volatile ("bkpt "#value) + + +/** + \brief Reverse bit order of value + \details Reverses the bit order of the given value. + \param [in] value Value to reverse + \return Reversed value + */ +#define __RBIT __builtin_arm_rbit + +/** + \brief Count leading zeros + \details 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 + */ +__STATIC_FORCEINLINE uint8_t __CLZ(uint32_t value) +{ + /* Even though __builtin_clz produces a CLZ instruction on ARM, formally + __builtin_clz(0) is undefined behaviour, so handle this case specially. + This guarantees ARM-compatible results if happening to compile on a non-ARM + target, and ensures the compiler doesn't decide to activate any + optimisations using the logic "value was passed to __builtin_clz, so it + is non-zero". + ARM Compiler 6.10 and possibly earlier will optimise this test away, leaving a + single CLZ instruction. + */ + if (value == 0U) + { + return 32U; + } + return __builtin_clz(value); +} + + +#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) +/** + \brief LDR Exclusive (8 bit) + \details Executes a exclusive LDR instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +#define __LDREXB (uint8_t)__builtin_arm_ldrex + + +/** + \brief LDR Exclusive (16 bit) + \details Executes a exclusive LDR instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +#define __LDREXH (uint16_t)__builtin_arm_ldrex + + +/** + \brief LDR Exclusive (32 bit) + \details Executes a exclusive LDR instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +#define __LDREXW (uint32_t)__builtin_arm_ldrex + + +/** + \brief STR Exclusive (8 bit) + \details Executes a exclusive STR instruction 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 (uint32_t)__builtin_arm_strex + + +/** + \brief STR Exclusive (16 bit) + \details Executes a exclusive STR instruction 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 (uint32_t)__builtin_arm_strex + + +/** + \brief STR Exclusive (32 bit) + \details Executes a exclusive STR instruction 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 (uint32_t)__builtin_arm_strex + + +/** + \brief Remove the exclusive lock + \details Removes the exclusive lock which is created by LDREX. + */ +#define __CLREX __builtin_arm_clrex + +#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ + + +#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) + +/** + \brief Signed Saturate + \details 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 __builtin_arm_ssat + + +/** + \brief Unsigned Saturate + \details 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 __builtin_arm_usat + + +/** + \brief Rotate Right with Extend (32 bit) + \details Moves each bit of a bitstring right by one bit. + The carry input is shifted in at the left end of the bitstring. + \param [in] value Value to rotate + \return Rotated value + */ +__STATIC_FORCEINLINE uint32_t __RRX(uint32_t value) +{ + uint32_t result; + + __ASM volatile ("rrx %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); + return(result); +} + + +/** + \brief LDRT Unprivileged (8 bit) + \details Executes a Unprivileged LDRT instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +__STATIC_FORCEINLINE uint8_t __LDRBT(volatile uint8_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldrbt %0, %1" : "=r" (result) : "Q" (*ptr) ); + return ((uint8_t) result); /* Add explicit type cast here */ +} + + +/** + \brief LDRT Unprivileged (16 bit) + \details Executes a Unprivileged LDRT instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +__STATIC_FORCEINLINE uint16_t __LDRHT(volatile uint16_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldrht %0, %1" : "=r" (result) : "Q" (*ptr) ); + return ((uint16_t) result); /* Add explicit type cast here */ +} + + +/** + \brief LDRT Unprivileged (32 bit) + \details Executes a Unprivileged LDRT instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +__STATIC_FORCEINLINE uint32_t __LDRT(volatile uint32_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldrt %0, %1" : "=r" (result) : "Q" (*ptr) ); + return(result); +} + + +/** + \brief STRT Unprivileged (8 bit) + \details Executes a Unprivileged STRT instruction for 8 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STRBT(uint8_t value, volatile uint8_t *ptr) +{ + __ASM volatile ("strbt %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); +} + + +/** + \brief STRT Unprivileged (16 bit) + \details Executes a Unprivileged STRT instruction for 16 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STRHT(uint16_t value, volatile uint16_t *ptr) +{ + __ASM volatile ("strht %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); +} + + +/** + \brief STRT Unprivileged (32 bit) + \details Executes a Unprivileged STRT instruction for 32 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STRT(uint32_t value, volatile uint32_t *ptr) +{ + __ASM volatile ("strt %1, %0" : "=Q" (*ptr) : "r" (value) ); +} + +#else /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ + +/** + \brief Signed Saturate + \details Saturates a signed value. + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (1..32) + \return Saturated value + */ +__STATIC_FORCEINLINE int32_t __SSAT(int32_t val, uint32_t sat) +{ + if ((sat >= 1U) && (sat <= 32U)) + { + const int32_t max = (int32_t)((1U << (sat - 1U)) - 1U); + const int32_t min = -1 - max ; + if (val > max) + { + return max; + } + else if (val < min) + { + return min; + } + } + return val; +} + +/** + \brief Unsigned Saturate + \details Saturates an unsigned value. + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (0..31) + \return Saturated value + */ +__STATIC_FORCEINLINE uint32_t __USAT(int32_t val, uint32_t sat) +{ + if (sat <= 31U) + { + const uint32_t max = ((1U << sat) - 1U); + if (val > (int32_t)max) + { + return max; + } + else if (val < 0) + { + return 0U; + } + } + return (uint32_t)val; +} + +#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ + + +#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) +/** + \brief Load-Acquire (8 bit) + \details Executes a LDAB instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +__STATIC_FORCEINLINE uint8_t __LDAB(volatile uint8_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldab %0, %1" : "=r" (result) : "Q" (*ptr) : "memory" ); + return ((uint8_t) result); +} + + +/** + \brief Load-Acquire (16 bit) + \details Executes a LDAH instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +__STATIC_FORCEINLINE uint16_t __LDAH(volatile uint16_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldah %0, %1" : "=r" (result) : "Q" (*ptr) : "memory" ); + return ((uint16_t) result); +} + + +/** + \brief Load-Acquire (32 bit) + \details Executes a LDA instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +__STATIC_FORCEINLINE uint32_t __LDA(volatile uint32_t *ptr) +{ + uint32_t result; + + __ASM volatile ("lda %0, %1" : "=r" (result) : "Q" (*ptr) : "memory" ); + return(result); +} + + +/** + \brief Store-Release (8 bit) + \details Executes a STLB instruction for 8 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STLB(uint8_t value, volatile uint8_t *ptr) +{ + __ASM volatile ("stlb %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) : "memory" ); +} + + +/** + \brief Store-Release (16 bit) + \details Executes a STLH instruction for 16 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STLH(uint16_t value, volatile uint16_t *ptr) +{ + __ASM volatile ("stlh %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) : "memory" ); +} + + +/** + \brief Store-Release (32 bit) + \details Executes a STL instruction for 32 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STL(uint32_t value, volatile uint32_t *ptr) +{ + __ASM volatile ("stl %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) : "memory" ); +} + + +/** + \brief Load-Acquire Exclusive (8 bit) + \details Executes a LDAB exclusive instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +#define __LDAEXB (uint8_t)__builtin_arm_ldaex + + +/** + \brief Load-Acquire Exclusive (16 bit) + \details Executes a LDAH exclusive instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +#define __LDAEXH (uint16_t)__builtin_arm_ldaex + + +/** + \brief Load-Acquire Exclusive (32 bit) + \details Executes a LDA exclusive instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +#define __LDAEX (uint32_t)__builtin_arm_ldaex + + +/** + \brief Store-Release Exclusive (8 bit) + \details Executes a STLB exclusive instruction 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 __STLEXB (uint32_t)__builtin_arm_stlex + + +/** + \brief Store-Release Exclusive (16 bit) + \details Executes a STLH exclusive instruction 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 __STLEXH (uint32_t)__builtin_arm_stlex + + +/** + \brief Store-Release Exclusive (32 bit) + \details Executes a STL exclusive instruction 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 __STLEX (uint32_t)__builtin_arm_stlex + +#endif /* ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ + +/*@}*/ /* end of group CMSIS_Core_InstructionInterface */ + + +/* ################### Compiler specific Intrinsics ########################### */ +/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics + Access to dedicated SIMD instructions + @{ +*/ + +#if (defined (__ARM_FEATURE_DSP) && (__ARM_FEATURE_DSP == 1)) + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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) \ +({ \ + int32_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; \ + }) + +__STATIC_FORCEINLINE uint32_t __UXTB16(uint32_t op1) +{ + uint32_t result; + + __ASM volatile ("uxtb16 %0, %1" : "=r" (result) : "r" (op1)); + return(result); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE uint32_t __SXTB16(uint32_t op1) +{ + uint32_t result; + + __ASM volatile ("sxtb16 %0, %1" : "=r" (result) : "r" (op1)); + return(result); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE uint64_t __SMLALD (uint32_t op1, uint32_t op2, uint64_t acc) +{ + union llreg_u{ + uint32_t w32[2]; + uint64_t w64; + } llr; + llr.w64 = acc; + +#ifndef __ARMEB__ /* Little endian */ + __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); +#else /* Big endian */ + __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); +#endif + + return(llr.w64); +} + +__STATIC_FORCEINLINE uint64_t __SMLALDX (uint32_t op1, uint32_t op2, uint64_t acc) +{ + union llreg_u{ + uint32_t w32[2]; + uint64_t w64; + } llr; + llr.w64 = acc; + +#ifndef __ARMEB__ /* Little endian */ + __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); +#else /* Big endian */ + __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); +#endif + + return(llr.w64); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE uint64_t __SMLSLD (uint32_t op1, uint32_t op2, uint64_t acc) +{ + union llreg_u{ + uint32_t w32[2]; + uint64_t w64; + } llr; + llr.w64 = acc; + +#ifndef __ARMEB__ /* Little endian */ + __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); +#else /* Big endian */ + __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); +#endif + + return(llr.w64); +} + +__STATIC_FORCEINLINE uint64_t __SMLSLDX (uint32_t op1, uint32_t op2, uint64_t acc) +{ + union llreg_u{ + uint32_t w32[2]; + uint64_t w64; + } llr; + llr.w64 = acc; + +#ifndef __ARMEB__ /* Little endian */ + __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); +#else /* Big endian */ + __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); +#endif + + return(llr.w64); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE int32_t __QADD( int32_t op1, int32_t op2) +{ + int32_t result; + + __ASM volatile ("qadd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE int32_t __QSUB( int32_t op1, int32_t op2) +{ + int32_t result; + + __ASM volatile ("qsub %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +#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) ) + +#define __SXTB16_RORn(ARG1, ARG2) __SXTB16(__ROR(ARG1, ARG2)) + +__STATIC_FORCEINLINE int32_t __SMMLA (int32_t op1, int32_t op2, int32_t op3) +{ + int32_t result; + + __ASM volatile ("smmla %0, %1, %2, %3" : "=r" (result): "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +#endif /* (__ARM_FEATURE_DSP == 1) */ +/*@} end of group CMSIS_SIMD_intrinsics */ + + +#endif /* __CMSIS_ARMCLANG_H */ diff --git a/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_compiler.h b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_compiler.h new file mode 100644 index 0000000000..8d3ab9721e --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_compiler.h @@ -0,0 +1,283 @@ +/****************************************************************************** + * @file cmsis_compiler.h + * @brief CMSIS compiler generic header file + * @version V5.1.0 + * @date 09. October 2018 + ******************************************************************************/ +/* + * Copyright (c) 2009-2018 Arm Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * 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 + * + * www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an AS IS BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef __CMSIS_COMPILER_H +#define __CMSIS_COMPILER_H + +#include + +/* + * Arm Compiler 4/5 + */ +#if defined ( __CC_ARM ) + #include "cmsis_armcc.h" + + +/* + * Arm Compiler 6.6 LTM (armclang) + */ +#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) && (__ARMCC_VERSION < 6100100) + #include "cmsis_armclang_ltm.h" + + /* + * Arm Compiler above 6.10.1 (armclang) + */ +#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6100100) + #include "cmsis_armclang.h" + + +/* + * GNU Compiler + */ +#elif defined ( __GNUC__ ) + #include "cmsis_gcc.h" + + +/* + * IAR Compiler + */ +#elif defined ( __ICCARM__ ) + #include + + +/* + * TI Arm Compiler + */ +#elif defined ( __TI_ARM__ ) + #include + + #ifndef __ASM + #define __ASM __asm + #endif + #ifndef __INLINE + #define __INLINE inline + #endif + #ifndef __STATIC_INLINE + #define __STATIC_INLINE static inline + #endif + #ifndef __STATIC_FORCEINLINE + #define __STATIC_FORCEINLINE __STATIC_INLINE + #endif + #ifndef __NO_RETURN + #define __NO_RETURN __attribute__((noreturn)) + #endif + #ifndef __USED + #define __USED __attribute__((used)) + #endif + #ifndef __WEAK + #define __WEAK __attribute__((weak)) + #endif + #ifndef __PACKED + #define __PACKED __attribute__((packed)) + #endif + #ifndef __PACKED_STRUCT + #define __PACKED_STRUCT struct __attribute__((packed)) + #endif + #ifndef __PACKED_UNION + #define __PACKED_UNION union __attribute__((packed)) + #endif + #ifndef __UNALIGNED_UINT32 /* deprecated */ + struct __attribute__((packed)) T_UINT32 { uint32_t v; }; + #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) + #endif + #ifndef __UNALIGNED_UINT16_WRITE + __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; + #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void*)(addr))->v) = (val)) + #endif + #ifndef __UNALIGNED_UINT16_READ + __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; + #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) + #endif + #ifndef __UNALIGNED_UINT32_WRITE + __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; + #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) + #endif + #ifndef __UNALIGNED_UINT32_READ + __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; + #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) + #endif + #ifndef __ALIGNED + #define __ALIGNED(x) __attribute__((aligned(x))) + #endif + #ifndef __RESTRICT + #define __RESTRICT __restrict + #endif + #ifndef __COMPILER_BARRIER + #warning No compiler specific solution for __COMPILER_BARRIER. __COMPILER_BARRIER is ignored. + #define __COMPILER_BARRIER() (void)0 + #endif + + +/* + * TASKING Compiler + */ +#elif defined ( __TASKING__ ) + /* + * 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. + */ + + #ifndef __ASM + #define __ASM __asm + #endif + #ifndef __INLINE + #define __INLINE inline + #endif + #ifndef __STATIC_INLINE + #define __STATIC_INLINE static inline + #endif + #ifndef __STATIC_FORCEINLINE + #define __STATIC_FORCEINLINE __STATIC_INLINE + #endif + #ifndef __NO_RETURN + #define __NO_RETURN __attribute__((noreturn)) + #endif + #ifndef __USED + #define __USED __attribute__((used)) + #endif + #ifndef __WEAK + #define __WEAK __attribute__((weak)) + #endif + #ifndef __PACKED + #define __PACKED __packed__ + #endif + #ifndef __PACKED_STRUCT + #define __PACKED_STRUCT struct __packed__ + #endif + #ifndef __PACKED_UNION + #define __PACKED_UNION union __packed__ + #endif + #ifndef __UNALIGNED_UINT32 /* deprecated */ + struct __packed__ T_UINT32 { uint32_t v; }; + #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) + #endif + #ifndef __UNALIGNED_UINT16_WRITE + __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; + #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) + #endif + #ifndef __UNALIGNED_UINT16_READ + __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; + #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) + #endif + #ifndef __UNALIGNED_UINT32_WRITE + __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; + #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) + #endif + #ifndef __UNALIGNED_UINT32_READ + __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; + #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) + #endif + #ifndef __ALIGNED + #define __ALIGNED(x) __align(x) + #endif + #ifndef __RESTRICT + #warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored. + #define __RESTRICT + #endif + #ifndef __COMPILER_BARRIER + #warning No compiler specific solution for __COMPILER_BARRIER. __COMPILER_BARRIER is ignored. + #define __COMPILER_BARRIER() (void)0 + #endif + + +/* + * COSMIC Compiler + */ +#elif defined ( __CSMC__ ) + #include + + #ifndef __ASM + #define __ASM _asm + #endif + #ifndef __INLINE + #define __INLINE inline + #endif + #ifndef __STATIC_INLINE + #define __STATIC_INLINE static inline + #endif + #ifndef __STATIC_FORCEINLINE + #define __STATIC_FORCEINLINE __STATIC_INLINE + #endif + #ifndef __NO_RETURN + // NO RETURN is automatically detected hence no warning here + #define __NO_RETURN + #endif + #ifndef __USED + #warning No compiler specific solution for __USED. __USED is ignored. + #define __USED + #endif + #ifndef __WEAK + #define __WEAK __weak + #endif + #ifndef __PACKED + #define __PACKED @packed + #endif + #ifndef __PACKED_STRUCT + #define __PACKED_STRUCT @packed struct + #endif + #ifndef __PACKED_UNION + #define __PACKED_UNION @packed union + #endif + #ifndef __UNALIGNED_UINT32 /* deprecated */ + @packed struct T_UINT32 { uint32_t v; }; + #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) + #endif + #ifndef __UNALIGNED_UINT16_WRITE + __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; + #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) + #endif + #ifndef __UNALIGNED_UINT16_READ + __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; + #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) + #endif + #ifndef __UNALIGNED_UINT32_WRITE + __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; + #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) + #endif + #ifndef __UNALIGNED_UINT32_READ + __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; + #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) + #endif + #ifndef __ALIGNED + #warning No compiler specific solution for __ALIGNED. __ALIGNED is ignored. + #define __ALIGNED(x) + #endif + #ifndef __RESTRICT + #warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored. + #define __RESTRICT + #endif + #ifndef __COMPILER_BARRIER + #warning No compiler specific solution for __COMPILER_BARRIER. __COMPILER_BARRIER is ignored. + #define __COMPILER_BARRIER() (void)0 + #endif + + +#else + #error Unknown compiler. +#endif + + +#endif /* __CMSIS_COMPILER_H */ + diff --git a/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_gcc.h b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_gcc.h new file mode 100644 index 0000000000..51682042b5 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_gcc.h @@ -0,0 +1,2177 @@ +/****************************************************************************** + * @file cmsis_gcc.h + * @brief CMSIS compiler GCC header file + * @version V5.3.0 + * @date 26. March 2020 + ******************************************************************************/ +/* + * Copyright (c) 2009-2020 Arm Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * 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 + * + * www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an AS IS BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef __CMSIS_GCC_H +#define __CMSIS_GCC_H + +/* ignore some GCC warnings */ +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wsign-conversion" +#pragma GCC diagnostic ignored "-Wconversion" +#pragma GCC diagnostic ignored "-Wunused-parameter" + +/* Fallback for __has_builtin */ +#ifndef __has_builtin + #define __has_builtin(x) (0) +#endif + +/* CMSIS compiler specific defines */ +#ifndef __ASM + #define __ASM __asm +#endif +#ifndef __INLINE + #define __INLINE inline +#endif +#ifndef __STATIC_INLINE + #define __STATIC_INLINE static inline +#endif +#ifndef __STATIC_FORCEINLINE + #define __STATIC_FORCEINLINE __attribute__((always_inline)) static inline +#endif +#ifndef __NO_RETURN + #define __NO_RETURN __attribute__((__noreturn__)) +#endif +#ifndef __USED + #define __USED __attribute__((used)) +#endif +#ifndef __WEAK + #define __WEAK __attribute__((weak)) +#endif +#ifndef __PACKED + #define __PACKED __attribute__((packed, aligned(1))) +#endif +#ifndef __PACKED_STRUCT + #define __PACKED_STRUCT struct __attribute__((packed, aligned(1))) +#endif +#ifndef __PACKED_UNION + #define __PACKED_UNION union __attribute__((packed, aligned(1))) +#endif +#ifndef __UNALIGNED_UINT32 /* deprecated */ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wpacked" + #pragma GCC diagnostic ignored "-Wattributes" + struct __attribute__((packed)) T_UINT32 { uint32_t v; }; + #pragma GCC diagnostic pop + #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) +#endif +#ifndef __UNALIGNED_UINT16_WRITE + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wpacked" + #pragma GCC diagnostic ignored "-Wattributes" + __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; + #pragma GCC diagnostic pop + #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) +#endif +#ifndef __UNALIGNED_UINT16_READ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wpacked" + #pragma GCC diagnostic ignored "-Wattributes" + __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; + #pragma GCC diagnostic pop + #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) +#endif +#ifndef __UNALIGNED_UINT32_WRITE + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wpacked" + #pragma GCC diagnostic ignored "-Wattributes" + __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; + #pragma GCC diagnostic pop + #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) +#endif +#ifndef __UNALIGNED_UINT32_READ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wpacked" + #pragma GCC diagnostic ignored "-Wattributes" + __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; + #pragma GCC diagnostic pop + #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) +#endif +#ifndef __ALIGNED + #define __ALIGNED(x) __attribute__((aligned(x))) +#endif +#ifndef __RESTRICT + #define __RESTRICT __restrict +#endif +#ifndef __COMPILER_BARRIER + #define __COMPILER_BARRIER() __ASM volatile("":::"memory") +#endif + +/* ######################### Startup and Lowlevel Init ######################## */ + +#ifndef __PROGRAM_START + +/** + \brief Initializes data and bss sections + \details This default implementations initialized all data and additional bss + sections relying on .copy.table and .zero.table specified properly + in the used linker script. + + */ +__STATIC_FORCEINLINE __NO_RETURN void __cmsis_start(void) +{ + extern void _start(void) __NO_RETURN; + + typedef struct { + uint32_t const* src; + uint32_t* dest; + uint32_t wlen; + } __copy_table_t; + + typedef struct { + uint32_t* dest; + uint32_t wlen; + } __zero_table_t; + + extern const __copy_table_t __copy_table_start__; + extern const __copy_table_t __copy_table_end__; + extern const __zero_table_t __zero_table_start__; + extern const __zero_table_t __zero_table_end__; + + for (__copy_table_t const* pTable = &__copy_table_start__; pTable < &__copy_table_end__; ++pTable) { + for(uint32_t i=0u; iwlen; ++i) { + pTable->dest[i] = pTable->src[i]; + } + } + + for (__zero_table_t const* pTable = &__zero_table_start__; pTable < &__zero_table_end__; ++pTable) { + for(uint32_t i=0u; iwlen; ++i) { + pTable->dest[i] = 0u; + } + } + + _start(); +} + +#define __PROGRAM_START __cmsis_start +#endif + +#ifndef __INITIAL_SP +#define __INITIAL_SP __StackTop +#endif + +#ifndef __STACK_LIMIT +#define __STACK_LIMIT __StackLimit +#endif + +#ifndef __VECTOR_TABLE +#define __VECTOR_TABLE __Vectors +#endif + +#ifndef __VECTOR_TABLE_ATTRIBUTE +#define __VECTOR_TABLE_ATTRIBUTE __attribute__((used, section(".vectors"))) +#endif + +/* ########################### Core Function Access ########################### */ +/** \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions + @{ + */ + +/** + \brief Enable IRQ Interrupts + \details Enables IRQ interrupts by clearing the I-bit in the CPSR. + Can only be executed in Privileged modes. + */ +__STATIC_FORCEINLINE void __enable_irq(void) +{ + __ASM volatile ("cpsie i" : : : "memory"); +} + + +/** + \brief Disable IRQ Interrupts + \details Disables IRQ interrupts by setting the I-bit in the CPSR. + Can only be executed in Privileged modes. + */ +__STATIC_FORCEINLINE void __disable_irq(void) +{ + __ASM volatile ("cpsid i" : : : "memory"); +} + + +/** + \brief Get Control Register + \details Returns the content of the Control Register. + \return Control Register value + */ +__STATIC_FORCEINLINE uint32_t __get_CONTROL(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, control" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Control Register (non-secure) + \details Returns the content of the non-secure Control Register when in secure mode. + \return non-secure Control Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_CONTROL_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, control_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Control Register + \details Writes the given value to the Control Register. + \param [in] control Control Register value to set + */ +__STATIC_FORCEINLINE void __set_CONTROL(uint32_t control) +{ + __ASM volatile ("MSR control, %0" : : "r" (control) : "memory"); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Control Register (non-secure) + \details Writes the given value to the non-secure Control Register when in secure state. + \param [in] control Control Register value to set + */ +__STATIC_FORCEINLINE void __TZ_set_CONTROL_NS(uint32_t control) +{ + __ASM volatile ("MSR control_ns, %0" : : "r" (control) : "memory"); +} +#endif + + +/** + \brief Get IPSR Register + \details Returns the content of the IPSR Register. + \return IPSR Register value + */ +__STATIC_FORCEINLINE uint32_t __get_IPSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, ipsr" : "=r" (result) ); + return(result); +} + + +/** + \brief Get APSR Register + \details Returns the content of the APSR Register. + \return APSR Register value + */ +__STATIC_FORCEINLINE uint32_t __get_APSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, apsr" : "=r" (result) ); + return(result); +} + + +/** + \brief Get xPSR Register + \details Returns the content of the xPSR Register. + \return xPSR Register value + */ +__STATIC_FORCEINLINE uint32_t __get_xPSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, xpsr" : "=r" (result) ); + return(result); +} + + +/** + \brief Get Process Stack Pointer + \details Returns the current value of the Process Stack Pointer (PSP). + \return PSP Register value + */ +__STATIC_FORCEINLINE uint32_t __get_PSP(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, psp" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Process Stack Pointer (non-secure) + \details Returns the current value of the non-secure Process Stack Pointer (PSP) when in secure state. + \return PSP Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_PSP_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, psp_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Process Stack Pointer + \details Assigns the given value to the Process Stack Pointer (PSP). + \param [in] topOfProcStack Process Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __set_PSP(uint32_t topOfProcStack) +{ + __ASM volatile ("MSR psp, %0" : : "r" (topOfProcStack) : ); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Process Stack Pointer (non-secure) + \details Assigns the given value to the non-secure Process Stack Pointer (PSP) when in secure state. + \param [in] topOfProcStack Process Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __TZ_set_PSP_NS(uint32_t topOfProcStack) +{ + __ASM volatile ("MSR psp_ns, %0" : : "r" (topOfProcStack) : ); +} +#endif + + +/** + \brief Get Main Stack Pointer + \details Returns the current value of the Main Stack Pointer (MSP). + \return MSP Register value + */ +__STATIC_FORCEINLINE uint32_t __get_MSP(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, msp" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Main Stack Pointer (non-secure) + \details Returns the current value of the non-secure Main Stack Pointer (MSP) when in secure state. + \return MSP Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_MSP_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, msp_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Main Stack Pointer + \details Assigns the given value to the Main Stack Pointer (MSP). + \param [in] topOfMainStack Main Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __set_MSP(uint32_t topOfMainStack) +{ + __ASM volatile ("MSR msp, %0" : : "r" (topOfMainStack) : ); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Main Stack Pointer (non-secure) + \details Assigns the given value to the non-secure Main Stack Pointer (MSP) when in secure state. + \param [in] topOfMainStack Main Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __TZ_set_MSP_NS(uint32_t topOfMainStack) +{ + __ASM volatile ("MSR msp_ns, %0" : : "r" (topOfMainStack) : ); +} +#endif + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Stack Pointer (non-secure) + \details Returns the current value of the non-secure Stack Pointer (SP) when in secure state. + \return SP Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_SP_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, sp_ns" : "=r" (result) ); + return(result); +} + + +/** + \brief Set Stack Pointer (non-secure) + \details Assigns the given value to the non-secure Stack Pointer (SP) when in secure state. + \param [in] topOfStack Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __TZ_set_SP_NS(uint32_t topOfStack) +{ + __ASM volatile ("MSR sp_ns, %0" : : "r" (topOfStack) : ); +} +#endif + + +/** + \brief Get Priority Mask + \details Returns the current state of the priority mask bit from the Priority Mask Register. + \return Priority Mask value + */ +__STATIC_FORCEINLINE uint32_t __get_PRIMASK(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, primask" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Priority Mask (non-secure) + \details Returns the current state of the non-secure priority mask bit from the Priority Mask Register when in secure state. + \return Priority Mask value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_PRIMASK_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, primask_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Priority Mask + \details Assigns the given value to the Priority Mask Register. + \param [in] priMask Priority Mask + */ +__STATIC_FORCEINLINE void __set_PRIMASK(uint32_t priMask) +{ + __ASM volatile ("MSR primask, %0" : : "r" (priMask) : "memory"); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Priority Mask (non-secure) + \details Assigns the given value to the non-secure Priority Mask Register when in secure state. + \param [in] priMask Priority Mask + */ +__STATIC_FORCEINLINE void __TZ_set_PRIMASK_NS(uint32_t priMask) +{ + __ASM volatile ("MSR primask_ns, %0" : : "r" (priMask) : "memory"); +} +#endif + + +#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) +/** + \brief Enable FIQ + \details Enables FIQ interrupts by clearing the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +__STATIC_FORCEINLINE void __enable_fault_irq(void) +{ + __ASM volatile ("cpsie f" : : : "memory"); +} + + +/** + \brief Disable FIQ + \details Disables FIQ interrupts by setting the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +__STATIC_FORCEINLINE void __disable_fault_irq(void) +{ + __ASM volatile ("cpsid f" : : : "memory"); +} + + +/** + \brief Get Base Priority + \details Returns the current value of the Base Priority register. + \return Base Priority register value + */ +__STATIC_FORCEINLINE uint32_t __get_BASEPRI(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, basepri" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Base Priority (non-secure) + \details Returns the current value of the non-secure Base Priority register when in secure state. + \return Base Priority register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_BASEPRI_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, basepri_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Base Priority + \details Assigns the given value to the Base Priority register. + \param [in] basePri Base Priority value to set + */ +__STATIC_FORCEINLINE void __set_BASEPRI(uint32_t basePri) +{ + __ASM volatile ("MSR basepri, %0" : : "r" (basePri) : "memory"); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Base Priority (non-secure) + \details Assigns the given value to the non-secure Base Priority register when in secure state. + \param [in] basePri Base Priority value to set + */ +__STATIC_FORCEINLINE void __TZ_set_BASEPRI_NS(uint32_t basePri) +{ + __ASM volatile ("MSR basepri_ns, %0" : : "r" (basePri) : "memory"); +} +#endif + + +/** + \brief Set Base Priority with condition + \details Assigns the given value to the Base Priority register only if BASEPRI masking is disabled, + or the new value increases the BASEPRI priority level. + \param [in] basePri Base Priority value to set + */ +__STATIC_FORCEINLINE void __set_BASEPRI_MAX(uint32_t basePri) +{ + __ASM volatile ("MSR basepri_max, %0" : : "r" (basePri) : "memory"); +} + + +/** + \brief Get Fault Mask + \details Returns the current value of the Fault Mask register. + \return Fault Mask register value + */ +__STATIC_FORCEINLINE uint32_t __get_FAULTMASK(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, faultmask" : "=r" (result) ); + return(result); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Fault Mask (non-secure) + \details Returns the current value of the non-secure Fault Mask register when in secure state. + \return Fault Mask register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_FAULTMASK_NS(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, faultmask_ns" : "=r" (result) ); + return(result); +} +#endif + + +/** + \brief Set Fault Mask + \details Assigns the given value to the Fault Mask register. + \param [in] faultMask Fault Mask value to set + */ +__STATIC_FORCEINLINE void __set_FAULTMASK(uint32_t faultMask) +{ + __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) : "memory"); +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Fault Mask (non-secure) + \details Assigns the given value to the non-secure Fault Mask register when in secure state. + \param [in] faultMask Fault Mask value to set + */ +__STATIC_FORCEINLINE void __TZ_set_FAULTMASK_NS(uint32_t faultMask) +{ + __ASM volatile ("MSR faultmask_ns, %0" : : "r" (faultMask) : "memory"); +} +#endif + +#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ + + +#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) + +/** + \brief Get Process Stack Pointer Limit + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence zero is returned always in non-secure + mode. + + \details Returns the current value of the Process Stack Pointer Limit (PSPLIM). + \return PSPLIM Register value + */ +__STATIC_FORCEINLINE uint32_t __get_PSPLIM(void) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + return 0U; +#else + uint32_t result; + __ASM volatile ("MRS %0, psplim" : "=r" (result) ); + return result; +#endif +} + +#if (defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Process Stack Pointer Limit (non-secure) + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence zero is returned always. + + \details Returns the current value of the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. + \return PSPLIM Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_PSPLIM_NS(void) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + return 0U; +#else + uint32_t result; + __ASM volatile ("MRS %0, psplim_ns" : "=r" (result) ); + return result; +#endif +} +#endif + + +/** + \brief Set Process Stack Pointer Limit + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence the write is silently ignored in non-secure + mode. + + \details Assigns the given value to the Process Stack Pointer Limit (PSPLIM). + \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set + */ +__STATIC_FORCEINLINE void __set_PSPLIM(uint32_t ProcStackPtrLimit) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + (void)ProcStackPtrLimit; +#else + __ASM volatile ("MSR psplim, %0" : : "r" (ProcStackPtrLimit)); +#endif +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Process Stack Pointer (non-secure) + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence the write is silently ignored. + + \details Assigns the given value to the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. + \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set + */ +__STATIC_FORCEINLINE void __TZ_set_PSPLIM_NS(uint32_t ProcStackPtrLimit) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + (void)ProcStackPtrLimit; +#else + __ASM volatile ("MSR psplim_ns, %0\n" : : "r" (ProcStackPtrLimit)); +#endif +} +#endif + + +/** + \brief Get Main Stack Pointer Limit + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence zero is returned always in non-secure + mode. + + \details Returns the current value of the Main Stack Pointer Limit (MSPLIM). + \return MSPLIM Register value + */ +__STATIC_FORCEINLINE uint32_t __get_MSPLIM(void) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + return 0U; +#else + uint32_t result; + __ASM volatile ("MRS %0, msplim" : "=r" (result) ); + return result; +#endif +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Get Main Stack Pointer Limit (non-secure) + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence zero is returned always. + + \details Returns the current value of the non-secure Main Stack Pointer Limit(MSPLIM) when in secure state. + \return MSPLIM Register value + */ +__STATIC_FORCEINLINE uint32_t __TZ_get_MSPLIM_NS(void) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + return 0U; +#else + uint32_t result; + __ASM volatile ("MRS %0, msplim_ns" : "=r" (result) ); + return result; +#endif +} +#endif + + +/** + \brief Set Main Stack Pointer Limit + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence the write is silently ignored in non-secure + mode. + + \details Assigns the given value to the Main Stack Pointer Limit (MSPLIM). + \param [in] MainStackPtrLimit Main Stack Pointer Limit value to set + */ +__STATIC_FORCEINLINE void __set_MSPLIM(uint32_t MainStackPtrLimit) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + (void)MainStackPtrLimit; +#else + __ASM volatile ("MSR msplim, %0" : : "r" (MainStackPtrLimit)); +#endif +} + + +#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) +/** + \brief Set Main Stack Pointer Limit (non-secure) + Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure + Stack Pointer Limit register hence the write is silently ignored. + + \details Assigns the given value to the non-secure Main Stack Pointer Limit (MSPLIM) when in secure state. + \param [in] MainStackPtrLimit Main Stack Pointer value to set + */ +__STATIC_FORCEINLINE void __TZ_set_MSPLIM_NS(uint32_t MainStackPtrLimit) +{ +#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + (void)MainStackPtrLimit; +#else + __ASM volatile ("MSR msplim_ns, %0" : : "r" (MainStackPtrLimit)); +#endif +} +#endif + +#endif /* ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ + + +/** + \brief Get FPSCR + \details Returns the current value of the Floating Point Status/Control register. + \return Floating Point Status/Control register value + */ +__STATIC_FORCEINLINE uint32_t __get_FPSCR(void) +{ +#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ + (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) +#if __has_builtin(__builtin_arm_get_fpscr) +// Re-enable using built-in when GCC has been fixed +// || (__GNUC__ > 7) || (__GNUC__ == 7 && __GNUC_MINOR__ >= 2) + /* see https://gcc.gnu.org/ml/gcc-patches/2017-04/msg00443.html */ + return __builtin_arm_get_fpscr(); +#else + uint32_t result; + + __ASM volatile ("VMRS %0, fpscr" : "=r" (result) ); + return(result); +#endif +#else + return(0U); +#endif +} + + +/** + \brief Set FPSCR + \details Assigns the given value to the Floating Point Status/Control register. + \param [in] fpscr Floating Point Status/Control value to set + */ +__STATIC_FORCEINLINE void __set_FPSCR(uint32_t fpscr) +{ +#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ + (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) +#if __has_builtin(__builtin_arm_set_fpscr) +// Re-enable using built-in when GCC has been fixed +// || (__GNUC__ > 7) || (__GNUC__ == 7 && __GNUC_MINOR__ >= 2) + /* see https://gcc.gnu.org/ml/gcc-patches/2017-04/msg00443.html */ + __builtin_arm_set_fpscr(fpscr); +#else + __ASM volatile ("VMSR fpscr, %0" : : "r" (fpscr) : "vfpcc", "memory"); +#endif +#else + (void)fpscr; +#endif +} + + +/*@} end of CMSIS_Core_RegAccFunctions */ + + +/* ########################## Core Instruction Access ######################### */ +/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface + Access to dedicated instructions + @{ +*/ + +/* Define macros for porting to both thumb1 and thumb2. + * For thumb1, use low register (r0-r7), specified by constraint "l" + * Otherwise, use general registers, specified by constraint "r" */ +#if defined (__thumb__) && !defined (__thumb2__) +#define __CMSIS_GCC_OUT_REG(r) "=l" (r) +#define __CMSIS_GCC_RW_REG(r) "+l" (r) +#define __CMSIS_GCC_USE_REG(r) "l" (r) +#else +#define __CMSIS_GCC_OUT_REG(r) "=r" (r) +#define __CMSIS_GCC_RW_REG(r) "+r" (r) +#define __CMSIS_GCC_USE_REG(r) "r" (r) +#endif + +/** + \brief No Operation + \details No Operation does nothing. This instruction can be used for code alignment purposes. + */ +#define __NOP() __ASM volatile ("nop") + +/** + \brief Wait For Interrupt + \details Wait For Interrupt is a hint instruction that suspends execution until one of a number of events occurs. + */ +#define __WFI() __ASM volatile ("wfi":::"memory") + + +/** + \brief Wait For Event + \details 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() __ASM volatile ("wfe":::"memory") + + +/** + \brief Send Event + \details Send Event is a hint instruction. It causes an event to be signaled to the CPU. + */ +#define __SEV() __ASM volatile ("sev") + + +/** + \brief Instruction Synchronization Barrier + \details 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. + */ +__STATIC_FORCEINLINE void __ISB(void) +{ + __ASM volatile ("isb 0xF":::"memory"); +} + + +/** + \brief Data Synchronization Barrier + \details Acts as a special kind of Data Memory Barrier. + It completes when all explicit memory accesses before this instruction complete. + */ +__STATIC_FORCEINLINE void __DSB(void) +{ + __ASM volatile ("dsb 0xF":::"memory"); +} + + +/** + \brief Data Memory Barrier + \details Ensures the apparent order of the explicit memory operations before + and after the instruction, without ensuring their completion. + */ +__STATIC_FORCEINLINE void __DMB(void) +{ + __ASM volatile ("dmb 0xF":::"memory"); +} + + +/** + \brief Reverse byte order (32 bit) + \details Reverses the byte order in unsigned integer value. For example, 0x12345678 becomes 0x78563412. + \param [in] value Value to reverse + \return Reversed value + */ +__STATIC_FORCEINLINE uint32_t __REV(uint32_t value) +{ +#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 5) + return __builtin_bswap32(value); +#else + uint32_t result; + + __ASM ("rev %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); + return result; +#endif +} + + +/** + \brief Reverse byte order (16 bit) + \details Reverses the byte order within each halfword of a word. For example, 0x12345678 becomes 0x34127856. + \param [in] value Value to reverse + \return Reversed value + */ +__STATIC_FORCEINLINE uint32_t __REV16(uint32_t value) +{ + uint32_t result; + + __ASM ("rev16 %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); + return result; +} + + +/** + \brief Reverse byte order (16 bit) + \details Reverses the byte order in a 16-bit value and returns the signed 16-bit result. For example, 0x0080 becomes 0x8000. + \param [in] value Value to reverse + \return Reversed value + */ +__STATIC_FORCEINLINE int16_t __REVSH(int16_t value) +{ +#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) + return (int16_t)__builtin_bswap16(value); +#else + int16_t result; + + __ASM ("revsh %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); + return result; +#endif +} + + +/** + \brief Rotate Right in unsigned value (32 bit) + \details Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits. + \param [in] op1 Value to rotate + \param [in] op2 Number of Bits to rotate + \return Rotated value + */ +__STATIC_FORCEINLINE uint32_t __ROR(uint32_t op1, uint32_t op2) +{ + op2 %= 32U; + if (op2 == 0U) + { + return op1; + } + return (op1 >> op2) | (op1 << (32U - op2)); +} + + +/** + \brief Breakpoint + \details Causes the processor to enter Debug state. + Debug tools can use this to investigate system state when the instruction at a particular address is reached. + \param [in] value is ignored by the processor. + If required, a debugger can use it to store additional information about the breakpoint. + */ +#define __BKPT(value) __ASM volatile ("bkpt "#value) + + +/** + \brief Reverse bit order of value + \details Reverses the bit order of the given value. + \param [in] value Value to reverse + \return Reversed value + */ +__STATIC_FORCEINLINE uint32_t __RBIT(uint32_t value) +{ + uint32_t result; + +#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) + __ASM ("rbit %0, %1" : "=r" (result) : "r" (value) ); +#else + uint32_t s = (4U /*sizeof(v)*/ * 8U) - 1U; /* extra shift needed at end */ + + result = value; /* r will be reversed bits of v; first get LSB of v */ + for (value >>= 1U; value != 0U; value >>= 1U) + { + result <<= 1U; + result |= value & 1U; + s--; + } + result <<= s; /* shift when v's highest bits are zero */ +#endif + return result; +} + + +/** + \brief Count leading zeros + \details 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 + */ +__STATIC_FORCEINLINE uint8_t __CLZ(uint32_t value) +{ + /* Even though __builtin_clz produces a CLZ instruction on ARM, formally + __builtin_clz(0) is undefined behaviour, so handle this case specially. + This guarantees ARM-compatible results if happening to compile on a non-ARM + target, and ensures the compiler doesn't decide to activate any + optimisations using the logic "value was passed to __builtin_clz, so it + is non-zero". + ARM GCC 7.3 and possibly earlier will optimise this test away, leaving a + single CLZ instruction. + */ + if (value == 0U) + { + return 32U; + } + return __builtin_clz(value); +} + + +#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) +/** + \brief LDR Exclusive (8 bit) + \details Executes a exclusive LDR instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +__STATIC_FORCEINLINE uint8_t __LDREXB(volatile uint8_t *addr) +{ + uint32_t result; + +#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) + __ASM volatile ("ldrexb %0, %1" : "=r" (result) : "Q" (*addr) ); +#else + /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not + accepted by assembler. So has to use following less efficient pattern. + */ + __ASM volatile ("ldrexb %0, [%1]" : "=r" (result) : "r" (addr) : "memory" ); +#endif + return ((uint8_t) result); /* Add explicit type cast here */ +} + + +/** + \brief LDR Exclusive (16 bit) + \details Executes a exclusive LDR instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +__STATIC_FORCEINLINE uint16_t __LDREXH(volatile uint16_t *addr) +{ + uint32_t result; + +#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) + __ASM volatile ("ldrexh %0, %1" : "=r" (result) : "Q" (*addr) ); +#else + /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not + accepted by assembler. So has to use following less efficient pattern. + */ + __ASM volatile ("ldrexh %0, [%1]" : "=r" (result) : "r" (addr) : "memory" ); +#endif + return ((uint16_t) result); /* Add explicit type cast here */ +} + + +/** + \brief LDR Exclusive (32 bit) + \details Executes a exclusive LDR instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +__STATIC_FORCEINLINE uint32_t __LDREXW(volatile uint32_t *addr) +{ + uint32_t result; + + __ASM volatile ("ldrex %0, %1" : "=r" (result) : "Q" (*addr) ); + return(result); +} + + +/** + \brief STR Exclusive (8 bit) + \details Executes a exclusive STR instruction for 8 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +__STATIC_FORCEINLINE uint32_t __STREXB(uint8_t value, volatile uint8_t *addr) +{ + uint32_t result; + + __ASM volatile ("strexb %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" ((uint32_t)value) ); + return(result); +} + + +/** + \brief STR Exclusive (16 bit) + \details Executes a exclusive STR instruction for 16 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +__STATIC_FORCEINLINE uint32_t __STREXH(uint16_t value, volatile uint16_t *addr) +{ + uint32_t result; + + __ASM volatile ("strexh %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" ((uint32_t)value) ); + return(result); +} + + +/** + \brief STR Exclusive (32 bit) + \details Executes a exclusive STR instruction for 32 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +__STATIC_FORCEINLINE uint32_t __STREXW(uint32_t value, volatile uint32_t *addr) +{ + uint32_t result; + + __ASM volatile ("strex %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" (value) ); + return(result); +} + + +/** + \brief Remove the exclusive lock + \details Removes the exclusive lock which is created by LDREX. + */ +__STATIC_FORCEINLINE void __CLREX(void) +{ + __ASM volatile ("clrex" ::: "memory"); +} + +#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ + + +#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) +/** + \brief Signed Saturate + \details Saturates a signed value. + \param [in] ARG1 Value to be saturated + \param [in] ARG2 Bit position to saturate to (1..32) + \return Saturated value + */ +#define __SSAT(ARG1, ARG2) \ +__extension__ \ +({ \ + int32_t __RES, __ARG1 = (ARG1); \ + __ASM volatile ("ssat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) : "cc" ); \ + __RES; \ + }) + + +/** + \brief Unsigned Saturate + \details Saturates an unsigned value. + \param [in] ARG1 Value to be saturated + \param [in] ARG2 Bit position to saturate to (0..31) + \return Saturated value + */ +#define __USAT(ARG1, ARG2) \ + __extension__ \ +({ \ + uint32_t __RES, __ARG1 = (ARG1); \ + __ASM volatile ("usat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) : "cc" ); \ + __RES; \ + }) + + +/** + \brief Rotate Right with Extend (32 bit) + \details Moves each bit of a bitstring right by one bit. + The carry input is shifted in at the left end of the bitstring. + \param [in] value Value to rotate + \return Rotated value + */ +__STATIC_FORCEINLINE uint32_t __RRX(uint32_t value) +{ + uint32_t result; + + __ASM volatile ("rrx %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); + return(result); +} + + +/** + \brief LDRT Unprivileged (8 bit) + \details Executes a Unprivileged LDRT instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +__STATIC_FORCEINLINE uint8_t __LDRBT(volatile uint8_t *ptr) +{ + uint32_t result; + +#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) + __ASM volatile ("ldrbt %0, %1" : "=r" (result) : "Q" (*ptr) ); +#else + /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not + accepted by assembler. So has to use following less efficient pattern. + */ + __ASM volatile ("ldrbt %0, [%1]" : "=r" (result) : "r" (ptr) : "memory" ); +#endif + return ((uint8_t) result); /* Add explicit type cast here */ +} + + +/** + \brief LDRT Unprivileged (16 bit) + \details Executes a Unprivileged LDRT instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +__STATIC_FORCEINLINE uint16_t __LDRHT(volatile uint16_t *ptr) +{ + uint32_t result; + +#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) + __ASM volatile ("ldrht %0, %1" : "=r" (result) : "Q" (*ptr) ); +#else + /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not + accepted by assembler. So has to use following less efficient pattern. + */ + __ASM volatile ("ldrht %0, [%1]" : "=r" (result) : "r" (ptr) : "memory" ); +#endif + return ((uint16_t) result); /* Add explicit type cast here */ +} + + +/** + \brief LDRT Unprivileged (32 bit) + \details Executes a Unprivileged LDRT instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +__STATIC_FORCEINLINE uint32_t __LDRT(volatile uint32_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldrt %0, %1" : "=r" (result) : "Q" (*ptr) ); + return(result); +} + + +/** + \brief STRT Unprivileged (8 bit) + \details Executes a Unprivileged STRT instruction for 8 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STRBT(uint8_t value, volatile uint8_t *ptr) +{ + __ASM volatile ("strbt %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); +} + + +/** + \brief STRT Unprivileged (16 bit) + \details Executes a Unprivileged STRT instruction for 16 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STRHT(uint16_t value, volatile uint16_t *ptr) +{ + __ASM volatile ("strht %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); +} + + +/** + \brief STRT Unprivileged (32 bit) + \details Executes a Unprivileged STRT instruction for 32 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STRT(uint32_t value, volatile uint32_t *ptr) +{ + __ASM volatile ("strt %1, %0" : "=Q" (*ptr) : "r" (value) ); +} + +#else /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ + +/** + \brief Signed Saturate + \details Saturates a signed value. + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (1..32) + \return Saturated value + */ +__STATIC_FORCEINLINE int32_t __SSAT(int32_t val, uint32_t sat) +{ + if ((sat >= 1U) && (sat <= 32U)) + { + const int32_t max = (int32_t)((1U << (sat - 1U)) - 1U); + const int32_t min = -1 - max ; + if (val > max) + { + return max; + } + else if (val < min) + { + return min; + } + } + return val; +} + +/** + \brief Unsigned Saturate + \details Saturates an unsigned value. + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (0..31) + \return Saturated value + */ +__STATIC_FORCEINLINE uint32_t __USAT(int32_t val, uint32_t sat) +{ + if (sat <= 31U) + { + const uint32_t max = ((1U << sat) - 1U); + if (val > (int32_t)max) + { + return max; + } + else if (val < 0) + { + return 0U; + } + } + return (uint32_t)val; +} + +#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ + + +#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) +/** + \brief Load-Acquire (8 bit) + \details Executes a LDAB instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +__STATIC_FORCEINLINE uint8_t __LDAB(volatile uint8_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldab %0, %1" : "=r" (result) : "Q" (*ptr) : "memory" ); + return ((uint8_t) result); +} + + +/** + \brief Load-Acquire (16 bit) + \details Executes a LDAH instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +__STATIC_FORCEINLINE uint16_t __LDAH(volatile uint16_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldah %0, %1" : "=r" (result) : "Q" (*ptr) : "memory" ); + return ((uint16_t) result); +} + + +/** + \brief Load-Acquire (32 bit) + \details Executes a LDA instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +__STATIC_FORCEINLINE uint32_t __LDA(volatile uint32_t *ptr) +{ + uint32_t result; + + __ASM volatile ("lda %0, %1" : "=r" (result) : "Q" (*ptr) : "memory" ); + return(result); +} + + +/** + \brief Store-Release (8 bit) + \details Executes a STLB instruction for 8 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STLB(uint8_t value, volatile uint8_t *ptr) +{ + __ASM volatile ("stlb %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) : "memory" ); +} + + +/** + \brief Store-Release (16 bit) + \details Executes a STLH instruction for 16 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STLH(uint16_t value, volatile uint16_t *ptr) +{ + __ASM volatile ("stlh %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) : "memory" ); +} + + +/** + \brief Store-Release (32 bit) + \details Executes a STL instruction for 32 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__STATIC_FORCEINLINE void __STL(uint32_t value, volatile uint32_t *ptr) +{ + __ASM volatile ("stl %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) : "memory" ); +} + + +/** + \brief Load-Acquire Exclusive (8 bit) + \details Executes a LDAB exclusive instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +__STATIC_FORCEINLINE uint8_t __LDAEXB(volatile uint8_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldaexb %0, %1" : "=r" (result) : "Q" (*ptr) : "memory" ); + return ((uint8_t) result); +} + + +/** + \brief Load-Acquire Exclusive (16 bit) + \details Executes a LDAH exclusive instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +__STATIC_FORCEINLINE uint16_t __LDAEXH(volatile uint16_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldaexh %0, %1" : "=r" (result) : "Q" (*ptr) : "memory" ); + return ((uint16_t) result); +} + + +/** + \brief Load-Acquire Exclusive (32 bit) + \details Executes a LDA exclusive instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +__STATIC_FORCEINLINE uint32_t __LDAEX(volatile uint32_t *ptr) +{ + uint32_t result; + + __ASM volatile ("ldaex %0, %1" : "=r" (result) : "Q" (*ptr) : "memory" ); + return(result); +} + + +/** + \brief Store-Release Exclusive (8 bit) + \details Executes a STLB exclusive instruction for 8 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +__STATIC_FORCEINLINE uint32_t __STLEXB(uint8_t value, volatile uint8_t *ptr) +{ + uint32_t result; + + __ASM volatile ("stlexb %0, %2, %1" : "=&r" (result), "=Q" (*ptr) : "r" ((uint32_t)value) : "memory" ); + return(result); +} + + +/** + \brief Store-Release Exclusive (16 bit) + \details Executes a STLH exclusive instruction for 16 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +__STATIC_FORCEINLINE uint32_t __STLEXH(uint16_t value, volatile uint16_t *ptr) +{ + uint32_t result; + + __ASM volatile ("stlexh %0, %2, %1" : "=&r" (result), "=Q" (*ptr) : "r" ((uint32_t)value) : "memory" ); + return(result); +} + + +/** + \brief Store-Release Exclusive (32 bit) + \details Executes a STL exclusive instruction for 32 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +__STATIC_FORCEINLINE uint32_t __STLEX(uint32_t value, volatile uint32_t *ptr) +{ + uint32_t result; + + __ASM volatile ("stlex %0, %2, %1" : "=&r" (result), "=Q" (*ptr) : "r" ((uint32_t)value) : "memory" ); + return(result); +} + +#endif /* ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ + +/*@}*/ /* end of group CMSIS_Core_InstructionInterface */ + + +/* ################### Compiler specific Intrinsics ########################### */ +/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics + Access to dedicated SIMD instructions + @{ +*/ + +#if (defined (__ARM_FEATURE_DSP) && (__ARM_FEATURE_DSP == 1)) + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE uint32_t __QADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("qadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SHADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("shadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE uint32_t __UQADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("uqadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UHADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("uhadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE uint32_t __QSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("qsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SHSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("shsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE uint32_t __UQSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("uqsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UHSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("uhsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE uint32_t __QADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("qadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SHADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("shadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE uint32_t __UQADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("uqadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UHADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("uhadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE uint32_t __QSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("qsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SHSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("shsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE uint32_t __UQSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("uqsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UHSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("uhsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE uint32_t __QASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("qasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SHASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("shasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE uint32_t __UQASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("uqasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UHASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("uhasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE uint32_t __QSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("qsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SHSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("shsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE uint32_t __UQSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("uqsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UHSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("uhsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __USAD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("usad8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __USADA8(uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM ("usada8 %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +#define __SSAT16(ARG1, ARG2) \ +({ \ + int32_t __RES, __ARG1 = (ARG1); \ + __ASM volatile ("ssat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) : "cc" ); \ + __RES; \ + }) + +#define __USAT16(ARG1, ARG2) \ +({ \ + uint32_t __RES, __ARG1 = (ARG1); \ + __ASM volatile ("usat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) : "cc" ); \ + __RES; \ + }) + +__STATIC_FORCEINLINE uint32_t __UXTB16(uint32_t op1) +{ + uint32_t result; + + __ASM ("uxtb16 %0, %1" : "=r" (result) : "r" (op1)); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __UXTAB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("uxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SXTB16(uint32_t op1) +{ + uint32_t result; + + __ASM ("sxtb16 %0, %1" : "=r" (result) : "r" (op1)); + return(result); +} + +__STATIC_FORCEINLINE uint32_t __SXTB16_RORn(uint32_t op1, uint32_t rotate) +{ + uint32_t result; + + __ASM ("sxtb16 %0, %1, ROR %2" : "=r" (result) : "r" (op1), "i" (rotate) ); + + return result; +} + +__STATIC_FORCEINLINE uint32_t __SXTAB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM ("sxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE uint64_t __SMLALD (uint32_t op1, uint32_t op2, uint64_t acc) +{ + union llreg_u{ + uint32_t w32[2]; + uint64_t w64; + } llr; + llr.w64 = acc; + +#ifndef __ARMEB__ /* Little endian */ + __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); +#else /* Big endian */ + __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); +#endif + + return(llr.w64); +} + +__STATIC_FORCEINLINE uint64_t __SMLALDX (uint32_t op1, uint32_t op2, uint64_t acc) +{ + union llreg_u{ + uint32_t w32[2]; + uint64_t w64; + } llr; + llr.w64 = acc; + +#ifndef __ARMEB__ /* Little endian */ + __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); +#else /* Big endian */ + __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); +#endif + + return(llr.w64); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE uint64_t __SMLSLD (uint32_t op1, uint32_t op2, uint64_t acc) +{ + union llreg_u{ + uint32_t w32[2]; + uint64_t w64; + } llr; + llr.w64 = acc; + +#ifndef __ARMEB__ /* Little endian */ + __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); +#else /* Big endian */ + __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); +#endif + + return(llr.w64); +} + +__STATIC_FORCEINLINE uint64_t __SMLSLDX (uint32_t op1, uint32_t op2, uint64_t acc) +{ + union llreg_u{ + uint32_t w32[2]; + uint64_t w64; + } llr; + llr.w64 = acc; + +#ifndef __ARMEB__ /* Little endian */ + __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); +#else /* Big endian */ + __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); +#endif + + return(llr.w64); +} + +__STATIC_FORCEINLINE 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); +} + +__STATIC_FORCEINLINE int32_t __QADD( int32_t op1, int32_t op2) +{ + int32_t result; + + __ASM volatile ("qadd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__STATIC_FORCEINLINE int32_t __QSUB( int32_t op1, int32_t op2) +{ + int32_t result; + + __ASM volatile ("qsub %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +#if 0 +#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; \ + }) +#endif + +#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) ) + +__STATIC_FORCEINLINE int32_t __SMMLA (int32_t op1, int32_t op2, int32_t op3) +{ + int32_t result; + + __ASM ("smmla %0, %1, %2, %3" : "=r" (result): "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +#endif /* (__ARM_FEATURE_DSP == 1) */ +/*@} end of group CMSIS_SIMD_intrinsics */ + + +#pragma GCC diagnostic pop + +#endif /* __CMSIS_GCC_H */ diff --git a/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_iccarm.h b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_iccarm.h new file mode 100644 index 0000000000..b9c90bf7ba --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_iccarm.h @@ -0,0 +1,968 @@ +/****************************************************************************** + * @file cmsis_iccarm.h + * @brief CMSIS compiler ICCARM (IAR Compiler for Arm) header file + * @version V5.2.0 + * @date 28. January 2020 + ******************************************************************************/ + +//------------------------------------------------------------------------------ +// +// Copyright (c) 2017-2019 IAR Systems +// Copyright (c) 2017-2019 Arm Limited. All rights reserved. +// +// SPDX-License-Identifier: Apache-2.0 +// +// Licensed under the Apache License, Version 2.0 (the "License") +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +//------------------------------------------------------------------------------ + + +#ifndef __CMSIS_ICCARM_H__ +#define __CMSIS_ICCARM_H__ + +#ifndef __ICCARM__ + #error This file should only be compiled by ICCARM +#endif + +#pragma system_include + +#define __IAR_FT _Pragma("inline=forced") __intrinsic + +#if (__VER__ >= 8000000) + #define __ICCARM_V8 1 +#else + #define __ICCARM_V8 0 +#endif + +#ifndef __ALIGNED + #if __ICCARM_V8 + #define __ALIGNED(x) __attribute__((aligned(x))) + #elif (__VER__ >= 7080000) + /* Needs IAR language extensions */ + #define __ALIGNED(x) __attribute__((aligned(x))) + #else + #warning No compiler specific solution for __ALIGNED.__ALIGNED is ignored. + #define __ALIGNED(x) + #endif +#endif + + +/* Define compiler macros for CPU architecture, used in CMSIS 5. + */ +#if __ARM_ARCH_6M__ || __ARM_ARCH_7M__ || __ARM_ARCH_7EM__ || __ARM_ARCH_8M_BASE__ || __ARM_ARCH_8M_MAIN__ +/* Macros already defined */ +#else + #if defined(__ARM8M_MAINLINE__) || defined(__ARM8EM_MAINLINE__) + #define __ARM_ARCH_8M_MAIN__ 1 + #elif defined(__ARM8M_BASELINE__) + #define __ARM_ARCH_8M_BASE__ 1 + #elif defined(__ARM_ARCH_PROFILE) && __ARM_ARCH_PROFILE == 'M' + #if __ARM_ARCH == 6 + #define __ARM_ARCH_6M__ 1 + #elif __ARM_ARCH == 7 + #if __ARM_FEATURE_DSP + #define __ARM_ARCH_7EM__ 1 + #else + #define __ARM_ARCH_7M__ 1 + #endif + #endif /* __ARM_ARCH */ + #endif /* __ARM_ARCH_PROFILE == 'M' */ +#endif + +/* Alternativ core deduction for older ICCARM's */ +#if !defined(__ARM_ARCH_6M__) && !defined(__ARM_ARCH_7M__) && !defined(__ARM_ARCH_7EM__) && \ + !defined(__ARM_ARCH_8M_BASE__) && !defined(__ARM_ARCH_8M_MAIN__) + #if defined(__ARM6M__) && (__CORE__ == __ARM6M__) + #define __ARM_ARCH_6M__ 1 + #elif defined(__ARM7M__) && (__CORE__ == __ARM7M__) + #define __ARM_ARCH_7M__ 1 + #elif defined(__ARM7EM__) && (__CORE__ == __ARM7EM__) + #define __ARM_ARCH_7EM__ 1 + #elif defined(__ARM8M_BASELINE__) && (__CORE == __ARM8M_BASELINE__) + #define __ARM_ARCH_8M_BASE__ 1 + #elif defined(__ARM8M_MAINLINE__) && (__CORE == __ARM8M_MAINLINE__) + #define __ARM_ARCH_8M_MAIN__ 1 + #elif defined(__ARM8EM_MAINLINE__) && (__CORE == __ARM8EM_MAINLINE__) + #define __ARM_ARCH_8M_MAIN__ 1 + #else + #error "Unknown target." + #endif +#endif + + + +#if defined(__ARM_ARCH_6M__) && __ARM_ARCH_6M__==1 + #define __IAR_M0_FAMILY 1 +#elif defined(__ARM_ARCH_8M_BASE__) && __ARM_ARCH_8M_BASE__==1 + #define __IAR_M0_FAMILY 1 +#else + #define __IAR_M0_FAMILY 0 +#endif + + +#ifndef __ASM + #define __ASM __asm +#endif + +#ifndef __COMPILER_BARRIER + #define __COMPILER_BARRIER() __ASM volatile("":::"memory") +#endif + +#ifndef __INLINE + #define __INLINE inline +#endif + +#ifndef __NO_RETURN + #if __ICCARM_V8 + #define __NO_RETURN __attribute__((__noreturn__)) + #else + #define __NO_RETURN _Pragma("object_attribute=__noreturn") + #endif +#endif + +#ifndef __PACKED + #if __ICCARM_V8 + #define __PACKED __attribute__((packed, aligned(1))) + #else + /* Needs IAR language extensions */ + #define __PACKED __packed + #endif +#endif + +#ifndef __PACKED_STRUCT + #if __ICCARM_V8 + #define __PACKED_STRUCT struct __attribute__((packed, aligned(1))) + #else + /* Needs IAR language extensions */ + #define __PACKED_STRUCT __packed struct + #endif +#endif + +#ifndef __PACKED_UNION + #if __ICCARM_V8 + #define __PACKED_UNION union __attribute__((packed, aligned(1))) + #else + /* Needs IAR language extensions */ + #define __PACKED_UNION __packed union + #endif +#endif + +#ifndef __RESTRICT + #if __ICCARM_V8 + #define __RESTRICT __restrict + #else + /* Needs IAR language extensions */ + #define __RESTRICT restrict + #endif +#endif + +#ifndef __STATIC_INLINE + #define __STATIC_INLINE static inline +#endif + +#ifndef __FORCEINLINE + #define __FORCEINLINE _Pragma("inline=forced") +#endif + +#ifndef __STATIC_FORCEINLINE + #define __STATIC_FORCEINLINE __FORCEINLINE __STATIC_INLINE +#endif + +#ifndef __UNALIGNED_UINT16_READ +#pragma language=save +#pragma language=extended +__IAR_FT uint16_t __iar_uint16_read(void const *ptr) +{ + return *(__packed uint16_t*)(ptr); +} +#pragma language=restore +#define __UNALIGNED_UINT16_READ(PTR) __iar_uint16_read(PTR) +#endif + + +#ifndef __UNALIGNED_UINT16_WRITE +#pragma language=save +#pragma language=extended +__IAR_FT void __iar_uint16_write(void const *ptr, uint16_t val) +{ + *(__packed uint16_t*)(ptr) = val;; +} +#pragma language=restore +#define __UNALIGNED_UINT16_WRITE(PTR,VAL) __iar_uint16_write(PTR,VAL) +#endif + +#ifndef __UNALIGNED_UINT32_READ +#pragma language=save +#pragma language=extended +__IAR_FT uint32_t __iar_uint32_read(void const *ptr) +{ + return *(__packed uint32_t*)(ptr); +} +#pragma language=restore +#define __UNALIGNED_UINT32_READ(PTR) __iar_uint32_read(PTR) +#endif + +#ifndef __UNALIGNED_UINT32_WRITE +#pragma language=save +#pragma language=extended +__IAR_FT void __iar_uint32_write(void const *ptr, uint32_t val) +{ + *(__packed uint32_t*)(ptr) = val;; +} +#pragma language=restore +#define __UNALIGNED_UINT32_WRITE(PTR,VAL) __iar_uint32_write(PTR,VAL) +#endif + +#ifndef __UNALIGNED_UINT32 /* deprecated */ +#pragma language=save +#pragma language=extended +__packed struct __iar_u32 { uint32_t v; }; +#pragma language=restore +#define __UNALIGNED_UINT32(PTR) (((struct __iar_u32 *)(PTR))->v) +#endif + +#ifndef __USED + #if __ICCARM_V8 + #define __USED __attribute__((used)) + #else + #define __USED _Pragma("__root") + #endif +#endif + +#ifndef __WEAK + #if __ICCARM_V8 + #define __WEAK __attribute__((weak)) + #else + #define __WEAK _Pragma("__weak") + #endif +#endif + +#ifndef __PROGRAM_START +#define __PROGRAM_START __iar_program_start +#endif + +#ifndef __INITIAL_SP +#define __INITIAL_SP CSTACK$$Limit +#endif + +#ifndef __STACK_LIMIT +#define __STACK_LIMIT CSTACK$$Base +#endif + +#ifndef __VECTOR_TABLE +#define __VECTOR_TABLE __vector_table +#endif + +#ifndef __VECTOR_TABLE_ATTRIBUTE +#define __VECTOR_TABLE_ATTRIBUTE @".intvec" +#endif + +#ifndef __ICCARM_INTRINSICS_VERSION__ + #define __ICCARM_INTRINSICS_VERSION__ 0 +#endif + +#if __ICCARM_INTRINSICS_VERSION__ == 2 + + #if defined(__CLZ) + #undef __CLZ + #endif + #if defined(__REVSH) + #undef __REVSH + #endif + #if defined(__RBIT) + #undef __RBIT + #endif + #if defined(__SSAT) + #undef __SSAT + #endif + #if defined(__USAT) + #undef __USAT + #endif + + #include "iccarm_builtin.h" + + #define __disable_fault_irq __iar_builtin_disable_fiq + #define __disable_irq __iar_builtin_disable_interrupt + #define __enable_fault_irq __iar_builtin_enable_fiq + #define __enable_irq __iar_builtin_enable_interrupt + #define __arm_rsr __iar_builtin_rsr + #define __arm_wsr __iar_builtin_wsr + + + #define __get_APSR() (__arm_rsr("APSR")) + #define __get_BASEPRI() (__arm_rsr("BASEPRI")) + #define __get_CONTROL() (__arm_rsr("CONTROL")) + #define __get_FAULTMASK() (__arm_rsr("FAULTMASK")) + + #if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ + (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) + #define __get_FPSCR() (__arm_rsr("FPSCR")) + #define __set_FPSCR(VALUE) (__arm_wsr("FPSCR", (VALUE))) + #else + #define __get_FPSCR() ( 0 ) + #define __set_FPSCR(VALUE) ((void)VALUE) + #endif + + #define __get_IPSR() (__arm_rsr("IPSR")) + #define __get_MSP() (__arm_rsr("MSP")) + #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + #define __get_MSPLIM() (0U) + #else + #define __get_MSPLIM() (__arm_rsr("MSPLIM")) + #endif + #define __get_PRIMASK() (__arm_rsr("PRIMASK")) + #define __get_PSP() (__arm_rsr("PSP")) + + #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + #define __get_PSPLIM() (0U) + #else + #define __get_PSPLIM() (__arm_rsr("PSPLIM")) + #endif + + #define __get_xPSR() (__arm_rsr("xPSR")) + + #define __set_BASEPRI(VALUE) (__arm_wsr("BASEPRI", (VALUE))) + #define __set_BASEPRI_MAX(VALUE) (__arm_wsr("BASEPRI_MAX", (VALUE))) + #define __set_CONTROL(VALUE) (__arm_wsr("CONTROL", (VALUE))) + #define __set_FAULTMASK(VALUE) (__arm_wsr("FAULTMASK", (VALUE))) + #define __set_MSP(VALUE) (__arm_wsr("MSP", (VALUE))) + + #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + #define __set_MSPLIM(VALUE) ((void)(VALUE)) + #else + #define __set_MSPLIM(VALUE) (__arm_wsr("MSPLIM", (VALUE))) + #endif + #define __set_PRIMASK(VALUE) (__arm_wsr("PRIMASK", (VALUE))) + #define __set_PSP(VALUE) (__arm_wsr("PSP", (VALUE))) + #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + #define __set_PSPLIM(VALUE) ((void)(VALUE)) + #else + #define __set_PSPLIM(VALUE) (__arm_wsr("PSPLIM", (VALUE))) + #endif + + #define __TZ_get_CONTROL_NS() (__arm_rsr("CONTROL_NS")) + #define __TZ_set_CONTROL_NS(VALUE) (__arm_wsr("CONTROL_NS", (VALUE))) + #define __TZ_get_PSP_NS() (__arm_rsr("PSP_NS")) + #define __TZ_set_PSP_NS(VALUE) (__arm_wsr("PSP_NS", (VALUE))) + #define __TZ_get_MSP_NS() (__arm_rsr("MSP_NS")) + #define __TZ_set_MSP_NS(VALUE) (__arm_wsr("MSP_NS", (VALUE))) + #define __TZ_get_SP_NS() (__arm_rsr("SP_NS")) + #define __TZ_set_SP_NS(VALUE) (__arm_wsr("SP_NS", (VALUE))) + #define __TZ_get_PRIMASK_NS() (__arm_rsr("PRIMASK_NS")) + #define __TZ_set_PRIMASK_NS(VALUE) (__arm_wsr("PRIMASK_NS", (VALUE))) + #define __TZ_get_BASEPRI_NS() (__arm_rsr("BASEPRI_NS")) + #define __TZ_set_BASEPRI_NS(VALUE) (__arm_wsr("BASEPRI_NS", (VALUE))) + #define __TZ_get_FAULTMASK_NS() (__arm_rsr("FAULTMASK_NS")) + #define __TZ_set_FAULTMASK_NS(VALUE)(__arm_wsr("FAULTMASK_NS", (VALUE))) + + #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + #define __TZ_get_PSPLIM_NS() (0U) + #define __TZ_set_PSPLIM_NS(VALUE) ((void)(VALUE)) + #else + #define __TZ_get_PSPLIM_NS() (__arm_rsr("PSPLIM_NS")) + #define __TZ_set_PSPLIM_NS(VALUE) (__arm_wsr("PSPLIM_NS", (VALUE))) + #endif + + #define __TZ_get_MSPLIM_NS() (__arm_rsr("MSPLIM_NS")) + #define __TZ_set_MSPLIM_NS(VALUE) (__arm_wsr("MSPLIM_NS", (VALUE))) + + #define __NOP __iar_builtin_no_operation + + #define __CLZ __iar_builtin_CLZ + #define __CLREX __iar_builtin_CLREX + + #define __DMB __iar_builtin_DMB + #define __DSB __iar_builtin_DSB + #define __ISB __iar_builtin_ISB + + #define __LDREXB __iar_builtin_LDREXB + #define __LDREXH __iar_builtin_LDREXH + #define __LDREXW __iar_builtin_LDREX + + #define __RBIT __iar_builtin_RBIT + #define __REV __iar_builtin_REV + #define __REV16 __iar_builtin_REV16 + + __IAR_FT int16_t __REVSH(int16_t val) + { + return (int16_t) __iar_builtin_REVSH(val); + } + + #define __ROR __iar_builtin_ROR + #define __RRX __iar_builtin_RRX + + #define __SEV __iar_builtin_SEV + + #if !__IAR_M0_FAMILY + #define __SSAT __iar_builtin_SSAT + #endif + + #define __STREXB __iar_builtin_STREXB + #define __STREXH __iar_builtin_STREXH + #define __STREXW __iar_builtin_STREX + + #if !__IAR_M0_FAMILY + #define __USAT __iar_builtin_USAT + #endif + + #define __WFE __iar_builtin_WFE + #define __WFI __iar_builtin_WFI + + #if __ARM_MEDIA__ + #define __SADD8 __iar_builtin_SADD8 + #define __QADD8 __iar_builtin_QADD8 + #define __SHADD8 __iar_builtin_SHADD8 + #define __UADD8 __iar_builtin_UADD8 + #define __UQADD8 __iar_builtin_UQADD8 + #define __UHADD8 __iar_builtin_UHADD8 + #define __SSUB8 __iar_builtin_SSUB8 + #define __QSUB8 __iar_builtin_QSUB8 + #define __SHSUB8 __iar_builtin_SHSUB8 + #define __USUB8 __iar_builtin_USUB8 + #define __UQSUB8 __iar_builtin_UQSUB8 + #define __UHSUB8 __iar_builtin_UHSUB8 + #define __SADD16 __iar_builtin_SADD16 + #define __QADD16 __iar_builtin_QADD16 + #define __SHADD16 __iar_builtin_SHADD16 + #define __UADD16 __iar_builtin_UADD16 + #define __UQADD16 __iar_builtin_UQADD16 + #define __UHADD16 __iar_builtin_UHADD16 + #define __SSUB16 __iar_builtin_SSUB16 + #define __QSUB16 __iar_builtin_QSUB16 + #define __SHSUB16 __iar_builtin_SHSUB16 + #define __USUB16 __iar_builtin_USUB16 + #define __UQSUB16 __iar_builtin_UQSUB16 + #define __UHSUB16 __iar_builtin_UHSUB16 + #define __SASX __iar_builtin_SASX + #define __QASX __iar_builtin_QASX + #define __SHASX __iar_builtin_SHASX + #define __UASX __iar_builtin_UASX + #define __UQASX __iar_builtin_UQASX + #define __UHASX __iar_builtin_UHASX + #define __SSAX __iar_builtin_SSAX + #define __QSAX __iar_builtin_QSAX + #define __SHSAX __iar_builtin_SHSAX + #define __USAX __iar_builtin_USAX + #define __UQSAX __iar_builtin_UQSAX + #define __UHSAX __iar_builtin_UHSAX + #define __USAD8 __iar_builtin_USAD8 + #define __USADA8 __iar_builtin_USADA8 + #define __SSAT16 __iar_builtin_SSAT16 + #define __USAT16 __iar_builtin_USAT16 + #define __UXTB16 __iar_builtin_UXTB16 + #define __UXTAB16 __iar_builtin_UXTAB16 + #define __SXTB16 __iar_builtin_SXTB16 + #define __SXTAB16 __iar_builtin_SXTAB16 + #define __SMUAD __iar_builtin_SMUAD + #define __SMUADX __iar_builtin_SMUADX + #define __SMMLA __iar_builtin_SMMLA + #define __SMLAD __iar_builtin_SMLAD + #define __SMLADX __iar_builtin_SMLADX + #define __SMLALD __iar_builtin_SMLALD + #define __SMLALDX __iar_builtin_SMLALDX + #define __SMUSD __iar_builtin_SMUSD + #define __SMUSDX __iar_builtin_SMUSDX + #define __SMLSD __iar_builtin_SMLSD + #define __SMLSDX __iar_builtin_SMLSDX + #define __SMLSLD __iar_builtin_SMLSLD + #define __SMLSLDX __iar_builtin_SMLSLDX + #define __SEL __iar_builtin_SEL + #define __QADD __iar_builtin_QADD + #define __QSUB __iar_builtin_QSUB + #define __PKHBT __iar_builtin_PKHBT + #define __PKHTB __iar_builtin_PKHTB + #endif + +#else /* __ICCARM_INTRINSICS_VERSION__ == 2 */ + + #if __IAR_M0_FAMILY + /* Avoid clash between intrinsics.h and arm_math.h when compiling for Cortex-M0. */ + #define __CLZ __cmsis_iar_clz_not_active + #define __SSAT __cmsis_iar_ssat_not_active + #define __USAT __cmsis_iar_usat_not_active + #define __RBIT __cmsis_iar_rbit_not_active + #define __get_APSR __cmsis_iar_get_APSR_not_active + #endif + + + #if (!((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ + (defined (__FPU_USED ) && (__FPU_USED == 1U)) )) + #define __get_FPSCR __cmsis_iar_get_FPSR_not_active + #define __set_FPSCR __cmsis_iar_set_FPSR_not_active + #endif + + #ifdef __INTRINSICS_INCLUDED + #error intrinsics.h is already included previously! + #endif + + #include + + #if __IAR_M0_FAMILY + /* Avoid clash between intrinsics.h and arm_math.h when compiling for Cortex-M0. */ + #undef __CLZ + #undef __SSAT + #undef __USAT + #undef __RBIT + #undef __get_APSR + + __STATIC_INLINE uint8_t __CLZ(uint32_t data) + { + if (data == 0U) { return 32U; } + + uint32_t count = 0U; + uint32_t mask = 0x80000000U; + + while ((data & mask) == 0U) + { + count += 1U; + mask = mask >> 1U; + } + return count; + } + + __STATIC_INLINE uint32_t __RBIT(uint32_t v) + { + uint8_t sc = 31U; + uint32_t r = v; + for (v >>= 1U; v; v >>= 1U) + { + r <<= 1U; + r |= v & 1U; + sc--; + } + return (r << sc); + } + + __STATIC_INLINE uint32_t __get_APSR(void) + { + uint32_t res; + __asm("MRS %0,APSR" : "=r" (res)); + return res; + } + + #endif + + #if (!((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ + (defined (__FPU_USED ) && (__FPU_USED == 1U)) )) + #undef __get_FPSCR + #undef __set_FPSCR + #define __get_FPSCR() (0) + #define __set_FPSCR(VALUE) ((void)VALUE) + #endif + + #pragma diag_suppress=Pe940 + #pragma diag_suppress=Pe177 + + #define __enable_irq __enable_interrupt + #define __disable_irq __disable_interrupt + #define __NOP __no_operation + + #define __get_xPSR __get_PSR + + #if (!defined(__ARM_ARCH_6M__) || __ARM_ARCH_6M__==0) + + __IAR_FT uint32_t __LDREXW(uint32_t volatile *ptr) + { + return __LDREX((unsigned long *)ptr); + } + + __IAR_FT uint32_t __STREXW(uint32_t value, uint32_t volatile *ptr) + { + return __STREX(value, (unsigned long *)ptr); + } + #endif + + + /* __CORTEX_M is defined in core_cm0.h, core_cm3.h and core_cm4.h. */ + #if (__CORTEX_M >= 0x03) + + __IAR_FT uint32_t __RRX(uint32_t value) + { + uint32_t result; + __ASM volatile("RRX %0, %1" : "=r"(result) : "r" (value)); + return(result); + } + + __IAR_FT void __set_BASEPRI_MAX(uint32_t value) + { + __asm volatile("MSR BASEPRI_MAX,%0"::"r" (value)); + } + + + #define __enable_fault_irq __enable_fiq + #define __disable_fault_irq __disable_fiq + + + #endif /* (__CORTEX_M >= 0x03) */ + + __IAR_FT uint32_t __ROR(uint32_t op1, uint32_t op2) + { + return (op1 >> op2) | (op1 << ((sizeof(op1)*8)-op2)); + } + + #if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) + + __IAR_FT uint32_t __get_MSPLIM(void) + { + uint32_t res; + #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + res = 0U; + #else + __asm volatile("MRS %0,MSPLIM" : "=r" (res)); + #endif + return res; + } + + __IAR_FT void __set_MSPLIM(uint32_t value) + { + #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure MSPLIM is RAZ/WI + (void)value; + #else + __asm volatile("MSR MSPLIM,%0" :: "r" (value)); + #endif + } + + __IAR_FT uint32_t __get_PSPLIM(void) + { + uint32_t res; + #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + res = 0U; + #else + __asm volatile("MRS %0,PSPLIM" : "=r" (res)); + #endif + return res; + } + + __IAR_FT void __set_PSPLIM(uint32_t value) + { + #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + (void)value; + #else + __asm volatile("MSR PSPLIM,%0" :: "r" (value)); + #endif + } + + __IAR_FT uint32_t __TZ_get_CONTROL_NS(void) + { + uint32_t res; + __asm volatile("MRS %0,CONTROL_NS" : "=r" (res)); + return res; + } + + __IAR_FT void __TZ_set_CONTROL_NS(uint32_t value) + { + __asm volatile("MSR CONTROL_NS,%0" :: "r" (value)); + } + + __IAR_FT uint32_t __TZ_get_PSP_NS(void) + { + uint32_t res; + __asm volatile("MRS %0,PSP_NS" : "=r" (res)); + return res; + } + + __IAR_FT void __TZ_set_PSP_NS(uint32_t value) + { + __asm volatile("MSR PSP_NS,%0" :: "r" (value)); + } + + __IAR_FT uint32_t __TZ_get_MSP_NS(void) + { + uint32_t res; + __asm volatile("MRS %0,MSP_NS" : "=r" (res)); + return res; + } + + __IAR_FT void __TZ_set_MSP_NS(uint32_t value) + { + __asm volatile("MSR MSP_NS,%0" :: "r" (value)); + } + + __IAR_FT uint32_t __TZ_get_SP_NS(void) + { + uint32_t res; + __asm volatile("MRS %0,SP_NS" : "=r" (res)); + return res; + } + __IAR_FT void __TZ_set_SP_NS(uint32_t value) + { + __asm volatile("MSR SP_NS,%0" :: "r" (value)); + } + + __IAR_FT uint32_t __TZ_get_PRIMASK_NS(void) + { + uint32_t res; + __asm volatile("MRS %0,PRIMASK_NS" : "=r" (res)); + return res; + } + + __IAR_FT void __TZ_set_PRIMASK_NS(uint32_t value) + { + __asm volatile("MSR PRIMASK_NS,%0" :: "r" (value)); + } + + __IAR_FT uint32_t __TZ_get_BASEPRI_NS(void) + { + uint32_t res; + __asm volatile("MRS %0,BASEPRI_NS" : "=r" (res)); + return res; + } + + __IAR_FT void __TZ_set_BASEPRI_NS(uint32_t value) + { + __asm volatile("MSR BASEPRI_NS,%0" :: "r" (value)); + } + + __IAR_FT uint32_t __TZ_get_FAULTMASK_NS(void) + { + uint32_t res; + __asm volatile("MRS %0,FAULTMASK_NS" : "=r" (res)); + return res; + } + + __IAR_FT void __TZ_set_FAULTMASK_NS(uint32_t value) + { + __asm volatile("MSR FAULTMASK_NS,%0" :: "r" (value)); + } + + __IAR_FT uint32_t __TZ_get_PSPLIM_NS(void) + { + uint32_t res; + #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + res = 0U; + #else + __asm volatile("MRS %0,PSPLIM_NS" : "=r" (res)); + #endif + return res; + } + + __IAR_FT void __TZ_set_PSPLIM_NS(uint32_t value) + { + #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ + (!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3))) + // without main extensions, the non-secure PSPLIM is RAZ/WI + (void)value; + #else + __asm volatile("MSR PSPLIM_NS,%0" :: "r" (value)); + #endif + } + + __IAR_FT uint32_t __TZ_get_MSPLIM_NS(void) + { + uint32_t res; + __asm volatile("MRS %0,MSPLIM_NS" : "=r" (res)); + return res; + } + + __IAR_FT void __TZ_set_MSPLIM_NS(uint32_t value) + { + __asm volatile("MSR MSPLIM_NS,%0" :: "r" (value)); + } + + #endif /* __ARM_ARCH_8M_MAIN__ or __ARM_ARCH_8M_BASE__ */ + +#endif /* __ICCARM_INTRINSICS_VERSION__ == 2 */ + +#define __BKPT(value) __asm volatile ("BKPT %0" : : "i"(value)) + +#if __IAR_M0_FAMILY + __STATIC_INLINE int32_t __SSAT(int32_t val, uint32_t sat) + { + if ((sat >= 1U) && (sat <= 32U)) + { + const int32_t max = (int32_t)((1U << (sat - 1U)) - 1U); + const int32_t min = -1 - max ; + if (val > max) + { + return max; + } + else if (val < min) + { + return min; + } + } + return val; + } + + __STATIC_INLINE uint32_t __USAT(int32_t val, uint32_t sat) + { + if (sat <= 31U) + { + const uint32_t max = ((1U << sat) - 1U); + if (val > (int32_t)max) + { + return max; + } + else if (val < 0) + { + return 0U; + } + } + return (uint32_t)val; + } +#endif + +#if (__CORTEX_M >= 0x03) /* __CORTEX_M is defined in core_cm0.h, core_cm3.h and core_cm4.h. */ + + __IAR_FT uint8_t __LDRBT(volatile uint8_t *addr) + { + uint32_t res; + __ASM volatile ("LDRBT %0, [%1]" : "=r" (res) : "r" (addr) : "memory"); + return ((uint8_t)res); + } + + __IAR_FT uint16_t __LDRHT(volatile uint16_t *addr) + { + uint32_t res; + __ASM volatile ("LDRHT %0, [%1]" : "=r" (res) : "r" (addr) : "memory"); + return ((uint16_t)res); + } + + __IAR_FT uint32_t __LDRT(volatile uint32_t *addr) + { + uint32_t res; + __ASM volatile ("LDRT %0, [%1]" : "=r" (res) : "r" (addr) : "memory"); + return res; + } + + __IAR_FT void __STRBT(uint8_t value, volatile uint8_t *addr) + { + __ASM volatile ("STRBT %1, [%0]" : : "r" (addr), "r" ((uint32_t)value) : "memory"); + } + + __IAR_FT void __STRHT(uint16_t value, volatile uint16_t *addr) + { + __ASM volatile ("STRHT %1, [%0]" : : "r" (addr), "r" ((uint32_t)value) : "memory"); + } + + __IAR_FT void __STRT(uint32_t value, volatile uint32_t *addr) + { + __ASM volatile ("STRT %1, [%0]" : : "r" (addr), "r" (value) : "memory"); + } + +#endif /* (__CORTEX_M >= 0x03) */ + +#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) + + + __IAR_FT uint8_t __LDAB(volatile uint8_t *ptr) + { + uint32_t res; + __ASM volatile ("LDAB %0, [%1]" : "=r" (res) : "r" (ptr) : "memory"); + return ((uint8_t)res); + } + + __IAR_FT uint16_t __LDAH(volatile uint16_t *ptr) + { + uint32_t res; + __ASM volatile ("LDAH %0, [%1]" : "=r" (res) : "r" (ptr) : "memory"); + return ((uint16_t)res); + } + + __IAR_FT uint32_t __LDA(volatile uint32_t *ptr) + { + uint32_t res; + __ASM volatile ("LDA %0, [%1]" : "=r" (res) : "r" (ptr) : "memory"); + return res; + } + + __IAR_FT void __STLB(uint8_t value, volatile uint8_t *ptr) + { + __ASM volatile ("STLB %1, [%0]" :: "r" (ptr), "r" (value) : "memory"); + } + + __IAR_FT void __STLH(uint16_t value, volatile uint16_t *ptr) + { + __ASM volatile ("STLH %1, [%0]" :: "r" (ptr), "r" (value) : "memory"); + } + + __IAR_FT void __STL(uint32_t value, volatile uint32_t *ptr) + { + __ASM volatile ("STL %1, [%0]" :: "r" (ptr), "r" (value) : "memory"); + } + + __IAR_FT uint8_t __LDAEXB(volatile uint8_t *ptr) + { + uint32_t res; + __ASM volatile ("LDAEXB %0, [%1]" : "=r" (res) : "r" (ptr) : "memory"); + return ((uint8_t)res); + } + + __IAR_FT uint16_t __LDAEXH(volatile uint16_t *ptr) + { + uint32_t res; + __ASM volatile ("LDAEXH %0, [%1]" : "=r" (res) : "r" (ptr) : "memory"); + return ((uint16_t)res); + } + + __IAR_FT uint32_t __LDAEX(volatile uint32_t *ptr) + { + uint32_t res; + __ASM volatile ("LDAEX %0, [%1]" : "=r" (res) : "r" (ptr) : "memory"); + return res; + } + + __IAR_FT uint32_t __STLEXB(uint8_t value, volatile uint8_t *ptr) + { + uint32_t res; + __ASM volatile ("STLEXB %0, %2, [%1]" : "=r" (res) : "r" (ptr), "r" (value) : "memory"); + return res; + } + + __IAR_FT uint32_t __STLEXH(uint16_t value, volatile uint16_t *ptr) + { + uint32_t res; + __ASM volatile ("STLEXH %0, %2, [%1]" : "=r" (res) : "r" (ptr), "r" (value) : "memory"); + return res; + } + + __IAR_FT uint32_t __STLEX(uint32_t value, volatile uint32_t *ptr) + { + uint32_t res; + __ASM volatile ("STLEX %0, %2, [%1]" : "=r" (res) : "r" (ptr), "r" (value) : "memory"); + return res; + } + +#endif /* __ARM_ARCH_8M_MAIN__ or __ARM_ARCH_8M_BASE__ */ + +#undef __IAR_FT +#undef __IAR_M0_FAMILY +#undef __ICCARM_V8 + +#pragma diag_default=Pe940 +#pragma diag_default=Pe177 + +#define __SXTB16_RORn(ARG1, ARG2) __SXTB16(__ROR(ARG1, ARG2)) + +#endif /* __CMSIS_ICCARM_H__ */ diff --git a/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_version.h b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_version.h new file mode 100644 index 0000000000..c999178e04 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/cmsis_version.h @@ -0,0 +1,39 @@ +/****************************************************************************** + * @file cmsis_version.h + * @brief CMSIS Core(M) Version definitions + * @version V5.0.4 + * @date 23. July 2019 + ******************************************************************************/ +/* + * Copyright (c) 2009-2019 ARM Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * 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 + * + * 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. + */ + +#if defined ( __ICCARM__ ) + #pragma system_include /* treat file as system include file for MISRA check */ +#elif defined (__clang__) + #pragma clang system_header /* treat file as system include file */ +#endif + +#ifndef __CMSIS_VERSION_H +#define __CMSIS_VERSION_H + +/* CMSIS Version definitions */ +#define __CM_CMSIS_VERSION_MAIN ( 5U) /*!< [31:16] CMSIS Core(M) main version */ +#define __CM_CMSIS_VERSION_SUB ( 4U) /*!< [15:0] CMSIS Core(M) sub version */ +#define __CM_CMSIS_VERSION ((__CM_CMSIS_VERSION_MAIN << 16U) | \ + __CM_CMSIS_VERSION_SUB ) /*!< CMSIS Core(M) version number */ +#endif diff --git a/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/core_cm4.h b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/core_cm4.h new file mode 100644 index 0000000000..0b9f9d7818 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/core_cm4.h @@ -0,0 +1,2129 @@ +/************************************************************************** + * @file core_cm4.h + * @brief CMSIS Cortex-M4 Core Peripheral Access Layer Header File + * @version V5.1.1 + * @date 27. March 2020 + ******************************************************************************/ +/* + * Copyright (c) 2009-2020 Arm Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * 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 + * + * 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. + */ + +#if defined ( __ICCARM__ ) + #pragma system_include /* treat file as system include file for MISRA check */ +#elif defined (__clang__) + #pragma clang system_header /* treat file as system include file */ +#endif + +#ifndef __CORE_CM4_H_GENERIC +#define __CORE_CM4_H_GENERIC + +#include + +#ifdef __cplusplus + extern "C" { +#endif + +/** + \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 + @{ + */ + +#include "cmsis_version.h" + +/* CMSIS CM4 definitions */ +#define __CM4_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ +#define __CM4_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ +#define __CM4_CMSIS_VERSION ((__CM4_CMSIS_VERSION_MAIN << 16U) | \ + __CM4_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ + +#define __CORTEX_M (4U) /*!< Cortex-M Core */ + +/** __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 defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) + #if defined __ARM_FP + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#elif defined ( __GNUC__ ) + #if defined (__VFP_FP__) && !defined(__SOFTFP__) + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#elif defined ( __ICCARM__ ) + #if defined __ARMVFP__ + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#elif defined ( __TI_ARM__ ) + #if defined __TI_VFP_SUPPORT__ + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#elif defined ( __TASKING__ ) + #if defined __FPU_VFP__ + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#elif defined ( __CSMC__ ) + #if ( __CSMC__ & 0x400U) + #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#endif + +#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ + + +#ifdef __cplusplus +} +#endif + +#endif /* __CORE_CM4_H_GENERIC */ + +#ifndef __CMSIS_GENERIC + +#ifndef __CORE_CM4_H_DEPENDANT +#define __CORE_CM4_H_DEPENDANT + +#ifdef __cplusplus + extern "C" { +#endif + +/* check device defines and use defaults */ +#if defined __CHECK_DEVICE_DEFINES + #ifndef __CM4_REV + #define __CM4_REV 0x0000U + #warning "__CM4_REV not defined in device header file; using default!" + #endif + + #ifndef __FPU_PRESENT + #define __FPU_PRESENT 0U + #warning "__FPU_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __MPU_PRESENT + #define __MPU_PRESENT 0U + #warning "__MPU_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __VTOR_PRESENT + #define __VTOR_PRESENT 1U + #warning "__VTOR_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __NVIC_PRIO_BITS + #define __NVIC_PRIO_BITS 3U + #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" + #endif + + #ifndef __Vendor_SysTickConfig + #define __Vendor_SysTickConfig 0U + #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 */ + +/* following defines should be used for structure members */ +#define __IM volatile const /*! Defines 'read only' structure member permissions */ +#define __OM volatile /*! Defines 'write only' structure member permissions */ +#define __IOM volatile /*! Defines 'read / write' structure member 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 + { + 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 */ + 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; + +/* APSR Register Definitions */ +#define APSR_N_Pos 31U /*!< APSR: N Position */ +#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ + +#define APSR_Z_Pos 30U /*!< APSR: Z Position */ +#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ + +#define APSR_C_Pos 29U /*!< APSR: C Position */ +#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ + +#define APSR_V_Pos 28U /*!< APSR: V Position */ +#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ + +#define APSR_Q_Pos 27U /*!< APSR: Q Position */ +#define APSR_Q_Msk (1UL << APSR_Q_Pos) /*!< APSR: Q Mask */ + +#define APSR_GE_Pos 16U /*!< APSR: GE Position */ +#define APSR_GE_Msk (0xFUL << APSR_GE_Pos) /*!< APSR: GE Mask */ + + +/** + \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; + +/* IPSR Register Definitions */ +#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ +#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ + + +/** + \brief Union type to access the Special-Purpose Program Status Registers (xPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ + uint32_t _reserved0:1; /*!< bit: 9 Reserved */ + uint32_t ICI_IT_1:6; /*!< bit: 10..15 ICI/IT part 1 */ + uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ + uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */ + uint32_t T:1; /*!< bit: 24 Thumb bit */ + uint32_t ICI_IT_2:2; /*!< bit: 25..26 ICI/IT part 2 */ + 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; + +/* xPSR Register Definitions */ +#define xPSR_N_Pos 31U /*!< xPSR: N Position */ +#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ + +#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ +#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ + +#define xPSR_C_Pos 29U /*!< xPSR: C Position */ +#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ + +#define xPSR_V_Pos 28U /*!< xPSR: V Position */ +#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ + +#define xPSR_Q_Pos 27U /*!< xPSR: Q Position */ +#define xPSR_Q_Msk (1UL << xPSR_Q_Pos) /*!< xPSR: Q Mask */ + +#define xPSR_ICI_IT_2_Pos 25U /*!< xPSR: ICI/IT part 2 Position */ +#define xPSR_ICI_IT_2_Msk (3UL << xPSR_ICI_IT_2_Pos) /*!< xPSR: ICI/IT part 2 Mask */ + +#define xPSR_T_Pos 24U /*!< xPSR: T Position */ +#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ + +#define xPSR_GE_Pos 16U /*!< xPSR: GE Position */ +#define xPSR_GE_Msk (0xFUL << xPSR_GE_Pos) /*!< xPSR: GE Mask */ + +#define xPSR_ICI_IT_1_Pos 10U /*!< xPSR: ICI/IT part 1 Position */ +#define xPSR_ICI_IT_1_Msk (0x3FUL << xPSR_ICI_IT_1_Pos) /*!< xPSR: ICI/IT part 1 Mask */ + +#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ +#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ + + +/** + \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; + +/* CONTROL Register Definitions */ +#define CONTROL_FPCA_Pos 2U /*!< CONTROL: FPCA Position */ +#define CONTROL_FPCA_Msk (1UL << CONTROL_FPCA_Pos) /*!< CONTROL: FPCA Mask */ + +#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ +#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ + +#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */ +#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ + +/*@} 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 +{ + __IOM uint32_t ISER[8U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ + uint32_t RESERVED0[24U]; + __IOM uint32_t ICER[8U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ + uint32_t RESERVED1[24U]; + __IOM uint32_t ISPR[8U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ + uint32_t RESERVED2[24U]; + __IOM uint32_t ICPR[8U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ + uint32_t RESERVED3[24U]; + __IOM uint32_t IABR[8U]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */ + uint32_t RESERVED4[56U]; + __IOM uint8_t IP[240U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */ + uint32_t RESERVED5[644U]; + __OM uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */ +} NVIC_Type; + +/* Software Triggered Interrupt Register Definitions */ +#define NVIC_STIR_INTID_Pos 0U /*!< 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 +{ + __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ + __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ + __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ + __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ + __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ + __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ + __IOM uint8_t SHP[12U]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */ + __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ + __IOM uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */ + __IOM uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */ + __IOM uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */ + __IOM uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */ + __IOM uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */ + __IOM uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */ + __IM uint32_t PFR[2U]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */ + __IM uint32_t DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */ + __IM uint32_t ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */ + __IM uint32_t MMFR[4U]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */ + __IM uint32_t ISAR[5U]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */ + uint32_t RESERVED0[5U]; + __IOM uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */ +} SCB_Type; + +/* SCB CPUID Register Definitions */ +#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ +#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ + +#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ +#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ + +#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ +#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ + +#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ +#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ + +#define SCB_CPUID_REVISION_Pos 0U /*!< 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 31U /*!< SCB ICSR: NMIPENDSET Position */ +#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ + +#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ +#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ + +#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ +#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ + +#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ +#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ + +#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ +#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ + +#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ +#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ + +#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ +#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ + +#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ +#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ + +#define SCB_ICSR_RETTOBASE_Pos 11U /*!< SCB ICSR: RETTOBASE Position */ +#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ + +#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< 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 7U /*!< 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 16U /*!< SCB AIRCR: VECTKEY Position */ +#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ + +#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ +#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ + +#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ +#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ + +#define SCB_AIRCR_PRIGROUP_Pos 8U /*!< SCB AIRCR: PRIGROUP Position */ +#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ + +#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ +#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ + +#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ +#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ + +#define SCB_AIRCR_VECTRESET_Pos 0U /*!< 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 4U /*!< SCB SCR: SEVONPEND Position */ +#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ + +#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ +#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ + +#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< 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 9U /*!< SCB CCR: STKALIGN Position */ +#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ + +#define SCB_CCR_BFHFNMIGN_Pos 8U /*!< 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 4U /*!< 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 3U /*!< 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 1U /*!< SCB CCR: USERSETMPEND Position */ +#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ + +#define SCB_CCR_NONBASETHRDENA_Pos 0U /*!< 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 18U /*!< SCB SHCSR: USGFAULTENA Position */ +#define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */ + +#define SCB_SHCSR_BUSFAULTENA_Pos 17U /*!< SCB SHCSR: BUSFAULTENA Position */ +#define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */ + +#define SCB_SHCSR_MEMFAULTENA_Pos 16U /*!< SCB SHCSR: MEMFAULTENA Position */ +#define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */ + +#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ +#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ + +#define SCB_SHCSR_BUSFAULTPENDED_Pos 14U /*!< SCB SHCSR: BUSFAULTPENDED Position */ +#define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */ + +#define SCB_SHCSR_MEMFAULTPENDED_Pos 13U /*!< SCB SHCSR: MEMFAULTPENDED Position */ +#define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */ + +#define SCB_SHCSR_USGFAULTPENDED_Pos 12U /*!< SCB SHCSR: USGFAULTPENDED Position */ +#define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */ + +#define SCB_SHCSR_SYSTICKACT_Pos 11U /*!< SCB SHCSR: SYSTICKACT Position */ +#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ + +#define SCB_SHCSR_PENDSVACT_Pos 10U /*!< SCB SHCSR: PENDSVACT Position */ +#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ + +#define SCB_SHCSR_MONITORACT_Pos 8U /*!< SCB SHCSR: MONITORACT Position */ +#define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */ + +#define SCB_SHCSR_SVCALLACT_Pos 7U /*!< SCB SHCSR: SVCALLACT Position */ +#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ + +#define SCB_SHCSR_USGFAULTACT_Pos 3U /*!< SCB SHCSR: USGFAULTACT Position */ +#define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */ + +#define SCB_SHCSR_BUSFAULTACT_Pos 1U /*!< SCB SHCSR: BUSFAULTACT Position */ +#define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */ + +#define SCB_SHCSR_MEMFAULTACT_Pos 0U /*!< SCB SHCSR: MEMFAULTACT Position */ +#define SCB_SHCSR_MEMFAULTACT_Msk (1UL /*<< SCB_SHCSR_MEMFAULTACT_Pos*/) /*!< SCB SHCSR: MEMFAULTACT Mask */ + +/* SCB Configurable Fault Status Register Definitions */ +#define SCB_CFSR_USGFAULTSR_Pos 16U /*!< 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 8U /*!< 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 0U /*!< 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 */ + +/* MemManage Fault Status Register (part of SCB Configurable Fault Status Register) */ +#define SCB_CFSR_MMARVALID_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 7U) /*!< SCB CFSR (MMFSR): MMARVALID Position */ +#define SCB_CFSR_MMARVALID_Msk (1UL << SCB_CFSR_MMARVALID_Pos) /*!< SCB CFSR (MMFSR): MMARVALID Mask */ + +#define SCB_CFSR_MLSPERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 5U) /*!< SCB CFSR (MMFSR): MLSPERR Position */ +#define SCB_CFSR_MLSPERR_Msk (1UL << SCB_CFSR_MLSPERR_Pos) /*!< SCB CFSR (MMFSR): MLSPERR Mask */ + +#define SCB_CFSR_MSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 4U) /*!< SCB CFSR (MMFSR): MSTKERR Position */ +#define SCB_CFSR_MSTKERR_Msk (1UL << SCB_CFSR_MSTKERR_Pos) /*!< SCB CFSR (MMFSR): MSTKERR Mask */ + +#define SCB_CFSR_MUNSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 3U) /*!< SCB CFSR (MMFSR): MUNSTKERR Position */ +#define SCB_CFSR_MUNSTKERR_Msk (1UL << SCB_CFSR_MUNSTKERR_Pos) /*!< SCB CFSR (MMFSR): MUNSTKERR Mask */ + +#define SCB_CFSR_DACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 1U) /*!< SCB CFSR (MMFSR): DACCVIOL Position */ +#define SCB_CFSR_DACCVIOL_Msk (1UL << SCB_CFSR_DACCVIOL_Pos) /*!< SCB CFSR (MMFSR): DACCVIOL Mask */ + +#define SCB_CFSR_IACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 0U) /*!< SCB CFSR (MMFSR): IACCVIOL Position */ +#define SCB_CFSR_IACCVIOL_Msk (1UL /*<< SCB_CFSR_IACCVIOL_Pos*/) /*!< SCB CFSR (MMFSR): IACCVIOL Mask */ + +/* BusFault Status Register (part of SCB Configurable Fault Status Register) */ +#define SCB_CFSR_BFARVALID_Pos (SCB_CFSR_BUSFAULTSR_Pos + 7U) /*!< SCB CFSR (BFSR): BFARVALID Position */ +#define SCB_CFSR_BFARVALID_Msk (1UL << SCB_CFSR_BFARVALID_Pos) /*!< SCB CFSR (BFSR): BFARVALID Mask */ + +#define SCB_CFSR_LSPERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 5U) /*!< SCB CFSR (BFSR): LSPERR Position */ +#define SCB_CFSR_LSPERR_Msk (1UL << SCB_CFSR_LSPERR_Pos) /*!< SCB CFSR (BFSR): LSPERR Mask */ + +#define SCB_CFSR_STKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 4U) /*!< SCB CFSR (BFSR): STKERR Position */ +#define SCB_CFSR_STKERR_Msk (1UL << SCB_CFSR_STKERR_Pos) /*!< SCB CFSR (BFSR): STKERR Mask */ + +#define SCB_CFSR_UNSTKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 3U) /*!< SCB CFSR (BFSR): UNSTKERR Position */ +#define SCB_CFSR_UNSTKERR_Msk (1UL << SCB_CFSR_UNSTKERR_Pos) /*!< SCB CFSR (BFSR): UNSTKERR Mask */ + +#define SCB_CFSR_IMPRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 2U) /*!< SCB CFSR (BFSR): IMPRECISERR Position */ +#define SCB_CFSR_IMPRECISERR_Msk (1UL << SCB_CFSR_IMPRECISERR_Pos) /*!< SCB CFSR (BFSR): IMPRECISERR Mask */ + +#define SCB_CFSR_PRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 1U) /*!< SCB CFSR (BFSR): PRECISERR Position */ +#define SCB_CFSR_PRECISERR_Msk (1UL << SCB_CFSR_PRECISERR_Pos) /*!< SCB CFSR (BFSR): PRECISERR Mask */ + +#define SCB_CFSR_IBUSERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 0U) /*!< SCB CFSR (BFSR): IBUSERR Position */ +#define SCB_CFSR_IBUSERR_Msk (1UL << SCB_CFSR_IBUSERR_Pos) /*!< SCB CFSR (BFSR): IBUSERR Mask */ + +/* UsageFault Status Register (part of SCB Configurable Fault Status Register) */ +#define SCB_CFSR_DIVBYZERO_Pos (SCB_CFSR_USGFAULTSR_Pos + 9U) /*!< SCB CFSR (UFSR): DIVBYZERO Position */ +#define SCB_CFSR_DIVBYZERO_Msk (1UL << SCB_CFSR_DIVBYZERO_Pos) /*!< SCB CFSR (UFSR): DIVBYZERO Mask */ + +#define SCB_CFSR_UNALIGNED_Pos (SCB_CFSR_USGFAULTSR_Pos + 8U) /*!< SCB CFSR (UFSR): UNALIGNED Position */ +#define SCB_CFSR_UNALIGNED_Msk (1UL << SCB_CFSR_UNALIGNED_Pos) /*!< SCB CFSR (UFSR): UNALIGNED Mask */ + +#define SCB_CFSR_NOCP_Pos (SCB_CFSR_USGFAULTSR_Pos + 3U) /*!< SCB CFSR (UFSR): NOCP Position */ +#define SCB_CFSR_NOCP_Msk (1UL << SCB_CFSR_NOCP_Pos) /*!< SCB CFSR (UFSR): NOCP Mask */ + +#define SCB_CFSR_INVPC_Pos (SCB_CFSR_USGFAULTSR_Pos + 2U) /*!< SCB CFSR (UFSR): INVPC Position */ +#define SCB_CFSR_INVPC_Msk (1UL << SCB_CFSR_INVPC_Pos) /*!< SCB CFSR (UFSR): INVPC Mask */ + +#define SCB_CFSR_INVSTATE_Pos (SCB_CFSR_USGFAULTSR_Pos + 1U) /*!< SCB CFSR (UFSR): INVSTATE Position */ +#define SCB_CFSR_INVSTATE_Msk (1UL << SCB_CFSR_INVSTATE_Pos) /*!< SCB CFSR (UFSR): INVSTATE Mask */ + +#define SCB_CFSR_UNDEFINSTR_Pos (SCB_CFSR_USGFAULTSR_Pos + 0U) /*!< SCB CFSR (UFSR): UNDEFINSTR Position */ +#define SCB_CFSR_UNDEFINSTR_Msk (1UL << SCB_CFSR_UNDEFINSTR_Pos) /*!< SCB CFSR (UFSR): UNDEFINSTR Mask */ + +/* SCB Hard Fault Status Register Definitions */ +#define SCB_HFSR_DEBUGEVT_Pos 31U /*!< SCB HFSR: DEBUGEVT Position */ +#define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */ + +#define SCB_HFSR_FORCED_Pos 30U /*!< SCB HFSR: FORCED Position */ +#define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */ + +#define SCB_HFSR_VECTTBL_Pos 1U /*!< 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 4U /*!< SCB DFSR: EXTERNAL Position */ +#define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */ + +#define SCB_DFSR_VCATCH_Pos 3U /*!< SCB DFSR: VCATCH Position */ +#define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */ + +#define SCB_DFSR_DWTTRAP_Pos 2U /*!< SCB DFSR: DWTTRAP Position */ +#define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */ + +#define SCB_DFSR_BKPT_Pos 1U /*!< SCB DFSR: BKPT Position */ +#define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */ + +#define SCB_DFSR_HALTED_Pos 0U /*!< 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[1U]; + __IM uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */ + __IOM uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */ +} SCnSCB_Type; + +/* Interrupt Controller Type Register Definitions */ +#define SCnSCB_ICTR_INTLINESNUM_Pos 0U /*!< 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 9U /*!< ACTLR: DISOOFP Position */ +#define SCnSCB_ACTLR_DISOOFP_Msk (1UL << SCnSCB_ACTLR_DISOOFP_Pos) /*!< ACTLR: DISOOFP Mask */ + +#define SCnSCB_ACTLR_DISFPCA_Pos 8U /*!< ACTLR: DISFPCA Position */ +#define SCnSCB_ACTLR_DISFPCA_Msk (1UL << SCnSCB_ACTLR_DISFPCA_Pos) /*!< ACTLR: DISFPCA Mask */ + +#define SCnSCB_ACTLR_DISFOLD_Pos 2U /*!< ACTLR: DISFOLD Position */ +#define SCnSCB_ACTLR_DISFOLD_Msk (1UL << SCnSCB_ACTLR_DISFOLD_Pos) /*!< ACTLR: DISFOLD Mask */ + +#define SCnSCB_ACTLR_DISDEFWBUF_Pos 1U /*!< ACTLR: DISDEFWBUF Position */ +#define SCnSCB_ACTLR_DISDEFWBUF_Msk (1UL << SCnSCB_ACTLR_DISDEFWBUF_Pos) /*!< ACTLR: DISDEFWBUF Mask */ + +#define SCnSCB_ACTLR_DISMCYCINT_Pos 0U /*!< 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 +{ + __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ + __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ + __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ + __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ +} SysTick_Type; + +/* SysTick Control / Status Register Definitions */ +#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ +#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ + +#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ +#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ + +#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ +#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ + +#define SysTick_CTRL_ENABLE_Pos 0U /*!< 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 0U /*!< 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 0U /*!< 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 31U /*!< SysTick CALIB: NOREF Position */ +#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ + +#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ +#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ + +#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ +#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_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 +{ + __OM union + { + __OM uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */ + __OM uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */ + __OM uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */ + } PORT [32U]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */ + uint32_t RESERVED0[864U]; + __IOM uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */ + uint32_t RESERVED1[15U]; + __IOM uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */ + uint32_t RESERVED2[15U]; + __IOM uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */ + uint32_t RESERVED3[32U]; + uint32_t RESERVED4[43U]; + __OM uint32_t LAR; /*!< Offset: 0xFB0 ( /W) ITM Lock Access Register */ + __IM uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) ITM Lock Status Register */ + uint32_t RESERVED5[6U]; + __IM uint32_t PID4; /*!< Offset: 0xFD0 (R/ ) ITM Peripheral Identification Register #4 */ + __IM uint32_t PID5; /*!< Offset: 0xFD4 (R/ ) ITM Peripheral Identification Register #5 */ + __IM uint32_t PID6; /*!< Offset: 0xFD8 (R/ ) ITM Peripheral Identification Register #6 */ + __IM uint32_t PID7; /*!< Offset: 0xFDC (R/ ) ITM Peripheral Identification Register #7 */ + __IM uint32_t PID0; /*!< Offset: 0xFE0 (R/ ) ITM Peripheral Identification Register #0 */ + __IM uint32_t PID1; /*!< Offset: 0xFE4 (R/ ) ITM Peripheral Identification Register #1 */ + __IM uint32_t PID2; /*!< Offset: 0xFE8 (R/ ) ITM Peripheral Identification Register #2 */ + __IM uint32_t PID3; /*!< Offset: 0xFEC (R/ ) ITM Peripheral Identification Register #3 */ + __IM uint32_t CID0; /*!< Offset: 0xFF0 (R/ ) ITM Component Identification Register #0 */ + __IM uint32_t CID1; /*!< Offset: 0xFF4 (R/ ) ITM Component Identification Register #1 */ + __IM uint32_t CID2; /*!< Offset: 0xFF8 (R/ ) ITM Component Identification Register #2 */ + __IM uint32_t CID3; /*!< Offset: 0xFFC (R/ ) ITM Component Identification Register #3 */ +} ITM_Type; + +/* ITM Trace Privilege Register Definitions */ +#define ITM_TPR_PRIVMASK_Pos 0U /*!< ITM TPR: PRIVMASK Position */ +#define ITM_TPR_PRIVMASK_Msk (0xFFFFFFFFUL /*<< ITM_TPR_PRIVMASK_Pos*/) /*!< ITM TPR: PRIVMASK Mask */ + +/* ITM Trace Control Register Definitions */ +#define ITM_TCR_BUSY_Pos 23U /*!< ITM TCR: BUSY Position */ +#define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */ + +#define ITM_TCR_TraceBusID_Pos 16U /*!< ITM TCR: ATBID Position */ +#define ITM_TCR_TraceBusID_Msk (0x7FUL << ITM_TCR_TraceBusID_Pos) /*!< ITM TCR: ATBID Mask */ + +#define ITM_TCR_GTSFREQ_Pos 10U /*!< 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 8U /*!< ITM TCR: TSPrescale Position */ +#define ITM_TCR_TSPrescale_Msk (3UL << ITM_TCR_TSPrescale_Pos) /*!< ITM TCR: TSPrescale Mask */ + +#define ITM_TCR_SWOENA_Pos 4U /*!< ITM TCR: SWOENA Position */ +#define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */ + +#define ITM_TCR_DWTENA_Pos 3U /*!< ITM TCR: DWTENA Position */ +#define ITM_TCR_DWTENA_Msk (1UL << ITM_TCR_DWTENA_Pos) /*!< ITM TCR: DWTENA Mask */ + +#define ITM_TCR_SYNCENA_Pos 2U /*!< ITM TCR: SYNCENA Position */ +#define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */ + +#define ITM_TCR_TSENA_Pos 1U /*!< ITM TCR: TSENA Position */ +#define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */ + +#define ITM_TCR_ITMENA_Pos 0U /*!< ITM TCR: ITM Enable bit Position */ +#define ITM_TCR_ITMENA_Msk (1UL /*<< ITM_TCR_ITMENA_Pos*/) /*!< ITM TCR: ITM Enable bit Mask */ + +/* ITM Lock Status Register Definitions */ +#define ITM_LSR_ByteAcc_Pos 2U /*!< ITM LSR: ByteAcc Position */ +#define ITM_LSR_ByteAcc_Msk (1UL << ITM_LSR_ByteAcc_Pos) /*!< ITM LSR: ByteAcc Mask */ + +#define ITM_LSR_Access_Pos 1U /*!< ITM LSR: Access Position */ +#define ITM_LSR_Access_Msk (1UL << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */ + +#define ITM_LSR_Present_Pos 0U /*!< 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 +{ + __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */ + __IOM uint32_t CYCCNT; /*!< Offset: 0x004 (R/W) Cycle Count Register */ + __IOM uint32_t CPICNT; /*!< Offset: 0x008 (R/W) CPI Count Register */ + __IOM uint32_t EXCCNT; /*!< Offset: 0x00C (R/W) Exception Overhead Count Register */ + __IOM uint32_t SLEEPCNT; /*!< Offset: 0x010 (R/W) Sleep Count Register */ + __IOM uint32_t LSUCNT; /*!< Offset: 0x014 (R/W) LSU Count Register */ + __IOM uint32_t FOLDCNT; /*!< Offset: 0x018 (R/W) Folded-instruction Count Register */ + __IM uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */ + __IOM uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */ + __IOM uint32_t MASK0; /*!< Offset: 0x024 (R/W) Mask Register 0 */ + __IOM uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */ + uint32_t RESERVED0[1U]; + __IOM uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */ + __IOM uint32_t MASK1; /*!< Offset: 0x034 (R/W) Mask Register 1 */ + __IOM uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */ + uint32_t RESERVED1[1U]; + __IOM uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */ + __IOM uint32_t MASK2; /*!< Offset: 0x044 (R/W) Mask Register 2 */ + __IOM uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */ + uint32_t RESERVED2[1U]; + __IOM uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */ + __IOM uint32_t MASK3; /*!< Offset: 0x054 (R/W) Mask Register 3 */ + __IOM uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */ +} DWT_Type; + +/* DWT Control Register Definitions */ +#define DWT_CTRL_NUMCOMP_Pos 28U /*!< DWT CTRL: NUMCOMP Position */ +#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */ + +#define DWT_CTRL_NOTRCPKT_Pos 27U /*!< DWT CTRL: NOTRCPKT Position */ +#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */ + +#define DWT_CTRL_NOEXTTRIG_Pos 26U /*!< DWT CTRL: NOEXTTRIG Position */ +#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */ + +#define DWT_CTRL_NOCYCCNT_Pos 25U /*!< DWT CTRL: NOCYCCNT Position */ +#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */ + +#define DWT_CTRL_NOPRFCNT_Pos 24U /*!< DWT CTRL: NOPRFCNT Position */ +#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */ + +#define DWT_CTRL_CYCEVTENA_Pos 22U /*!< DWT CTRL: CYCEVTENA Position */ +#define DWT_CTRL_CYCEVTENA_Msk (0x1UL << DWT_CTRL_CYCEVTENA_Pos) /*!< DWT CTRL: CYCEVTENA Mask */ + +#define DWT_CTRL_FOLDEVTENA_Pos 21U /*!< DWT CTRL: FOLDEVTENA Position */ +#define DWT_CTRL_FOLDEVTENA_Msk (0x1UL << DWT_CTRL_FOLDEVTENA_Pos) /*!< DWT CTRL: FOLDEVTENA Mask */ + +#define DWT_CTRL_LSUEVTENA_Pos 20U /*!< DWT CTRL: LSUEVTENA Position */ +#define DWT_CTRL_LSUEVTENA_Msk (0x1UL << DWT_CTRL_LSUEVTENA_Pos) /*!< DWT CTRL: LSUEVTENA Mask */ + +#define DWT_CTRL_SLEEPEVTENA_Pos 19U /*!< DWT CTRL: SLEEPEVTENA Position */ +#define DWT_CTRL_SLEEPEVTENA_Msk (0x1UL << DWT_CTRL_SLEEPEVTENA_Pos) /*!< DWT CTRL: SLEEPEVTENA Mask */ + +#define DWT_CTRL_EXCEVTENA_Pos 18U /*!< DWT CTRL: EXCEVTENA Position */ +#define DWT_CTRL_EXCEVTENA_Msk (0x1UL << DWT_CTRL_EXCEVTENA_Pos) /*!< DWT CTRL: EXCEVTENA Mask */ + +#define DWT_CTRL_CPIEVTENA_Pos 17U /*!< DWT CTRL: CPIEVTENA Position */ +#define DWT_CTRL_CPIEVTENA_Msk (0x1UL << DWT_CTRL_CPIEVTENA_Pos) /*!< DWT CTRL: CPIEVTENA Mask */ + +#define DWT_CTRL_EXCTRCENA_Pos 16U /*!< DWT CTRL: EXCTRCENA Position */ +#define DWT_CTRL_EXCTRCENA_Msk (0x1UL << DWT_CTRL_EXCTRCENA_Pos) /*!< DWT CTRL: EXCTRCENA Mask */ + +#define DWT_CTRL_PCSAMPLENA_Pos 12U /*!< DWT CTRL: PCSAMPLENA Position */ +#define DWT_CTRL_PCSAMPLENA_Msk (0x1UL << DWT_CTRL_PCSAMPLENA_Pos) /*!< DWT CTRL: PCSAMPLENA Mask */ + +#define DWT_CTRL_SYNCTAP_Pos 10U /*!< DWT CTRL: SYNCTAP Position */ +#define DWT_CTRL_SYNCTAP_Msk (0x3UL << DWT_CTRL_SYNCTAP_Pos) /*!< DWT CTRL: SYNCTAP Mask */ + +#define DWT_CTRL_CYCTAP_Pos 9U /*!< DWT CTRL: CYCTAP Position */ +#define DWT_CTRL_CYCTAP_Msk (0x1UL << DWT_CTRL_CYCTAP_Pos) /*!< DWT CTRL: CYCTAP Mask */ + +#define DWT_CTRL_POSTINIT_Pos 5U /*!< DWT CTRL: POSTINIT Position */ +#define DWT_CTRL_POSTINIT_Msk (0xFUL << DWT_CTRL_POSTINIT_Pos) /*!< DWT CTRL: POSTINIT Mask */ + +#define DWT_CTRL_POSTPRESET_Pos 1U /*!< DWT CTRL: POSTPRESET Position */ +#define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */ + +#define DWT_CTRL_CYCCNTENA_Pos 0U /*!< 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 0U /*!< 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 0U /*!< 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 0U /*!< 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 0U /*!< 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 0U /*!< 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 0U /*!< 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 24U /*!< DWT FUNCTION: MATCHED Position */ +#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */ + +#define DWT_FUNCTION_DATAVADDR1_Pos 16U /*!< DWT FUNCTION: DATAVADDR1 Position */ +#define DWT_FUNCTION_DATAVADDR1_Msk (0xFUL << DWT_FUNCTION_DATAVADDR1_Pos) /*!< DWT FUNCTION: DATAVADDR1 Mask */ + +#define DWT_FUNCTION_DATAVADDR0_Pos 12U /*!< DWT FUNCTION: DATAVADDR0 Position */ +#define DWT_FUNCTION_DATAVADDR0_Msk (0xFUL << DWT_FUNCTION_DATAVADDR0_Pos) /*!< DWT FUNCTION: DATAVADDR0 Mask */ + +#define DWT_FUNCTION_DATAVSIZE_Pos 10U /*!< DWT FUNCTION: DATAVSIZE Position */ +#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */ + +#define DWT_FUNCTION_LNK1ENA_Pos 9U /*!< DWT FUNCTION: LNK1ENA Position */ +#define DWT_FUNCTION_LNK1ENA_Msk (0x1UL << DWT_FUNCTION_LNK1ENA_Pos) /*!< DWT FUNCTION: LNK1ENA Mask */ + +#define DWT_FUNCTION_DATAVMATCH_Pos 8U /*!< DWT FUNCTION: DATAVMATCH Position */ +#define DWT_FUNCTION_DATAVMATCH_Msk (0x1UL << DWT_FUNCTION_DATAVMATCH_Pos) /*!< DWT FUNCTION: DATAVMATCH Mask */ + +#define DWT_FUNCTION_CYCMATCH_Pos 7U /*!< DWT FUNCTION: CYCMATCH Position */ +#define DWT_FUNCTION_CYCMATCH_Msk (0x1UL << DWT_FUNCTION_CYCMATCH_Pos) /*!< DWT FUNCTION: CYCMATCH Mask */ + +#define DWT_FUNCTION_EMITRANGE_Pos 5U /*!< DWT FUNCTION: EMITRANGE Position */ +#define DWT_FUNCTION_EMITRANGE_Msk (0x1UL << DWT_FUNCTION_EMITRANGE_Pos) /*!< DWT FUNCTION: EMITRANGE Mask */ + +#define DWT_FUNCTION_FUNCTION_Pos 0U /*!< 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 +{ + __IM uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Size Register */ + __IOM uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Size Register */ + uint32_t RESERVED0[2U]; + __IOM uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */ + uint32_t RESERVED1[55U]; + __IOM uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */ + uint32_t RESERVED2[131U]; + __IM uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */ + __IOM uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */ + __IM uint32_t FSCR; /*!< Offset: 0x308 (R/ ) Formatter Synchronization Counter Register */ + uint32_t RESERVED3[759U]; + __IM uint32_t TRIGGER; /*!< Offset: 0xEE8 (R/ ) TRIGGER Register */ + __IM uint32_t FIFO0; /*!< Offset: 0xEEC (R/ ) Integration ETM Data */ + __IM uint32_t ITATBCTR2; /*!< Offset: 0xEF0 (R/ ) ITATBCTR2 */ + uint32_t RESERVED4[1U]; + __IM uint32_t ITATBCTR0; /*!< Offset: 0xEF8 (R/ ) ITATBCTR0 */ + __IM uint32_t FIFO1; /*!< Offset: 0xEFC (R/ ) Integration ITM Data */ + __IOM uint32_t ITCTRL; /*!< Offset: 0xF00 (R/W) Integration Mode Control */ + uint32_t RESERVED5[39U]; + __IOM uint32_t CLAIMSET; /*!< Offset: 0xFA0 (R/W) Claim tag set */ + __IOM uint32_t CLAIMCLR; /*!< Offset: 0xFA4 (R/W) Claim tag clear */ + uint32_t RESERVED7[8U]; + __IM uint32_t DEVID; /*!< Offset: 0xFC8 (R/ ) TPIU_DEVID */ + __IM uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) TPIU_DEVTYPE */ +} TPI_Type; + +/* TPI Asynchronous Clock Prescaler Register Definitions */ +#define TPI_ACPR_PRESCALER_Pos 0U /*!< 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 0U /*!< 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 3U /*!< TPI FFSR: FtNonStop Position */ +#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */ + +#define TPI_FFSR_TCPresent_Pos 2U /*!< TPI FFSR: TCPresent Position */ +#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */ + +#define TPI_FFSR_FtStopped_Pos 1U /*!< TPI FFSR: FtStopped Position */ +#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */ + +#define TPI_FFSR_FlInProg_Pos 0U /*!< 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 8U /*!< TPI FFCR: TrigIn Position */ +#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */ + +#define TPI_FFCR_EnFCont_Pos 1U /*!< 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 0U /*!< 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 29U /*!< TPI FIFO0: ITM_ATVALID Position */ +#define TPI_FIFO0_ITM_ATVALID_Msk (0x1UL << TPI_FIFO0_ITM_ATVALID_Pos) /*!< TPI FIFO0: ITM_ATVALID Mask */ + +#define TPI_FIFO0_ITM_bytecount_Pos 27U /*!< 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 26U /*!< TPI FIFO0: ETM_ATVALID Position */ +#define TPI_FIFO0_ETM_ATVALID_Msk (0x1UL << TPI_FIFO0_ETM_ATVALID_Pos) /*!< TPI FIFO0: ETM_ATVALID Mask */ + +#define TPI_FIFO0_ETM_bytecount_Pos 24U /*!< 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 16U /*!< TPI FIFO0: ETM2 Position */ +#define TPI_FIFO0_ETM2_Msk (0xFFUL << TPI_FIFO0_ETM2_Pos) /*!< TPI FIFO0: ETM2 Mask */ + +#define TPI_FIFO0_ETM1_Pos 8U /*!< TPI FIFO0: ETM1 Position */ +#define TPI_FIFO0_ETM1_Msk (0xFFUL << TPI_FIFO0_ETM1_Pos) /*!< TPI FIFO0: ETM1 Mask */ + +#define TPI_FIFO0_ETM0_Pos 0U /*!< 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_ATREADY2_Pos 0U /*!< TPI ITATBCTR2: ATREADY2 Position */ +#define TPI_ITATBCTR2_ATREADY2_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY2_Pos*/) /*!< TPI ITATBCTR2: ATREADY2 Mask */ + +#define TPI_ITATBCTR2_ATREADY1_Pos 0U /*!< TPI ITATBCTR2: ATREADY1 Position */ +#define TPI_ITATBCTR2_ATREADY1_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY1_Pos*/) /*!< TPI ITATBCTR2: ATREADY1 Mask */ + +/* TPI Integration ITM Data Register Definitions (FIFO1) */ +#define TPI_FIFO1_ITM_ATVALID_Pos 29U /*!< TPI FIFO1: ITM_ATVALID Position */ +#define TPI_FIFO1_ITM_ATVALID_Msk (0x1UL << TPI_FIFO1_ITM_ATVALID_Pos) /*!< TPI FIFO1: ITM_ATVALID Mask */ + +#define TPI_FIFO1_ITM_bytecount_Pos 27U /*!< 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 26U /*!< TPI FIFO1: ETM_ATVALID Position */ +#define TPI_FIFO1_ETM_ATVALID_Msk (0x1UL << TPI_FIFO1_ETM_ATVALID_Pos) /*!< TPI FIFO1: ETM_ATVALID Mask */ + +#define TPI_FIFO1_ETM_bytecount_Pos 24U /*!< 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 16U /*!< TPI FIFO1: ITM2 Position */ +#define TPI_FIFO1_ITM2_Msk (0xFFUL << TPI_FIFO1_ITM2_Pos) /*!< TPI FIFO1: ITM2 Mask */ + +#define TPI_FIFO1_ITM1_Pos 8U /*!< TPI FIFO1: ITM1 Position */ +#define TPI_FIFO1_ITM1_Msk (0xFFUL << TPI_FIFO1_ITM1_Pos) /*!< TPI FIFO1: ITM1 Mask */ + +#define TPI_FIFO1_ITM0_Pos 0U /*!< 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_ATREADY2_Pos 0U /*!< TPI ITATBCTR0: ATREADY2 Position */ +#define TPI_ITATBCTR0_ATREADY2_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY2_Pos*/) /*!< TPI ITATBCTR0: ATREADY2 Mask */ + +#define TPI_ITATBCTR0_ATREADY1_Pos 0U /*!< TPI ITATBCTR0: ATREADY1 Position */ +#define TPI_ITATBCTR0_ATREADY1_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY1_Pos*/) /*!< TPI ITATBCTR0: ATREADY1 Mask */ + +/* TPI Integration Mode Control Register Definitions */ +#define TPI_ITCTRL_Mode_Pos 0U /*!< TPI ITCTRL: Mode Position */ +#define TPI_ITCTRL_Mode_Msk (0x3UL /*<< TPI_ITCTRL_Mode_Pos*/) /*!< TPI ITCTRL: Mode Mask */ + +/* TPI DEVID Register Definitions */ +#define TPI_DEVID_NRZVALID_Pos 11U /*!< TPI DEVID: NRZVALID Position */ +#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */ + +#define TPI_DEVID_MANCVALID_Pos 10U /*!< TPI DEVID: MANCVALID Position */ +#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */ + +#define TPI_DEVID_PTINVALID_Pos 9U /*!< TPI DEVID: PTINVALID Position */ +#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */ + +#define TPI_DEVID_MinBufSz_Pos 6U /*!< TPI DEVID: MinBufSz Position */ +#define TPI_DEVID_MinBufSz_Msk (0x7UL << TPI_DEVID_MinBufSz_Pos) /*!< TPI DEVID: MinBufSz Mask */ + +#define TPI_DEVID_AsynClkIn_Pos 5U /*!< TPI DEVID: AsynClkIn Position */ +#define TPI_DEVID_AsynClkIn_Msk (0x1UL << TPI_DEVID_AsynClkIn_Pos) /*!< TPI DEVID: AsynClkIn Mask */ + +#define TPI_DEVID_NrTraceInput_Pos 0U /*!< 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 4U /*!< TPI DEVTYPE: SubType Position */ +#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */ + +#define TPI_DEVTYPE_MajorType_Pos 0U /*!< TPI DEVTYPE: MajorType Position */ +#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */ + +/*@}*/ /* end of group CMSIS_TPI */ + + +#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) +/** + \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 +{ + __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ + __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ + __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region RNRber Register */ + __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ + __IOM uint32_t RASR; /*!< Offset: 0x010 (R/W) MPU Region Attribute and Size Register */ + __IOM uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Alias 1 Region Base Address Register */ + __IOM uint32_t RASR_A1; /*!< Offset: 0x018 (R/W) MPU Alias 1 Region Attribute and Size Register */ + __IOM uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Alias 2 Region Base Address Register */ + __IOM uint32_t RASR_A2; /*!< Offset: 0x020 (R/W) MPU Alias 2 Region Attribute and Size Register */ + __IOM uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Alias 3 Region Base Address Register */ + __IOM uint32_t RASR_A3; /*!< Offset: 0x028 (R/W) MPU Alias 3 Region Attribute and Size Register */ +} MPU_Type; + +#define MPU_TYPE_RALIASES 4U + +/* MPU Type Register Definitions */ +#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */ +#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ + +#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */ +#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ + +#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */ +#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ + +/* MPU Control Register Definitions */ +#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */ +#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ + +#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */ +#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ + +#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */ +#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ + +/* MPU Region Number Register Definitions */ +#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */ +#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ + +/* MPU Region Base Address Register Definitions */ +#define MPU_RBAR_ADDR_Pos 5U /*!< MPU RBAR: ADDR Position */ +#define MPU_RBAR_ADDR_Msk (0x7FFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */ + +#define MPU_RBAR_VALID_Pos 4U /*!< MPU RBAR: VALID Position */ +#define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ + +#define MPU_RBAR_REGION_Pos 0U /*!< MPU RBAR: REGION Position */ +#define MPU_RBAR_REGION_Msk (0xFUL /*<< MPU_RBAR_REGION_Pos*/) /*!< MPU RBAR: REGION Mask */ + +/* MPU Region Attribute and Size Register Definitions */ +#define MPU_RASR_ATTRS_Pos 16U /*!< 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 28U /*!< 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 24U /*!< 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 19U /*!< 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 18U /*!< 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 17U /*!< 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 16U /*!< 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 8U /*!< 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 1U /*!< 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 0U /*!< 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 /* defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) */ + + +/** + \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[1U]; + __IOM uint32_t FPCCR; /*!< Offset: 0x004 (R/W) Floating-Point Context Control Register */ + __IOM uint32_t FPCAR; /*!< Offset: 0x008 (R/W) Floating-Point Context Address Register */ + __IOM uint32_t FPDSCR; /*!< Offset: 0x00C (R/W) Floating-Point Default Status Control Register */ + __IM uint32_t MVFR0; /*!< Offset: 0x010 (R/ ) Media and FP Feature Register 0 */ + __IM uint32_t MVFR1; /*!< Offset: 0x014 (R/ ) Media and FP Feature Register 1 */ + __IM uint32_t MVFR2; /*!< Offset: 0x018 (R/ ) Media and FP Feature Register 2 */ +} FPU_Type; + +/* Floating-Point Context Control Register Definitions */ +#define FPU_FPCCR_ASPEN_Pos 31U /*!< FPCCR: ASPEN bit Position */ +#define FPU_FPCCR_ASPEN_Msk (1UL << FPU_FPCCR_ASPEN_Pos) /*!< FPCCR: ASPEN bit Mask */ + +#define FPU_FPCCR_LSPEN_Pos 30U /*!< FPCCR: LSPEN Position */ +#define FPU_FPCCR_LSPEN_Msk (1UL << FPU_FPCCR_LSPEN_Pos) /*!< FPCCR: LSPEN bit Mask */ + +#define FPU_FPCCR_MONRDY_Pos 8U /*!< FPCCR: MONRDY Position */ +#define FPU_FPCCR_MONRDY_Msk (1UL << FPU_FPCCR_MONRDY_Pos) /*!< FPCCR: MONRDY bit Mask */ + +#define FPU_FPCCR_BFRDY_Pos 6U /*!< FPCCR: BFRDY Position */ +#define FPU_FPCCR_BFRDY_Msk (1UL << FPU_FPCCR_BFRDY_Pos) /*!< FPCCR: BFRDY bit Mask */ + +#define FPU_FPCCR_MMRDY_Pos 5U /*!< FPCCR: MMRDY Position */ +#define FPU_FPCCR_MMRDY_Msk (1UL << FPU_FPCCR_MMRDY_Pos) /*!< FPCCR: MMRDY bit Mask */ + +#define FPU_FPCCR_HFRDY_Pos 4U /*!< FPCCR: HFRDY Position */ +#define FPU_FPCCR_HFRDY_Msk (1UL << FPU_FPCCR_HFRDY_Pos) /*!< FPCCR: HFRDY bit Mask */ + +#define FPU_FPCCR_THREAD_Pos 3U /*!< 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 1U /*!< 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 0U /*!< 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 Definitions */ +#define FPU_FPCAR_ADDRESS_Pos 3U /*!< FPCAR: ADDRESS bit Position */ +#define FPU_FPCAR_ADDRESS_Msk (0x1FFFFFFFUL << FPU_FPCAR_ADDRESS_Pos) /*!< FPCAR: ADDRESS bit Mask */ + +/* Floating-Point Default Status Control Register Definitions */ +#define FPU_FPDSCR_AHP_Pos 26U /*!< FPDSCR: AHP bit Position */ +#define FPU_FPDSCR_AHP_Msk (1UL << FPU_FPDSCR_AHP_Pos) /*!< FPDSCR: AHP bit Mask */ + +#define FPU_FPDSCR_DN_Pos 25U /*!< FPDSCR: DN bit Position */ +#define FPU_FPDSCR_DN_Msk (1UL << FPU_FPDSCR_DN_Pos) /*!< FPDSCR: DN bit Mask */ + +#define FPU_FPDSCR_FZ_Pos 24U /*!< FPDSCR: FZ bit Position */ +#define FPU_FPDSCR_FZ_Msk (1UL << FPU_FPDSCR_FZ_Pos) /*!< FPDSCR: FZ bit Mask */ + +#define FPU_FPDSCR_RMode_Pos 22U /*!< FPDSCR: RMode bit Position */ +#define FPU_FPDSCR_RMode_Msk (3UL << FPU_FPDSCR_RMode_Pos) /*!< FPDSCR: RMode bit Mask */ + +/* Media and FP Feature Register 0 Definitions */ +#define FPU_MVFR0_FP_rounding_modes_Pos 28U /*!< 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 24U /*!< 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 20U /*!< 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 16U /*!< 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 12U /*!< 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 8U /*!< 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 4U /*!< 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 0U /*!< 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 Definitions */ +#define FPU_MVFR1_FP_fused_MAC_Pos 28U /*!< 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 24U /*!< 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 4U /*!< 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 0U /*!< MVFR1: FtZ mode bits Position */ +#define FPU_MVFR1_FtZ_mode_Msk (0xFUL /*<< FPU_MVFR1_FtZ_mode_Pos*/) /*!< MVFR1: FtZ mode bits Mask */ + +/* Media and FP Feature Register 2 Definitions */ + +#define FPU_MVFR2_VFP_Misc_Pos 4U /*!< MVFR2: VFP Misc bits Position */ +#define FPU_MVFR2_VFP_Misc_Msk (0xFUL << FPU_MVFR2_VFP_Misc_Pos) /*!< MVFR2: VFP Misc bits Mask */ + +/*@} end of group CMSIS_FPU */ + + +/** + \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 +{ + __IOM uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */ + __OM uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */ + __IOM uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */ + __IOM uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */ +} CoreDebug_Type; + +/* Debug Halting Control and Status Register Definitions */ +#define CoreDebug_DHCSR_DBGKEY_Pos 16U /*!< 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 25U /*!< 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 24U /*!< 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 19U /*!< 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 18U /*!< 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 17U /*!< 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 16U /*!< 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 5U /*!< 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 3U /*!< 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 2U /*!< 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 1U /*!< 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 0U /*!< 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 Definitions */ +#define CoreDebug_DCRSR_REGWnR_Pos 16U /*!< CoreDebug DCRSR: REGWnR Position */ +#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ + +#define CoreDebug_DCRSR_REGSEL_Pos 0U /*!< CoreDebug DCRSR: REGSEL Position */ +#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */ + +/* Debug Exception and Monitor Control Register Definitions */ +#define CoreDebug_DEMCR_TRCENA_Pos 24U /*!< CoreDebug DEMCR: TRCENA Position */ +#define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */ + +#define CoreDebug_DEMCR_MON_REQ_Pos 19U /*!< 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 18U /*!< 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 17U /*!< 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 16U /*!< 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 10U /*!< 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 9U /*!< 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 8U /*!< 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 7U /*!< 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 6U /*!< 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 5U /*!< 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 4U /*!< 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 0U /*!< 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_bitfield Core register bit field macros + \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). + @{ + */ + +/** + \brief Mask and shift a bit field value for use in a register bit range. + \param[in] field Name of the register bit field. + \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. + \return Masked and shifted value. +*/ +#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) + +/** + \brief Mask and shift a register value to extract a bit filed value. + \param[in] field Name of the register bit field. + \param[in] value Value of register. This parameter is interpreted as an uint32_t type. + \return Masked and shifted bit field value. +*/ +#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) + +/*@} end of group CMSIS_core_bitfield */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_core_base Core Definitions + \brief Definitions for base addresses, unions, and structures. + @{ + */ + +/* Memory mapping of Core 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 defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) + #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ + #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ +#endif + +#define FPU_BASE (SCS_BASE + 0x0F30UL) /*!< Floating Point Unit */ +#define FPU ((FPU_Type *) FPU_BASE ) /*!< Floating Point Unit */ + +/*@} */ + + + +/******************************************************************************* + * 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. + @{ + */ + +#ifdef CMSIS_NVIC_VIRTUAL + #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE + #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" + #endif + #include CMSIS_NVIC_VIRTUAL_HEADER_FILE +#else + #define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping + #define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping + #define NVIC_EnableIRQ __NVIC_EnableIRQ + #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ + #define NVIC_DisableIRQ __NVIC_DisableIRQ + #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ + #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ + #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ + #define NVIC_GetActive __NVIC_GetActive + #define NVIC_SetPriority __NVIC_SetPriority + #define NVIC_GetPriority __NVIC_GetPriority + #define NVIC_SystemReset __NVIC_SystemReset +#endif /* CMSIS_NVIC_VIRTUAL */ + +#ifdef CMSIS_VECTAB_VIRTUAL + #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE + #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" + #endif + #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE +#else + #define NVIC_SetVector __NVIC_SetVector + #define NVIC_GetVector __NVIC_GetVector +#endif /* (CMSIS_VECTAB_VIRTUAL) */ + +#define NVIC_USER_IRQ_OFFSET 16 + + +/* The following EXC_RETURN values are saved the LR on exception entry */ +#define EXC_RETURN_HANDLER (0xFFFFFFF1UL) /* return to Handler mode, uses MSP after return */ +#define EXC_RETURN_THREAD_MSP (0xFFFFFFF9UL) /* return to Thread mode, uses MSP after return */ +#define EXC_RETURN_THREAD_PSP (0xFFFFFFFDUL) /* return to Thread mode, uses PSP after return */ +#define EXC_RETURN_HANDLER_FPU (0xFFFFFFE1UL) /* return to Handler mode, uses MSP after return, restore floating-point state */ +#define EXC_RETURN_THREAD_MSP_FPU (0xFFFFFFE9UL) /* return to Thread mode, uses MSP after return, restore floating-point state */ +#define EXC_RETURN_THREAD_PSP_FPU (0xFFFFFFEDUL) /* return to Thread mode, uses PSP after return, restore floating-point state */ + + +/** + \brief Set Priority Grouping + \details 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)0x07UL); /* only values 0..7 are used */ + + reg_value = SCB->AIRCR; /* read old register configuration */ + reg_value &= ~((uint32_t)(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk)); /* clear bits to change */ + reg_value = (reg_value | + ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | + (PriorityGroupTmp << SCB_AIRCR_PRIGROUP_Pos) ); /* Insert write key and priority group */ + SCB->AIRCR = reg_value; +} + + +/** + \brief Get Priority Grouping + \details 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 ((uint32_t)((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); +} + + +/** + \brief Enable Interrupt + \details Enables a device specific interrupt in the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + __COMPILER_BARRIER(); + NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + __COMPILER_BARRIER(); + } +} + + +/** + \brief Get Interrupt Enable status + \details Returns a device specific interrupt enable status from the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt is not enabled. + \return 1 Interrupt is enabled. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Disable Interrupt + \details Disables a device specific interrupt in the NVIC interrupt controller. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + __DSB(); + __ISB(); + } +} + + +/** + \brief Get Pending Interrupt + \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt status is not pending. + \return 1 Interrupt status is pending. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Set Pending Interrupt + \details Sets the pending bit of a device specific interrupt in the NVIC pending register. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Clear Pending Interrupt + \details Clears the pending bit of a device specific interrupt in the NVIC pending register. + \param [in] IRQn Device specific interrupt number. + \note IRQn must not be negative. + */ +__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); + } +} + + +/** + \brief Get Active Interrupt + \details Reads the active register in the NVIC and returns the active bit for the device specific interrupt. + \param [in] IRQn Device specific interrupt number. + \return 0 Interrupt status is not active. + \return 1 Interrupt status is active. + \note IRQn must not be negative. + */ +__STATIC_INLINE uint32_t __NVIC_GetActive(IRQn_Type IRQn) +{ + if ((int32_t)(IRQn) >= 0) + { + return((uint32_t)(((NVIC->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); + } + else + { + return(0U); + } +} + + +/** + \brief Set Interrupt Priority + \details Sets the priority of a device specific interrupt or a processor exception. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \param [in] priority Priority to set. + \note The priority cannot be set for every processor exception. + */ +__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) +{ + if ((int32_t)(IRQn) >= 0) + { + NVIC->IP[((uint32_t)IRQn)] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); + } + else + { + SCB->SHP[(((uint32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); + } +} + + +/** + \brief Get Interrupt Priority + \details Reads the priority of a device specific interrupt or a processor exception. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \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 ((int32_t)(IRQn) >= 0) + { + return(((uint32_t)NVIC->IP[((uint32_t)IRQn)] >> (8U - __NVIC_PRIO_BITS))); + } + else + { + return(((uint32_t)SCB->SHP[(((uint32_t)IRQn) & 0xFUL)-4UL] >> (8U - __NVIC_PRIO_BITS))); + } +} + + +/** + \brief Encode Priority + \details 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 smallest 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 & (uint32_t)0x07UL); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); + SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); + + return ( + ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | + ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) + ); +} + + +/** + \brief Decode Priority + \details 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 smallest 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* const pPreemptPriority, uint32_t* const pSubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); + SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); + + *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); + *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); +} + + +/** + \brief Set Interrupt Vector + \details Sets an interrupt vector in SRAM based interrupt vector table. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + VTOR must been relocated to SRAM before. + \param [in] IRQn Interrupt number + \param [in] vector Address of interrupt handler function + */ +__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) +{ + uint32_t *vectors = (uint32_t *)SCB->VTOR; + vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET] = vector; + /* ARM Application Note 321 states that the M4 does not require the architectural barrier */ +} + + +/** + \brief Get Interrupt Vector + \details Reads an interrupt vector from interrupt vector table. + The interrupt number can be positive to specify a device specific interrupt, + or negative to specify a processor exception. + \param [in] IRQn Interrupt number. + \return Address of interrupt handler function + */ +__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) +{ + uint32_t *vectors = (uint32_t *)SCB->VTOR; + return vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET]; +} + + +/** + \brief System Reset + \details Initiates a system reset request to reset the MCU. + */ +__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) +{ + __DSB(); /* Ensure all outstanding memory accesses included + buffered write are completed before reset */ + SCB->AIRCR = (uint32_t)((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | + (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | + SCB_AIRCR_SYSRESETREQ_Msk ); /* Keep priority group unchanged */ + __DSB(); /* Ensure completion of memory access */ + + for(;;) /* wait until reset */ + { + __NOP(); + } +} + +/*@} end of CMSIS_Core_NVICFunctions */ + + +/* ########################## MPU functions #################################### */ + +#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) + +#include "mpu_armv7.h" + +#endif + + +/* ########################## FPU functions #################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_FpuFunctions FPU Functions + \brief Function that provides FPU type. + @{ + */ + +/** + \brief get FPU type + \details returns the FPU type + \returns + - \b 0: No FPU + - \b 1: Single precision FPU + - \b 2: Double + Single precision FPU + */ +__STATIC_INLINE uint32_t SCB_GetFPUType(void) +{ + uint32_t mvfr0; + + mvfr0 = FPU->MVFR0; + if ((mvfr0 & (FPU_MVFR0_Single_precision_Msk | FPU_MVFR0_Double_precision_Msk)) == 0x020U) + { + return 1U; /* Single precision FPU */ + } + else + { + return 0U; /* No FPU */ + } +} + + +/*@} end of CMSIS_Core_FpuFunctions */ + + + +/* ################################## SysTick function ############################################ */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_SysTickFunctions SysTick Functions + \brief Functions that configure the System. + @{ + */ + +#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) + +/** + \brief System Tick Configuration + \details 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 - 1UL) > SysTick_LOAD_RELOAD_Msk) + { + return (1UL); /* Reload value impossible */ + } + + SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ + NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ + SysTick->VAL = 0UL; /* 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 (0UL); /* 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 ((int32_t)0x5AA55AA5U) /*!< Value identifying \ref ITM_RxBuffer is ready for next character. */ + + +/** + \brief ITM Send Character + \details 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) != 0UL) && /* ITM enabled */ + ((ITM->TER & 1UL ) != 0UL) ) /* ITM Port #0 enabled */ + { + while (ITM->PORT[0U].u32 == 0UL) + { + __NOP(); + } + ITM->PORT[0U].u8 = (uint8_t)ch; + } + return (ch); +} + + +/** + \brief ITM Receive Character + \details 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 + \details 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 */ + + + + +#ifdef __cplusplus +} +#endif + +#endif /* __CORE_CM4_H_DEPENDANT */ + +#endif /* __CMSIS_GENERIC */ diff --git a/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/mpu_armv7.h b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/mpu_armv7.h new file mode 100644 index 0000000000..791a8dae65 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/mpu_armv7.h @@ -0,0 +1,275 @@ +/****************************************************************************** + * @file mpu_armv7.h + * @brief CMSIS MPU API for Armv7-M MPU + * @version V5.1.1 + * @date 10. February 2020 + ******************************************************************************/ +/* + * Copyright (c) 2017-2020 Arm Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * 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 + * + * 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. + */ + +#if defined ( __ICCARM__ ) + #pragma system_include /* treat file as system include file for MISRA check */ +#elif defined (__clang__) + #pragma clang system_header /* treat file as system include file */ +#endif + +#ifndef ARM_MPU_ARMV7_H +#define ARM_MPU_ARMV7_H + +#define ARM_MPU_REGION_SIZE_32B ((uint8_t)0x04U) ///!< MPU Region Size 32 Bytes +#define ARM_MPU_REGION_SIZE_64B ((uint8_t)0x05U) ///!< MPU Region Size 64 Bytes +#define ARM_MPU_REGION_SIZE_128B ((uint8_t)0x06U) ///!< MPU Region Size 128 Bytes +#define ARM_MPU_REGION_SIZE_256B ((uint8_t)0x07U) ///!< MPU Region Size 256 Bytes +#define ARM_MPU_REGION_SIZE_512B ((uint8_t)0x08U) ///!< MPU Region Size 512 Bytes +#define ARM_MPU_REGION_SIZE_1KB ((uint8_t)0x09U) ///!< MPU Region Size 1 KByte +#define ARM_MPU_REGION_SIZE_2KB ((uint8_t)0x0AU) ///!< MPU Region Size 2 KBytes +#define ARM_MPU_REGION_SIZE_4KB ((uint8_t)0x0BU) ///!< MPU Region Size 4 KBytes +#define ARM_MPU_REGION_SIZE_8KB ((uint8_t)0x0CU) ///!< MPU Region Size 8 KBytes +#define ARM_MPU_REGION_SIZE_16KB ((uint8_t)0x0DU) ///!< MPU Region Size 16 KBytes +#define ARM_MPU_REGION_SIZE_32KB ((uint8_t)0x0EU) ///!< MPU Region Size 32 KBytes +#define ARM_MPU_REGION_SIZE_64KB ((uint8_t)0x0FU) ///!< MPU Region Size 64 KBytes +#define ARM_MPU_REGION_SIZE_128KB ((uint8_t)0x10U) ///!< MPU Region Size 128 KBytes +#define ARM_MPU_REGION_SIZE_256KB ((uint8_t)0x11U) ///!< MPU Region Size 256 KBytes +#define ARM_MPU_REGION_SIZE_512KB ((uint8_t)0x12U) ///!< MPU Region Size 512 KBytes +#define ARM_MPU_REGION_SIZE_1MB ((uint8_t)0x13U) ///!< MPU Region Size 1 MByte +#define ARM_MPU_REGION_SIZE_2MB ((uint8_t)0x14U) ///!< MPU Region Size 2 MBytes +#define ARM_MPU_REGION_SIZE_4MB ((uint8_t)0x15U) ///!< MPU Region Size 4 MBytes +#define ARM_MPU_REGION_SIZE_8MB ((uint8_t)0x16U) ///!< MPU Region Size 8 MBytes +#define ARM_MPU_REGION_SIZE_16MB ((uint8_t)0x17U) ///!< MPU Region Size 16 MBytes +#define ARM_MPU_REGION_SIZE_32MB ((uint8_t)0x18U) ///!< MPU Region Size 32 MBytes +#define ARM_MPU_REGION_SIZE_64MB ((uint8_t)0x19U) ///!< MPU Region Size 64 MBytes +#define ARM_MPU_REGION_SIZE_128MB ((uint8_t)0x1AU) ///!< MPU Region Size 128 MBytes +#define ARM_MPU_REGION_SIZE_256MB ((uint8_t)0x1BU) ///!< MPU Region Size 256 MBytes +#define ARM_MPU_REGION_SIZE_512MB ((uint8_t)0x1CU) ///!< MPU Region Size 512 MBytes +#define ARM_MPU_REGION_SIZE_1GB ((uint8_t)0x1DU) ///!< MPU Region Size 1 GByte +#define ARM_MPU_REGION_SIZE_2GB ((uint8_t)0x1EU) ///!< MPU Region Size 2 GBytes +#define ARM_MPU_REGION_SIZE_4GB ((uint8_t)0x1FU) ///!< MPU Region Size 4 GBytes + +#define ARM_MPU_AP_NONE 0U ///!< MPU Access Permission no access +#define ARM_MPU_AP_PRIV 1U ///!< MPU Access Permission privileged access only +#define ARM_MPU_AP_URO 2U ///!< MPU Access Permission unprivileged access read-only +#define ARM_MPU_AP_FULL 3U ///!< MPU Access Permission full access +#define ARM_MPU_AP_PRO 5U ///!< MPU Access Permission privileged access read-only +#define ARM_MPU_AP_RO 6U ///!< MPU Access Permission read-only access + +/** MPU Region Base Address Register Value +* +* \param Region The region to be configured, number 0 to 15. +* \param BaseAddress The base address for the region. +*/ +#define ARM_MPU_RBAR(Region, BaseAddress) \ + (((BaseAddress) & MPU_RBAR_ADDR_Msk) | \ + ((Region) & MPU_RBAR_REGION_Msk) | \ + (MPU_RBAR_VALID_Msk)) + +/** +* MPU Memory Access Attributes +* +* \param TypeExtField Type extension field, allows you to configure memory access type, for example strongly ordered, peripheral. +* \param IsShareable Region is shareable between multiple bus masters. +* \param IsCacheable Region is cacheable, i.e. its value may be kept in cache. +* \param IsBufferable Region is bufferable, i.e. using write-back caching. Cacheable but non-bufferable regions use write-through policy. +*/ +#define ARM_MPU_ACCESS_(TypeExtField, IsShareable, IsCacheable, IsBufferable) \ + ((((TypeExtField) << MPU_RASR_TEX_Pos) & MPU_RASR_TEX_Msk) | \ + (((IsShareable) << MPU_RASR_S_Pos) & MPU_RASR_S_Msk) | \ + (((IsCacheable) << MPU_RASR_C_Pos) & MPU_RASR_C_Msk) | \ + (((IsBufferable) << MPU_RASR_B_Pos) & MPU_RASR_B_Msk)) + +/** +* MPU Region Attribute and Size Register Value +* +* \param DisableExec Instruction access disable bit, 1= disable instruction fetches. +* \param AccessPermission Data access permissions, allows you to configure read/write access for User and Privileged mode. +* \param AccessAttributes Memory access attribution, see \ref ARM_MPU_ACCESS_. +* \param SubRegionDisable Sub-region disable field. +* \param Size Region size of the region to be configured, for example 4K, 8K. +*/ +#define ARM_MPU_RASR_EX(DisableExec, AccessPermission, AccessAttributes, SubRegionDisable, Size) \ + ((((DisableExec) << MPU_RASR_XN_Pos) & MPU_RASR_XN_Msk) | \ + (((AccessPermission) << MPU_RASR_AP_Pos) & MPU_RASR_AP_Msk) | \ + (((AccessAttributes) & (MPU_RASR_TEX_Msk | MPU_RASR_S_Msk | MPU_RASR_C_Msk | MPU_RASR_B_Msk))) | \ + (((SubRegionDisable) << MPU_RASR_SRD_Pos) & MPU_RASR_SRD_Msk) | \ + (((Size) << MPU_RASR_SIZE_Pos) & MPU_RASR_SIZE_Msk) | \ + (((MPU_RASR_ENABLE_Msk)))) + +/** +* MPU Region Attribute and Size Register Value +* +* \param DisableExec Instruction access disable bit, 1= disable instruction fetches. +* \param AccessPermission Data access permissions, allows you to configure read/write access for User and Privileged mode. +* \param TypeExtField Type extension field, allows you to configure memory access type, for example strongly ordered, peripheral. +* \param IsShareable Region is shareable between multiple bus masters. +* \param IsCacheable Region is cacheable, i.e. its value may be kept in cache. +* \param IsBufferable Region is bufferable, i.e. using write-back caching. Cacheable but non-bufferable regions use write-through policy. +* \param SubRegionDisable Sub-region disable field. +* \param Size Region size of the region to be configured, for example 4K, 8K. +*/ +#define ARM_MPU_RASR(DisableExec, AccessPermission, TypeExtField, IsShareable, IsCacheable, IsBufferable, SubRegionDisable, Size) \ + ARM_MPU_RASR_EX(DisableExec, AccessPermission, ARM_MPU_ACCESS_(TypeExtField, IsShareable, IsCacheable, IsBufferable), SubRegionDisable, Size) + +/** +* MPU Memory Access Attribute for strongly ordered memory. +* - TEX: 000b +* - Shareable +* - Non-cacheable +* - Non-bufferable +*/ +#define ARM_MPU_ACCESS_ORDERED ARM_MPU_ACCESS_(0U, 1U, 0U, 0U) + +/** +* MPU Memory Access Attribute for device memory. +* - TEX: 000b (if shareable) or 010b (if non-shareable) +* - Shareable or non-shareable +* - Non-cacheable +* - Bufferable (if shareable) or non-bufferable (if non-shareable) +* +* \param IsShareable Configures the device memory as shareable or non-shareable. +*/ +#define ARM_MPU_ACCESS_DEVICE(IsShareable) ((IsShareable) ? ARM_MPU_ACCESS_(0U, 1U, 0U, 1U) : ARM_MPU_ACCESS_(2U, 0U, 0U, 0U)) + +/** +* MPU Memory Access Attribute for normal memory. +* - TEX: 1BBb (reflecting outer cacheability rules) +* - Shareable or non-shareable +* - Cacheable or non-cacheable (reflecting inner cacheability rules) +* - Bufferable or non-bufferable (reflecting inner cacheability rules) +* +* \param OuterCp Configures the outer cache policy. +* \param InnerCp Configures the inner cache policy. +* \param IsShareable Configures the memory as shareable or non-shareable. +*/ +#define ARM_MPU_ACCESS_NORMAL(OuterCp, InnerCp, IsShareable) ARM_MPU_ACCESS_((4U | (OuterCp)), IsShareable, ((InnerCp) >> 1U), ((InnerCp) & 1U)) + +/** +* MPU Memory Access Attribute non-cacheable policy. +*/ +#define ARM_MPU_CACHEP_NOCACHE 0U + +/** +* MPU Memory Access Attribute write-back, write and read allocate policy. +*/ +#define ARM_MPU_CACHEP_WB_WRA 1U + +/** +* MPU Memory Access Attribute write-through, no write allocate policy. +*/ +#define ARM_MPU_CACHEP_WT_NWA 2U + +/** +* MPU Memory Access Attribute write-back, no write allocate policy. +*/ +#define ARM_MPU_CACHEP_WB_NWA 3U + + +/** +* Struct for a single MPU Region +*/ +typedef struct { + uint32_t RBAR; //!< The region base address register value (RBAR) + uint32_t RASR; //!< The region attribute and size register value (RASR) \ref MPU_RASR +} ARM_MPU_Region_t; + +/** Enable the MPU. +* \param MPU_Control Default access permissions for unconfigured regions. +*/ +__STATIC_INLINE void ARM_MPU_Enable(uint32_t MPU_Control) +{ + __DMB(); + MPU->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk; +#ifdef SCB_SHCSR_MEMFAULTENA_Msk + SCB->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk; +#endif + __DSB(); + __ISB(); +} + +/** Disable the MPU. +*/ +__STATIC_INLINE void ARM_MPU_Disable(void) +{ + __DMB(); +#ifdef SCB_SHCSR_MEMFAULTENA_Msk + SCB->SHCSR &= ~SCB_SHCSR_MEMFAULTENA_Msk; +#endif + MPU->CTRL &= ~MPU_CTRL_ENABLE_Msk; + __DSB(); + __ISB(); +} + +/** Clear and disable the given MPU region. +* \param rnr Region number to be cleared. +*/ +__STATIC_INLINE void ARM_MPU_ClrRegion(uint32_t rnr) +{ + MPU->RNR = rnr; + MPU->RASR = 0U; +} + +/** Configure an MPU region. +* \param rbar Value for RBAR register. +* \param rsar Value for RSAR register. +*/ +__STATIC_INLINE void ARM_MPU_SetRegion(uint32_t rbar, uint32_t rasr) +{ + MPU->RBAR = rbar; + MPU->RASR = rasr; +} + +/** Configure the given MPU region. +* \param rnr Region number to be configured. +* \param rbar Value for RBAR register. +* \param rsar Value for RSAR register. +*/ +__STATIC_INLINE void ARM_MPU_SetRegionEx(uint32_t rnr, uint32_t rbar, uint32_t rasr) +{ + MPU->RNR = rnr; + MPU->RBAR = rbar; + MPU->RASR = rasr; +} + +/** Memcopy with strictly ordered memory access, e.g. for register targets. +* \param dst Destination data is copied to. +* \param src Source data is copied from. +* \param len Amount of data words to be copied. +*/ +__STATIC_INLINE void ARM_MPU_OrderedMemcpy(volatile uint32_t* dst, const uint32_t* __RESTRICT src, uint32_t len) +{ + uint32_t i; + for (i = 0U; i < len; ++i) + { + dst[i] = src[i]; + } +} + +/** Load the given number of MPU regions from a table. +* \param table Pointer to the MPU configuration table. +* \param cnt Amount of regions to be configured. +*/ +__STATIC_INLINE void ARM_MPU_Load(ARM_MPU_Region_t const* table, uint32_t cnt) +{ + const uint32_t rowWordSize = sizeof(ARM_MPU_Region_t)/4U; + while (cnt > MPU_TYPE_RALIASES) { + ARM_MPU_OrderedMemcpy(&(MPU->RBAR), &(table->RBAR), MPU_TYPE_RALIASES*rowWordSize); + table += MPU_TYPE_RALIASES; + cnt -= MPU_TYPE_RALIASES; + } + ARM_MPU_OrderedMemcpy(&(MPU->RBAR), &(table->RBAR), cnt*rowWordSize); +} + +#endif diff --git a/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/mpu_armv8.h b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/mpu_armv8.h new file mode 100644 index 0000000000..ef44ad01df --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/mpu_armv8.h @@ -0,0 +1,352 @@ +/****************************************************************************** + * @file mpu_armv8.h + * @brief CMSIS MPU API for Armv8-M and Armv8.1-M MPU + * @version V5.1.2 + * @date 10. February 2020 + ******************************************************************************/ +/* + * Copyright (c) 2017-2020 Arm Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * 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 + * + * 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. + */ + +#if defined ( __ICCARM__ ) + #pragma system_include /* treat file as system include file for MISRA check */ +#elif defined (__clang__) + #pragma clang system_header /* treat file as system include file */ +#endif + +#ifndef ARM_MPU_ARMV8_H +#define ARM_MPU_ARMV8_H + +/** \brief Attribute for device memory (outer only) */ +#define ARM_MPU_ATTR_DEVICE ( 0U ) + +/** \brief Attribute for non-cacheable, normal memory */ +#define ARM_MPU_ATTR_NON_CACHEABLE ( 4U ) + +/** \brief Attribute for normal memory (outer and inner) +* \param NT Non-Transient: Set to 1 for non-transient data. +* \param WB Write-Back: Set to 1 to use write-back update policy. +* \param RA Read Allocation: Set to 1 to use cache allocation on read miss. +* \param WA Write Allocation: Set to 1 to use cache allocation on write miss. +*/ +#define ARM_MPU_ATTR_MEMORY_(NT, WB, RA, WA) \ + ((((NT) & 1U) << 3U) | (((WB) & 1U) << 2U) | (((RA) & 1U) << 1U) | ((WA) & 1U)) + +/** \brief Device memory type non Gathering, non Re-ordering, non Early Write Acknowledgement */ +#define ARM_MPU_ATTR_DEVICE_nGnRnE (0U) + +/** \brief Device memory type non Gathering, non Re-ordering, Early Write Acknowledgement */ +#define ARM_MPU_ATTR_DEVICE_nGnRE (1U) + +/** \brief Device memory type non Gathering, Re-ordering, Early Write Acknowledgement */ +#define ARM_MPU_ATTR_DEVICE_nGRE (2U) + +/** \brief Device memory type Gathering, Re-ordering, Early Write Acknowledgement */ +#define ARM_MPU_ATTR_DEVICE_GRE (3U) + +/** \brief Memory Attribute +* \param O Outer memory attributes +* \param I O == ARM_MPU_ATTR_DEVICE: Device memory attributes, else: Inner memory attributes +*/ +#define ARM_MPU_ATTR(O, I) ((((O) & 0xFU) << 4U) | ((((O) & 0xFU) != 0U) ? ((I) & 0xFU) : (((I) & 0x3U) << 2U))) + +/** \brief Normal memory non-shareable */ +#define ARM_MPU_SH_NON (0U) + +/** \brief Normal memory outer shareable */ +#define ARM_MPU_SH_OUTER (2U) + +/** \brief Normal memory inner shareable */ +#define ARM_MPU_SH_INNER (3U) + +/** \brief Memory access permissions +* \param RO Read-Only: Set to 1 for read-only memory. +* \param NP Non-Privileged: Set to 1 for non-privileged memory. +*/ +#define ARM_MPU_AP_(RO, NP) ((((RO) & 1U) << 1U) | ((NP) & 1U)) + +/** \brief Region Base Address Register value +* \param BASE The base address bits [31:5] of a memory region. The value is zero extended. Effective address gets 32 byte aligned. +* \param SH Defines the Shareability domain for this memory region. +* \param RO Read-Only: Set to 1 for a read-only memory region. +* \param NP Non-Privileged: Set to 1 for a non-privileged memory region. +* \oaram XN eXecute Never: Set to 1 for a non-executable memory region. +*/ +#define ARM_MPU_RBAR(BASE, SH, RO, NP, XN) \ + (((BASE) & MPU_RBAR_BASE_Msk) | \ + (((SH) << MPU_RBAR_SH_Pos) & MPU_RBAR_SH_Msk) | \ + ((ARM_MPU_AP_(RO, NP) << MPU_RBAR_AP_Pos) & MPU_RBAR_AP_Msk) | \ + (((XN) << MPU_RBAR_XN_Pos) & MPU_RBAR_XN_Msk)) + +/** \brief Region Limit Address Register value +* \param LIMIT The limit address bits [31:5] for this memory region. The value is one extended. +* \param IDX The attribute index to be associated with this memory region. +*/ +#define ARM_MPU_RLAR(LIMIT, IDX) \ + (((LIMIT) & MPU_RLAR_LIMIT_Msk) | \ + (((IDX) << MPU_RLAR_AttrIndx_Pos) & MPU_RLAR_AttrIndx_Msk) | \ + (MPU_RLAR_EN_Msk)) + +#if defined(MPU_RLAR_PXN_Pos) + +/** \brief Region Limit Address Register with PXN value +* \param LIMIT The limit address bits [31:5] for this memory region. The value is one extended. +* \param PXN Privileged execute never. Defines whether code can be executed from this privileged region. +* \param IDX The attribute index to be associated with this memory region. +*/ +#define ARM_MPU_RLAR_PXN(LIMIT, PXN, IDX) \ + (((LIMIT) & MPU_RLAR_LIMIT_Msk) | \ + (((PXN) << MPU_RLAR_PXN_Pos) & MPU_RLAR_PXN_Msk) | \ + (((IDX) << MPU_RLAR_AttrIndx_Pos) & MPU_RLAR_AttrIndx_Msk) | \ + (MPU_RLAR_EN_Msk)) + +#endif + +/** +* Struct for a single MPU Region +*/ +typedef struct { + uint32_t RBAR; /*!< Region Base Address Register value */ + uint32_t RLAR; /*!< Region Limit Address Register value */ +} ARM_MPU_Region_t; + +/** Enable the MPU. +* \param MPU_Control Default access permissions for unconfigured regions. +*/ +__STATIC_INLINE void ARM_MPU_Enable(uint32_t MPU_Control) +{ + __DMB(); + MPU->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk; +#ifdef SCB_SHCSR_MEMFAULTENA_Msk + SCB->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk; +#endif + __DSB(); + __ISB(); +} + +/** Disable the MPU. +*/ +__STATIC_INLINE void ARM_MPU_Disable(void) +{ + __DMB(); +#ifdef SCB_SHCSR_MEMFAULTENA_Msk + SCB->SHCSR &= ~SCB_SHCSR_MEMFAULTENA_Msk; +#endif + MPU->CTRL &= ~MPU_CTRL_ENABLE_Msk; + __DSB(); + __ISB(); +} + +#ifdef MPU_NS +/** Enable the Non-secure MPU. +* \param MPU_Control Default access permissions for unconfigured regions. +*/ +__STATIC_INLINE void ARM_MPU_Enable_NS(uint32_t MPU_Control) +{ + __DMB(); + MPU_NS->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk; +#ifdef SCB_SHCSR_MEMFAULTENA_Msk + SCB_NS->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk; +#endif + __DSB(); + __ISB(); +} + +/** Disable the Non-secure MPU. +*/ +__STATIC_INLINE void ARM_MPU_Disable_NS(void) +{ + __DMB(); +#ifdef SCB_SHCSR_MEMFAULTENA_Msk + SCB_NS->SHCSR &= ~SCB_SHCSR_MEMFAULTENA_Msk; +#endif + MPU_NS->CTRL &= ~MPU_CTRL_ENABLE_Msk; + __DSB(); + __ISB(); +} +#endif + +/** Set the memory attribute encoding to the given MPU. +* \param mpu Pointer to the MPU to be configured. +* \param idx The attribute index to be set [0-7] +* \param attr The attribute value to be set. +*/ +__STATIC_INLINE void ARM_MPU_SetMemAttrEx(MPU_Type* mpu, uint8_t idx, uint8_t attr) +{ + const uint8_t reg = idx / 4U; + const uint32_t pos = ((idx % 4U) * 8U); + const uint32_t mask = 0xFFU << pos; + + if (reg >= (sizeof(mpu->MAIR) / sizeof(mpu->MAIR[0]))) { + return; // invalid index + } + + mpu->MAIR[reg] = ((mpu->MAIR[reg] & ~mask) | ((attr << pos) & mask)); +} + +/** Set the memory attribute encoding. +* \param idx The attribute index to be set [0-7] +* \param attr The attribute value to be set. +*/ +__STATIC_INLINE void ARM_MPU_SetMemAttr(uint8_t idx, uint8_t attr) +{ + ARM_MPU_SetMemAttrEx(MPU, idx, attr); +} + +#ifdef MPU_NS +/** Set the memory attribute encoding to the Non-secure MPU. +* \param idx The attribute index to be set [0-7] +* \param attr The attribute value to be set. +*/ +__STATIC_INLINE void ARM_MPU_SetMemAttr_NS(uint8_t idx, uint8_t attr) +{ + ARM_MPU_SetMemAttrEx(MPU_NS, idx, attr); +} +#endif + +/** Clear and disable the given MPU region of the given MPU. +* \param mpu Pointer to MPU to be used. +* \param rnr Region number to be cleared. +*/ +__STATIC_INLINE void ARM_MPU_ClrRegionEx(MPU_Type* mpu, uint32_t rnr) +{ + mpu->RNR = rnr; + mpu->RLAR = 0U; +} + +/** Clear and disable the given MPU region. +* \param rnr Region number to be cleared. +*/ +__STATIC_INLINE void ARM_MPU_ClrRegion(uint32_t rnr) +{ + ARM_MPU_ClrRegionEx(MPU, rnr); +} + +#ifdef MPU_NS +/** Clear and disable the given Non-secure MPU region. +* \param rnr Region number to be cleared. +*/ +__STATIC_INLINE void ARM_MPU_ClrRegion_NS(uint32_t rnr) +{ + ARM_MPU_ClrRegionEx(MPU_NS, rnr); +} +#endif + +/** Configure the given MPU region of the given MPU. +* \param mpu Pointer to MPU to be used. +* \param rnr Region number to be configured. +* \param rbar Value for RBAR register. +* \param rlar Value for RLAR register. +*/ +__STATIC_INLINE void ARM_MPU_SetRegionEx(MPU_Type* mpu, uint32_t rnr, uint32_t rbar, uint32_t rlar) +{ + mpu->RNR = rnr; + mpu->RBAR = rbar; + mpu->RLAR = rlar; +} + +/** Configure the given MPU region. +* \param rnr Region number to be configured. +* \param rbar Value for RBAR register. +* \param rlar Value for RLAR register. +*/ +__STATIC_INLINE void ARM_MPU_SetRegion(uint32_t rnr, uint32_t rbar, uint32_t rlar) +{ + ARM_MPU_SetRegionEx(MPU, rnr, rbar, rlar); +} + +#ifdef MPU_NS +/** Configure the given Non-secure MPU region. +* \param rnr Region number to be configured. +* \param rbar Value for RBAR register. +* \param rlar Value for RLAR register. +*/ +__STATIC_INLINE void ARM_MPU_SetRegion_NS(uint32_t rnr, uint32_t rbar, uint32_t rlar) +{ + ARM_MPU_SetRegionEx(MPU_NS, rnr, rbar, rlar); +} +#endif + +/** Memcopy with strictly ordered memory access, e.g. for register targets. +* \param dst Destination data is copied to. +* \param src Source data is copied from. +* \param len Amount of data words to be copied. +*/ +__STATIC_INLINE void ARM_MPU_OrderedMemcpy(volatile uint32_t* dst, const uint32_t* __RESTRICT src, uint32_t len) +{ + uint32_t i; + for (i = 0U; i < len; ++i) + { + dst[i] = src[i]; + } +} + +/** Load the given number of MPU regions from a table to the given MPU. +* \param mpu Pointer to the MPU registers to be used. +* \param rnr First region number to be configured. +* \param table Pointer to the MPU configuration table. +* \param cnt Amount of regions to be configured. +*/ +__STATIC_INLINE void ARM_MPU_LoadEx(MPU_Type* mpu, uint32_t rnr, ARM_MPU_Region_t const* table, uint32_t cnt) +{ + const uint32_t rowWordSize = sizeof(ARM_MPU_Region_t)/4U; + if (cnt == 1U) { + mpu->RNR = rnr; + ARM_MPU_OrderedMemcpy(&(mpu->RBAR), &(table->RBAR), rowWordSize); + } else { + uint32_t rnrBase = rnr & ~(MPU_TYPE_RALIASES-1U); + uint32_t rnrOffset = rnr % MPU_TYPE_RALIASES; + + mpu->RNR = rnrBase; + while ((rnrOffset + cnt) > MPU_TYPE_RALIASES) { + uint32_t c = MPU_TYPE_RALIASES - rnrOffset; + ARM_MPU_OrderedMemcpy(&(mpu->RBAR)+(rnrOffset*2U), &(table->RBAR), c*rowWordSize); + table += c; + cnt -= c; + rnrOffset = 0U; + rnrBase += MPU_TYPE_RALIASES; + mpu->RNR = rnrBase; + } + + ARM_MPU_OrderedMemcpy(&(mpu->RBAR)+(rnrOffset*2U), &(table->RBAR), cnt*rowWordSize); + } +} + +/** Load the given number of MPU regions from a table. +* \param rnr First region number to be configured. +* \param table Pointer to the MPU configuration table. +* \param cnt Amount of regions to be configured. +*/ +__STATIC_INLINE void ARM_MPU_Load(uint32_t rnr, ARM_MPU_Region_t const* table, uint32_t cnt) +{ + ARM_MPU_LoadEx(MPU, rnr, table, cnt); +} + +#ifdef MPU_NS +/** Load the given number of MPU regions from a table to the Non-secure MPU. +* \param rnr First region number to be configured. +* \param table Pointer to the MPU configuration table. +* \param cnt Amount of regions to be configured. +*/ +__STATIC_INLINE void ARM_MPU_Load_NS(uint32_t rnr, ARM_MPU_Region_t const* table, uint32_t cnt) +{ + ARM_MPU_LoadEx(MPU_NS, rnr, table, cnt); +} +#endif + +#endif + diff --git a/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/pmu_armv8.h b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/pmu_armv8.h new file mode 100644 index 0000000000..dbd39d20c7 --- /dev/null +++ b/lib/main/AT32F43x/Drivers/CMSIS/cm4/core_support/pmu_armv8.h @@ -0,0 +1,337 @@ +/****************************************************************************** + * @file pmu_armv8.h + * @brief CMSIS PMU API for Armv8.1-M PMU + * @version V1.0.0 + * @date 24. March 2020 + ******************************************************************************/ +/* + * Copyright (c) 2020 Arm Limited. All rights reserved. + * + * SPDX-License-Identifier: Apache-2.0 + * + * 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 + * + * 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. + */ + +#if defined ( __ICCARM__ ) + #pragma system_include /* treat file as system include file for MISRA check */ +#elif defined (__clang__) + #pragma clang system_header /* treat file as system include file */ +#endif + +#ifndef ARM_PMU_ARMV8_H +#define ARM_PMU_ARMV8_H + +/** + * \brief PMU Events + * \note See the Armv8.1-M Architecture Reference Manual for full details on these PMU events. + * */ + +#define ARM_PMU_SW_INCR 0x0000 /*!< Software update to the PMU_SWINC register, architecturally executed and condition code check pass */ +#define ARM_PMU_L1I_CACHE_REFILL 0x0001 /*!< L1 I-Cache refill */ +#define ARM_PMU_L1D_CACHE_REFILL 0x0003 /*!< L1 D-Cache refill */ +#define ARM_PMU_L1D_CACHE 0x0004 /*!< L1 D-Cache access */ +#define ARM_PMU_LD_RETIRED 0x0006 /*!< Memory-reading instruction architecturally executed and condition code check pass */ +#define ARM_PMU_ST_RETIRED 0x0007 /*!< Memory-writing instruction architecturally executed and condition code check pass */ +#define ARM_PMU_INST_RETIRED 0x0008 /*!< Instruction architecturally executed */ +#define ARM_PMU_EXC_TAKEN 0x0009 /*!< Exception entry */ +#define ARM_PMU_EXC_RETURN 0x000A /*!< Exception return instruction architecturally executed and the condition code check pass */ +#define ARM_PMU_PC_WRITE_RETIRED 0x000C /*!< Software change to the Program Counter (PC). Instruction is architecturally executed and condition code check pass */ +#define ARM_PMU_BR_IMMED_RETIRED 0x000D /*!< Immediate branch architecturally executed */ +#define ARM_PMU_BR_RETURN_RETIRED 0x000E /*!< Function return instruction architecturally executed and the condition code check pass */ +#define ARM_PMU_UNALIGNED_LDST_RETIRED 0x000F /*!< Unaligned memory memory-reading or memory-writing instruction architecturally executed and condition code check pass */ +#define ARM_PMU_BR_MIS_PRED 0x0010 /*!< Mispredicted or not predicted branch speculatively executed */ +#define ARM_PMU_CPU_CYCLES 0x0011 /*!< Cycle */ +#define ARM_PMU_BR_PRED 0x0012 /*!< Predictable branch speculatively executed */ +#define ARM_PMU_MEM_ACCESS 0x0013 /*!< Data memory access */ +#define ARM_PMU_L1I_CACHE 0x0014 /*!< Level 1 instruction cache access */ +#define ARM_PMU_L1D_CACHE_WB 0x0015 /*!< Level 1 data cache write-back */ +#define ARM_PMU_L2D_CACHE 0x0016 /*!< Level 2 data cache access */ +#define ARM_PMU_L2D_CACHE_REFILL 0x0017 /*!< Level 2 data cache refill */ +#define ARM_PMU_L2D_CACHE_WB 0x0018 /*!< Level 2 data cache write-back */ +#define ARM_PMU_BUS_ACCESS 0x0019 /*!< Bus access */ +#define ARM_PMU_MEMORY_ERROR 0x001A /*!< Local memory error */ +#define ARM_PMU_INST_SPEC 0x001B /*!< Instruction speculatively executed */ +#define ARM_PMU_BUS_CYCLES 0x001D /*!< Bus cycles */ +#define ARM_PMU_CHAIN 0x001E /*!< For an odd numbered counter, increment when an overflow occurs on the preceding even-numbered counter on the same PE */ +#define ARM_PMU_L1D_CACHE_ALLOCATE 0x001F /*!< Level 1 data cache allocation without refill */ +#define ARM_PMU_L2D_CACHE_ALLOCATE 0x0020 /*!< Level 2 data cache allocation without refill */ +#define ARM_PMU_BR_RETIRED 0x0021 /*!< Branch instruction architecturally executed */ +#define ARM_PMU_BR_MIS_PRED_RETIRED 0x0022 /*!< Mispredicted branch instruction architecturally executed */ +#define ARM_PMU_STALL_FRONTEND 0x0023 /*!< No operation issued because of the frontend */ +#define ARM_PMU_STALL_BACKEND 0x0024 /*!< No operation issued because of the backend */ +#define ARM_PMU_L2I_CACHE 0x0027 /*!< Level 2 instruction cache access */ +#define ARM_PMU_L2I_CACHE_REFILL 0x0028 /*!< Level 2 instruction cache refill */ +#define ARM_PMU_L3D_CACHE_ALLOCATE 0x0029 /*!< Level 3 data cache allocation without refill */ +#define ARM_PMU_L3D_CACHE_REFILL 0x002A /*!< Level 3 data cache refill */ +#define ARM_PMU_L3D_CACHE 0x002B /*!< Level 3 data cache access */ +#define ARM_PMU_L3D_CACHE_WB 0x002C /*!< Level 3 data cache write-back */ +#define ARM_PMU_LL_CACHE_RD 0x0036 /*!< Last level data cache read */ +#define ARM_PMU_LL_CACHE_MISS_RD 0x0037 /*!< Last level data cache read miss */ +#define ARM_PMU_L1D_CACHE_MISS_RD 0x0039 /*!< Level 1 data cache read miss */ +#define ARM_PMU_OP_COMPLETE 0x003A /*!< Operation retired */ +#define ARM_PMU_OP_SPEC 0x003B /*!< Operation speculatively executed */ +#define ARM_PMU_STALL 0x003C /*!< Stall cycle for instruction or operation not sent for execution */ +#define ARM_PMU_STALL_OP_BACKEND 0x003D /*!< Stall cycle for instruction or operation not sent for execution due to pipeline backend */ +#define ARM_PMU_STALL_OP_FRONTEND 0x003E /*!< Stall cycle for instruction or operation not sent for execution due to pipeline frontend */ +#define ARM_PMU_STALL_OP 0x003F /*!< Instruction or operation slots not occupied each cycle */ +#define ARM_PMU_L1D_CACHE_RD 0x0040 /*!< Level 1 data cache read */ +#define ARM_PMU_LE_RETIRED 0x0100 /*!< Loop end instruction executed */ +#define ARM_PMU_LE_SPEC 0x0101 /*!< Loop end instruction speculatively executed */ +#define ARM_PMU_BF_RETIRED 0x0104 /*!< Branch future instruction architecturally executed and condition code check pass */ +#define ARM_PMU_BF_SPEC 0x0105 /*!< Branch future instruction speculatively executed and condition code check pass */ +#define ARM_PMU_LE_CANCEL 0x0108 /*!< Loop end instruction not taken */ +#define ARM_PMU_BF_CANCEL 0x0109 /*!< Branch future instruction not taken */ +#define ARM_PMU_SE_CALL_S 0x0114 /*!< Call to secure function, resulting in Security state change */ +#define ARM_PMU_SE_CALL_NS 0x0115 /*!< Call to non-secure function, resulting in Security state change */ +#define ARM_PMU_DWT_CMPMATCH0 0x0118 /*!< DWT comparator 0 match */ +#define ARM_PMU_DWT_CMPMATCH1 0x0119 /*!< DWT comparator 1 match */ +#define ARM_PMU_DWT_CMPMATCH2 0x011A /*!< DWT comparator 2 match */ +#define ARM_PMU_DWT_CMPMATCH3 0x011B /*!< DWT comparator 3 match */ +#define ARM_PMU_MVE_INST_RETIRED 0x0200 /*!< MVE instruction architecturally executed */ +#define ARM_PMU_MVE_INST_SPEC 0x0201 /*!< MVE instruction speculatively executed */ +#define ARM_PMU_MVE_FP_RETIRED 0x0204 /*!< MVE floating-point instruction architecturally executed */ +#define ARM_PMU_MVE_FP_SPEC 0x0205 /*!< MVE floating-point instruction speculatively executed */ +#define ARM_PMU_MVE_FP_HP_RETIRED 0x0208 /*!< MVE half-precision floating-point instruction architecturally executed */ +#define ARM_PMU_MVE_FP_HP_SPEC 0x0209 /*!< MVE half-precision floating-point instruction speculatively executed */ +#define ARM_PMU_MVE_FP_SP_RETIRED 0x020C /*!< MVE single-precision floating-point instruction architecturally executed */ +#define ARM_PMU_MVE_FP_SP_SPEC 0x020D /*!< MVE single-precision floating-point instruction speculatively executed */ +#define ARM_PMU_MVE_FP_MAC_RETIRED 0x0214 /*!< MVE floating-point multiply or multiply-accumulate instruction architecturally executed */ +#define ARM_PMU_MVE_FP_MAC_SPEC 0x0215 /*!< MVE floating-point multiply or multiply-accumulate instruction speculatively executed */ +#define ARM_PMU_MVE_INT_RETIRED 0x0224 /*!< MVE integer instruction architecturally executed */ +#define ARM_PMU_MVE_INT_SPEC 0x0225 /*!< MVE integer instruction speculatively executed */ +#define ARM_PMU_MVE_INT_MAC_RETIRED 0x0228 /*!< MVE multiply or multiply-accumulate instruction architecturally executed */ +#define ARM_PMU_MVE_INT_MAC_SPEC 0x0229 /*!< MVE multiply or multiply-accumulate instruction speculatively executed */ +#define ARM_PMU_MVE_LDST_RETIRED 0x0238 /*!< MVE load or store instruction architecturally executed */ +#define ARM_PMU_MVE_LDST_SPEC 0x0239 /*!< MVE load or store instruction speculatively executed */ +#define ARM_PMU_MVE_LD_RETIRED 0x023C /*!< MVE load instruction architecturally executed */ +#define ARM_PMU_MVE_LD_SPEC 0x023D /*!< MVE load instruction speculatively executed */ +#define ARM_PMU_MVE_ST_RETIRED 0x0240 /*!< MVE store instruction architecturally executed */ +#define ARM_PMU_MVE_ST_SPEC 0x0241 /*!< MVE store instruction speculatively executed */ +#define ARM_PMU_MVE_LDST_CONTIG_RETIRED 0x0244 /*!< MVE contiguous load or store instruction architecturally executed */ +#define ARM_PMU_MVE_LDST_CONTIG_SPEC 0x0245 /*!< MVE contiguous load or store instruction speculatively executed */ +#define ARM_PMU_MVE_LD_CONTIG_RETIRED 0x0248 /*!< MVE contiguous load instruction architecturally executed */ +#define ARM_PMU_MVE_LD_CONTIG_SPEC 0x0249 /*!< MVE contiguous load instruction speculatively executed */ +#define ARM_PMU_MVE_ST_CONTIG_RETIRED 0x024C /*!< MVE contiguous store instruction architecturally executed */ +#define ARM_PMU_MVE_ST_CONTIG_SPEC 0x024D /*!< MVE contiguous store instruction speculatively executed */ +#define ARM_PMU_MVE_LDST_NONCONTIG_RETIRED 0x0250 /*!< MVE non-contiguous load or store instruction architecturally executed */ +#define ARM_PMU_MVE_LDST_NONCONTIG_SPEC 0x0251 /*!< MVE non-contiguous load or store instruction speculatively executed */ +#define ARM_PMU_MVE_LD_NONCONTIG_RETIRED 0x0254 /*!< MVE non-contiguous load instruction architecturally executed */ +#define ARM_PMU_MVE_LD_NONCONTIG_SPEC 0x0255 /*!< MVE non-contiguous load instruction speculatively executed */ +#define ARM_PMU_MVE_ST_NONCONTIG_RETIRED 0x0258 /*!< MVE non-contiguous store instruction architecturally executed */ +#define ARM_PMU_MVE_ST_NONCONTIG_SPEC 0x0259 /*!< MVE non-contiguous store instruction speculatively executed */ +#define ARM_PMU_MVE_LDST_MULTI_RETIRED 0x025C /*!< MVE memory instruction targeting multiple registers architecturally executed */ +#define ARM_PMU_MVE_LDST_MULTI_SPEC 0x025D /*!< MVE memory instruction targeting multiple registers speculatively executed */ +#define ARM_PMU_MVE_LD_MULTI_RETIRED 0x0260 /*!< MVE memory load instruction targeting multiple registers architecturally executed */ +#define ARM_PMU_MVE_LD_MULTI_SPEC 0x0261 /*!< MVE memory load instruction targeting multiple registers speculatively executed */ +#define ARM_PMU_MVE_ST_MULTI_RETIRED 0x0261 /*!< MVE memory store instruction targeting multiple registers architecturally executed */ +#define ARM_PMU_MVE_ST_MULTI_SPEC 0x0265 /*!< MVE memory store instruction targeting multiple registers speculatively executed */ +#define ARM_PMU_MVE_LDST_UNALIGNED_RETIRED 0x028C /*!< MVE unaligned memory load or store instruction architecturally executed */ +#define ARM_PMU_MVE_LDST_UNALIGNED_SPEC 0x028D /*!< MVE unaligned memory load or store instruction speculatively executed */ +#define ARM_PMU_MVE_LD_UNALIGNED_RETIRED 0x0290 /*!< MVE unaligned load instruction architecturally executed */ +#define ARM_PMU_MVE_LD_UNALIGNED_SPEC 0x0291 /*!< MVE unaligned load instruction speculatively executed */ +#define ARM_PMU_MVE_ST_UNALIGNED_RETIRED 0x0294 /*!< MVE unaligned store instruction architecturally executed */ +#define ARM_PMU_MVE_ST_UNALIGNED_SPEC 0x0295 /*!< MVE unaligned store instruction speculatively executed */ +#define ARM_PMU_MVE_LDST_UNALIGNED_NONCONTIG_RETIRED 0x0298 /*!< MVE unaligned noncontiguous load or store instruction architecturally executed */ +#define ARM_PMU_MVE_LDST_UNALIGNED_NONCONTIG_SPEC 0x0299 /*!< MVE unaligned noncontiguous load or store instruction speculatively executed */ +#define ARM_PMU_MVE_VREDUCE_RETIRED 0x02A0 /*!< MVE vector reduction instruction architecturally executed */ +#define ARM_PMU_MVE_VREDUCE_SPEC 0x02A1 /*!< MVE vector reduction instruction speculatively executed */ +#define ARM_PMU_MVE_VREDUCE_FP_RETIRED 0x02A4 /*!< MVE floating-point vector reduction instruction architecturally executed */ +#define ARM_PMU_MVE_VREDUCE_FP_SPEC 0x02A5 /*!< MVE floating-point vector reduction instruction speculatively executed */ +#define ARM_PMU_MVE_VREDUCE_INT_RETIRED 0x02A8 /*!< MVE integer vector reduction instruction architecturally executed */ +#define ARM_PMU_MVE_VREDUCE_INT_SPEC 0x02A9 /*!< MVE integer vector reduction instruction speculatively executed */ +#define ARM_PMU_MVE_PRED 0x02B8 /*!< Cycles where one or more predicated beats architecturally executed */ +#define ARM_PMU_MVE_STALL 0x02CC /*!< Stall cycles caused by an MVE instruction */ +#define ARM_PMU_MVE_STALL_RESOURCE 0x02CD /*!< Stall cycles caused by an MVE instruction because of resource conflicts */ +#define ARM_PMU_MVE_STALL_RESOURCE_MEM 0x02CE /*!< Stall cycles caused by an MVE instruction because of memory resource conflicts */ +#define ARM_PMU_MVE_STALL_RESOURCE_FP 0x02CF /*!< Stall cycles caused by an MVE instruction because of floating-point resource conflicts */ +#define ARM_PMU_MVE_STALL_RESOURCE_INT 0x02D0 /*!< Stall cycles caused by an MVE instruction because of integer resource conflicts */ +#define ARM_PMU_MVE_STALL_BREAK 0x02D3 /*!< Stall cycles caused by an MVE chain break */ +#define ARM_PMU_MVE_STALL_DEPENDENCY 0x02D4 /*!< Stall cycles caused by MVE register dependency */ +#define ARM_PMU_ITCM_ACCESS 0x4007 /*!< Instruction TCM access */ +#define ARM_PMU_DTCM_ACCESS 0x4008 /*!< Data TCM access */ +#define ARM_PMU_TRCEXTOUT0 0x4010 /*!< ETM external output 0 */ +#define ARM_PMU_TRCEXTOUT1 0x4011 /*!< ETM external output 1 */ +#define ARM_PMU_TRCEXTOUT2 0x4012 /*!< ETM external output 2 */ +#define ARM_PMU_TRCEXTOUT3 0x4013 /*!< ETM external output 3 */ +#define ARM_PMU_CTI_TRIGOUT4 0x4018 /*!< Cross-trigger Interface output trigger 4 */ +#define ARM_PMU_CTI_TRIGOUT5 0x4019 /*!< Cross-trigger Interface output trigger 5 */ +#define ARM_PMU_CTI_TRIGOUT6 0x401A /*!< Cross-trigger Interface output trigger 6 */ +#define ARM_PMU_CTI_TRIGOUT7 0x401B /*!< Cross-trigger Interface output trigger 7 */ + +/** \brief PMU Functions */ + +__STATIC_INLINE void ARM_PMU_Enable(void); +__STATIC_INLINE void ARM_PMU_Disable(void); + +__STATIC_INLINE void ARM_PMU_Set_EVTYPER(uint32_t num, uint32_t type); + +__STATIC_INLINE void ARM_PMU_CYCCNT_Reset(void); +__STATIC_INLINE void ARM_PMU_EVCNTR_ALL_Reset(void); + +__STATIC_INLINE void ARM_PMU_CNTR_Enable(uint32_t mask); +__STATIC_INLINE void ARM_PMU_CNTR_Disable(uint32_t mask); + +__STATIC_INLINE uint32_t ARM_PMU_Get_CCNTR(void); +__STATIC_INLINE uint32_t ARM_PMU_Get_EVCNTR(uint32_t num); + +__STATIC_INLINE uint32_t ARM_PMU_Get_CNTR_OVS(void); +__STATIC_INLINE void ARM_PMU_Set_CNTR_OVS(uint32_t mask); + +__STATIC_INLINE void ARM_PMU_Set_CNTR_IRQ_Enable(uint32_t mask); +__STATIC_INLINE void ARM_PMU_Set_CNTR_IRQ_Disable(uint32_t mask); + +__STATIC_INLINE void ARM_PMU_CNTR_Increment(uint32_t mask); + +/** + \brief Enable the PMU +*/ +__STATIC_INLINE void ARM_PMU_Enable(void) +{ + PMU->CTRL |= PMU_CTRL_ENABLE_Msk; +} + +/** + \brief Disable the PMU +*/ +__STATIC_INLINE void ARM_PMU_Disable(void) +{ + PMU->CTRL &= ~PMU_CTRL_ENABLE_Msk; +} + +/** + \brief Set event to count for PMU eventer counter + \param [in] num Event counter (0-30) to configure + \param [in] type Event to count +*/ +__STATIC_INLINE void ARM_PMU_Set_EVTYPER(uint32_t num, uint32_t type) +{ + PMU->EVTYPER[num] = type; +} + +/** + \brief Reset cycle counter +*/ +__STATIC_INLINE void ARM_PMU_CYCCNT_Reset(void) +{ + PMU->CTRL |= PMU_CTRL_CYCCNT_RESET_Msk; +} + +/** + \brief Reset all event counters +*/ +__STATIC_INLINE void ARM_PMU_EVCNTR_ALL_Reset(void) +{ + PMU->CTRL |= PMU_CTRL_EVENTCNT_RESET_Msk; +} + +/** + \brief Enable counters + \param [in] mask Counters to enable + \note Enables one or more of the following: + - event counters (0-30) + - cycle counter +*/ +__STATIC_INLINE void ARM_PMU_CNTR_Enable(uint32_t mask) +{ + PMU->CNTENSET = mask; +} + +/** + \brief Disable counters + \param [in] mask Counters to enable + \note Disables one or more of the following: + - event counters (0-30) + - cycle counter +*/ +__STATIC_INLINE void ARM_PMU_CNTR_Disable(uint32_t mask) +{ + PMU->CNTENCLR = mask; +} + +/** + \brief Read cycle counter + \return Cycle count +*/ +__STATIC_INLINE uint32_t ARM_PMU_Get_CCNTR(void) +{ + return PMU->CCNTR; +} + +/** + \brief Read event counter + \param [in] num Event counter (0-30) to read + \return Event count +*/ +__STATIC_INLINE uint32_t ARM_PMU_Get_EVCNTR(uint32_t num) +{ + return PMU->EVCNTR[num]; +} + +/** + \brief Read counter overflow status + \return Counter overflow status bits for the following: + - event counters (0-30) + - cycle counter +*/ +__STATIC_INLINE uint32_t ARM_PMU_Get_CNTR_OVS(void) +{ + return PMU->OVSSET; +} + +/** + \brief Clear counter overflow status + \param [in] mask Counter overflow status bits to clear + \note Clears overflow status bits for one or more of the following: + - event counters (0-30) + - cycle counter +*/ +__STATIC_INLINE void ARM_PMU_Set_CNTR_OVS(uint32_t mask) +{ + PMU->OVSCLR = mask; +} + +/** + \brief Enable counter overflow interrupt request + \param [in] mask Counter overflow interrupt request bits to set + \note Sets overflow interrupt request bits for one or more of the following: + - event counters (0-30) + - cycle counter +*/ +__STATIC_INLINE void ARM_PMU_Set_CNTR_IRQ_Enable(uint32_t mask) +{ + PMU->INTENSET = mask; +} + +/** + \brief Disable counter overflow interrupt request + \param [in] mask Counter overflow interrupt request bits to clear + \note Clears overflow interrupt request bits for one or more of the following: + - event counters (0-30) + - cycle counter +*/ +__STATIC_INLINE void ARM_PMU_Set_CNTR_IRQ_Disable(uint32_t mask) +{ + PMU->INTENCLR = mask; +} + +/** + \brief Software increment event counter + \param [in] mask Counters to increment + \note Software increment bits for one or more event counters (0-30) +*/ +__STATIC_INLINE void ARM_PMU_CNTR_Increment(uint32_t mask) +{ + PMU->SWINC = mask; +} + +#endif diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/cdc/cdc_class.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/cdc/cdc_class.c new file mode 100644 index 0000000000..cf83d2e4cf --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/cdc/cdc_class.c @@ -0,0 +1,439 @@ +/** + ************************************************************************** + * @file cdc_class.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb cdc class type + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +#include "usbd_core.h" +#include "cdc_class.h" +#include "cdc_desc.h" + +/** @addtogroup AT32F435_437_middlewares_usbd_class + * @{ + */ + +/** @defgroup USB_cdc_class + * @brief usb device class cdc demo + * @{ + */ + +/** @defgroup USB_cdc_class_private_functions + * @{ + */ + +static usb_sts_type class_init_handler(void *udev); +static usb_sts_type class_clear_handler(void *udev); +static usb_sts_type class_setup_handler(void *udev, usb_setup_type *setup); +static usb_sts_type class_ept0_tx_handler(void *udev); +static usb_sts_type class_ept0_rx_handler(void *udev); +static usb_sts_type class_in_handler(void *udev, uint8_t ept_num); +static usb_sts_type class_out_handler(void *udev, uint8_t ept_num); +static usb_sts_type class_sof_handler(void *udev); +static usb_sts_type class_event_handler(void *udev, usbd_event_type event); + +static usb_sts_type cdc_struct_init(cdc_struct_type *pcdc); +extern void usb_usart_config( linecoding_type linecoding); +static void usb_vcp_cmd_process(void *udev, uint8_t cmd, uint8_t *buff, uint16_t len); + +linecoding_type linecoding = +{ + 115200, + 0, + 0, + 8 +}; + +/* cdc data struct */ +cdc_struct_type cdc_struct; + +/* usb device class handler */ +usbd_class_handler cdc_class_handler = +{ + class_init_handler, + class_clear_handler, + class_setup_handler, + class_ept0_tx_handler, + class_ept0_rx_handler, + class_in_handler, + class_out_handler, + class_sof_handler, + class_event_handler, + &cdc_struct +}; +/** + * @brief initialize usb custom hid endpoint + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type class_init_handler(void *udev) +{ + usb_sts_type status = USB_OK; + usbd_core_type *pudev = (usbd_core_type *)udev; + cdc_struct_type *pcdc = (cdc_struct_type *)pudev->class_handler->pdata; + + /* init cdc struct */ + cdc_struct_init(pcdc); + + /* open in endpoint */ + usbd_ept_open(pudev, USBD_CDC_INT_EPT, EPT_INT_TYPE, USBD_CDC_CMD_MAXPACKET_SIZE); + + /* open in endpoint */ + usbd_ept_open(pudev, USBD_CDC_BULK_IN_EPT, EPT_BULK_TYPE, USBD_CDC_IN_MAXPACKET_SIZE); + + /* open out endpoint */ + usbd_ept_open(pudev, USBD_CDC_BULK_OUT_EPT, EPT_BULK_TYPE, USBD_CDC_OUT_MAXPACKET_SIZE); + + /* set out endpoint to receive status */ + usbd_ept_recv(pudev, USBD_CDC_BULK_OUT_EPT, pcdc->g_rx_buff, USBD_CDC_OUT_MAXPACKET_SIZE); + + return status; +} + +/** + * @brief clear endpoint or other state + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type class_clear_handler(void *udev) +{ + usb_sts_type status = USB_OK; + usbd_core_type *pudev = (usbd_core_type *)udev; + + /* close in endpoint */ + usbd_ept_close(pudev, USBD_CDC_INT_EPT); + + /* close in endpoint */ + usbd_ept_close(pudev, USBD_CDC_BULK_IN_EPT); + + /* close out endpoint */ + usbd_ept_close(pudev, USBD_CDC_BULK_OUT_EPT); + + return status; +} + +/** + * @brief usb device class setup request handler + * @param udev: to the structure of usbd_core_type + * @param setup: setup packet + * @retval status of usb_sts_type + */ +static usb_sts_type class_setup_handler(void *udev, usb_setup_type *setup) +{ + usb_sts_type status = USB_OK; + usbd_core_type *pudev = (usbd_core_type *)udev; + cdc_struct_type *pcdc = (cdc_struct_type *)pudev->class_handler->pdata; + + switch(setup->bmRequestType & USB_REQ_TYPE_RESERVED) + { + /* class request */ + case USB_REQ_TYPE_CLASS: + if(setup->wLength) + { + if(setup->bmRequestType & USB_REQ_DIR_DTH) + { + usb_vcp_cmd_process(udev, setup->bRequest, pcdc->g_cmd, setup->wLength); + usbd_ctrl_send(pudev, pcdc->g_cmd, setup->wLength); + } + else + { + pcdc->g_req = setup->bRequest; + pcdc->g_len = setup->wLength; + usbd_ctrl_recv(pudev, pcdc->g_cmd, pcdc->g_len); + + } + } + break; + /* standard request */ + case USB_REQ_TYPE_STANDARD: + switch(setup->bRequest) + { + case USB_STD_REQ_GET_DESCRIPTOR: + usbd_ctrl_unsupport(pudev); + break; + case USB_STD_REQ_GET_INTERFACE: + usbd_ctrl_send(pudev, (uint8_t *)&pcdc->alt_setting, 1); + break; + case USB_STD_REQ_SET_INTERFACE: + pcdc->alt_setting = setup->wValue; + break; + default: + break; + } + break; + default: + usbd_ctrl_unsupport(pudev); + break; + } + return status; +} + +/** + * @brief usb device endpoint 0 in status stage complete + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type class_ept0_tx_handler(void *udev) +{ + usb_sts_type status = USB_OK; + + /* ...user code... */ + UNUSED(udev); + return status; +} + +/** + * @brief usb device endpoint 0 out status stage complete + * @param udev: usb device core handler type + * @retval status of usb_sts_type + */ +static usb_sts_type class_ept0_rx_handler(void *udev) +{ + usb_sts_type status = USB_OK; + usbd_core_type *pudev = (usbd_core_type *)udev; + cdc_struct_type *pcdc = (cdc_struct_type *)pudev->class_handler->pdata; + uint32_t recv_len = usbd_get_recv_len(pudev, 0); + /* ...user code... */ + if( pcdc->g_req == SET_LINE_CODING) + { + /* class process */ + usb_vcp_cmd_process(udev, pcdc->g_req, pcdc->g_cmd, recv_len); + } + + return status; +} + +/** + * @brief usb device transmision complete handler + * @param udev: to the structure of usbd_core_type + * @param ept_num: endpoint number + * @retval status of usb_sts_type + */ +static usb_sts_type class_in_handler(void *udev, uint8_t ept_num) +{ + usbd_core_type *pudev = (usbd_core_type *)udev; + cdc_struct_type *pcdc = (cdc_struct_type *)pudev->class_handler->pdata; + usb_sts_type status = USB_OK; + + /* ...user code... + trans next packet data + */ + usbd_flush_tx_fifo(pudev, ept_num); + pcdc->g_tx_completed = 1; + + return status; +} + +/** + * @brief usb device endpoint receive data + * @param udev: to the structure of usbd_core_type + * @param ept_num: endpoint number + * @retval status of usb_sts_type + */ +static usb_sts_type class_out_handler(void *udev, uint8_t ept_num) +{ + usb_sts_type status = USB_OK; + usbd_core_type *pudev = (usbd_core_type *)udev; + cdc_struct_type *pcdc = (cdc_struct_type *)pudev->class_handler->pdata; + + /* get endpoint receive data length */ + pcdc->g_rxlen = usbd_get_recv_len(pudev, ept_num); + + /*set recv flag*/ + pcdc->g_rx_completed = 1; + + return status; +} + +/** + * @brief usb device sof handler + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type class_sof_handler(void *udev) +{ + usb_sts_type status = USB_OK; + + /* ...user code... */ + UNUSED(udev); + return status; +} + +/** + * @brief usb device event handler + * @param udev: to the structure of usbd_core_type + * @param event: usb device event + * @retval status of usb_sts_type + */ +static usb_sts_type class_event_handler(void *udev, usbd_event_type event) +{ + usb_sts_type status = USB_OK; + UNUSED(udev); + switch(event) + { + case USBD_RESET_EVENT: + + /* ...user code... */ + + break; + case USBD_SUSPEND_EVENT: + + /* ...user code... */ + + break; + case USBD_WAKEUP_EVENT: + /* ...user code... */ + + break; + case USBD_INISOINCOM_EVENT: + break; + case USBD_OUTISOINCOM_EVENT: + break; + + default: + break; + } + return status; +} + +/** + * @brief usb device cdc init + * @param pcdc: to the structure of cdc_struct + * @retval status of usb_sts_type + */ +static usb_sts_type cdc_struct_init(cdc_struct_type *pcdc) +{ + pcdc->g_tx_completed = 1; + pcdc->g_rx_completed = 0; + pcdc->alt_setting = 0; + pcdc->linecoding.bitrate = linecoding.bitrate; + pcdc->linecoding.data = linecoding.data; + pcdc->linecoding.format = linecoding.format; + pcdc->linecoding.parity = linecoding.parity; + return USB_OK; +} + +/** + * @brief usb device class rx data process + * @param udev: to the structure of usbd_core_type + * @param recv_data: receive buffer + * @retval receive data len + */ +uint16_t usb_vcp_get_rxdata(void *udev, uint8_t *recv_data) +{ + uint16_t i_index = 0; + uint16_t tmp_len = 0; + usbd_core_type *pudev = (usbd_core_type *)udev; + cdc_struct_type *pcdc = (cdc_struct_type *)pudev->class_handler->pdata; + + if(pcdc->g_rx_completed == 0) + { + return 0; + } + pcdc->g_rx_completed = 0; + tmp_len = pcdc->g_rxlen; + for(i_index = 0; i_index < pcdc->g_rxlen; i_index ++) + { + recv_data[i_index] = pcdc->g_rx_buff[i_index]; + } + + usbd_ept_recv(pudev, USBD_CDC_BULK_OUT_EPT, pcdc->g_rx_buff, USBD_CDC_OUT_MAXPACKET_SIZE); + + return tmp_len; +} + +/** + * @brief usb device class send data + * @param udev: to the structure of usbd_core_type + * @param send_data: send data buffer + * @param len: send length + * @retval error status + */ +error_status usb_vcp_send_data(void *udev, uint8_t *send_data, uint16_t len) +{ + error_status status = SUCCESS; + usbd_core_type *pudev = (usbd_core_type *)udev; + cdc_struct_type *pcdc = (cdc_struct_type *)pudev->class_handler->pdata; + if(pcdc->g_tx_completed) + { + pcdc->g_tx_completed = 0; + usbd_ept_send(pudev, USBD_CDC_BULK_IN_EPT, send_data, len); + } + else + { + status = ERROR; + } + return status; +} + +/** + * @brief usb device function + * @param udev: to the structure of usbd_core_type + * @param cmd: request number + * @param buff: request buffer + * @param len: buffer length + * @retval none + */ +static void usb_vcp_cmd_process(void *udev, uint8_t cmd, uint8_t *buff, uint16_t len) +{ + UNUSED(len); + usbd_core_type *pudev = (usbd_core_type *)udev; + cdc_struct_type *pcdc = (cdc_struct_type *)pudev->class_handler->pdata; + switch(cmd) + { + case SET_LINE_CODING: + pcdc->linecoding.bitrate = (uint32_t)(buff[0] | (buff[1] << 8) | (buff[2] << 16) | (buff[3] <<24)); + pcdc->linecoding.format = buff[4]; + pcdc->linecoding.parity = buff[5]; + pcdc->linecoding.data = buff[6]; +#ifdef USB_VIRTUAL_COMPORT + /* set hardware usart */ + usb_usart_config(pcdc->linecoding); +#endif + break; + + case GET_LINE_CODING: + buff[0] = (uint8_t)pcdc->linecoding.bitrate; + buff[1] = (uint8_t)(pcdc->linecoding.bitrate >> 8); + buff[2] = (uint8_t)(pcdc->linecoding.bitrate >> 16); + buff[3] = (uint8_t)(pcdc->linecoding.bitrate >> 24); + buff[4] = (uint8_t)(pcdc->linecoding.format); + buff[5] = (uint8_t)(pcdc->linecoding.parity); + buff[6] = (uint8_t)(pcdc->linecoding.data); + break; + + default: + break; + } +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/cdc/cdc_class.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/cdc/cdc_class.h new file mode 100644 index 0000000000..be7e0b82af --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/cdc/cdc_class.h @@ -0,0 +1,117 @@ +/** + ************************************************************************** + * @file cdc_class.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb cdc class file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + + /* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __CDC_CLASS_H +#define __CDC_CLASS_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "usb_std.h" +#include "usbd_core.h" + +/** @addtogroup AT32F435_437_middlewares_usbd_class + * @{ + */ + +/** @addtogroup USB_cdc_class + * @{ + */ + +/** @defgroup USB_cdc_class_definition + * @{ + */ + +/** + * @brief usb cdc use endpoint define + */ +#define USBD_CDC_INT_EPT 0x82 +#define USBD_CDC_BULK_IN_EPT 0x81 +#define USBD_CDC_BULK_OUT_EPT 0x01 + +/** + * @brief usb cdc in and out max packet size define + */ +#define USBD_CDC_IN_MAXPACKET_SIZE 0x40 +#define USBD_CDC_OUT_MAXPACKET_SIZE 0x40 +#define USBD_CDC_CMD_MAXPACKET_SIZE 0x08 + +/** + * @} + */ + +/** @defgroup USB_cdc_class_exported_types + * @{ + */ + +/** + * @brief usb cdc class struct + */ +typedef struct +{ + uint32_t alt_setting; + uint8_t g_rx_buff[USBD_CDC_OUT_MAXPACKET_SIZE]; + uint8_t g_cmd[USBD_CDC_CMD_MAXPACKET_SIZE]; + uint8_t g_req; + uint16_t g_len, g_rxlen; + __IO uint8_t g_tx_completed, g_rx_completed; + linecoding_type linecoding; +}cdc_struct_type; + + +/** + * @} + */ + +/** @defgroup USB_cdc_class_exported_functions + * @{ + */ +extern usbd_class_handler cdc_class_handler; +uint16_t usb_vcp_get_rxdata(void *udev, uint8_t *recv_data); +error_status usb_vcp_send_data(void *udev, uint8_t *send_data, uint16_t len); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif + + + + diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/cdc/cdc_desc.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/cdc/cdc_desc.c new file mode 100644 index 0000000000..bb268bf855 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/cdc/cdc_desc.c @@ -0,0 +1,446 @@ +/** + ************************************************************************** + * @file cdc_desc.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb cdc device descriptor + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +#include "stdio.h" +#include "usb_std.h" +#include "usbd_sdr.h" +#include "usbd_core.h" +#include "cdc_desc.h" + +/** @addtogroup AT32F435_437_middlewares_usbd_class + * @{ + */ + +/** @defgroup USB_cdc_desc + * @brief usb device cdc descriptor + * @{ + */ + +/** @defgroup USB_cdc_desc_private_functions + * @{ + */ + +static usbd_desc_t *get_device_descriptor(void); +static usbd_desc_t *get_device_qualifier(void); +static usbd_desc_t *get_device_configuration(void); +static usbd_desc_t *get_device_other_speed(void); +static usbd_desc_t *get_device_lang_id(void); +static usbd_desc_t *get_device_manufacturer_string(void); +static usbd_desc_t *get_device_product_string(void); +static usbd_desc_t *get_device_serial_string(void); +static usbd_desc_t *get_device_interface_string(void); +static usbd_desc_t *get_device_config_string(void); + +static uint16_t usbd_unicode_convert(uint8_t *string, uint8_t *unicode_buf); +static void usbd_int_to_unicode (uint32_t value , uint8_t *pbuf , uint8_t len); +static void get_serial_num(void); +static uint8_t g_usbd_desc_buffer[256]; + +/** + * @brief device descriptor handler structure + */ +usbd_desc_handler cdc_desc_handler = +{ + get_device_descriptor, + get_device_qualifier, + get_device_configuration, + get_device_other_speed, + get_device_lang_id, + get_device_manufacturer_string, + get_device_product_string, + get_device_serial_string, + get_device_interface_string, + get_device_config_string, +}; + +/** + * @brief usb device standard descriptor + */ +#if defined ( __ICCARM__ ) /* iar compiler */ + #pragma data_alignment=4 +#endif +ALIGNED_HEAD static uint8_t g_usbd_descriptor[USB_DEVICE_DESC_LEN] ALIGNED_TAIL = +{ + USB_DEVICE_DESC_LEN, /* bLength */ + USB_DESCIPTOR_TYPE_DEVICE, /* bDescriptorType */ + 0x00, /* bcdUSB */ + 0x02, + 0x02, /* bDeviceClass */ + 0x00, /* bDeviceSubClass */ + 0x00, /* bDeviceProtocol */ + USB_MAX_EP0_SIZE, /* bMaxPacketSize */ + LBYTE(USBD_CDC_VENDOR_ID), /* idVendor */ + HBYTE(USBD_CDC_VENDOR_ID), /* idVendor */ + LBYTE(USBD_CDC_PRODUCT_ID), /* idProduct */ + HBYTE(USBD_CDC_PRODUCT_ID), /* idProduct */ + 0x00, /* bcdDevice rel. 2.00 */ + 0x02, + USB_MFC_STRING, /* Index of manufacturer string */ + USB_PRODUCT_STRING, /* Index of product string */ + USB_SERIAL_STRING, /* Index of serial number string */ + 1 /* bNumConfigurations */ +}; + +/** + * @brief usb configuration standard descriptor + */ +#if defined ( __ICCARM__ ) /* iar compiler */ + #pragma data_alignment=4 +#endif +ALIGNED_HEAD static uint8_t g_usbd_configuration[USBD_CDC_CONFIG_DESC_SIZE] ALIGNED_TAIL = +{ + USB_DEVICE_CFG_DESC_LEN, /* bLength: configuration descriptor size */ + USB_DESCIPTOR_TYPE_CONFIGURATION, /* bDescriptorType: configuration */ + LBYTE(USBD_CDC_CONFIG_DESC_SIZE), /* wTotalLength: bytes returned */ + HBYTE(USBD_CDC_CONFIG_DESC_SIZE), /* wTotalLength: bytes returned */ + 0x02, /* bNumInterfaces: 2 interface */ + 0x01, /* bConfigurationValue: configuration value */ + 0x00, /* iConfiguration: index of string descriptor describing + the configuration */ + 0xC0, /* bmAttributes: self powered */ + 0x32, /* MaxPower 100 mA: this current is used for detecting vbus */ + + USB_DEVICE_IF_DESC_LEN, /* bLength: interface descriptor size */ + USB_DESCIPTOR_TYPE_INTERFACE, /* bDescriptorType: interface descriptor type */ + 0x00, /* bInterfaceNumber: number of interface */ + 0x00, /* bAlternateSetting: alternate set */ + 0x01, /* bNumEndpoints: number of endpoints */ + USB_CLASS_CODE_CDC, /* bInterfaceClass: CDC class code */ + 0x02, /* bInterfaceSubClass: subclass code, Abstract Control Model*/ + 0x01, /* bInterfaceProtocol: protocol code, AT Command */ + 0x00, /* iInterface: index of string descriptor */ + + 0x05, /* bFunctionLength: size of this descriptor in bytes */ + USBD_CDC_CS_INTERFACE, /* bDescriptorType: CDC interface descriptor type */ + USBD_CDC_SUBTYPE_HEADER, /* bDescriptorSubtype: Header function Descriptor 0x00*/ + LBYTE(CDC_BCD_NUM), + HBYTE(CDC_BCD_NUM), /* bcdCDC: USB class definitions for communications */ + + 0x05, /* bFunctionLength: size of this descriptor in bytes */ + USBD_CDC_CS_INTERFACE, /* bDescriptorType: CDC interface descriptor type */ + USBD_CDC_SUBTYPE_CMF, /* bDescriptorSubtype: Call Management function descriptor subtype 0x01 */ + 0x00, /* bmCapabilities: 0x00*/ + 0x01, /* bDataInterface: interface number of data class interface optionally used for call management */ + + 0x04, /* bFunctionLength: size of this descriptor in bytes */ + USBD_CDC_CS_INTERFACE, /* bDescriptorType: CDC interface descriptor type */ + USBD_CDC_SUBTYPE_ACM, /* bDescriptorSubtype: Abstract Control Management functional descriptor subtype 0x02 */ + 0x02, /* bmCapabilities: Support Set_Line_Coding and Get_Line_Coding 0x02 */ + + 0x05, /* bFunctionLength: size of this descriptor in bytes */ + USBD_CDC_CS_INTERFACE, /* bDescriptorType: CDC interface descriptor type */ + USBD_CDC_SUBTYPE_UFD, /* bDescriptorSubtype: Union Function Descriptor subtype 0x06 */ + 0x00, /* bControlInterface: The interface number of the communications or data class interface 0x00 */ + 0x01, /* bSubordinateInterface0: interface number of first subordinate interface in the union */ + + USB_DEVICE_EPT_LEN, /* bLength: size of endpoint descriptor in bytes */ + USB_DESCIPTOR_TYPE_ENDPOINT, /* bDescriptorType: endpoint descriptor type */ + USBD_CDC_INT_EPT, /* bEndpointAddress: the address of endpoint on usb device described by this descriptor */ + USB_EPT_DESC_INTERRUPT, /* bmAttributes: endpoint attributes */ + LBYTE(USBD_CDC_CMD_MAXPACKET_SIZE), + HBYTE(USBD_CDC_CMD_MAXPACKET_SIZE), /* wMaxPacketSize: maximum packe size this endpoint */ + CDC_HID_BINTERVAL_TIME, /* bInterval: interval for polling endpoint for data transfers */ + + + USB_DEVICE_IF_DESC_LEN, /* bLength: interface descriptor size */ + USB_DESCIPTOR_TYPE_INTERFACE, /* bDescriptorType: interface descriptor type */ + 0x01, /* bInterfaceNumber: number of interface */ + 0x00, /* bAlternateSetting: alternate set */ + 0x02, /* bNumEndpoints: number of endpoints */ + USB_CLASS_CODE_CDCDATA, /* bInterfaceClass: CDC-data class code */ + 0x00, /* bInterfaceSubClass: Data interface subclass code 0x00*/ + 0x00, /* bInterfaceProtocol: data class protocol code 0x00 */ + 0x00, /* iInterface: index of string descriptor */ + + USB_DEVICE_EPT_LEN, /* bLength: size of endpoint descriptor in bytes */ + USB_DESCIPTOR_TYPE_ENDPOINT, /* bDescriptorType: endpoint descriptor type */ + USBD_CDC_BULK_IN_EPT, /* bEndpointAddress: the address of endpoint on usb device described by this descriptor */ + USB_EPT_DESC_BULK, /* bmAttributes: endpoint attributes */ + LBYTE(USBD_CDC_IN_MAXPACKET_SIZE), + HBYTE(USBD_CDC_IN_MAXPACKET_SIZE), /* wMaxPacketSize: maximum packe size this endpoint */ + 0x00, /* bInterval: interval for polling endpoint for data transfers */ + + USB_DEVICE_EPT_LEN, /* bLength: size of endpoint descriptor in bytes */ + USB_DESCIPTOR_TYPE_ENDPOINT, /* bDescriptorType: endpoint descriptor type */ + USBD_CDC_BULK_OUT_EPT, /* bEndpointAddress: the address of endpoint on usb device described by this descriptor */ + USB_EPT_DESC_BULK, /* bmAttributes: endpoint attributes */ + LBYTE(USBD_CDC_OUT_MAXPACKET_SIZE), + HBYTE(USBD_CDC_OUT_MAXPACKET_SIZE), /* wMaxPacketSize: maximum packe size this endpoint */ + 0x00, /* bInterval: interval for polling endpoint for data transfers */ +}; + +/** + * @brief usb string lang id + */ +#if defined ( __ICCARM__ ) /* iar compiler */ + #pragma data_alignment=4 +#endif +ALIGNED_HEAD static uint8_t g_string_lang_id[USBD_CDC_SIZ_STRING_LANGID] ALIGNED_TAIL = +{ + USBD_CDC_SIZ_STRING_LANGID, + USB_DESCIPTOR_TYPE_STRING, + 0x09, + 0x04, +}; + +/** + * @brief usb string serial + */ +#if defined ( __ICCARM__ ) /* iar compiler */ + #pragma data_alignment=4 +#endif +ALIGNED_HEAD static uint8_t g_string_serial[USBD_CDC_SIZ_STRING_SERIAL] ALIGNED_TAIL = +{ + USBD_CDC_SIZ_STRING_SERIAL, + USB_DESCIPTOR_TYPE_STRING, +}; + + +/* device descriptor */ +static usbd_desc_t device_descriptor = +{ + USB_DEVICE_DESC_LEN, + g_usbd_descriptor +}; + +/* config descriptor */ +static usbd_desc_t config_descriptor = +{ + USBD_CDC_CONFIG_DESC_SIZE, + g_usbd_configuration +}; + +/* langid descriptor */ +static usbd_desc_t langid_descriptor = +{ + USBD_CDC_SIZ_STRING_LANGID, + g_string_lang_id +}; + +/* serial descriptor */ +static usbd_desc_t serial_descriptor = +{ + USBD_CDC_SIZ_STRING_SERIAL, + g_string_serial +}; + +static usbd_desc_t vp_desc; + +/** + * @brief standard usb unicode convert + * @param string: source string + * @param unicode_buf: unicode buffer + * @retval length + */ +static uint16_t usbd_unicode_convert(uint8_t *string, uint8_t *unicode_buf) +{ + uint16_t str_len = 0, id_pos = 2; + uint8_t *tmp_str = string; + + while(*tmp_str != '\0') + { + str_len ++; + unicode_buf[id_pos ++] = *tmp_str ++; + unicode_buf[id_pos ++] = 0x00; + } + + str_len = str_len * 2 + 2; + unicode_buf[0] = (uint8_t)str_len; + unicode_buf[1] = USB_DESCIPTOR_TYPE_STRING; + + return str_len; +} + +/** + * @brief usb int convert to unicode + * @param value: int value + * @param pbus: unicode buffer + * @param len: length + * @retval none + */ +static void usbd_int_to_unicode (uint32_t value , uint8_t *pbuf , uint8_t len) +{ + uint8_t idx = 0; + + for( idx = 0 ; idx < len ; idx ++) + { + if( ((value >> 28)) < 0xA ) + { + pbuf[ 2 * idx] = (value >> 28) + '0'; + } + else + { + pbuf[2 * idx] = (value >> 28) + 'A' - 10; + } + + value = value << 4; + + pbuf[2 * idx + 1] = 0; + } +} + +/** + * @brief usb get serial number + * @param none + * @retval none + */ +static void get_serial_num(void) +{ + uint32_t serial0, serial1, serial2; + + serial0 = *(uint32_t*)MCU_ID1; + serial1 = *(uint32_t*)MCU_ID2; + serial2 = *(uint32_t*)MCU_ID3; + + serial0 += serial2; + + if (serial0 != 0) + { + usbd_int_to_unicode (serial0, &g_string_serial[2] ,8); + usbd_int_to_unicode (serial1, &g_string_serial[18] ,4); + } +} + +/** + * @brief get device descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_descriptor(void) +{ + return &device_descriptor; +} + +/** + * @brief get device qualifier + * @param none + * @retval usbd_desc + */ +static usbd_desc_t * get_device_qualifier(void) +{ + return NULL; +} + +/** + * @brief get config descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_configuration(void) +{ + return &config_descriptor; +} + +/** + * @brief get other speed descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_other_speed(void) +{ + return NULL; +} + +/** + * @brief get lang id descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_lang_id(void) +{ + return &langid_descriptor; +} + + +/** + * @brief get manufacturer descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_manufacturer_string(void) +{ + vp_desc.length = usbd_unicode_convert((uint8_t *)USBD_CDC_DESC_MANUFACTURER_STRING, g_usbd_desc_buffer); + vp_desc.descriptor = g_usbd_desc_buffer; + return &vp_desc; +} + +/** + * @brief get product descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_product_string(void) +{ + vp_desc.length = usbd_unicode_convert((uint8_t *)USBD_CDC_DESC_PRODUCT_STRING, g_usbd_desc_buffer); + vp_desc.descriptor = g_usbd_desc_buffer; + return &vp_desc; +} + +/** + * @brief get serial descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_serial_string(void) +{ + get_serial_num(); + return &serial_descriptor; +} + +/** + * @brief get interface descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_interface_string(void) +{ + vp_desc.length = usbd_unicode_convert((uint8_t *)USBD_CDC_DESC_INTERFACE_STRING, g_usbd_desc_buffer); + vp_desc.descriptor = g_usbd_desc_buffer; + return &vp_desc; +} + +/** + * @brief get device config descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_config_string(void) +{ + vp_desc.length = usbd_unicode_convert((uint8_t *)USBD_CDC_DESC_CONFIGURATION_STRING, g_usbd_desc_buffer); + vp_desc.descriptor = g_usbd_desc_buffer; + return &vp_desc; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/cdc/cdc_desc.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/cdc/cdc_desc.h new file mode 100644 index 0000000000..dd406f720b --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/cdc/cdc_desc.h @@ -0,0 +1,104 @@ +/** + ************************************************************************** + * @file cdc_desc.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb cdc descriptor header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __CDC_DESC_H +#define __CDC_DESC_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "cdc_class.h" +#include "usbd_core.h" + +/** @addtogroup AT32F435_437_middlewares_usbd_class + * @{ + */ + +/** @addtogroup USB_cdc_desc + * @{ + */ + +/** @defgroup USB_cdc_desc_definition + * @{ + */ +/** + * @brief usb bcd number define + */ +#define CDC_BCD_NUM 0x0110 + +/** + * @brief usb vendor id and product id define + */ +#define USBD_CDC_VENDOR_ID 0x2E3C +#define USBD_CDC_PRODUCT_ID 0x5740 + +/** + * @brief usb descriptor size define + */ +#define USBD_CDC_CONFIG_DESC_SIZE 67 +#define USBD_CDC_SIZ_STRING_LANGID 4 +#define USBD_CDC_SIZ_STRING_SERIAL 0x1A + +/** + * @brief usb string define(vendor, product configuration, interface) + */ +#define USBD_CDC_DESC_MANUFACTURER_STRING "Artery" +#define USBD_CDC_DESC_PRODUCT_STRING "AT32 Virtual Com Port " +#define USBD_CDC_DESC_CONFIGURATION_STRING "Virtual ComPort Config" +#define USBD_CDC_DESC_INTERFACE_STRING "Virtual ComPort Interface" + +/** + * @brief usb endpoint interval define + */ +#define CDC_HID_BINTERVAL_TIME 0xFF + +/** + * @brief usb mcu id address deine + */ +#define MCU_ID1 (0x1FFFF7E8) +#define MCU_ID2 (0x1FFFF7EC) +#define MCU_ID3 (0x1FFFF7F0) +/** + * @} + */ + +extern usbd_desc_handler cdc_desc_handler; + + +/** + * @} + */ + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/hid_iap/hid_iap_class.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/hid_iap/hid_iap_class.c new file mode 100644 index 0000000000..ea2c9810e3 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/hid_iap/hid_iap_class.c @@ -0,0 +1,342 @@ +/** + ************************************************************************** + * @file hid_iap_class.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb hid iap class type + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +#include "usbd_core.h" +#include "hid_iap_class.h" +#include "hid_iap_desc.h" + +/** @addtogroup AT32F435_437_middlewares_usbd_class + * @{ + */ + +/** @defgroup USB_hid_iap_class + * @brief usb device class hid iap demo + * @{ + */ + +/** @defgroup USB_hid_iap_class_private_functions + * @{ + */ + + +static usb_sts_type class_init_handler(void *udev); +static usb_sts_type class_clear_handler(void *udev); +static usb_sts_type class_setup_handler(void *udev, usb_setup_type *setup); +static usb_sts_type class_ept0_tx_handler(void *udev); +static usb_sts_type class_ept0_rx_handler(void *udev); +static usb_sts_type class_in_handler(void *udev, uint8_t ept_num); +static usb_sts_type class_out_handler(void *udev, uint8_t ept_num); +static usb_sts_type class_sof_handler(void *udev); +static usb_sts_type class_event_handler(void *udev, usbd_event_type event); + +iap_info_type iap_info; + +/* usb device class handler */ +usbd_class_handler hid_iap_class_handler = +{ + class_init_handler, + class_clear_handler, + class_setup_handler, + class_ept0_tx_handler, + class_ept0_rx_handler, + class_in_handler, + class_out_handler, + class_sof_handler, + class_event_handler, + &iap_info +}; + +/** + * @brief initialize usb custom hid endpoint + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type class_init_handler(void *udev) +{ + usb_sts_type status = USB_OK; + usbd_core_type *pudev = (usbd_core_type *)udev; + iap_info_type *piap = (iap_info_type *)pudev->class_handler->pdata; + /* open hid iap in endpoint */ + usbd_ept_open(pudev, USBD_HIDIAP_IN_EPT, EPT_INT_TYPE, USBD_HIDIAP_IN_MAXPACKET_SIZE); + + /* open hid iap out endpoint */ + usbd_ept_open(pudev, USBD_HIDIAP_OUT_EPT, EPT_INT_TYPE, USBD_HIDIAP_OUT_MAXPACKET_SIZE); + + /* set out endpoint to receive status */ + usbd_ept_recv(pudev, USBD_HIDIAP_OUT_EPT, piap->g_rxhid_buff, USBD_HIDIAP_OUT_MAXPACKET_SIZE); + + return status; +} + +/** + * @brief clear endpoint or other state + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type class_clear_handler(void *udev) +{ + usb_sts_type status = USB_OK; + usbd_core_type *pudev = (usbd_core_type *)udev; + + /* close hid iap in endpoint */ + usbd_ept_close(pudev, USBD_HIDIAP_IN_EPT); + + /* close hid iap out endpoint */ + usbd_ept_close(pudev, USBD_HIDIAP_OUT_EPT); + + return status; +} + +/** + * @brief usb device class setup request handler + * @param udev: to the structure of usbd_core_type + * @param setup: setup packet + * @retval status of usb_sts_type + */ +static usb_sts_type class_setup_handler(void *udev, usb_setup_type *setup) +{ + usb_sts_type status = USB_OK; + usbd_core_type *pudev = (usbd_core_type *)udev; + iap_info_type *piap = (iap_info_type *)pudev->class_handler->pdata; + uint16_t len; + uint8_t *buf; + + switch(setup->bmRequestType & USB_REQ_TYPE_RESERVED) + { + /* class request */ + case USB_REQ_TYPE_CLASS: + switch(setup->bRequest) + { + case HID_REQ_SET_PROTOCOL: + piap->hid_protocol = (uint8_t)setup->wValue; + break; + case HID_REQ_GET_PROTOCOL: + usbd_ctrl_send(pudev, (uint8_t *)&piap->hid_protocol, 1); + break; + case HID_REQ_SET_IDLE: + piap->hid_set_idle = (uint8_t)(setup->wValue >> 8); + break; + case HID_REQ_GET_IDLE: + usbd_ctrl_send(pudev, (uint8_t *)&piap->hid_set_idle, 1); + break; + case HID_REQ_SET_REPORT: + piap->hid_state = HID_REQ_SET_REPORT; + usbd_ctrl_recv(pudev, piap->hid_set_report, setup->wLength); + break; + default: + usbd_ctrl_unsupport(pudev); + break; + } + break; + /* standard request */ + case USB_REQ_TYPE_STANDARD: + switch(setup->bRequest) + { + case USB_STD_REQ_GET_DESCRIPTOR: + if(setup->wValue >> 8 == HID_REPORT_DESC) + { + len = MIN(USBD_HIDIAP_SIZ_REPORT_DESC, setup->wLength); + buf = (uint8_t *)g_usbd_hidiap_report; + } + else if(setup->wValue >> 8 == HID_DESCRIPTOR_TYPE) + { + len = MIN(9, setup->wLength); + buf = (uint8_t *)g_hidiap_usb_desc; + } + usbd_ctrl_send(pudev, (uint8_t *)buf, len); + break; + case USB_STD_REQ_GET_INTERFACE: + usbd_ctrl_send(pudev, (uint8_t *)&piap->alt_setting, 1); + break; + case USB_STD_REQ_SET_INTERFACE: + piap->alt_setting = setup->wValue; + break; + default: + break; + } + break; + default: + usbd_ctrl_unsupport(pudev); + break; + } + return status; +} + +/** + * @brief usb device endpoint 0 in status stage complete + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type class_ept0_tx_handler(void *udev) +{ + usb_sts_type status = USB_OK; + + /* ...user code... */ + + return status; +} + +/** + * @brief usb device endpoint 0 out status stage complete + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type class_ept0_rx_handler(void *udev) +{ + usb_sts_type status = USB_OK; + usbd_core_type *pudev = (usbd_core_type *)udev; + iap_info_type *piap = (iap_info_type *)pudev->class_handler->pdata; + uint32_t recv_len = usbd_get_recv_len(pudev, 0); + /* ...user code... */ + if( piap->hid_state == HID_REQ_SET_REPORT) + { + /* hid buffer process */ + piap->hid_state = 0; + } + + return status; +} + +/** + * @brief usb device transmision complete handler + * @param udev: to the structure of usbd_core_type + * @param ept_num: endpoint number + * @retval status of usb_sts_type + */ +static usb_sts_type class_in_handler(void *udev, uint8_t ept_num) +{ + usb_sts_type status = USB_OK; + + /* ...user code... + trans next packet data + */ + usbd_hid_iap_in_complete(udev); + + return status; +} + +/** + * @brief usb device endpoint receive data + * @param udev: to the structure of usbd_core_type + * @param ept_num: endpoint number + * @retval status of usb_sts_type + */ +static usb_sts_type class_out_handler(void *udev, uint8_t ept_num) +{ + usb_sts_type status = USB_OK; + usbd_core_type *pudev = (usbd_core_type *)udev; + iap_info_type *piap = (iap_info_type *)pudev->class_handler->pdata; + + /* get endpoint receive data length */ + uint32_t recv_len = usbd_get_recv_len(pudev, ept_num); + + /* hid iap process */ + usbd_hid_iap_process(udev, piap->g_rxhid_buff, recv_len); + + /* start receive next packet */ + usbd_ept_recv(pudev, USBD_HIDIAP_OUT_EPT, piap->g_rxhid_buff, USBD_HIDIAP_OUT_MAXPACKET_SIZE); + + return status; +} + +/** + * @brief usb device sof handler + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type class_sof_handler(void *udev) +{ + usb_sts_type status = USB_OK; + + /* ...user code... */ + + return status; +} + +/** + * @brief usb device event handler + * @param udev: to the structure of usbd_core_type + * @param event: usb device event + * @retval status of usb_sts_type + */ +static usb_sts_type class_event_handler(void *udev, usbd_event_type event) +{ + usb_sts_type status = USB_OK; + switch(event) + { + case USBD_RESET_EVENT: + + /* ...user code... */ + + break; + case USBD_SUSPEND_EVENT: + + /* ...user code... */ + + break; + case USBD_WAKEUP_EVENT: + /* ...user code... */ + + break; + default: + break; + } + return status; +} + +/** + * @brief usb device class send report + * @param udev: to the structure of usbd_core_type + * @param report: report buffer + * @param len: report length + * @retval status of usb_sts_type + */ +usb_sts_type usb_iap_class_send_report(void *udev, uint8_t *report, uint16_t len) +{ + usb_sts_type status = USB_OK; + usbd_core_type *pudev = (usbd_core_type *)udev; + + if(usbd_connect_state_get(pudev) == USB_CONN_STATE_CONFIGURED) + usbd_ept_send(pudev, USBD_HIDIAP_IN_EPT, report, len); + + return status; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + + + + + diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/hid_iap/hid_iap_class.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/hid_iap/hid_iap_class.h new file mode 100644 index 0000000000..00d6d7b5a0 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/hid_iap/hid_iap_class.h @@ -0,0 +1,159 @@ +/** + ************************************************************************** + * @file hid_iap_class.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb hid iap header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + + /* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __HID_IAP_CLASS_H +#define __HID_IAP_CLASS_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "usb_std.h" +#include "usbd_core.h" + + +/** @addtogroup AT32F435_437_middlewares_usbd_class + * @{ + */ + +/** @addtogroup USB_hid_iap_class + * @{ + */ + +/** @defgroup USB_hid_iap_class_definition + * @{ + */ + + +#define USBD_HIDIAP_IN_EPT 0x81 +#define USBD_HIDIAP_OUT_EPT 0x01 + +#define USBD_HIDIAP_IN_MAXPACKET_SIZE 0x40 +#define USBD_HIDIAP_OUT_MAXPACKET_SIZE 0x40 + +#define FLASH_SIZE_REG() ((*(uint32_t *)0x1FFFF7E0) & 0xFFFF) /*Get Flash size*/ +#define KB_TO_B(kb) ((kb) << 10) + +#define SECTOR_SIZE_1K 0x400 +#define SECTOR_SIZE_2K 0x800 +#define SECTOR_SIZE_4K 0x1000 + +/** + * @brief iap command + */ +#define IAP_CMD_IDLE 0x5AA0 +#define IAP_CMD_START 0x5AA1 +#define IAP_CMD_ADDR 0x5AA2 +#define IAP_CMD_DATA 0x5AA3 +#define IAP_CMD_FINISH 0x5AA4 +#define IAP_CMD_CRC 0x5AA5 +#define IAP_CMD_JMP 0x5AA6 +#define IAP_CMD_GET 0x5AA7 + +#define HID_IAP_BUFFER_LEN 1024 +#define IAP_UPGRADE_COMPLETE_FLAG 0x41544B38 +#define CONVERT_ENDIAN(dwValue) ((dwValue >> 24) | ((dwValue >> 8) & 0xFF00) | \ + ((dwValue << 8) & 0xFF0000) | (dwValue << 24) ) + +#define IAP_ACK 0xFF00 +#define IAP_NACK 0x00FF + +typedef enum +{ + IAP_SUCCESS, + IAP_WAIT, + IAP_FAILED +}iap_result_type; + +typedef enum +{ + IAP_STS_IDLE, + IAP_STS_START, + IAP_STS_ADDR, + IAP_STS_DATA, + IAP_STS_FINISH, + IAP_STS_CRC, + IAP_STS_JMP_WAIT, + IAP_STS_JMP, +}iap_machine_state_type; + +typedef struct +{ + + uint8_t iap_fifo[HID_IAP_BUFFER_LEN]; + uint8_t iap_rx[USBD_HIDIAP_OUT_MAXPACKET_SIZE]; + uint8_t iap_tx[USBD_HIDIAP_IN_MAXPACKET_SIZE]; + + uint32_t fifo_length; + uint32_t tx_length; + + uint32_t app_address; + uint32_t iap_address; + uint32_t flag_address; + + uint32_t flash_start_address; + uint32_t flash_end_address; + + uint32_t sector_size; + uint32_t flash_size; + + uint32_t respond_flag; + + uint8_t g_rxhid_buff[USBD_HIDIAP_OUT_MAXPACKET_SIZE]; + uint32_t hid_protocol; + uint32_t hid_set_idle; + uint32_t alt_setting; + uint32_t hid_state; + uint8_t hid_set_report[64]; + + iap_machine_state_type state; +}iap_info_type; + +extern usbd_class_handler hid_iap_class_handler; +extern iap_info_type iap_info; +usb_sts_type usb_iap_class_send_report(void *udev, uint8_t *report, uint16_t len); +iap_result_type usbd_hid_iap_process(void *udev, uint8_t *report, uint16_t len); +void usbd_hid_iap_in_complete(void *udev); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif + + diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/hid_iap/hid_iap_desc.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/hid_iap/hid_iap_desc.c new file mode 100644 index 0000000000..4cab141e45 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/hid_iap/hid_iap_desc.c @@ -0,0 +1,468 @@ +/** + ************************************************************************** + * @file hid_iap_desc.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb hid iap device descriptor + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +#include "usb_std.h" +#include "usbd_sdr.h" +#include "usbd_core.h" +#include "hid_iap_desc.h" + + +/** @addtogroup AT32F435_437_middlewares_usbd_class + * @{ + */ + +/** @defgroup USB_hid_iap_desc + * @brief usb device hid_iap descriptor + * @{ + */ + +/** @defgroup USB_hid_iap_desc_private_functions + * @{ + */ + + +static usbd_desc_t *get_device_descriptor(void); +static usbd_desc_t *get_device_qualifier(void); +static usbd_desc_t *get_device_configuration(void); +static usbd_desc_t *get_device_other_speed(void); +static usbd_desc_t *get_device_lang_id(void); +static usbd_desc_t *get_device_manufacturer_string(void); +static usbd_desc_t *get_device_product_string(void); +static usbd_desc_t *get_device_serial_string(void); +static usbd_desc_t *get_device_interface_string(void); +static usbd_desc_t *get_device_config_string(void); + +static uint16_t usbd_unicode_convert(uint8_t *string, uint8_t *unicode_buf); +static void usbd_int_to_unicode (uint32_t value , uint8_t *pbuf , uint8_t len); +static void get_serial_num(void); +static uint8_t g_usbd_desc_buffer[256]; + +/** + * @brief hid device descriptor handler structure + */ +usbd_desc_handler hid_iap_desc_handler = +{ + get_device_descriptor, + get_device_qualifier, + get_device_configuration, + get_device_other_speed, + get_device_lang_id, + get_device_manufacturer_string, + get_device_product_string, + get_device_serial_string, + get_device_interface_string, + get_device_config_string, +}; + +/** + * @brief usb device standard descriptor + */ +#if defined ( __ICCARM__ ) /* iar compiler */ + #pragma data_alignment=4 +#endif +ALIGNED_HEAD static uint8_t g_usbd_descriptor[USB_DEVICE_DESC_LEN] ALIGNED_TAIL = +{ + USB_DEVICE_DESC_LEN, /* bLength */ + USB_DESCIPTOR_TYPE_DEVICE, /* bDescriptorType */ + 0x00, /* bcdUSB */ + 0x02, + 0x00, /* bDeviceClass */ + 0x00, /* bDeviceSubClass */ + 0x00, /* bDeviceProtocol */ + USB_MAX_EP0_SIZE, /* bMaxPacketSize */ + LBYTE(USBD_HIDIAP_VENDOR_ID), /* idVendor */ + HBYTE(USBD_HIDIAP_VENDOR_ID), /* idVendor */ + LBYTE(USBD_HIDIAP_PRODUCT_ID), /* idProduct */ + HBYTE(USBD_HIDIAP_PRODUCT_ID), /* idProduct */ + 0x00, /* bcdDevice rel. 2.00 */ + 0x02, + USB_MFC_STRING, /* Index of manufacturer string */ + USB_PRODUCT_STRING, /* Index of product string */ + USB_SERIAL_STRING, /* Index of serial number string */ + 1 /* bNumConfigurations */ +}; + +/** + * @brief usb configuration standard descriptor + */ +#if defined ( __ICCARM__ ) /* iar compiler */ + #pragma data_alignment=4 +#endif +ALIGNED_HEAD static uint8_t g_usbd_configuration[USBD_HIDIAP_CONFIG_DESC_SIZE] ALIGNED_TAIL = +{ + USB_DEVICE_CFG_DESC_LEN, /* bLength: configuration descriptor size */ + USB_DESCIPTOR_TYPE_CONFIGURATION, /* bDescriptorType: configuration */ + LBYTE(USBD_HIDIAP_CONFIG_DESC_SIZE), /* wTotalLength: bytes returned */ + HBYTE(USBD_HIDIAP_CONFIG_DESC_SIZE), /* wTotalLength: bytes returned */ + 0x01, /* bNumInterfaces: 1 interface */ + 0x01, /* bConfigurationValue: configuration value */ + 0x00, /* iConfiguration: index of string descriptor describing + the configuration */ + 0xC0, /* bmAttributes: self powered */ + 0x32, /* MaxPower 100 mA: this current is used for detecting vbus */ + + USB_DEVICE_IF_DESC_LEN, /* bLength: interface descriptor size */ + USB_DESCIPTOR_TYPE_INTERFACE, /* bDescriptorType: interface descriptor type */ + 0x00, /* bInterfaceNumber: number of interface */ + 0x00, /* bAlternateSetting: alternate set */ + 0x02, /* bNumEndpoints: number of endpoints */ + USB_CLASS_CODE_HID, /* bInterfaceClass: class code hid */ + 0x00, /* bInterfaceSubClass: subclass code */ + 0x00, /* bInterfaceProtocol: protocol code */ + 0x00, /* iInterface: index of string descriptor */ + + 0x09, /* bLength: size of HID descriptor in bytes */ + HID_CLASS_DESC_HID, /* bDescriptorType: HID descriptor type */ + LBYTE(HIDIAP_BCD_NUM), + HBYTE(HIDIAP_BCD_NUM), /* bcdHID: HID class specification release number */ + 0x00, /* bCountryCode: hardware target conutry */ + 0x01, /* bNumDescriptors: number of HID class descriptor to follow */ + HID_CLASS_DESC_REPORT, /* bDescriptorType: report descriptor type */ + LBYTE(sizeof(g_usbd_hidiap_report)), + HBYTE(sizeof(g_usbd_hidiap_report)), /* wDescriptorLength: total length of reprot descriptor */ + + USB_DEVICE_EPT_LEN, /* bLength: size of endpoint descriptor in bytes */ + USB_DESCIPTOR_TYPE_ENDPOINT, /* bDescriptorType: endpoint descriptor type */ + USBD_HIDIAP_IN_EPT, /* bEndpointAddress: the address of endpoint on usb device described by this descriptor */ + USB_EPT_DESC_INTERRUPT, /* bmAttributes: endpoint attributes */ + LBYTE(USBD_HIDIAP_IN_MAXPACKET_SIZE), + HBYTE(USBD_HIDIAP_IN_MAXPACKET_SIZE), /* wMaxPacketSize: maximum packe size this endpoint */ + HIDIAP_BINTERVAL_TIME, /* bInterval: interval for polling endpoint for data transfers */ + + USB_DEVICE_EPT_LEN, /* bLength: size of endpoint descriptor in bytes */ + USB_DESCIPTOR_TYPE_ENDPOINT, /* bDescriptorType: endpoint descriptor type */ + USBD_HIDIAP_OUT_EPT, /* bEndpointAddress: the address of endpoint on usb device described by this descriptor */ + USB_EPT_DESC_INTERRUPT, /* bmAttributes: endpoint attributes */ + LBYTE(USBD_HIDIAP_OUT_MAXPACKET_SIZE), + HBYTE(USBD_HIDIAP_OUT_MAXPACKET_SIZE), /* wMaxPacketSize: maximum packe size this endpoint */ + HIDIAP_BINTERVAL_TIME, /* bInterval: interval for polling endpoint for data transfers */ +}; + +/** + * @brief usb hid report descriptor + */ +#if defined ( __ICCARM__ ) /* iar compiler */ + #pragma data_alignment=4 +#endif +ALIGNED_HEAD uint8_t g_usbd_hidiap_report[USBD_HIDIAP_SIZ_REPORT_DESC] ALIGNED_TAIL = +{ + 0x06, 0xFF, 0x00, /* USAGE_PAGE(Vendor Page:0xFF00) */ + 0x09, 0x01, /* USAGE (Demo Kit) */ + 0xa1, 0x01, /* COLLECTION (Application) */ + + /* 6 */ + 0x15, 0x00, /* LOGICAL_MINIMUM (0) */ + 0x25, 0xFF, /* LOGICAL_MAXIMUM (255) */ + 0x75, 0x08, /* REPORT_SIZE (8) */ + 0x95, 0x40, /* REPORT_COUNT (64) */ + + 0x09, 0x01, + 0x81, 0x02, + 0x95, 0x40, + + 0x09, 0x01, + 0x91, 0x02, + 0x95, 0x01, + + 0x09, 0x01, + 0xB1, 0x02, + 0xC0 +}; + +/** + * @brief usb hid descriptor + */ +#if defined ( __ICCARM__ ) /* iar compiler */ + #pragma data_alignment=4 +#endif +ALIGNED_HEAD uint8_t g_hidiap_usb_desc[9] ALIGNED_TAIL = +{ + 0x09, /* bLength: size of HID descriptor in bytes */ + HID_CLASS_DESC_HID, /* bDescriptorType: HID descriptor type */ + LBYTE(HIDIAP_BCD_NUM), + HBYTE(HIDIAP_BCD_NUM), /* bcdHID: HID class specification release number */ + 0x00, /* bCountryCode: hardware target conutry */ + 0x01, /* bNumDescriptors: number of HID class descriptor to follow */ + HID_CLASS_DESC_REPORT, /* bDescriptorType: report descriptor type */ + LBYTE(sizeof(g_usbd_hidiap_report)), + HBYTE(sizeof(g_usbd_hidiap_report)), /* wDescriptorLength: total length of reprot descriptor */ +}; + + +/** + * @brief usb string lang id + */ +#if defined ( __ICCARM__ ) /* iar compiler */ + #pragma data_alignment=4 +#endif +ALIGNED_HEAD static uint8_t g_string_lang_id[USBD_HIDIAP_SIZ_STRING_LANGID] ALIGNED_TAIL = +{ + USBD_HIDIAP_SIZ_STRING_LANGID, + USB_DESCIPTOR_TYPE_STRING, + 0x09, + 0x04, +}; + +/** + * @brief usb string serial + */ +#if defined ( __ICCARM__ ) /* iar compiler */ + #pragma data_alignment=4 +#endif +ALIGNED_HEAD static uint8_t g_string_serial[USBD_HIDIAP_SIZ_STRING_SERIAL] ALIGNED_TAIL = +{ + USBD_HIDIAP_SIZ_STRING_SERIAL, + USB_DESCIPTOR_TYPE_STRING, +}; + + +/* device descriptor */ +static usbd_desc_t device_descriptor = +{ + USB_DEVICE_DESC_LEN, + g_usbd_descriptor +}; + +/* config descriptor */ +static usbd_desc_t config_descriptor = +{ + USBD_HIDIAP_CONFIG_DESC_SIZE, + g_usbd_configuration +}; + +/* langid descriptor */ +static usbd_desc_t langid_descriptor = +{ + USBD_HIDIAP_SIZ_STRING_LANGID, + g_string_lang_id +}; + +/* serial descriptor */ +static usbd_desc_t serial_descriptor = +{ + USBD_HIDIAP_SIZ_STRING_SERIAL, + g_string_serial +}; + +static usbd_desc_t vp_desc; + +/** + * @brief standard usb unicode convert + * @param string: source string + * @param unicode_buf: unicode buffer + * @retval length + */ +static uint16_t usbd_unicode_convert(uint8_t *string, uint8_t *unicode_buf) +{ + uint16_t str_len = 0, id_pos = 2; + uint8_t *tmp_str = string; + + while(*tmp_str != '\0') + { + str_len ++; + unicode_buf[id_pos ++] = *tmp_str ++; + unicode_buf[id_pos ++] = 0x00; + } + + str_len = str_len * 2 + 2; + unicode_buf[0] = str_len; + unicode_buf[1] = USB_DESCIPTOR_TYPE_STRING; + + return str_len; +} + +/** + * @brief usb int convert to unicode + * @param value: int value + * @param pbus: unicode buffer + * @param len: length + * @retval none + */ +static void usbd_int_to_unicode (uint32_t value , uint8_t *pbuf , uint8_t len) +{ + uint8_t idx = 0; + + for( idx = 0 ; idx < len ; idx ++) + { + if( ((value >> 28)) < 0xA ) + { + pbuf[ 2 * idx] = (value >> 28) + '0'; + } + else + { + pbuf[2 * idx] = (value >> 28) + 'A' - 10; + } + + value = value << 4; + + pbuf[2 * idx + 1] = 0; + } +} + +/** + * @brief usb get serial number + * @param none + * @retval none + */ +static void get_serial_num(void) +{ + uint32_t serial0, serial1, serial2; + + serial0 = *(uint32_t*)MCU_ID1; + serial1 = *(uint32_t*)MCU_ID2; + serial2 = *(uint32_t*)MCU_ID3; + + serial0 += serial2; + + if (serial0 != 0) + { + usbd_int_to_unicode (serial0, &g_string_serial[2] ,8); + usbd_int_to_unicode (serial1, &g_string_serial[18] ,4); + } +} + +/** + * @brief get device descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_descriptor(void) +{ + return &device_descriptor; +} + +/** + * @brief get device qualifier + * @param none + * @retval usbd_desc + */ +static usbd_desc_t * get_device_qualifier(void) +{ + return NULL; +} + +/** + * @brief get config descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_configuration(void) +{ + return &config_descriptor; +} + +/** + * @brief get other speed descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_other_speed(void) +{ + return NULL; +} + +/** + * @brief get lang id descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_lang_id(void) +{ + return &langid_descriptor; +} + + +/** + * @brief get manufacturer descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_manufacturer_string(void) +{ + vp_desc.length = usbd_unicode_convert((uint8_t *)USBD_HIDIAP_DESC_MANUFACTURER_STRING, g_usbd_desc_buffer); + vp_desc.descriptor = g_usbd_desc_buffer; + return &vp_desc; +} + +/** + * @brief get product descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_product_string(void) +{ + vp_desc.length = usbd_unicode_convert((uint8_t *)USBD_HIDIAP_DESC_PRODUCT_STRING, g_usbd_desc_buffer); + vp_desc.descriptor = g_usbd_desc_buffer; + return &vp_desc; +} + +/** + * @brief get serial descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_serial_string(void) +{ + get_serial_num(); + return &serial_descriptor; +} + +/** + * @brief get interface descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_interface_string(void) +{ + vp_desc.length = usbd_unicode_convert((uint8_t *)USBD_HIDIAP_DESC_INTERFACE_STRING, g_usbd_desc_buffer); + vp_desc.descriptor = g_usbd_desc_buffer; + return &vp_desc; +} + +/** + * @brief get device config descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_config_string(void) +{ + vp_desc.length = usbd_unicode_convert((uint8_t *)USBD_HIDIAP_DESC_CONFIGURATION_STRING, g_usbd_desc_buffer); + vp_desc.descriptor = g_usbd_desc_buffer; + return &vp_desc; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + + diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/hid_iap/hid_iap_desc.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/hid_iap/hid_iap_desc.h new file mode 100644 index 0000000000..ef3b76e435 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/hid_iap/hid_iap_desc.h @@ -0,0 +1,94 @@ +/** + ************************************************************************** + * @file hid_iap_desc.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb hid iap descriptor header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __HID_IAP_DESC_H +#define __HID_IAP_DESC_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "hid_iap_class.h" +#include "usbd_core.h" + +/** @addtogroup AT32F435_437_middlewares_usbd_class + * @{ + */ + +/** @addtogroup USB_hid_iap_desc + * @{ + */ + +/** @defgroup USB_hid_iap_desc_definition + * @{ + */ + + +#define HIDIAP_BCD_NUM 0x0110 + +#define USBD_HIDIAP_VENDOR_ID 0x2E3C +#define USBD_HIDIAP_PRODUCT_ID 0xAF01 + +#define USBD_HIDIAP_CONFIG_DESC_SIZE 41 +#define USBD_HIDIAP_SIZ_REPORT_DESC 32 +#define USBD_HIDIAP_SIZ_STRING_LANGID 4 +#define USBD_HIDIAP_SIZ_STRING_SERIAL 0x1A + +#define USBD_HIDIAP_DESC_MANUFACTURER_STRING "Artery" +#define USBD_HIDIAP_DESC_PRODUCT_STRING "HID IAP" +#define USBD_HIDIAP_DESC_CONFIGURATION_STRING "HID IAP Config" +#define USBD_HIDIAP_DESC_INTERFACE_STRING "HID IAP Interface" + +#define HIDIAP_BINTERVAL_TIME 0x01 + +#define MCU_ID1 (0x1FFFF7E8) +#define MCU_ID2 (0x1FFFF7EC) +#define MCU_ID3 (0x1FFFF7F0) +extern uint8_t g_usbd_hidiap_report[USBD_HIDIAP_SIZ_REPORT_DESC]; +extern uint8_t g_hidiap_usb_desc[9]; + +extern usbd_desc_handler hid_iap_desc_handler; + + +/** + * @} + */ + +/** + * @} + */ + + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif + diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_bot_scsi.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_bot_scsi.c new file mode 100644 index 0000000000..0a458cd5ca --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_bot_scsi.c @@ -0,0 +1,835 @@ +/** + ************************************************************************** + * @file msc_bot_scsi.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb mass storage bulk-only transport and scsi command + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +#include "msc_bot_scsi.h" +#include "msc/at32_msc_diskio.h" + +/** @addtogroup AT32F435_437_middlewares_usbd_class + * @{ + */ + +/** @defgroup USB_msc_bot_scsi + * @brief usb device class mass storage demo + * @{ + */ + +/** @defgroup USB_msc_bot_functions + * @{ + */ + + +#if defined ( __ICCARM__ ) /* iar compiler */ + #pragma data_alignment=4 +#endif +ALIGNED_HEAD uint8_t page00_inquiry_data[] ALIGNED_TAIL = { + 0x00, + 0x00, + 0x00, + 0x00, + 0x00, + +}; +#if defined ( __ICCARM__ ) /* iar compiler */ + #pragma data_alignment=4 +#endif +ALIGNED_HEAD sense_type sense_data ALIGNED_TAIL = +{ + 0x70, + 0x00, + SENSE_KEY_ILLEGAL_REQUEST, + 0x00000000, + 0x0A, + 0x00000000, + 0x20, + 0x00, + 0x00000000 +}; + +#if defined ( __ICCARM__ ) /* iar compiler */ + #pragma data_alignment=4 +#endif +ALIGNED_HEAD uint8_t mode_sense6_data[8] ALIGNED_TAIL = +{ + 0x00, + 0x00, + 0x00, + 0x00, + 0x00, + 0x00, + 0x00, + 0x00 +}; + +#if defined ( __ICCARM__ ) /* iar compiler */ + #pragma data_alignment=4 +#endif +ALIGNED_HEAD uint8_t mode_sense10_data[8] ALIGNED_TAIL = +{ + 0x00, + 0x06, + 0x00, + 0x00, + 0x00, + 0x00, + 0x00, + 0x00 +}; +/** + * @brief initialize bulk-only transport and scsi + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void bot_scsi_init(void *udev) +{ + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + pmsc->msc_state = MSC_STATE_MACHINE_IDLE; + pmsc->bot_status = MSC_BOT_STATE_IDLE; + pmsc->max_lun = MSC_SUPPORT_MAX_LUN - 1; + + pmsc->csw_struct.dCSWSignature = CSW_DCSWSIGNATURE; + pmsc->csw_struct.dCSWDataResidue = 0; + pmsc->csw_struct.dCSWSignature = 0; + pmsc->csw_struct.dCSWTag = CSW_BCSWSTATUS_PASS; + + usbd_flush_tx_fifo(pudev, USBD_MSC_BULK_IN_EPT&0x7F); + + /* set out endpoint to receive status */ + usbd_ept_recv(pudev, USBD_MSC_BULK_OUT_EPT, (uint8_t *)&pmsc->cbw_struct, CBW_CMD_LENGTH); +} + +/** + * @brief reset bulk-only transport and scsi + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void bot_scsi_reset(void *udev) +{ + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + pmsc->msc_state = MSC_STATE_MACHINE_IDLE; + pmsc->bot_status = MSC_BOT_STATE_RECOVERY; + pmsc->max_lun = MSC_SUPPORT_MAX_LUN - 1; + usbd_flush_tx_fifo(pudev, USBD_MSC_BULK_IN_EPT&0x7F); + + /* set out endpoint to receive status */ + usbd_ept_recv(pudev, USBD_MSC_BULK_OUT_EPT, (uint8_t *)&pmsc->cbw_struct, CBW_CMD_LENGTH); +} + +/** + * @brief bulk-only transport data in handler + * @param udev: to the structure of usbd_core_type + * @param ept_num: endpoint number + * @retval none + */ +void bot_scsi_datain_handler(void *udev, uint8_t ept_num) +{ + UNUSED(ept_num); + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + switch(pmsc->msc_state) + { + case MSC_STATE_MACHINE_DATA_IN: + if(bot_scsi_cmd_process(udev) != USB_OK) + { + bot_scsi_send_csw(udev, CSW_BCSWSTATUS_FAILED); + } + break; + + case MSC_STATE_MACHINE_LAST_DATA: + case MSC_STATE_MACHINE_SEND_DATA: + bot_scsi_send_csw(udev, CSW_BCSWSTATUS_PASS); + break; + + default: + break; + } +} + +/** + * @brief bulk-only transport data out handler + * @param udev: to the structure of usbd_core_type + * @param ept_num: endpoint number + * @retval none + */ +void bot_scsi_dataout_handler(void *udev, uint8_t ept_num) +{ + UNUSED(ept_num); + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + switch(pmsc->msc_state) + { + case MSC_STATE_MACHINE_IDLE: + bot_cbw_decode(udev); + break; + + case MSC_STATE_MACHINE_DATA_OUT: + if(bot_scsi_cmd_process(udev) != USB_OK) + { + bot_scsi_send_csw(udev, CSW_BCSWSTATUS_FAILED); + } + break; + } +} + +/** + * @brief bulk-only cbw decode + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void bot_cbw_decode(void *udev) +{ + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + + pmsc->csw_struct.dCSWTag = pmsc->cbw_struct.dCBWTage; + pmsc->csw_struct.dCSWDataResidue = pmsc->cbw_struct.dCBWDataTransferLength; + + /* check param */ + if((pmsc->cbw_struct.dCBWSignature != CBW_DCBWSIGNATURE) || + (usbd_get_recv_len(pudev, USBD_MSC_BULK_OUT_EPT) != CBW_CMD_LENGTH) + || (pmsc->cbw_struct.bCBWLUN > MSC_SUPPORT_MAX_LUN) || + (pmsc->cbw_struct.bCBWCBLength < 1) || (pmsc->cbw_struct.bCBWCBLength > 16)) + { + bot_scsi_sense_code(udev, SENSE_KEY_ILLEGAL_REQUEST, INVALID_COMMAND); + pmsc->bot_status = MSC_BOT_STATE_ERROR; + bot_scsi_stall(udev); + } + else + { + if(bot_scsi_cmd_process(udev) != USB_OK) + { + bot_scsi_stall(udev); + } + else if((pmsc->msc_state != MSC_STATE_MACHINE_DATA_IN) && + (pmsc->msc_state != MSC_STATE_MACHINE_DATA_OUT) && + (pmsc->msc_state != MSC_STATE_MACHINE_LAST_DATA)) + { + if(pmsc->data_len == 0) + { + bot_scsi_send_csw(udev, CSW_BCSWSTATUS_PASS); + } + else if(pmsc->data_len > 0) + { + bot_scsi_send_data(udev, pmsc->data, pmsc->data_len); + } + } + } +} + +/** + * @brief send bot data + * @param udev: to the structure of usbd_core_type + * @param buffer: data buffer + * @param len: data len + * @retval none + */ +void bot_scsi_send_data(void *udev, uint8_t *buffer, uint32_t len) +{ + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + uint32_t data_len = MIN(len, pmsc->cbw_struct.dCBWDataTransferLength); + + pmsc->csw_struct.dCSWDataResidue -= data_len; + pmsc->csw_struct.bCSWStatus = CSW_BCSWSTATUS_PASS; + + pmsc->msc_state = MSC_STATE_MACHINE_SEND_DATA; + + usbd_ept_send(pudev, USBD_MSC_BULK_IN_EPT, + buffer, data_len); +} + +/** + * @brief send command status + * @param udev: to the structure of usbd_core_type + * @param status: csw status + * @retval none + */ +void bot_scsi_send_csw(void *udev, uint8_t status) +{ + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + + pmsc->csw_struct.bCSWStatus = status; + pmsc->csw_struct.dCSWSignature = CSW_DCSWSIGNATURE; + pmsc->msc_state = MSC_STATE_MACHINE_IDLE; + + usbd_ept_send(pudev, USBD_MSC_BULK_IN_EPT, + (uint8_t *)&pmsc->csw_struct, CSW_CMD_LENGTH); + + usbd_ept_recv(pudev, USBD_MSC_BULK_OUT_EPT, + (uint8_t *)&pmsc->cbw_struct, CBW_CMD_LENGTH); +} + + +/** + * @brief send scsi sense code + * @param udev: to the structure of usbd_core_type + * @param sense_key: sense key + * @param asc: asc + * @retval none + */ +void bot_scsi_sense_code(void *udev, uint8_t sense_key, uint8_t asc) +{ + UNUSED(udev); + sense_data.sense_key = sense_key; + sense_data.asc = asc; +} + + +/** + * @brief check address + * @param udev: to the structure of usbd_core_type + * @param lun: logical units number + * @param blk_offset: blk offset address + * @param blk_count: blk number + * @retval usb_sts_type + */ +usb_sts_type bot_scsi_check_address(void *udev, uint8_t lun, uint32_t blk_offset, uint32_t blk_count) +{ + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + if((blk_offset + blk_count) > pmsc->blk_nbr[lun]) + { + bot_scsi_sense_code(udev, SENSE_KEY_ILLEGAL_REQUEST, ADDRESS_OUT_OF_RANGE); + return USB_FAIL; + } + return USB_OK; +} + +/** + * @brief bot endpoint stall + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void bot_scsi_stall(void *udev) +{ + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + + if((pmsc->cbw_struct.dCBWDataTransferLength != 0) && + (pmsc->cbw_struct.bmCBWFlags == 0) && + pmsc->bot_status == MSC_BOT_STATE_IDLE) + { + usbd_set_stall(pudev, USBD_MSC_BULK_OUT_EPT); + } + usbd_set_stall(pudev, USBD_MSC_BULK_IN_EPT); + + if(pmsc->bot_status == MSC_BOT_STATE_ERROR) + { + usbd_ept_recv(pudev, USBD_MSC_BULK_OUT_EPT, + (uint8_t *)&pmsc->cbw_struct, CBW_CMD_LENGTH); + } +} + +/** + * @brief bulk-only transport scsi command test unit + * @param udev: to the structure of usbd_core_type + * @param lun: logical units number + * @retval status of usb_sts_type + */ +usb_sts_type bot_scsi_test_unit(void *udev, uint8_t lun) +{ + UNUSED(lun); + usb_sts_type status = USB_OK; + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + + if(pmsc->cbw_struct.dCBWDataTransferLength != 0) + { + bot_scsi_sense_code(udev, SENSE_KEY_ILLEGAL_REQUEST, INVALID_COMMAND); + return USB_FAIL; + } + + pmsc->data_len = 0; + return status; +} + +/** + * @brief bulk-only transport scsi command inquiry + * @param udev: to the structure of usbd_core_type + * @param lun: logical units number + * @retval status of usb_sts_type + */ +usb_sts_type bot_scsi_inquiry(void *udev, uint8_t lun) +{ + uint8_t *pdata; + uint32_t trans_len = 0; + usb_sts_type status = USB_OK; + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + + if(pmsc->cbw_struct.CBWCB[1] & 0x01) + { + pdata = page00_inquiry_data; + trans_len = 5; + } + else + { + pdata = get_inquiry(lun); + if(pmsc->cbw_struct.dCBWDataTransferLength < SCSI_INQUIRY_DATA_LENGTH) + { + trans_len = pmsc->cbw_struct.dCBWDataTransferLength; + } + else + { + trans_len = SCSI_INQUIRY_DATA_LENGTH; + } + } + + pmsc->data_len = trans_len; + while(trans_len) + { + trans_len --; + pmsc->data[trans_len] = pdata[trans_len]; + } + return status; +} + +/** + * @brief bulk-only transport scsi command start stop + * @param udev: to the structure of usbd_core_type + * @param lun: logical units number + * @retval status of usb_sts_type + */ +usb_sts_type bot_scsi_start_stop(void *udev, uint8_t lun) +{ + UNUSED(lun); + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + pmsc->data_len = 0; + return USB_OK; +} + +/** + * @brief bulk-only transport scsi command meidum removal + * @param udev: to the structure of usbd_core_type + * @param lun: logical units number + * @retval status of usb_sts_type + */ +usb_sts_type bot_scsi_allow_medium_removal(void *udev, uint8_t lun) +{ + UNUSED(lun); + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + pmsc->data_len = 0; + return USB_OK; +} + +/** + * @brief bulk-only transport scsi command mode sense6 + * @param udev: to the structure of usbd_core_type + * @param lun: logical units number + * @retval status of usb_sts_type + */ +usb_sts_type bot_scsi_mode_sense6(void *udev, uint8_t lun) +{ + UNUSED(lun); + uint8_t data_len = 8; + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + pmsc->data_len = 8; + while(data_len) + { + data_len --; + pmsc->data[data_len] = mode_sense6_data[data_len]; + }; + return USB_OK; +} + +/** + * @brief bulk-only transport scsi command mode sense10 + * @param udev: to the structure of usbd_core_type + * @param lun: logical units number + * @retval status of usb_sts_type + */ +usb_sts_type bot_scsi_mode_sense10(void *udev, uint8_t lun) +{ + UNUSED(lun); + uint8_t data_len = 8; + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + pmsc->data_len = 8; + while(data_len) + { + data_len --; + pmsc->data[data_len] = mode_sense10_data[data_len]; + }; + return USB_OK; +} + +/** + * @brief bulk-only transport scsi command capacity + * @param udev: to the structure of usbd_core_type + * @param lun: logical units number + * @retval status of usb_sts_type + */ +usb_sts_type bot_scsi_capacity(void *udev, uint8_t lun) +{ + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + uint8_t *pdata = pmsc->data; + msc_disk_capacity(lun, &pmsc->blk_nbr[lun], &pmsc->blk_size[lun]); + + pdata[0] = (uint8_t)((pmsc->blk_nbr[lun] - 1) >> 24); + pdata[1] = (uint8_t)((pmsc->blk_nbr[lun] - 1) >> 16); + pdata[2] = (uint8_t)((pmsc->blk_nbr[lun] - 1) >> 8); + pdata[3] = (uint8_t)((pmsc->blk_nbr[lun] - 1)); + + pdata[4] = (uint8_t)((pmsc->blk_size[lun]) >> 24); + pdata[5] = (uint8_t)((pmsc->blk_size[lun]) >> 16); + pdata[6] = (uint8_t)((pmsc->blk_size[lun]) >> 8); + pdata[7] = (uint8_t)((pmsc->blk_size[lun])); + + pmsc->data_len = 8; + return USB_OK; +} + +/** + * @brief bulk-only transport scsi command format capacity + * @param udev: to the structure of usbd_core_type + * @param lun: logical units number + * @retval status of usb_sts_type + */ +usb_sts_type bot_scsi_format_capacity(void *udev, uint8_t lun) +{ + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + uint8_t *pdata = pmsc->data; + + pdata[0] = 0; + pdata[1] = 0; + pdata[2] = 0; + pdata[3] = 0x08; + + msc_disk_capacity(lun, &pmsc->blk_nbr[lun], &pmsc->blk_size[lun]); + + pdata[4] = (uint8_t)((pmsc->blk_nbr[lun] - 1) >> 24); + pdata[5] = (uint8_t)((pmsc->blk_nbr[lun] - 1) >> 16); + pdata[6] = (uint8_t)((pmsc->blk_nbr[lun] - 1) >> 8); + pdata[7] = (uint8_t)((pmsc->blk_nbr[lun] - 1)); + + pdata[8] = 0x02; + + pdata[9] = (uint8_t)((pmsc->blk_size[lun]) >> 16); + pdata[10] = (uint8_t)((pmsc->blk_size[lun]) >> 8); + pdata[11] = (uint8_t)((pmsc->blk_size[lun])); + + pmsc->data_len = 12; + + return USB_OK; +} + +/** + * @brief bulk-only transport scsi command request sense + * @param udev: to the structure of usbd_core_type + * @param lun: logical units number + * @retval status of usb_sts_type + */ +usb_sts_type bot_scsi_request_sense(void *udev, uint8_t lun) +{ + UNUSED(lun); + uint32_t trans_len = 0x12; + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + uint8_t *pdata = pmsc->data; + uint8_t *sdata = (uint8_t *)&sense_data; + + while(trans_len) + { + trans_len --; + pdata[trans_len] = sdata[trans_len]; + } + + if(pmsc->cbw_struct.dCBWDataTransferLength < REQ_SENSE_STANDARD_DATA_LEN) + { + pmsc->data_len = pmsc->cbw_struct.dCBWDataTransferLength; + } + else + { + pmsc->data_len = REQ_SENSE_STANDARD_DATA_LEN; + } + return USB_OK; +} + +/** + * @brief bulk-only transport scsi command verify + * @param udev: to the structure of usbd_core_type + * @param lun: logical units number + * @retval status of usb_sts_type + */ +usb_sts_type bot_scsi_verify(void *udev, uint8_t lun) +{ + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + uint8_t *cmd = pmsc->cbw_struct.CBWCB; + if((pmsc->cbw_struct.CBWCB[1] & 0x02) == 0x02) + { + bot_scsi_sense_code(udev, SENSE_KEY_ILLEGAL_REQUEST, INVALID_FIELED_IN_COMMAND); + return USB_FAIL; + } + + pmsc->blk_addr = cmd[2] << 24 | cmd[3] << 16 | cmd[4] << 8 | cmd[5]; + pmsc->blk_len = cmd[7] << 8 | cmd[8]; + + if(bot_scsi_check_address(udev, lun, pmsc->blk_addr, pmsc->blk_len) != USB_OK) + { + return USB_FAIL; + } + pmsc->data_len = 0; + return USB_OK; +} + +/** + * @brief bulk-only transport scsi command read10 + * @param udev: to the structure of usbd_core_type + * @param lun: logical units number + * @retval status of usb_sts_type + */ +usb_sts_type bot_scsi_read10(void *udev, uint8_t lun) +{ + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + uint8_t *cmd = pmsc->cbw_struct.CBWCB; + uint32_t len; + + if(pmsc->msc_state == MSC_STATE_MACHINE_IDLE) + { + if((pmsc->cbw_struct.bmCBWFlags & 0x80) != 0x80) + { + bot_scsi_sense_code(udev, SENSE_KEY_ILLEGAL_REQUEST, INVALID_COMMAND); + return USB_FAIL; + } + + pmsc->blk_addr = cmd[2] << 24 | cmd[3] << 16 | cmd[4] << 8 | cmd[5]; + pmsc->blk_len = cmd[7] << 8 | cmd[8]; + + if(bot_scsi_check_address(udev, lun, pmsc->blk_addr, pmsc->blk_len) != USB_OK) + { + return USB_FAIL; + } + + pmsc->blk_addr *= pmsc->blk_size[lun]; + pmsc->blk_len *= pmsc->blk_size[lun]; + + if(pmsc->cbw_struct.dCBWDataTransferLength != pmsc->blk_len) + { + bot_scsi_sense_code(udev, SENSE_KEY_ILLEGAL_REQUEST, INVALID_COMMAND); + return USB_FAIL; + } + pmsc->msc_state = MSC_STATE_MACHINE_DATA_IN; + } + pmsc->data_len = MSC_MAX_DATA_BUF_LEN; + + len = MIN(pmsc->blk_len, MSC_MAX_DATA_BUF_LEN); + if( msc_disk_read(lun, pmsc->blk_addr, pmsc->data, len) != USB_OK) + { + bot_scsi_sense_code(udev, SENSE_KEY_HARDWARE_ERROR, MEDIUM_NOT_PRESENT); + return USB_FAIL; + } + usbd_ept_send(pudev, USBD_MSC_BULK_IN_EPT, pmsc->data, len); + pmsc->blk_addr += len; + pmsc->blk_len -= len; + + pmsc->csw_struct.dCSWDataResidue -= len; + if(pmsc->blk_len == 0) + { + pmsc->msc_state = MSC_STATE_MACHINE_LAST_DATA; + } + + return USB_OK; +} + + +/** + * @brief bulk-only transport scsi command write10 + * @param udev: to the structure of usbd_core_type + * @param lun: logical units number + * @retval status of usb_sts_type + */ +usb_sts_type bot_scsi_write10(void *udev, uint8_t lun) +{ + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + uint8_t *cmd = pmsc->cbw_struct.CBWCB; + uint32_t len; + + if(pmsc->msc_state == MSC_STATE_MACHINE_IDLE) + { + if((pmsc->cbw_struct.bmCBWFlags & 0x80) == 0x80) + { + bot_scsi_sense_code(udev, SENSE_KEY_ILLEGAL_REQUEST, INVALID_COMMAND); + return USB_FAIL; + } + + pmsc->blk_addr = cmd[2] << 24 | cmd[3] << 16 | cmd[4] << 8 | cmd[5]; + pmsc->blk_len = cmd[7] << 8 | cmd[8]; + + if(bot_scsi_check_address(udev, lun, pmsc->blk_addr, pmsc->blk_len) != USB_OK) + { + return USB_FAIL; + } + + pmsc->blk_addr *= pmsc->blk_size[lun]; + pmsc->blk_len *= pmsc->blk_size[lun]; + + if(pmsc->cbw_struct.dCBWDataTransferLength != pmsc->blk_len) + { + bot_scsi_sense_code(udev, SENSE_KEY_ILLEGAL_REQUEST, INVALID_COMMAND); + return USB_FAIL; + } + + pmsc->msc_state = MSC_STATE_MACHINE_DATA_OUT; + len = MIN(pmsc->blk_len, MSC_MAX_DATA_BUF_LEN); + usbd_ept_recv(pudev, USBD_MSC_BULK_OUT_EPT, (uint8_t *)pmsc->data, len); + + } + else + { + len = MIN(pmsc->blk_len, MSC_MAX_DATA_BUF_LEN); + if(msc_disk_write(lun, pmsc->blk_addr, pmsc->data, len) != USB_OK) + { + bot_scsi_sense_code(udev, SENSE_KEY_HARDWARE_ERROR, MEDIUM_NOT_PRESENT); + return USB_FAIL; + } + + pmsc->blk_addr += len; + pmsc->blk_len -= len; + + pmsc->csw_struct.dCSWDataResidue -= len; + + if(pmsc->blk_len == 0) + { + bot_scsi_send_csw(udev, CSW_BCSWSTATUS_PASS); + } + else + { + len = MIN(pmsc->blk_len, MSC_MAX_DATA_BUF_LEN); + usbd_ept_recv(pudev, USBD_MSC_BULK_OUT_EPT, (uint8_t *)pmsc->data, len); + } + } + return USB_OK; +} + +/** + * @brief clear feature + * @param udev: to the structure of usbd_core_type + * @param etp_num: endpoint number + * @retval status of usb_sts_type + */ +void bot_scsi_clear_feature(void *udev, uint8_t ept_num) +{ + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + if(pmsc->bot_status == MSC_BOT_STATE_ERROR) + { + usbd_set_stall(pudev, USBD_MSC_BULK_IN_EPT); + pmsc->bot_status = MSC_BOT_STATE_IDLE; + } + else if(((ept_num & 0x80) == 0x80) && (pmsc->bot_status != MSC_BOT_STATE_RECOVERY)) + { + bot_scsi_send_csw(udev, CSW_BCSWSTATUS_FAILED); + } +} + +/** + * @brief bulk-only transport scsi command process + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +usb_sts_type bot_scsi_cmd_process(void *udev) +{ + usb_sts_type status = USB_FAIL; + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + switch(pmsc->cbw_struct.CBWCB[0]) + { + case MSC_CMD_INQUIRY: + status = bot_scsi_inquiry(udev, pmsc->cbw_struct.bCBWLUN); + break; + + case MSC_CMD_START_STOP: + status = bot_scsi_start_stop(udev, pmsc->cbw_struct.bCBWLUN); + break; + + case MSC_CMD_MODE_SENSE6: + status = bot_scsi_mode_sense6(udev, pmsc->cbw_struct.bCBWLUN); + break; + + case MSC_CMD_MODE_SENSE10: + status = bot_scsi_mode_sense10(udev, pmsc->cbw_struct.bCBWLUN); + break; + + case MSC_CMD_ALLOW_MEDIUM_REMOVAL: + status = bot_scsi_allow_medium_removal(udev, pmsc->cbw_struct.bCBWLUN); + break; + + case MSC_CMD_READ_10: + status = bot_scsi_read10(udev, pmsc->cbw_struct.bCBWLUN); + break; + + case MSC_CMD_READ_CAPACITY: + status = bot_scsi_capacity(udev, pmsc->cbw_struct.bCBWLUN); + break; + + case MSC_CMD_REQUEST_SENSE: + status = bot_scsi_request_sense(udev, pmsc->cbw_struct.bCBWLUN); + break; + + case MSC_CMD_TEST_UNIT: + status = bot_scsi_test_unit(udev, pmsc->cbw_struct.bCBWLUN); + break; + + case MSC_CMD_VERIFY: + status = bot_scsi_verify(udev, pmsc->cbw_struct.bCBWLUN); + break; + + case MSC_CMD_WRITE_10: + status = bot_scsi_write10(udev, pmsc->cbw_struct.bCBWLUN); + break; + + case MSC_CMD_READ_FORMAT_CAPACITY: + status = bot_scsi_format_capacity(udev, pmsc->cbw_struct.bCBWLUN); + break; + + default: + bot_scsi_sense_code(udev, SENSE_KEY_ILLEGAL_REQUEST, INVALID_COMMAND); + status = USB_FAIL; + break; + } + return status; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_bot_scsi.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_bot_scsi.h new file mode 100644 index 0000000000..0c3948268e --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_bot_scsi.h @@ -0,0 +1,256 @@ +/** + ************************************************************************** + * @file msc_bot_scsi.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb mass storage bulk-only transport and scsi command header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __MSC_BOT_SCSI_H +#define __MSC_BOT_SCSI_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "msc_class.h" +#include "usbd_core.h" + +/** @addtogroup AT32F435_437_middlewares_usbd_class + * @{ + */ + +/** @addtogroup USB_msc_bot_scsi + * @{ + */ + +/** @defgroup USB_msc_bot_scsi_definition + * @{ + */ + +#define MSC_SUPPORT_MAX_LUN 1 +#define MSC_MAX_DATA_BUF_LEN 4096 + +#define MSC_CMD_FORMAT_UNIT 0x04 +#define MSC_CMD_INQUIRY 0x12 +#define MSC_CMD_START_STOP 0x1B +#define MSC_CMD_MODE_SENSE6 0x1A +#define MSC_CMD_MODE_SENSE10 0x5A +#define MSC_CMD_ALLOW_MEDIUM_REMOVAL 0x1E +#define MSC_CMD_READ_10 0x28 +#define MSC_CMD_READ_12 0xA8 +#define MSC_CMD_READ_CAPACITY 0x25 +#define MSC_CMD_READ_FORMAT_CAPACITY 0x23 +#define MSC_CMD_REQUEST_SENSE 0x03 +#define MSC_CMD_TEST_UNIT 0x00 +#define MSC_CMD_VERIFY 0x2F +#define MSC_CMD_WRITE_10 0x2A +#define MSC_CMD_WRITE_12 0xAA +#define MSC_CMD_WRITE_VERIFY 0x2E + +#define MSC_REQ_GET_MAX_LUN 0xFE /*!< get max lun */ +#define MSC_REQ_BO_RESET 0xFF /*!< bulk only mass storage reset */ + +#define SET_LINE_CODING 0x20 +#define GET_LINE_CODING 0x21 + +#define CBW_CMD_LENGTH 31 +#define CBW_DCBWSIGNATURE 0x43425355 +#define CBW_BMCBWFLAGS_DIR_OUT 0x00 +#define CBW_BMCBWFLAGS_DIR_IN 0x80 + +#define CSW_CMD_LENGTH 13 +#define CSW_DCSWSIGNATURE 0x53425355 +#define CSW_BCSWSTATUS_PASS 0x00 +#define CSW_BCSWSTATUS_FAILED 0x01 +#define CSW_BCSWSTATUS_PHASE_ERR 0x02 + +#define MSC_STATE_MACHINE_CMD 0x00 +#define MSC_STATE_MACHINE_DATA_IN 0x01 +#define MSC_STATE_MACHINE_DATA_OUT 0x02 +#define MSC_STATE_MACHINE_SEND_DATA 0x03 +#define MSC_STATE_MACHINE_LAST_DATA 0x04 +#define MSC_STATE_MACHINE_STATUS 0x05 +#define MSC_STATE_MACHINE_FAILED 0x06 +#define MSC_STATE_MACHINE_IDLE 0x07 + +#define MSC_BOT_STATE_IDLE 0x00 +#define MSC_BOT_STATE_RECOVERY 0x01 +#define MSC_BOT_STATE_ERROR 0x02 + +#define REQ_SENSE_STANDARD_DATA_LEN 0x12 +#define SENSE_KEY_NO_SENSE 0x00 +#define SENSE_KEY_RECOVERED_ERROR 0x01 +#define SENSE_KEY_NOT_READY 0x02 +#define SENSE_KEY_MEDIUM_ERROR 0x03 +#define SENSE_KEY_HARDWARE_ERROR 0x04 +#define SENSE_KEY_ILLEGAL_REQUEST 0x05 +#define SENSE_KEY_UNIT_ATTENTION 0x06 +#define SENSE_KEY_DATA_PROTECT 0x07 +#define SENSE_KEY_BLANK_CHECK 0x08 +#define SENSE_KEY_VENDERO_SPECIFIC 0x09 +#define SENSE_KEY_ABORTED_COMMAND 0x0B +#define SENSE_KEY_VOLUME_OVERFLOW 0x0D +#define SENSE_KEY_MISCOMPARE 0x0E + + +#define INVALID_COMMAND 0x20 +#define INVALID_FIELED_IN_COMMAND 0x24 +#define PARAMETER_LIST_LENGTH_ERROR 0x1A +#define INVALID_FIELD_IN_PARAMETER_LIST 0x26 +#define ADDRESS_OUT_OF_RANGE 0x21 +#define MEDIUM_NOT_PRESENT 0x3A +#define MEDIUM_HAVE_CHANGED 0x28 + +#define SCSI_INQUIRY_DATA_LENGTH 36 + +/** + * @brief typical command block description + */ +typedef struct +{ + uint8_t opcode; + uint8_t lun; + uint32_t address; + uint8_t reserved1; + uint32_t alloc_length; + uint16_t reserved2; +}cbd_typical_type; + +/** + * @brief extended command block description + */ +typedef struct +{ + uint8_t opcode; + uint8_t lun; + uint32_t address; + uint8_t reserved1; + uint32_t alloc_length; + uint16_t reserved2; +}cbd_extended_type; + +/** + * @brief command block wrapper + */ +typedef struct +{ + uint32_t dCBWSignature; + uint32_t dCBWTage; + uint32_t dCBWDataTransferLength; + uint8_t bmCBWFlags; + uint8_t bCBWLUN; + uint8_t bCBWCBLength; + uint8_t CBWCB[16]; +}cbw_type; + +/** + * @brief command block wrapper + */ +typedef struct +{ + uint32_t dCSWSignature; + uint32_t dCSWTag; + uint32_t dCSWDataResidue; + uint32_t bCSWStatus; +}csw_type; + +/** + * @brief request sense standard data + */ +typedef struct +{ + uint8_t err_code; + uint8_t reserved1; + uint8_t sense_key; + uint32_t information; + uint8_t as_length; + uint32_t reserved2; + uint8_t asc; + uint8_t ascq; + uint32_t reserved3; +}sense_type; + + +typedef struct +{ + uint8_t msc_state; + uint8_t bot_status; + uint32_t max_lun; + + uint32_t blk_nbr[MSC_SUPPORT_MAX_LUN]; + uint32_t blk_size[MSC_SUPPORT_MAX_LUN]; + + uint32_t blk_addr; + uint32_t blk_len; + + uint32_t data_len; + uint8_t data[MSC_MAX_DATA_BUF_LEN]; + + uint32_t alt_setting; + + cbw_type cbw_struct; + csw_type csw_struct; + +}msc_type; + +void bot_scsi_init(void *udev); +void bot_scsi_reset(void *udev); +void bot_scsi_datain_handler(void *pudev, uint8_t ept_num); +void bot_scsi_dataout_handler(void *pudev, uint8_t ept_num); +void bot_cbw_decode(void *udev); +void bot_scsi_send_data(void *udev, uint8_t *buffer, uint32_t len); +void bot_scsi_send_csw(void *udev, uint8_t status); +void bot_scsi_sense_code(void *udev, uint8_t sense_key, uint8_t asc); +usb_sts_type bot_scsi_check_address(void *udev, uint8_t lun, uint32_t blk_offset, uint32_t blk_count); +void bot_scsi_stall(void *udev); +usb_sts_type bot_scsi_cmd_process(void *udev); + +usb_sts_type bot_scsi_test_unit(void *udev, uint8_t lun); +usb_sts_type bot_scsi_inquiry(void *udev, uint8_t lun); +usb_sts_type bot_scsi_start_stop(void *udev, uint8_t lun); +usb_sts_type bot_scsi_allow_medium_removal(void *udev, uint8_t lun); +usb_sts_type bot_scsi_mode_sense6(void *udev, uint8_t lun); +usb_sts_type bot_scsi_mode_sense10(void *udev, uint8_t lun); +usb_sts_type bot_scsi_read10(void *udev, uint8_t lun); +usb_sts_type bot_scsi_capacity(void *udev, uint8_t lun); +usb_sts_type bot_scsi_format_capacity(void *udev, uint8_t lun); +usb_sts_type bot_scsi_request_sense(void *udev, uint8_t lun); +usb_sts_type bot_scsi_verify(void *udev, uint8_t lun); +usb_sts_type bot_scsi_write10(void *udev, uint8_t lun); +void bot_scsi_clear_feature(void *udev, uint8_t ept_num); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_class.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_class.c new file mode 100644 index 0000000000..d9418a9c45 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_class.c @@ -0,0 +1,298 @@ +/** + ************************************************************************** + * @file msc_class.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb msc class type + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +#include "usbd_core.h" +#include "msc_class.h" +#include "msc_desc.h" +#include "msc_bot_scsi.h" + +/** @addtogroup AT32F435_437_middlewares_usbd_class + * @{ + */ + +/** @defgroup USB_msc_class + * @brief usb device class msc demo + * @{ + */ + +/** @defgroup USB_msc_class_private_functions + * @{ + */ + +static usb_sts_type class_init_handler(void *udev); +static usb_sts_type class_clear_handler(void *udev); +static usb_sts_type class_setup_handler(void *udev, usb_setup_type *setup); +static usb_sts_type class_ept0_tx_handler(void *udev); +static usb_sts_type class_ept0_rx_handler(void *udev); +static usb_sts_type class_in_handler(void *udev, uint8_t ept_num); +static usb_sts_type class_out_handler(void *udev, uint8_t ept_num); +static usb_sts_type class_sof_handler(void *udev); +static usb_sts_type class_event_handler(void *udev, usbd_event_type event); + +msc_type msc_struct; + +/* usb device class handler */ +usbd_class_handler msc_class_handler = +{ + class_init_handler, + class_clear_handler, + class_setup_handler, + class_ept0_tx_handler, + class_ept0_rx_handler, + class_in_handler, + class_out_handler, + class_sof_handler, + class_event_handler, + &msc_struct +}; + +/** + * @brief initialize usb endpoint + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type class_init_handler(void *udev) +{ + usb_sts_type status = USB_OK; + usbd_core_type *pudev = (usbd_core_type *)udev; + + /* open in endpoint */ + usbd_ept_open(pudev, USBD_MSC_BULK_IN_EPT, EPT_BULK_TYPE, USBD_OUT_MAXPACKET_SIZE); + + /* open out endpoint */ + usbd_ept_open(pudev, USBD_MSC_BULK_OUT_EPT, EPT_BULK_TYPE, USBD_OUT_MAXPACKET_SIZE); + + bot_scsi_init(udev); + + return status; +} + +/** + * @brief clear endpoint or other state + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type class_clear_handler(void *udev) +{ + usb_sts_type status = USB_OK; + usbd_core_type *pudev = (usbd_core_type *)udev; + + /* close in endpoint */ + usbd_ept_close(pudev, USBD_MSC_BULK_IN_EPT); + + /* close out endpoint */ + usbd_ept_close(pudev, USBD_MSC_BULK_OUT_EPT); + + return status; +} + +/** + * @brief usb device class setup request handler + * @param udev: to the structure of usbd_core_type + * @param setup: setup packet + * @retval status of usb_sts_type + */ +static usb_sts_type class_setup_handler(void *udev, usb_setup_type *setup) +{ + usb_sts_type status = USB_OK; + usbd_core_type *pudev = (usbd_core_type *)udev; + msc_type *pmsc = (msc_type *)pudev->class_handler->pdata; + switch(setup->bmRequestType & USB_REQ_TYPE_RESERVED) + { + /* class request */ + case USB_REQ_TYPE_CLASS: + + switch(setup->bRequest) + { + case MSC_REQ_GET_MAX_LUN: + usbd_ctrl_send(pudev, (uint8_t *)&pmsc->max_lun, 1); + break; + case MSC_REQ_BO_RESET: + bot_scsi_reset(udev); + usbd_ctrl_send_status(pudev); + break; + default: + usbd_ctrl_unsupport(pudev); + break; + + } + break; + /* standard request */ + case USB_REQ_TYPE_STANDARD: + + switch(setup->bRequest) + { + case USB_STD_REQ_GET_DESCRIPTOR: + usbd_ctrl_unsupport(pudev); + break; + case USB_STD_REQ_GET_INTERFACE: + usbd_ctrl_send(pudev, (uint8_t *)&pmsc->alt_setting, 1); + break; + case USB_STD_REQ_SET_INTERFACE: + pmsc->alt_setting = setup->wValue; + break; + case USB_STD_REQ_CLEAR_FEATURE: + usbd_ept_close(pudev, (uint8_t)setup->wIndex); + + if((setup->wIndex & 0x80) == 0x80) + { + usbd_flush_tx_fifo(pudev, setup->wIndex & 0x7F); + usbd_ept_open(pudev, (uint8_t)setup->wIndex, EPT_BULK_TYPE, USBD_IN_MAXPACKET_SIZE); + } + else + { + usbd_ept_open(pudev, (uint8_t)setup->wIndex, EPT_BULK_TYPE, USBD_OUT_MAXPACKET_SIZE); + } + bot_scsi_clear_feature(udev, setup->wIndex); + break; + default: + break; + } + break; + default: + usbd_ctrl_unsupport(pudev); + break; + } + return status; +} + +/** + * @brief usb device endpoint 0 in status stage complete + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type class_ept0_tx_handler(void *udev) +{ + usb_sts_type status = USB_OK; + + /* ...user code... */ + UNUSED(udev); + + return status; +} + +/** + * @brief usb device endpoint 0 out status stage complete + * @param udev: usb device core handler type + * @retval status of usb_sts_type + */ +static usb_sts_type class_ept0_rx_handler(void *udev) +{ + usb_sts_type status = USB_OK; + usbd_core_type *pudev = (usbd_core_type *)udev; + uint32_t recv_len = usbd_get_recv_len(pudev, 0); + /* ...user code... */ + UNUSED(recv_len); + return status; +} + +/** + * @brief usb device transmision complete handler + * @param udev: to the structure of usbd_core_type + * @param ept_num: endpoint number + * @retval status of usb_sts_type + */ +static usb_sts_type class_in_handler(void *udev, uint8_t ept_num) +{ + usb_sts_type status = USB_OK; + usbd_core_type *pudev = (usbd_core_type *)udev; + usbd_flush_tx_fifo(pudev, ept_num&0x7F); + bot_scsi_datain_handler(udev, ept_num); + return status; +} + +/** + * @brief usb device endpoint receive data + * @param udev: to the structure of usbd_core_type + * @param ept_num: endpoint number + * @retval status of usb_sts_type + */ +static usb_sts_type class_out_handler(void *udev, uint8_t ept_num) +{ + usb_sts_type status = USB_OK; + + bot_scsi_dataout_handler(udev, ept_num); + return status; +} + +/** + * @brief usb device sof handler + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type class_sof_handler(void *udev) +{ + usb_sts_type status = USB_OK; + + /* ...user code... */ + UNUSED(udev); + + return status; +} + +/** + * @brief usb device event handler + * @param udev: to the structure of usbd_core_type + * @param event: usb device event + * @retval status of usb_sts_type + */ +static usb_sts_type class_event_handler(void *udev, usbd_event_type event) +{ + UNUSED(udev); + usb_sts_type status = USB_OK; + switch(event) + { + case USBD_RESET_EVENT: + + /* ...user code... */ + + break; + case USBD_SUSPEND_EVENT: + + /* ...user code... */ + + break; + case USBD_WAKEUP_EVENT: + /* ...user code... */ + + break; + + default: + break; + } + return status; +} +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_class.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_class.h new file mode 100644 index 0000000000..80c7c1774c --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_class.h @@ -0,0 +1,72 @@ +/** + ************************************************************************** + * @file msc_class.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb msc class file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + /* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __MSC_CLASS_H +#define __MSC_CLASS_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "usb_std.h" +#include "usbd_core.h" + +/** @addtogroup AT32F435_437_middlewares_usbd_class + * @{ + */ + +/** @addtogroup USB_msc_class + * @{ + */ + +/** @defgroup USB_msc_class_definition + * @{ + */ + +#define USBD_MSC_BULK_IN_EPT 0x81 +#define USBD_MSC_BULK_OUT_EPT 0x01 + +#define USBD_IN_MAXPACKET_SIZE 0x40 +#define USBD_OUT_MAXPACKET_SIZE 0x40 + + +extern usbd_class_handler msc_class_handler; +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_desc.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_desc.c new file mode 100644 index 0000000000..414ee43009 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_desc.c @@ -0,0 +1,404 @@ +/** + ************************************************************************** + * @file msc_desc.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb msc device descriptor + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +#include "stdio.h" +#include "usb_std.h" +#include "usbd_sdr.h" +#include "usbd_core.h" +#include "msc_desc.h" + +/** @addtogroup AT32F435_437_middlewares_usbd_class + * @{ + */ + +/** @defgroup USB_msc_desc + * @brief usb device msc descriptor + * @{ + */ + +/** @defgroup USB_msc_desc_private_functions + * @{ + */ + +static usbd_desc_t *get_device_descriptor(void); +static usbd_desc_t *get_device_qualifier(void); +static usbd_desc_t *get_device_configuration(void); +static usbd_desc_t *get_device_other_speed(void); +static usbd_desc_t *get_device_lang_id(void); +static usbd_desc_t *get_device_manufacturer_string(void); +static usbd_desc_t *get_device_product_string(void); +static usbd_desc_t *get_device_serial_string(void); +static usbd_desc_t *get_device_interface_string(void); +static usbd_desc_t *get_device_config_string(void); + +static uint16_t usbd_unicode_convert(uint8_t *string, uint8_t *unicode_buf); +static void usbd_int_to_unicode (uint32_t value , uint8_t *pbuf , uint8_t len); +static void get_serial_num(void); +static uint8_t g_usbd_desc_buffer[256]; + +/** + * @brief device descriptor handler structure + */ +usbd_desc_handler msc_desc_handler = +{ + get_device_descriptor, + get_device_qualifier, + get_device_configuration, + get_device_other_speed, + get_device_lang_id, + get_device_manufacturer_string, + get_device_product_string, + get_device_serial_string, + get_device_interface_string, + get_device_config_string, +}; + +/** + * @brief usb device standard descriptor + */ +#if defined ( __ICCARM__ ) /* iar compiler */ + #pragma data_alignment=4 +#endif +ALIGNED_HEAD static uint8_t g_usbd_descriptor[USB_DEVICE_DESC_LEN] ALIGNED_TAIL = +{ + USB_DEVICE_DESC_LEN, /* bLength */ + USB_DESCIPTOR_TYPE_DEVICE, /* bDescriptorType */ + 0x00, /* bcdUSB */ + 0x02, + 0x00, /* bDeviceClass */ + 0x00, /* bDeviceSubClass */ + 0x00, /* bDeviceProtocol */ + USB_MAX_EP0_SIZE, /* bMaxPacketSize */ + LBYTE(USBD_MSC_VENDOR_ID), /* idVendor */ + HBYTE(USBD_MSC_VENDOR_ID), /* idVendor */ + LBYTE(USBD_MSC_PRODUCT_ID), /* idProduct */ + HBYTE(USBD_MSC_PRODUCT_ID), /* idProduct */ + 0x00, /* bcdDevice rel. 2.00 */ + 0x02, + USB_MFC_STRING, /* Index of manufacturer string */ + USB_PRODUCT_STRING, /* Index of product string */ + USB_SERIAL_STRING, /* Index of serial number string */ + 1 /* bNumConfigurations */ +}; + +/** + * @brief usb configuration standard descriptor + */ +#if defined ( __ICCARM__ ) /* iar compiler */ + #pragma data_alignment=4 +#endif +ALIGNED_HEAD static uint8_t g_usbd_configuration[USBD_MSC_CONFIG_DESC_SIZE] ALIGNED_TAIL = +{ + USB_DEVICE_CFG_DESC_LEN, /* bLength: configuration descriptor size */ + USB_DESCIPTOR_TYPE_CONFIGURATION, /* bDescriptorType: configuration */ + LBYTE(USBD_MSC_CONFIG_DESC_SIZE), /* wTotalLength: bytes returned */ + HBYTE(USBD_MSC_CONFIG_DESC_SIZE), /* wTotalLength: bytes returned */ + 0x01, /* bNumInterfaces: 2 interface */ + 0x01, /* bConfigurationValue: configuration value */ + 0x04, /* iConfiguration: index of string descriptor describing + the configuration */ + 0xC0, /* bmAttributes: self powered */ + 0x32, /* MaxPower 100 mA: this current is used for detecting vbus */ + + USB_DEVICE_IF_DESC_LEN, /* bLength: interface descriptor size */ + USB_DESCIPTOR_TYPE_INTERFACE, /* bDescriptorType: interface descriptor type */ + 0x00, /* bInterfaceNumber: number of interface */ + 0x00, /* bAlternateSetting: alternate set */ + 0x02, /* bNumEndpoints: number of endpoints */ + USB_CLASS_CODE_MSC, /* bInterfaceClass: msc class code */ + 0x06, /* bInterfaceSubClass: subclass code scsi */ + 0x50, /* bInterfaceProtocol: protocol code BBB */ + 0x05, /* iInterface: index of string descriptor */ + + USB_DEVICE_EPT_LEN, /* bLength: size of endpoint descriptor in bytes */ + USB_DESCIPTOR_TYPE_ENDPOINT, /* bDescriptorType: endpoint descriptor type */ + USBD_MSC_BULK_IN_EPT, /* bEndpointAddress: the address of endpoint on usb device described by this descriptor */ + USB_EPT_DESC_BULK, /* bmAttributes: endpoint attributes */ + LBYTE(USBD_IN_MAXPACKET_SIZE), + HBYTE(USBD_IN_MAXPACKET_SIZE), /* wMaxPacketSize: maximum packe size this endpoint */ + 0x00, /* bInterval: interval for polling endpoint for data transfers */ + + USB_DEVICE_EPT_LEN, /* bLength: size of endpoint descriptor in bytes */ + USB_DESCIPTOR_TYPE_ENDPOINT, /* bDescriptorType: endpoint descriptor type */ + USBD_MSC_BULK_OUT_EPT, /* bEndpointAddress: the address of endpoint on usb device described by this descriptor */ + USB_EPT_DESC_BULK, /* bmAttributes: endpoint attributes */ + LBYTE(USBD_OUT_MAXPACKET_SIZE), + HBYTE(USBD_OUT_MAXPACKET_SIZE), /* wMaxPacketSize: maximum packe size this endpoint */ + 0x00, /* bInterval: interval for polling endpoint for data transfers */ +}; + +/** + * @brief usb string lang id + */ +#if defined ( __ICCARM__ ) /* iar compiler */ + #pragma data_alignment=4 +#endif +ALIGNED_HEAD static uint8_t g_string_lang_id[USBD_MSC_SIZ_STRING_LANGID] ALIGNED_TAIL = +{ + USBD_MSC_SIZ_STRING_LANGID, + USB_DESCIPTOR_TYPE_STRING, + 0x09, + 0x04, +}; + +/** + * @brief usb string serial + */ +#if defined ( __ICCARM__ ) /* iar compiler */ + #pragma data_alignment=4 +#endif +ALIGNED_HEAD static uint8_t g_string_serial[USBD_MSC_SIZ_STRING_SERIAL] ALIGNED_TAIL = +{ + USBD_MSC_SIZ_STRING_SERIAL, + USB_DESCIPTOR_TYPE_STRING, +}; + + +/* device descriptor */ +static usbd_desc_t device_descriptor = +{ + USB_DEVICE_DESC_LEN, + g_usbd_descriptor +}; + +/* config descriptor */ +static usbd_desc_t config_descriptor = +{ + USBD_MSC_CONFIG_DESC_SIZE, + g_usbd_configuration +}; + +/* langid descriptor */ +static usbd_desc_t langid_descriptor = +{ + USBD_MSC_SIZ_STRING_LANGID, + g_string_lang_id +}; + +/* serial descriptor */ +static usbd_desc_t serial_descriptor = +{ + USBD_MSC_SIZ_STRING_SERIAL, + g_string_serial +}; + +static usbd_desc_t vp_desc; + +/** + * @brief standard usb unicode convert + * @param string: source string + * @param unicode_buf: unicode buffer + * @retval length + */ +static uint16_t usbd_unicode_convert(uint8_t *string, uint8_t *unicode_buf) +{ + uint16_t str_len = 0, id_pos = 2; + uint8_t *tmp_str = string; + + while(*tmp_str != '\0') + { + str_len ++; + unicode_buf[id_pos ++] = *tmp_str ++; + unicode_buf[id_pos ++] = 0x00; + } + + str_len = str_len * 2 + 2; + unicode_buf[0] = (uint8_t)str_len; + unicode_buf[1] = USB_DESCIPTOR_TYPE_STRING; + + return str_len; +} + +/** + * @brief usb int convert to unicode + * @param value: int value + * @param pbus: unicode buffer + * @param len: length + * @retval none + */ +static void usbd_int_to_unicode (uint32_t value , uint8_t *pbuf , uint8_t len) +{ + uint8_t idx = 0; + + for( idx = 0 ; idx < len ; idx ++) + { + if( ((value >> 28)) < 0xA ) + { + pbuf[ 2 * idx] = (value >> 28) + '0'; + } + else + { + pbuf[2 * idx] = (value >> 28) + 'A' - 10; + } + + value = value << 4; + + pbuf[2 * idx + 1] = 0; + } +} + +/** + * @brief usb get serial number + * @param none + * @retval none + */ +static void get_serial_num(void) +{ + uint32_t serial0, serial1, serial2; + + serial0 = *(uint32_t*)MCU_ID1; + serial1 = *(uint32_t*)MCU_ID2; + serial2 = *(uint32_t*)MCU_ID3; + + serial0 += serial2; + + if (serial0 != 0) + { + usbd_int_to_unicode (serial0, &g_string_serial[2] ,8); + usbd_int_to_unicode (serial1, &g_string_serial[18] ,4); + } +} + +/** + * @brief get device descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_descriptor(void) +{ + return &device_descriptor; +} + +/** + * @brief get device qualifier + * @param none + * @retval usbd_desc + */ +static usbd_desc_t * get_device_qualifier(void) +{ + return NULL; +} + +/** + * @brief get config descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_configuration(void) +{ + return &config_descriptor; +} + +/** + * @brief get other speed descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_other_speed(void) +{ + return NULL; +} + +/** + * @brief get lang id descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_lang_id(void) +{ + return &langid_descriptor; +} + + +/** + * @brief get manufacturer descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_manufacturer_string(void) +{ + vp_desc.length = usbd_unicode_convert((uint8_t *)USBD_MSC_DESC_MANUFACTURER_STRING, g_usbd_desc_buffer); + vp_desc.descriptor = g_usbd_desc_buffer; + return &vp_desc; +} + +/** + * @brief get product descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_product_string(void) +{ + vp_desc.length = usbd_unicode_convert((uint8_t *)USBD_MSC_DESC_PRODUCT_STRING, g_usbd_desc_buffer); + vp_desc.descriptor = g_usbd_desc_buffer; + return &vp_desc; +} + +/** + * @brief get serial descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_serial_string(void) +{ + get_serial_num(); + return &serial_descriptor; +} + +/** + * @brief get interface descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_interface_string(void) +{ + vp_desc.length = usbd_unicode_convert((uint8_t *)USBD_MSC_DESC_INTERFACE_STRING, g_usbd_desc_buffer); + vp_desc.descriptor = g_usbd_desc_buffer; + return &vp_desc; +} + +/** + * @brief get device config descriptor + * @param none + * @retval usbd_desc + */ +static usbd_desc_t *get_device_config_string(void) +{ + vp_desc.length = usbd_unicode_convert((uint8_t *)USBD_MSC_DESC_CONFIGURATION_STRING, g_usbd_desc_buffer); + vp_desc.descriptor = g_usbd_desc_buffer; + return &vp_desc; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_desc.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_desc.h new file mode 100644 index 0000000000..72edbcdc45 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbd_class/msc/msc_desc.h @@ -0,0 +1,85 @@ +/** + ************************************************************************** + * @file msc_desc.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb msc descriptor header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __MSC_DESC_H +#define __MSC_DESC_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "msc_class.h" +#include "usbd_core.h" + +/** @addtogroup AT32F435_437_middlewares_usbd_class + * @{ + */ + +/** @addtogroup USB_msc_desc + * @{ + */ + +/** @defgroup USB_msc_desc_definition + * @{ + */ + +#define MSC_BCD_NUM 0x0110 + +#define USBD_MSC_VENDOR_ID 0x2E3C +#define USBD_MSC_PRODUCT_ID 0x5720 + +#define USBD_MSC_CONFIG_DESC_SIZE 32 +#define USBD_MSC_SIZ_STRING_LANGID 4 +#define USBD_MSC_SIZ_STRING_SERIAL 0x1A + +#define USBD_MSC_DESC_MANUFACTURER_STRING "Artery" +#define USBD_MSC_DESC_PRODUCT_STRING "AT32 Mass Storage" +#define USBD_MSC_DESC_CONFIGURATION_STRING "Mass Storage Config" +#define USBD_MSC_DESC_INTERFACE_STRING "Mass Storage Interface" + +#define MCU_ID1 (0x1FFFF7E8) +#define MCU_ID2 (0x1FFFF7EC) +#define MCU_ID3 (0x1FFFF7F0) + +extern usbd_desc_handler msc_desc_handler; + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_cdc/usbh_cdc_class.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_cdc/usbh_cdc_class.c new file mode 100644 index 0000000000..b8a37bd2aa --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_cdc/usbh_cdc_class.c @@ -0,0 +1,532 @@ +/** + ************************************************************************** + * @file usbh_cdc_class.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb host msc class type + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +#include "usbh_cdc_class.h" +#include "usb_conf.h" +#include "usbh_core.h" +#include "usbh_ctrl.h" +#include "string.h" + +/** @addtogroup AT32F435_437_middlewares_usbh_class + * @{ + */ + +/** @defgroup usbh_cdc_class + * @brief usb host class cdc demo + * @{ + */ + +/** @defgroup usbh_cdc_class_private_functions + * @{ + */ + +static usb_sts_type uhost_init_handler(void *uhost); +static usb_sts_type uhost_reset_handler(void *uhost); +static usb_sts_type uhost_request_handler(void *uhost); +static usb_sts_type uhost_process_handler(void *uhost); +static usb_sts_type get_linecoding(usbh_core_type *uhost, cdc_line_coding_type *linecoding); +static usb_sts_type set_linecoding(usbh_core_type *uhost, cdc_line_coding_type *linecoding); + +static void cdc_process_transmission(usbh_core_type *uhost); +static void cdc_process_reception(usbh_core_type *uhost); +usbh_cdc_type usbh_cdc; + +usbh_class_handler_type uhost_cdc_class_handler = +{ + uhost_init_handler, + uhost_reset_handler, + uhost_request_handler, + uhost_process_handler, + &usbh_cdc +}; + +/** + * @brief usb host class init handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +static usb_sts_type uhost_init_handler(void *uhost) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usb_sts_type status = USB_OK; + uint8_t if_x; + usbh_cdc_type *pcdc = &usbh_cdc; + puhost->class_handler->pdata = &usbh_cdc; + + memset((void *)pcdc, 0, sizeof(usbh_cdc_type)); + if_x = usbh_find_interface(puhost, USB_CLASS_CODE_CDC, ABSTRACT_CONTROL_MODEL, COMMON_AT_COMMAND); + if(if_x == 0xFF) + { + USBH_DEBUG("cannot find the interface for communication interface class!"); + return USB_NOT_SUPPORT; + } + else + { + if(if_x < puhost->dev.cfg_desc.cfg.bNumInterfaces) + { + USBH_DEBUG ("switching to interface (#%d)", if_x); + USBH_DEBUG ("class : %xh", puhost->dev.cfg_desc.interface[if_x].interface.bInterfaceClass); + USBH_DEBUG ("subclass : %xh", puhost->dev.cfg_desc.interface[if_x].interface.bInterfaceSubClass ); + USBH_DEBUG ("protocol : %xh", puhost->dev.cfg_desc.interface[if_x].interface.bInterfaceProtocol ); + if(puhost->dev.cfg_desc.interface[if_x].interface.bInterfaceClass == COMMUNICATION_INTERFACE_CLASS_CODE) + { + USBH_DEBUG("CDC device!"); + } + } + else + { + USBH_DEBUG ("cannot select this interface."); + } + + /* collect the notification endpoint address and length */ + if(puhost->dev.cfg_desc.interface[if_x].endpoint[0].bEndpointAddress & 0x80) + { + pcdc->common_interface.notif_endpoint = puhost->dev.cfg_desc.interface[if_x].endpoint[0].bEndpointAddress; + pcdc->common_interface.notif_endpoint_size = puhost->dev.cfg_desc.interface[if_x].endpoint[0].wMaxPacketSize; + } + /* allocate the length for host channel number in */ + pcdc->common_interface.notif_channel = usbh_alloc_channel(puhost, pcdc->common_interface.notif_endpoint); + + /* enable channel */ + usbh_hc_open(puhost, + pcdc->common_interface.notif_channel, + pcdc->common_interface.notif_endpoint, + puhost->dev.address, + EPT_INT_TYPE, + pcdc->common_interface.notif_endpoint_size, + puhost->dev.speed); + + usbh_set_toggle(puhost, pcdc->common_interface.notif_channel, 0); + + + if_x = usbh_find_interface(puhost, DATA_INTERFACE_CLASS_CODE, RESERVED, NO_CLASS_SPECIFIC_PROTOCOL_CODE); + if(if_x == 0xFF) + { + USBH_DEBUG("cannot find the interface for data interface class!"); + return USB_NOT_SUPPORT; + } + else + { + /* collect the class specific endpoint address and length */ + if(puhost->dev.cfg_desc.interface[if_x].endpoint[0].bEndpointAddress & 0x80) + { + pcdc->data_interface.in_endpoint = puhost->dev.cfg_desc.interface[if_x].endpoint[0].bEndpointAddress; + pcdc->data_interface.in_endpoint_size = puhost->dev.cfg_desc.interface[if_x].endpoint[0].wMaxPacketSize; + } + else + { + pcdc->data_interface.out_endpoint = puhost->dev.cfg_desc.interface[if_x].endpoint[0].bEndpointAddress; + pcdc->data_interface.out_endpoint_size = puhost->dev.cfg_desc.interface[if_x].endpoint[0].wMaxPacketSize; + } + + if(puhost->dev.cfg_desc.interface[if_x].endpoint[1].bEndpointAddress & 0x80) + { + pcdc->data_interface.in_endpoint = puhost->dev.cfg_desc.interface[if_x].endpoint[1].bEndpointAddress; + pcdc->data_interface.in_endpoint_size = puhost->dev.cfg_desc.interface[if_x].endpoint[1].wMaxPacketSize; + } + else + { + pcdc->data_interface.out_endpoint = puhost->dev.cfg_desc.interface[if_x].endpoint[1].bEndpointAddress; + pcdc->data_interface.out_endpoint_size = puhost->dev.cfg_desc.interface[if_x].endpoint[1].wMaxPacketSize; + } + + /* allocate the length for host channel number in */ + pcdc->data_interface.in_channel = usbh_alloc_channel(puhost, pcdc->data_interface.in_endpoint); + /* allocate the length for host channel number out */ + pcdc->data_interface.out_channel = usbh_alloc_channel(puhost, pcdc->data_interface.out_endpoint); + + /* enable in channel */ + usbh_hc_open(puhost, + pcdc->data_interface.in_channel, + pcdc->data_interface.in_endpoint, + puhost->dev.address, + EPT_BULK_TYPE, + pcdc->data_interface.in_endpoint_size, + puhost->dev.speed); + + /* enable out channel */ + usbh_hc_open(puhost, + pcdc->data_interface.out_channel, + pcdc->data_interface.out_endpoint, + puhost->dev.address, + EPT_BULK_TYPE, + pcdc->data_interface.out_endpoint_size, + puhost->dev.speed); + + usbh_set_toggle(puhost, pcdc->data_interface.in_channel, 0); + usbh_set_toggle(puhost, pcdc->data_interface.out_channel, 0); + + pcdc->state = CDC_IDLE_STATE; + + } + } + return status; +} + +/** + * @brief usb host class reset handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +static usb_sts_type uhost_reset_handler(void *uhost) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usbh_cdc_type *pcdc = (usbh_cdc_type *)puhost->class_handler->pdata; + usb_sts_type status = USB_OK; + + if(puhost->class_handler->pdata == NULL) + { + return status; + } + + if(pcdc->common_interface.notif_channel != 0 ) + { + usbh_free_channel(puhost, pcdc->common_interface.notif_channel); + usbh_ch_disable(puhost, pcdc->common_interface.notif_channel); + pcdc->common_interface.notif_channel = 0; + } + + if(pcdc->data_interface.in_channel != 0 ) + { + usbh_free_channel(puhost, pcdc->data_interface.in_channel); + usbh_ch_disable(puhost, pcdc->data_interface.in_channel); + pcdc->data_interface.in_channel = 0; + } + + if(pcdc->data_interface.out_channel != 0 ) + { + usbh_free_channel(puhost, pcdc->data_interface.out_channel); + usbh_ch_disable(puhost, pcdc->data_interface.out_channel); + pcdc->data_interface.out_channel = 0; + } + + return status; +} + +/** + * @brief usb host cdc class request handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +static usb_sts_type uhost_request_handler(void *uhost) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usbh_cdc_type *pcdc = (usbh_cdc_type *)puhost->class_handler->pdata; + usb_sts_type status = USB_WAIT; + + status = get_linecoding(uhost, &pcdc->linecoding); + + return status; +} + +/** + * @brief usb host cdc get linecoding handler + * @param uhost: to the structure of usbh_core_type + * @param linecoding: pointer to the structure of cdc_line_coding_type + * @retval status: usb_sts_type status + */ +static usb_sts_type get_linecoding(usbh_core_type *uhost, cdc_line_coding_type *linecoding) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usb_sts_type status = USB_WAIT; + if(puhost->ctrl.state == CONTROL_IDLE ) + { + uhost->ctrl.setup.bmRequestType = USB_DIR_D2H | USB_REQ_TYPE_CLASS | USB_REQ_RECIPIENT_INTERFACE; + uhost->ctrl.setup.bRequest = CDC_GET_LINE_CODING; + uhost->ctrl.setup.wValue = 0; + uhost->ctrl.setup.wLength = LINE_CODING_STRUCTURE_SIZE; + uhost->ctrl.setup.wIndex = 0; + + usbh_ctrl_request(uhost, linecoding->array, LINE_CODING_STRUCTURE_SIZE); + } + else + { + status = usbh_ctrl_result_check(puhost, CONTROL_IDLE, ENUM_IDLE); + if(status == USB_OK || status == USB_NOT_SUPPORT) + { + status = USB_OK; + } + } + + return status; +} + +/** + * @brief usb host cdc set linecoding handler + * @param uhost: to the structure of usbh_core_type + * @param linecoding: pointer to the structure of cdc_line_coding_type + * @retval status: usb_sts_type status + */ +static usb_sts_type set_linecoding(usbh_core_type *uhost, cdc_line_coding_type *linecoding) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usb_sts_type status = USB_WAIT; + + if(puhost->ctrl.state == CONTROL_IDLE ) + { + uhost->ctrl.setup.bmRequestType = USB_DIR_H2D | USB_REQ_TYPE_CLASS | USB_REQ_RECIPIENT_INTERFACE; + uhost->ctrl.setup.bRequest = CDC_SET_LINE_CODING; + uhost->ctrl.setup.wValue = 0; + uhost->ctrl.setup.wLength = LINE_CODING_STRUCTURE_SIZE; + uhost->ctrl.setup.wIndex = 0; + + status = usbh_ctrl_request(uhost, linecoding->array, LINE_CODING_STRUCTURE_SIZE); + } + else + { + status = usbh_ctrl_result_check(puhost, CONTROL_IDLE, ENUM_IDLE); + if(status == USB_OK || status == USB_NOT_SUPPORT) + { + status = USB_OK; + } + } + + return status; +} + +/** + * @brief usb host class process handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +static usb_sts_type uhost_process_handler(void *uhost) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usbh_cdc_type *pcdc = (usbh_cdc_type *)puhost->class_handler->pdata; + usb_sts_type status; + + switch(pcdc->state) + { + case CDC_IDLE_STATE: + status = USB_OK; + break; + + case CDC_SET_LINE_CODING_STATE: + status = set_linecoding(puhost, pcdc->puserlinecoding); + if(status == USB_OK) + pcdc->state = CDC_GET_LAST_LINE_CODING_STATE; + break; + + case CDC_GET_LAST_LINE_CODING_STATE: + status = get_linecoding(puhost, &(pcdc->linecoding)); + if(status == USB_OK) + { + pcdc->state = CDC_IDLE_STATE; + if((pcdc->linecoding.line_coding_b.char_format == pcdc->puserlinecoding->line_coding_b.char_format)&& + (pcdc->linecoding.line_coding_b.data_bits == pcdc->puserlinecoding->line_coding_b.data_bits)&& + (pcdc->linecoding.line_coding_b.parity_type == pcdc->puserlinecoding->line_coding_b.parity_type)&& + (pcdc->linecoding.line_coding_b.data_baudrate == pcdc->puserlinecoding->line_coding_b.data_baudrate)) + { + /* line coding changed */ + } + } + pcdc->state = CDC_IDLE_STATE; + break; + + case CDC_TRANSFER_DATA: + cdc_process_transmission(puhost); + cdc_process_reception(puhost); + break; + + case CDC_ERROR_STATE: + status = usbh_clear_ept_feature(puhost, 0, pcdc->common_interface.notif_channel); + if(status == USB_OK) + pcdc->state = CDC_IDLE_STATE; + break; + + default: + break; + } + + return status; +} + +/** + * @brief usb host cdc class process transmission handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +static void cdc_process_transmission(usbh_core_type *uhost) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usbh_cdc_type *pcdc = (usbh_cdc_type *)puhost->class_handler->pdata; + + switch(pcdc->data_tx_state) + { + case CDC_SEND_DATA: + if(pcdc->tx_len > pcdc->data_interface.out_endpoint_size) + { + usbh_bulk_send(puhost, pcdc->data_interface.out_channel, (uint8_t*)pcdc->tx_data, pcdc->data_interface.out_endpoint_size); + } + else + { + usbh_bulk_send(puhost, pcdc->data_interface.out_channel, (uint8_t*)pcdc->tx_data, pcdc->tx_len); + } + pcdc->data_tx_state = CDC_SEND_DATA_WAIT; + break; + + case CDC_SEND_DATA_WAIT: + if(uhost->urb_state[pcdc->data_interface.out_channel] == URB_DONE) + { + if(pcdc->tx_len > pcdc->data_interface.out_endpoint_size) + { + pcdc->tx_len -= pcdc->data_interface.out_endpoint_size; + pcdc->tx_data += pcdc->data_interface.out_endpoint_size; + pcdc->data_tx_state = CDC_SEND_DATA; + } + else + { + pcdc->tx_len = 0; + pcdc->data_tx_state = CDC_IDLE; + cdc_transmit_complete(uhost); + } + } + else if( uhost->urb_state[pcdc->data_interface.out_channel] == URB_NOTREADY) + { + pcdc->data_tx_state = CDC_SEND_DATA; + } + break; + + default: + break; + } +} + +/** + * @brief usb host cdc class start transmission handler + * @param uhost: to the structure of usbh_core_type + * @param data: tx data pointer + * @param len: tx data len + * @retval status: usb_sts_type status + */ +void cdc_start_transmission(usbh_core_type *uhost, uint8_t *data, uint32_t len) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usbh_cdc_type *pcdc = (usbh_cdc_type *)puhost->class_handler->pdata; + if(pcdc->data_tx_state == CDC_IDLE) + { + pcdc->data_tx_state = CDC_SEND_DATA; + pcdc->state = CDC_TRANSFER_DATA; + pcdc->tx_data = data; + pcdc->tx_len = len; + } +} + + +/** + * @brief usb host cdc class transmit complete + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +__weak void cdc_transmit_complete(usbh_core_type *uhost) +{ + +} + +/** + * @brief usb host cdc class process reception handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +static void cdc_process_reception(usbh_core_type *uhost) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usbh_cdc_type *pcdc = (usbh_cdc_type *)puhost->class_handler->pdata; + uint32_t len = 0; + + switch(pcdc->data_rx_state) + { + case CDC_RECEIVE_DATA: + usbh_bulk_recv(puhost, pcdc->data_interface.in_channel, (uint8_t*)pcdc->rx_data, pcdc->data_interface.in_endpoint_size); + pcdc->data_rx_state = CDC_RECEIVE_DATA_WAIT; + break; + + case CDC_RECEIVE_DATA_WAIT: + if(uhost->urb_state[pcdc->data_interface.in_channel] == URB_DONE) + { + len = uhost->hch[pcdc->data_interface.in_channel].trans_count; + if(pcdc->rx_len > len && len > pcdc->data_interface.in_endpoint_size) + { + pcdc->rx_len -= len; + pcdc->rx_data += len; + pcdc->data_rx_state = CDC_RECEIVE_DATA; + } + else + { + pcdc->data_rx_state = CDC_IDLE; + cdc_receive_complete(uhost); + + } + } + + break; + + default: + break; + } +} + +/** + * @brief usb host cdc class start reception handler + * @param uhost: to the structure of usbh_core_type + * @param data: receive data pointer + * @param len: receive data len + * @retval status: usb_sts_type status + */ +void cdc_start_reception(usbh_core_type *uhost, uint8_t *data, uint32_t len) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usbh_cdc_type *pcdc = (usbh_cdc_type *)puhost->class_handler->pdata; + + if(pcdc->data_rx_state == CDC_IDLE) + { + pcdc->data_rx_state = CDC_RECEIVE_DATA; + pcdc->state = CDC_TRANSFER_DATA; + pcdc->rx_data = data; + pcdc->rx_len = len; + } +} + +/** + * @brief usb host cdc class reception complete + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +__weak void cdc_receive_complete(usbh_core_type *uhost) +{ + +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_cdc/usbh_cdc_class.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_cdc/usbh_cdc_class.h new file mode 100644 index 0000000000..f5eb101fed --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_cdc/usbh_cdc_class.h @@ -0,0 +1,284 @@ +/** + ************************************************************************** + * @file usbh_cdc_class.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb host cdc class header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USBH_MSC_CLASS_H +#define __USBH_MSC_CLASS_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "usbh_core.h" +#include "usb_conf.h" + +/** @addtogroup AT32F435_437_middlewares_usbh_class + * @{ + */ + +/** @addtogroup USBH_cdc_class + * @{ + */ + +/** @defgroup USBH_cdc_class_definition + * @{ + */ + +/*Communication Class codes*/ +#define USB_CDC_CLASS 0x02 +#define COMMUNICATION_INTERFACE_CLASS_CODE 0x02 + +/*Data Interface Class Codes*/ +#define DATA_INTERFACE_CLASS_CODE 0x0A + +/*Communication sub class codes*/ +#define RESERVED 0x00 +#define DIRECT_LINE_CONTROL_MODEL 0x01 +#define ABSTRACT_CONTROL_MODEL 0x02 +#define TELEPHONE_CONTROL_MODEL 0x03 +#define MULTICHANNEL_CONTROL_MODEL 0x04 +#define CAPI_CONTROL_MODEL 0x05 +#define ETHERNET_NETWORKING_CONTROL_MODEL 0x06 +#define ATM_NETWORKING_CONTROL_MODEL 0x07 + + +/*Communication Interface Class Control Protocol Codes*/ +#define NO_CLASS_SPECIFIC_PROTOCOL_CODE 0x00 +#define COMMON_AT_COMMAND 0x01 +#define VENDOR_SPECIFIC 0xFF + + +#define CS_INTERFACE 0x24 +#define CDC_PAGE_SIZE_64 0x40 + +/*Class-Specific Request Codes*/ +#define CDC_SEND_ENCAPSULATED_COMMAND 0x00 +#define CDC_GET_ENCAPSULATED_RESPONSE 0x01 +#define CDC_SET_COMM_FEATURE 0x02 +#define CDC_GET_COMM_FEATURE 0x03 +#define CDC_CLEAR_COMM_FEATURE 0x04 + +#define CDC_SET_AUX_LINE_STATE 0x10 +#define CDC_SET_HOOK_STATE 0x11 +#define CDC_PULSE_SETUP 0x12 +#define CDC_SEND_PULSE 0x13 +#define CDC_SET_PULSE_TIME 0x14 +#define CDC_RING_AUX_JACK 0x15 + +#define CDC_SET_LINE_CODING 0x20 +#define CDC_GET_LINE_CODING 0x21 +#define CDC_SET_CONTROL_LINE_STATE 0x22 +#define CDC_SEND_BREAK 0x23 + +#define CDC_SET_RINGER_PARMS 0x30 +#define CDC_GET_RINGER_PARMS 0x31 +#define CDC_SET_OPERATION_PARMS 0x32 +#define CDC_GET_OPERATION_PARMS 0x33 +#define CDC_SET_LINE_PARMS 0x34 +#define CDC_GET_LINE_PARMS 0x35 +#define CDC_DIAL_DIGITS 0x36 +#define CDC_SET_UNIT_PARAMETER 0x37 +#define CDC_GET_UNIT_PARAMETER 0x38 +#define CDC_CLEAR_UNIT_PARAMETER 0x39 +#define CDC_GET_PROFILE 0x3A + +#define CDC_SET_ETHERNET_MULTICAST_FILTERS 0x40 +#define CDC_SET_ETHERNET_POWER_MANAGEMENT_PATTERN FILTER 0x41 +#define CDC_GET_ETHERNET_POWER_MANAGEMENT_PATTERN FILTER 0x42 +#define CDC_SET_ETHERNET_PACKET_FILTER 0x43 +#define CDC_GET_ETHERNET_STATISTIC 0x44 + +#define CDC_SET_ATM_DATA_FORMAT 0x50 +#define CDC_GET_ATM_DEVICE_STATISTICS 0x51 +#define CDC_SET_ATM_DEFAULT_VC 0x52 +#define CDC_GET_ATM_VC_STATISTICS 0x53 + + +/* wValue for SetControlLineState*/ +#define CDC_ACTIVATE_CARRIER_SIGNAL_RTS 0x0002 +#define CDC_DEACTIVATE_CARRIER_SIGNAL_RTS 0x0000 +#define CDC_ACTIVATE_SIGNAL_DTR 0x0001 +#define CDC_DEACTIVATE_SIGNAL_DTR 0x0000 + +#define LINE_CODING_STRUCTURE_SIZE 0x07 + +/* states for cdc state machine */ +typedef enum +{ + CDC_IDLE = 0x0, + CDC_SEND_DATA = 0x1, + CDC_SEND_DATA_WAIT = 0x2, + CDC_RECEIVE_DATA = 0x3, + CDC_RECEIVE_DATA_WAIT = 0x4, +} cdc_data_state_type; + +typedef enum +{ + CDC_IDLE_STATE = 0x0, + CDC_SET_LINE_CODING_STATE = 0x1, + CDC_GET_LAST_LINE_CODING_STATE = 0x2, + CDC_TRANSFER_DATA = 0x3, + CDC_ERROR_STATE = 0x4, +} cdc_state_type; + + +/*line coding structure*/ +typedef union _cdc_line_coding_structure +{ + uint8_t array[LINE_CODING_STRUCTURE_SIZE]; + + struct + { + uint32_t data_baudrate; /*data terminal rate, in bits per second*/ + uint8_t char_format; /* Stop bits + 0 - 1 Stop bit + 1 - 1.5 Stop bits + 2 - 2 Stop bits*/ + uint8_t parity_type; /* parity + 0 - none + 1 - odd + 2 - even + 3 - mark + 4 - space*/ + uint8_t data_bits; /* data bits (5, 6, 7, 8 or 16). */ + }line_coding_b; +} cdc_line_coding_type; + + + +/* header functional descriptor */ +typedef struct _functional_descriptor_header +{ + uint8_t bfunctionlength; /* size of this descriptor. */ + uint8_t bdescriptortype; /* cs_interface (0x24) */ + uint8_t bdescriptorsubtype; /* header functional descriptor subtype as */ + uint16_t bcdcdc; /* usb class definitions for communication + devices specification release number in + binary-coded decimal. */ +} cdc_headerfuncdesc_type; + +/* call management functional descriptor */ +typedef struct _callmgmt_functional_descriptor +{ + uint8_t blength; /* size of this functional descriptor, in bytes */ + uint8_t bdescriptortype; /* cs_interface (0x24) */ + uint8_t bdescriptorsubtype; /* call management functional descriptor subtype */ + uint8_t bmcapabilities; /* bmcapabilities: d0+d1 */ + uint8_t bdatainterface; /* bdatainterface: 1 */ +} cdc_callmgmtfuncdesc_type; + +/* abstract control management functional descriptor */ +typedef struct _abstractcntrlmgmt_functional_descriptor +{ + uint8_t blength; /* size of this functional descriptor, in bytes */ + uint8_t bdescriptortype; /* cs_interface (0x24) */ + uint8_t bdescriptorsubtype; /* abstract control management functional + descriptor subtype */ + uint8_t bmcapabilities; /* the capabilities that this configuration supports */ +} cdc_abstcntrlmgmtfuncdesc_type; + +/* union functional descriptor */ +typedef struct _union_functional_descriptor +{ + uint8_t blength; /* size of this functional descriptor, in bytes */ + uint8_t bdescriptortype; /* cs_interface (0x24) */ + uint8_t bdescriptorsubtype; /* union functional descriptor subtype */ + uint8_t bmasterinterface; /* the interface number of the communication or + data class interface */ + uint8_t bslaveinterface0; /* interface number of first slave */ +} cdc_unionfuncdesc_type; + + +typedef struct _usbh_cdcinterfacedesc +{ + cdc_headerfuncdesc_type cdc_headerfuncdesc; + cdc_callmgmtfuncdesc_type cdc_callmgmtfuncdesc; + cdc_abstcntrlmgmtfuncdesc_type cdc_abstcntrlmgmtfuncdesc; + cdc_unionfuncdesc_type cdc_unionfuncdesc; +} cdc_interfacedesc_type; + + +/* structure for cdc process */ +typedef struct +{ + uint8_t notif_channel; + uint8_t notif_endpoint; + uint8_t buff[8]; + uint16_t notif_endpoint_size; +} cdc_common_interface_type; + +typedef struct +{ + uint8_t in_channel; + uint8_t out_channel; + uint8_t out_endpoint; + uint8_t in_endpoint; + uint8_t buff[8]; + uint16_t out_endpoint_size; + uint16_t in_endpoint_size; +} cdc_data_interface_type; + +/** + * @brief usb cdc struct + */ +typedef struct +{ + cdc_common_interface_type common_interface; + cdc_data_interface_type data_interface; + cdc_interfacedesc_type cdc_desc; + cdc_line_coding_type linecoding; + cdc_line_coding_type *puserlinecoding; + cdc_state_type state; + cdc_data_state_type data_tx_state; + cdc_data_state_type data_rx_state; + + uint8_t *rx_data; + uint8_t *tx_data; + uint32_t rx_len; + uint32_t tx_len; +}usbh_cdc_type; + +extern usbh_class_handler_type uhost_cdc_class_handler; +extern usbh_cdc_type usbh_cdc; +void cdc_start_transmission(usbh_core_type *phost, uint8_t *data, uint32_t len); +void cdc_start_reception(usbh_core_type *uhost, uint8_t *data, uint32_t len); +__weak void cdc_transmit_complete(usbh_core_type *uhost); +__weak void cdc_receive_complete(usbh_core_type *uhost); +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_class.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_class.c new file mode 100644 index 0000000000..7bc618e90f --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_class.c @@ -0,0 +1,453 @@ +/** + ************************************************************************** + * @file usbh_hid_class.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb host hid class type + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + #include "usbh_hid_class.h" + #include "usb_conf.h" + #include "usbh_core.h" + #include "usbh_ctrl.h" + #include "usbh_hid_mouse.h" + #include "usbh_hid_keyboard.h" + + /** @addtogroup AT32F435_437_middlewares_usbh_class + * @{ + */ + +/** @defgroup USBH_hid_class + * @brief usb host class hid demo + * @{ + */ + +/** @defgroup USBH_hid_class_private_functions + * @{ + */ + + static usb_sts_type uhost_init_handler(void *uhost); + static usb_sts_type uhost_reset_handler(void *uhost); + static usb_sts_type uhost_request_handler(void *uhost); + static usb_sts_type uhost_process_handler(void *uhost); + + usbh_hid_type usbh_hid; + usbh_class_handler_type uhost_hid_class_handler = + { + uhost_init_handler, + uhost_reset_handler, + uhost_request_handler, + uhost_process_handler, + &usbh_hid + }; + +/** + * @brief usb host class init handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +static usb_sts_type uhost_init_handler(void *uhost) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usb_sts_type status = USB_OK; + uint8_t hidx, eptidx = 0; + usbh_hid_type *phid = &usbh_hid; + + puhost->class_handler->pdata = &usbh_hid; + + /* get hid interface */ + hidx = usbh_find_interface(puhost, USB_CLASS_CODE_HID, 0x01, 0xFF); + if(hidx == 0xFF) + { + USBH_DEBUG("Unsupport Device!"); + return USB_NOT_SUPPORT; + } + + /* get hid protocol */ + phid->protocol = puhost->dev.cfg_desc.interface[hidx].interface.bInterfaceProtocol; + + if(phid->protocol == USB_HID_MOUSE_PROTOCOL_CODE) + { + USBH_DEBUG("Mouse Device!"); + } + else if(phid->protocol == USB_HID_KEYBOARD_PROTOCOL_CODE) + { + USBH_DEBUG("Keyboard Device!"); + } + + for(eptidx = 0; eptidx < puhost->dev.cfg_desc.interface[hidx].interface.bNumEndpoints; eptidx ++) + { + if(puhost->dev.cfg_desc.interface[hidx].endpoint[eptidx].bEndpointAddress & 0x80) + { + /* find interface out endpoint information */ + phid->eptin = puhost->dev.cfg_desc.interface[hidx].endpoint[eptidx].bEndpointAddress; + phid->in_maxpacket = puhost->dev.cfg_desc.interface[hidx].endpoint[eptidx].wMaxPacketSize; + phid->in_poll = puhost->dev.cfg_desc.interface[hidx].endpoint[eptidx].bInterval; + + phid->chin = usbh_alloc_channel(puhost, phid->eptin); + /* enable channel */ + usbh_hc_open(puhost, phid->chin,phid->eptin, + puhost->dev.address, EPT_INT_TYPE, + phid->in_maxpacket, + puhost->dev.speed); + usbh_set_toggle(puhost, phid->chin, 0); + } + else + { + /* get interface out endpoint information */ + phid->eptout = puhost->dev.cfg_desc.interface[hidx].endpoint[eptidx].bEndpointAddress; + phid->out_maxpacket = puhost->dev.cfg_desc.interface[hidx].endpoint[eptidx].wMaxPacketSize; + phid->out_poll = puhost->dev.cfg_desc.interface[hidx].endpoint[eptidx].bInterval; + + phid->chout = usbh_alloc_channel(puhost, usbh_hid.eptout); + /* enable channel */ + usbh_hc_open(puhost, phid->chout, phid->eptout, + puhost->dev.address, EPT_INT_TYPE, + phid->out_maxpacket, + puhost->dev.speed); + usbh_set_toggle(puhost, phid->chout, 0); + } + } + phid->ctrl_state = USB_HID_STATE_IDLE; + return status; +} + +/** + * @brief usb host class reset handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +static usb_sts_type uhost_reset_handler(void *uhost) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usbh_hid_type *phid = (usbh_hid_type *)puhost->class_handler->pdata; + usb_sts_type status = USB_OK; + if(puhost->class_handler->pdata == NULL) + { + return status; + } + + if(phid->chin != 0) + { + /* free in channel */ + usbh_free_channel(puhost, phid->chin); + usbh_ch_disable(puhost, phid->chin); + phid->chin = 0; + } + + if(phid->chout != 0) + { + /* free out channel */ + usbh_free_channel(puhost, phid->chout); + usbh_ch_disable(puhost, phid->chout); + phid->chout = 0; + } + + return status; +} + +/** + * @brief usb host hid class get descriptor + * @param uhost: to the structure of usbh_core_type + * @param length: descriptor length + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_hid_get_desc(void *uhost, uint16_t length) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usbh_hid_type *phid = (usbh_hid_type *)puhost->class_handler->pdata; + usb_sts_type status = USB_WAIT; + uint8_t bm_req; + uint16_t wvalue; + if(puhost->ctrl.state == CONTROL_IDLE) + { + bm_req = USB_REQ_RECIPIENT_INTERFACE | USB_REQ_TYPE_STANDARD; + wvalue = (0x21 << 8) & 0xFF00; + + usbh_get_descriptor(puhost, length, bm_req, + wvalue, puhost->rx_buffer); + } + else + { + if(usbh_ctrl_result_check(puhost, CONTROL_IDLE, ENUM_IDLE) == USB_OK) + { + phid->hid_desc.bLength = puhost->rx_buffer[0]; + phid->hid_desc.bDescriptorType = puhost->rx_buffer[1]; + phid->hid_desc.bcdHID = SWAPBYTE(puhost->rx_buffer+2); + phid->hid_desc.bCountryCode = puhost->rx_buffer[4]; + phid->hid_desc.bNumDescriptors = puhost->rx_buffer[5]; + phid->hid_desc.bReportDescriptorType = puhost->rx_buffer[6]; + phid->hid_desc.wItemLength = SWAPBYTE(puhost->rx_buffer+7); + status = USB_OK; + } + } + return status; +} + + +/** + * @brief usb host hid class get report + * @param uhost: to the structure of usbh_core_type + * @param length: reprot length + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_hid_get_report(void *uhost, uint16_t length) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usb_sts_type status = USB_WAIT; + uint8_t bm_req; + uint16_t wvalue; + if(puhost->ctrl.state == CONTROL_IDLE) + { + bm_req = USB_REQ_RECIPIENT_INTERFACE | USB_REQ_TYPE_STANDARD; + wvalue = (0x22 << 8) & 0xFF00; + + usbh_get_descriptor(puhost, length, bm_req, + wvalue, puhost->rx_buffer); + } + else + { + if(usbh_ctrl_result_check(puhost, CONTROL_IDLE, ENUM_IDLE) == USB_OK) + { + status = USB_OK; + } + } + return status; +} + +/** + * @brief usb host hid class set idle + * @param uhost: to the structure of usbh_core_type + * @param id: id + * @param dr: dr + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_hid_set_idle(void *uhost, uint8_t id, uint8_t dr) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usb_sts_type status = USB_WAIT; + if(puhost->ctrl.state == CONTROL_IDLE) + { + puhost->ctrl.setup.bmRequestType = USB_DIR_H2D | USB_REQ_RECIPIENT_INTERFACE | USB_REQ_TYPE_CLASS; + puhost->ctrl.setup.bRequest = USB_HID_SET_IDLE; + puhost->ctrl.setup.wValue = (dr << 8) | id; + puhost->ctrl.setup.wIndex = 0; + puhost->ctrl.setup.wLength = 0; + usbh_ctrl_request(puhost, 0, 0); + } + else + { + status = usbh_ctrl_result_check(puhost, CONTROL_IDLE, ENUM_IDLE); + if(status == USB_OK || status == USB_NOT_SUPPORT) + { + status = USB_OK; + } + } + return status; +} + +/** + * @brief usb host hid class set protocol + * @param uhost: to the structure of usbh_core_type + * @param protocol: portocol number + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_hid_set_protocol(void *uhost, uint8_t protocol) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usb_sts_type status = USB_WAIT; + if(puhost->ctrl.state == CONTROL_IDLE) + { + puhost->ctrl.setup.bmRequestType = USB_DIR_H2D | USB_REQ_RECIPIENT_INTERFACE | USB_REQ_TYPE_CLASS; + puhost->ctrl.setup.bRequest = USB_HID_SET_PROTOCOL; + puhost->ctrl.setup.wValue = protocol; + puhost->ctrl.setup.wIndex = 0; + puhost->ctrl.setup.wLength = 0; + usbh_ctrl_request(puhost, 0, 0); + } + else + { + status = usbh_ctrl_result_check(puhost, CONTROL_IDLE, ENUM_IDLE); + if(status == USB_OK || status == USB_NOT_SUPPORT) + { + status = USB_OK; + } + } + return status; +} + +/** + * @brief usb host clear feature + * @param uhost: to the structure of usbh_core_type + * @param ept_num: endpoint number + * @param hc_num: channel number + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_clear_endpoint_feature(usbh_core_type *uhost, uint8_t ept_num, uint8_t hc_num) +{ + usb_sts_type status = USB_WAIT; + usbh_core_type *puhost = (usbh_core_type *)uhost; + uint8_t bm_req; + bm_req = USB_REQ_RECIPIENT_ENDPOINT | USB_REQ_TYPE_STANDARD; + if(puhost->ctrl.state == CONTROL_IDLE) + { + puhost->ctrl.setup.bmRequestType = USB_DIR_H2D | bm_req; + puhost->ctrl.setup.bRequest = USB_STD_REQ_CLEAR_FEATURE; + puhost->ctrl.setup.wValue = 0x00; + puhost->ctrl.setup.wLength = 0; + puhost->ctrl.setup.wIndex = ept_num; + if((ept_num & 0x80) == USB_DIR_D2H) + { + puhost->hch[hc_num].toggle_in = 0; + } + else + { + puhost->hch[hc_num].toggle_out = 0; + } + status = usbh_ctrl_request(puhost, 0, 0); + } + if(usbh_ctrl_result_check(puhost, CONTROL_IDLE, ENUM_IDLE) == USB_OK) + { + status = USB_OK; + } + return status; +} + +/** + * @brief usb host hid class request handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +static usb_sts_type uhost_request_handler(void *uhost) +{ + usb_sts_type status = USB_WAIT; + usbh_core_type *puhost = (usbh_core_type *)uhost; + usbh_hid_type *phid = (usbh_hid_type *)puhost->class_handler->pdata; + + switch(phid->ctrl_state) + { + case USB_HID_STATE_IDLE: + phid->ctrl_state = USB_HID_STATE_GET_DESC; + break; + case USB_HID_STATE_GET_DESC: + if(usbh_hid_get_desc(puhost, 9) == USB_OK) + { + phid->ctrl_state = USB_HID_STATE_GET_REPORT; + } + break; + case USB_HID_STATE_GET_REPORT: + if(usbh_hid_get_report(puhost, phid->hid_desc.wItemLength) == USB_OK) + { + phid->ctrl_state = USB_HID_STATE_SET_IDLE; + } + break; + case USB_HID_STATE_SET_IDLE: + if(usbh_hid_set_idle(puhost, 0, 0) == USB_OK) + { + phid->ctrl_state = USB_HID_STATE_SET_PROTOCOL; + } + break; + case USB_HID_STATE_SET_PROTOCOL: + if(usbh_hid_set_protocol(puhost, 0) == USB_OK) + { + phid->ctrl_state = USB_HID_STATE_COMPLETE; + } + break; + case USB_HID_STATE_COMPLETE: + phid->state = USB_HID_INIT; + status = USB_OK; + break; + default: + break; + } + + return status; +} + +/** + * @brief usb host hid class process handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +static usb_sts_type uhost_process_handler(void *uhost) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usbh_hid_type *phid = (usbh_hid_type *)puhost->class_handler->pdata; + urb_sts_type urb_status; + switch(phid->state) + { + case USB_HID_INIT: + phid->state = USB_HID_GET; + break; + + case USB_HID_GET: + usbh_interrupt_recv(puhost, phid->chin, (uint8_t *)phid->buffer, phid->in_maxpacket); + phid->state = USB_HID_POLL; + phid->poll_timer = usbh_get_frame(puhost->usb_reg); + break; + + case USB_HID_POLL: + if((usbh_get_frame(puhost->usb_reg) - phid->poll_timer) >= phid->in_poll ) + { + phid->state = USB_HID_GET; + } + else + { + urb_status = usbh_get_urb_status(puhost, phid->chin); + if(urb_status == URB_DONE) + { + puhost->urb_state[phid->chin] = URB_IDLE; + if(phid->protocol == USB_HID_MOUSE_PROTOCOL_CODE) + { + usbh_hid_mouse_decode((uint8_t *)phid->buffer); + } + else if(phid->protocol == USB_HID_KEYBOARD_PROTOCOL_CODE) + { + usbh_hid_keyboard_decode((uint8_t *)phid->buffer); + } + + } + else if(urb_status == URB_STALL) + { + if(usbh_clear_endpoint_feature(puhost, phid->eptin, phid->chin) == USB_OK) + { + phid->state = USB_HID_GET; + } + } + } + break; + + default: + break; + } + return USB_OK; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_class.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_class.h new file mode 100644 index 0000000000..311b821812 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_class.h @@ -0,0 +1,148 @@ +/** + ************************************************************************** + * @file usbh_hid_class.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb host hid class header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USBH_HID_CLASS_H +#define __USBH_HID_CLASS_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "usbh_core.h" +#include "usb_conf.h" + +/** @addtogroup AT32F435_437_middlewares_usbh_class + * @{ + */ + +/** @addtogroup USBH_hid_class + * @{ + */ + +/** @defgroup USBH_hid_class_definition + * @{ + */ + +/** + * @brief usb hid protocol code + */ +#define USB_HID_NONE_PROTOCOL_CODE 0x00 +#define USB_HID_KEYBOARD_PROTOCOL_CODE 0x01 +#define USB_HID_MOUSE_PROTOCOL_CODE 0x02 + +/** + * @brief usb hid request code + */ +#define USB_HID_GET_REPORT 0x01 +#define USB_HID_GET_IDLE 0x02 +#define USB_HID_GET_PROTOCOL 0x03 +#define USB_HID_SET_REPORT 0x09 +#define USB_HID_SET_IDLE 0x0A +#define USB_HID_SET_PROTOCOL 0x0B + +/** + * @brief usb hid request state + */ +typedef enum +{ + USB_HID_STATE_IDLE, + USB_HID_STATE_GET_DESC, + USB_HID_STATE_GET_REPORT, + USB_HID_STATE_SET_IDLE, + USB_HID_STATE_SET_PROTOCOL, + USB_HID_STATE_COMPLETE, +}usb_hid_ctrl_state_type; + +/** + * @brief usb hid process state + */ +typedef enum +{ + USB_HID_INIT, + USB_HID_GET, + USB_HID_SEND, + USB_HID_POLL, + USB_HID_BUSY, + USB_HID_ERROR, +}usb_hid_state_type; + +/** + * @brief usb hid descriptor type + */ +typedef struct +{ + uint8_t bLength; + uint8_t bDescriptorType; + uint16_t bcdHID; + uint8_t bCountryCode; + uint8_t bNumDescriptors; + uint8_t bReportDescriptorType; + uint16_t wItemLength; +}usb_hid_desc_type; + +/** + * @brief usb hid struct + */ +typedef struct +{ + uint8_t chin; + uint8_t eptin; + uint16_t in_maxpacket; + uint8_t in_poll; + + uint8_t chout; + uint8_t eptout; + uint16_t out_maxpacket; + uint8_t out_poll; + uint8_t protocol; + + + usb_hid_desc_type hid_desc; + usb_hid_ctrl_state_type ctrl_state; + usb_hid_state_type state; + uint16_t poll_timer; + uint32_t buffer[16]; +}usbh_hid_type; + +extern usbh_class_handler_type uhost_hid_class_handler; + + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_keyboard.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_keyboard.c new file mode 100644 index 0000000000..3c124306f8 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_keyboard.c @@ -0,0 +1,255 @@ +/** + ************************************************************************** + * @file usbh_hid_keyboard.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb host hid keyboard type + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + #include "usbh_hid_keyboard.h" + +/** @addtogroup AT32F435_437_middlewares_usbh_class + * @{ + */ + +/** @defgroup USBH_hid_class_keyboard + * @brief usb host class hid keyboard + * @{ + */ + +/** @defgroup USBH_hid_class_keyboard_private_functions + * @{ + */ + +static const uint8_t hid_keyboard_codes[] = +{ + 0, 0, 0, 0, 31, 50, 48, 33, + 19, 34, 35, 36, 24, 37, 38, 39, + 52, 51, 25, 26, 17, 20, 32, 21, + 23, 49, 18, 47, 22, 46, 2, 3, + 4, 5, 6, 7, 8, 9, 10, 11, + 43, 110, 15, 16, 61, 12, 13, 27, + 28, 29, 42, 40, 41, 1, 53, 54, + 55, 30, 112, 113, 114, 115, 116, 117, + 118, 119, 120, 121, 122, 123, 124, 125, + 126, 75, 80, 85, 76, 81, 86, 89, + 79, 84, 83, 90, 95, 100, 105, 106, + 108, 93, 98, 103, 92, 97, 102, 91, + 96, 101, 99, 104, 45, 129, 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, 107, 0, 56, + 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, 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, + 58, 44, 60, 127, 64, 57, 62, 128, +}; + +#ifdef QWERTY_KEYBOARD + +static const int8_t hid_keyboard_key[] = { + '\0', '`', '1', '2', '3', '4', '5', '6', + '7', '8', '9', '0', '-', '=', '\0', '\r', + '\t', 'q', 'w', 'e', 'r', 't', 'y', 'u', + 'i', 'o', 'p', '[', ']', '\\', + '\0', 'a', 's', 'd', 'f', 'g', 'h', 'j', + 'k', 'l', ';', '\'', '\0', '\n', + '\0', '\0', 'z', 'x', 'c', 'v', 'b', 'n', + 'm', ',', '.', '/', '\0', '\0', + '\0', '\0', '\0', ' ', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\r', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', + '\0', '\0', '7', '4', '1', + '\0', '/', '8', '5', '2', + '0', '*', '9', '6', '3', + '.', '-', '+', '\0', '\n', '\0', '\0', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0' +}; + +static const int8_t hid_keyboard_key_shift[] = { + '\0', '~', '!', '@', '#', '$', '%', '^', '&', '*', '(', ')', + '_', '+', '\0', '\0', '\0', 'Q', 'W', 'E', 'R', 'T', 'Y', 'U', + 'I', 'O', 'P', '{', '}', '|', '\0', 'A', 'S', 'D', 'F', 'G', + 'H', 'J', 'K', 'L', ':', '"', '\0', '\n', '\0', '\0', 'Z', 'X', + 'C', 'V', 'B', 'N', 'M', '<', '>', '?', '\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', '\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' +}; + +#else +static const int8_t hid_keyboard_key[] = { + '\0', '`', '1', '2', '3', '4', '5', '6', '7', '8', '9', '0', + '-', '=', '\0', '\r', '\t', 'a', 'z', 'e', 'r', 't', 'y', 'u', + 'i', 'o', 'p', '[', ']', '\\', '\0', 'q', 's', 'd', 'f', 'g', + 'h', 'j', 'k', 'l', 'm', '\0', '\0', '\n', '\0', '\0', 'w', 'x', + 'c', 'v', 'b', 'n', ',', ';', ':', '!', '\0', '\0', '\0', '\0', + '\0', ' ', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\r', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', '\0', '7', '4', '1','\0', '/', + '8', '5', '2', '0', '*', '9', '6', '3', '.', '-', '+', '\0', + '\n', '\0', '\0', '\0', '\0', '\0', '\0','\0', '\0', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0' +}; + +static const int8_t hid_keyboard_key_shift[] = { + '\0', '~', '!', '@', '#', '$', '%', '^', '&', '*', '(', ')', '_', + '+', '\0', '\0', '\0', 'A', 'Z', 'E', 'R', 'T', 'Y', 'U', 'I', 'O', + 'P', '{', '}', '*', '\0', 'Q', 'S', 'D', 'F', 'G', 'H', 'J', 'K', + 'L', 'M', '%', '\0', '\n', '\0', '\0', 'W', 'X', 'C', 'V', 'B', 'N', + '?', '.', '/', '\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', '\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' +}; +#endif + +/** + * @brief usb host hid keyboard decode + * @param data: keyboard data + * @retval none + */ +void usbh_hid_keyboard_decode(uint8_t *data) +{ + static uint8_t shift; + static uint8_t keys[KEYBOARD_MAX_NB_PRESSED]; + static uint8_t keys_n[KEYBOARD_MAX_NB_PRESSED]; + static uint8_t keys_l[KEYBOARD_MAX_NB_PRESSED]; + static uint8_t key_newest; + static uint8_t nb_keys; + static uint8_t nb_keys_n; + static uint8_t nb_keys_l; + + uint8_t idx; + uint8_t idy; + uint8_t err; + uint8_t out; + + nb_keys = 0; + nb_keys_n = 0; + nb_keys_l = 0; + key_newest = 0; + + if(data[0] == KEYBOARD_LEFT_SHIFT || data[0] == KEYBOARD_RIGHT_SHIFT) + { + shift = TRUE; + } + else + { + shift = FALSE; + } + err = FALSE; + + for(idx = 2; idx < 2 + KEYBOARD_MAX_NB_PRESSED; idx ++) + { + if((data[idx] == 0x01) || + (data[idx] == 0x02) || + (data[idx] == 0x03)) + { + err = TRUE; + } + } + + if(err == TRUE) + { + return; + } + + nb_keys = 0; + nb_keys_n = 0; + for(idx = 2; idx < 2 + KEYBOARD_MAX_NB_PRESSED; idx ++) + { + if(data[idx] != 0) + { + keys[nb_keys] = data[idx]; + nb_keys ++; + for(idy = 0; idy < nb_keys_l; idy ++) + { + if(data[idx] == keys_l[idy]) + { + break; + } + } + + if(idy == nb_keys_l) + { + keys_n[nb_keys_n] = data[idx]; + nb_keys_n ++; + } + + } + } + + if(nb_keys_n == 1) + { + key_newest = keys_n[0]; + + if(shift == TRUE) + { + out = hid_keyboard_key_shift[hid_keyboard_codes[key_newest]]; + } + else + { + out = hid_keyboard_key[hid_keyboard_codes[key_newest]]; + } + /* callback user handler */ + USBH_DEBUG("%c", out); + } + else + { + key_newest = 0; + } + + nb_keys_l = nb_keys; + for(idx = 0; idx < KEYBOARD_MAX_NB_PRESSED; idx ++) + { + keys_l[idx] = keys[idx]; + } + return; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_keyboard.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_keyboard.h new file mode 100644 index 0000000000..f9aba52aa6 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_keyboard.h @@ -0,0 +1,84 @@ +/** + ************************************************************************** + * @file usbh_hid_keyboard.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb host hid keyboard header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USBH_HID_KEYBOARD_H +#define __USBH_HID_KEYBOARD_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "usb_conf.h" + +/** @addtogroup AT32F435_437_middlewares_usbh_class + * @{ + */ + +/** @addtogroup USBH_hid_class_keyboard + * @{ + */ + +/** @defgroup USBH_hid_class_keyboard_definition + * @{ + */ + + /** + * @brief usb keyboard option code + */ +#define KEYBOARD_LEFT_CTRL 0x01 +#define KEYBOARD_LEFT_SHIFT 0x02 +#define KEYBOARD_LEFT_ALT 0x04 +#define KEYBOARD_LEFT_GUI 0x08 +#define KEYBOARD_RIGHT_CTRL 0x10 +#define KEYBOARD_RIGHT_SHIFT 0x20 +#define KEYBOARD_RIGHT_ALT 0x40 +#define KEYBOARD_RIGHT_GUI 0x80 + +#define KEYBOARD_MAX_NB_PRESSED 6 + +#ifndef AZERTY_KEYBOARD + #define QWERTY_KEYBOARD +#endif + +void usbh_hid_keyboard_decode(uint8_t *data); + + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_mouse.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_mouse.c new file mode 100644 index 0000000000..75228a0902 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_mouse.c @@ -0,0 +1,188 @@ +/** + ************************************************************************** + * @file usbh_hid_mouse.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb host hid mouse type + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +#include "usbh_hid_mouse.h" + +/** @addtogroup AT32F435_437_middlewares_usbh_class + * @{ + */ + +/** @defgroup USBH_hid_class_mouse + * @brief usb host class hid mouse + * @{ + */ + +/** @defgroup USBH_hid_class_mouse_private_functions + * @{ + */ + +usb_hid_mouse_type hid_mouse; +uint16_t x_pos = 0, y_pos = 0; + +/** + * @brief usb host hid position + * @param x: x position + * @param y: y position + * @retval none + */ +void usbh_hid_mouse_position(uint8_t x, uint8_t y) +{ + if((x != 0) || (y != 0)) + { + x_pos += x / 2; + y_pos += y / 2; + + if(x_pos > MOUSE_WINDOW_WIDTH - 12) + { + x_pos = MOUSE_WINDOW_WIDTH - 12; + } + if(y_pos > MOUSE_WINDOW_HEIGHT - 12) + { + y_pos = MOUSE_WINDOW_HEIGHT - 12; + } + + if(x_pos < 2) + { + x_pos = 2; + } + if(y_pos < 2) + { + y_pos = 2; + } + USBH_DEBUG("Moving Mouse"); + } + +} + +/** + * @brief usb host hid button press + * @param button: button id + * @retval none + */ +void usbh_hid_mouse_button_press(uint8_t button) +{ + switch(button) + { + case MOUSE_BUTTON_LEFT: + /* left button */ + USBH_DEBUG("Left Button Pressed "); + break; + case MOUSE_BUTTON_RIGHT: + USBH_DEBUG("Right Button Pressed "); + /* left button */ + break; + case MOUSE_BUTTON_MIDDLE: + USBH_DEBUG("Middle Button Pressed "); + /* middle button */ + break; + } +} + +/** + * @brief usb host hid button release + * @param button: button id + * @retval none + */ +void usbh_hid_mouse_button_release(uint8_t button) +{ + switch(button) + { + case MOUSE_BUTTON_LEFT: + /* left button */ + USBH_DEBUG("Left Button Released "); + break; + case MOUSE_BUTTON_RIGHT: + /* left button */ + USBH_DEBUG("Right Button Released "); + break; + case MOUSE_BUTTON_MIDDLE: + /* middle button */ + USBH_DEBUG("Middle Button Released "); + break; + } +} + +/** + * @brief usb host hid mouse process + * @param mouse: mouse data type + * @retval none + */ +void usbh_hid_mouse_process(usb_hid_mouse_type *mouse) +{ + uint8_t idx = 1; + static uint8_t b_state[3] = {0}; + if((mouse->x != 0) && (mouse->y != 0)) + { + usbh_hid_mouse_position(mouse->x, mouse->y); + } + + for(idx = 0; idx < 3; idx ++) + { + if(mouse->button & 1 << idx) + { + if(b_state[idx] == 0) + { + usbh_hid_mouse_button_press(idx); + b_state[idx] = 1; + } + } + else + { + if(b_state[idx] == 1) + { + usbh_hid_mouse_button_release(idx); + b_state[idx] = 0; + } + } + } +} + +/** + * @brief usb host hid mouse decode + * @param mouse_data: mouse data + * @retval none + */ +void usbh_hid_mouse_decode(uint8_t *mouse_data) +{ + hid_mouse.button = mouse_data[0]; + hid_mouse.x = mouse_data[1]; + hid_mouse.y = mouse_data[2]; + hid_mouse.z = mouse_data[3]; + + usbh_hid_mouse_process(&hid_mouse); +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_mouse.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_mouse.h new file mode 100644 index 0000000000..ac32a1fb29 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_hid/usbh_hid_mouse.h @@ -0,0 +1,93 @@ +/** + ************************************************************************** + * @file usbh_hid_mouse.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb host hid mouse header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USBH_HID_MOUSE_H +#define __USBH_HID_MOUSE_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "usb_conf.h" + +/** @addtogroup AT32F435_437_middlewares_usbh_class + * @{ + */ + +/** @addtogroup USBH_hid_class_mouse + * @{ + */ + +/** @defgroup USBH_hid_class_mouse_definition + * @{ + */ + +/** + * @brief usb hid mouse x y + */ +#define MOUSE_WINDOW_X 100 +#define MOUSE_WINDOW_Y 220 +#define MOUSE_WINDOW_HEIGHT 90 +#define MOUSE_WINDOW_WIDTH 128 + + /** + * @brief usb hid mouse button + */ +#define MOUSE_BUTTON_LEFT 0x00 +#define MOUSE_BUTTON_RIGHT 0x01 +#define MOUSE_BUTTON_MIDDLE 0x02 + +/** + * @brief usb hid mouse type + */ +typedef struct +{ + uint8_t button; + uint8_t x; + uint8_t y; + uint8_t z; +}usb_hid_mouse_type; + +void usbh_hid_mouse_decode(uint8_t *mouse_data); + + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif + diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_msc/usbh_msc_bot_scsi.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_msc/usbh_msc_bot_scsi.c new file mode 100644 index 0000000000..928ff25ba4 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_msc/usbh_msc_bot_scsi.c @@ -0,0 +1,671 @@ +/** + ************************************************************************** + * @file usbh_msc_bot_scsi.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb host msc bulk-only transfer and scsi type + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +#include "usbh_msc_bot_scsi.h" +#include "usbh_msc_class.h" +#include "usb_conf.h" +#include "usbh_core.h" +#include "usbh_ctrl.h" + +/** @addtogroup AT32F435_437_middlewares_usbh_class + * @{ + */ + +/** @defgroup USBH_msc_bot_scsi_class + * @brief usb host class msc bot scsi + * @{ + */ + +/** @defgroup USBH_msc_bot_scsi_class_private_functions + * @{ + */ + +static usb_sts_type usbh_bot_cbw(msc_bot_cbw_type *cbw, uint32_t data_length, uint8_t cmd_len, uint8_t flag); +static usb_sts_type usbh_cmd_inquiry(msc_bot_trans_type *bot_trans, uint8_t *cmd, uint8_t lun); +static usb_sts_type usbh_cmd_capacity10(msc_bot_trans_type *bot_trans, uint8_t *cmd, uint8_t lun); +static usb_sts_type usbh_cmd_test_unit_ready(msc_bot_trans_type *bot_trans, uint8_t *cmd, uint8_t lun); +static usb_sts_type usbh_cmd_requset_sense(msc_bot_trans_type *bot_trans, uint8_t *cmd, uint8_t lun); +static usb_sts_type usbh_cmd_write(msc_bot_trans_type *bot_trans, uint8_t *cmd, uint8_t lun, + uint32_t data_len, uint32_t address, uint8_t *buffer); +static usb_sts_type usbh_cmd_read(msc_bot_trans_type *bot_trans, uint8_t *cmd, uint8_t lun, + uint32_t data_len, uint32_t address, uint8_t *buffer); + +/** + * @brief usb host bulk-only cbw + * @param cbw: to the structure of msc_bot_cbw_type + * @param data_length: data length + * @param cmd_len: command len + * @param flag: cbw flag + * @retval status: usb_sts_type status + */ +static usb_sts_type usbh_bot_cbw(msc_bot_cbw_type *cbw, uint32_t data_length, uint8_t cmd_len, uint8_t flag) +{ + uint8_t i_index; + cbw->dCBWSignature = MSC_CBW_SIGNATURE; + cbw->dCBWTag = MSC_CBW_TAG; + cbw->dCBWDataTransferLength = data_length; + cbw->bmCBWFlags = flag; + cbw->bCBWCBLength = cmd_len; + for(i_index = 0; i_index < MSC_CBW_CB_LEN; i_index ++) + { + cbw->CBWCB[i_index] = 0x00; + } + return USB_OK; +} + +/** + * @brief usb host msc command inquiry + * @param bot_trans: to the structure of msc_bot_trans_type + * @param cmd: command buffer + * @param lun: logical unit number + * @retval status: usb_sts_type status + */ +static usb_sts_type usbh_cmd_inquiry(msc_bot_trans_type *bot_trans, uint8_t *cmd, uint8_t lun) +{ + usbh_msc_type *msc_struct = (usbh_msc_type *)bot_trans->msc_struct; + cmd[0] = MSC_OPCODE_INQUIRY; + cmd[1] = lun << 5; + cmd[4] = MSC_INQUIRY_DATA_LEN; + + bot_trans->data = (uint8_t *)&msc_struct->l_unit_n[lun].inquiry; + return USB_OK; +} + +/** + * @brief usb host msc command capacity10 + * @param bot_trans: to the structure of msc_bot_trans_type + * @param cmd: command buffer + * @param lun: logical unit number + * @retval status: usb_sts_type status + */ +static usb_sts_type usbh_cmd_capacity10(msc_bot_trans_type *bot_trans, uint8_t *cmd, uint8_t lun) +{ + usbh_msc_type *msc_struct = (usbh_msc_type *)bot_trans->msc_struct; + cmd[0] = MSC_OPCODE_CAPACITY; + cmd[1] = lun << 5; + + msc_struct->bot_trans.data = (uint8_t *)bot_trans->buffer; + return USB_OK; +} + +/** + * @brief usb host msc command test unit ready + * @param bot_trans: to the structure of msc_bot_trans_type + * @param cmd: command buffer + * @param lun: logical unit number + * @retval status: usb_sts_type status + */ +static usb_sts_type usbh_cmd_test_unit_ready(msc_bot_trans_type *bot_trans, uint8_t *cmd, uint8_t lun) +{ + cmd[0] = MSC_OPCODE_TEST_UNIT_READY; + cmd[1] = lun << 5; + + return USB_OK; +} + +/** + * @brief usb host msc command request sense + * @param bot_trans: to the structure of msc_bot_trans_type + * @param cmd: command buffer + * @param lun: logical unit number + * @retval status: usb_sts_type status + */ +static usb_sts_type usbh_cmd_requset_sense(msc_bot_trans_type *bot_trans, uint8_t *cmd, uint8_t lun) +{ + cmd[0] = MSC_OPCODE_REQUEST_SENSE; + cmd[1] = lun << 5; + cmd[4] = MSC_REQUEST_SENSE_DATA_LEN; + + bot_trans->data = bot_trans->buffer; + return USB_OK; +} + +/** + * @brief usb host msc command write + * @param bot_trans: to the structure of msc_bot_trans_type + * @param cmd: command buffer + * @param lun: logical unit number + * @param data_len: transfer data length + * @param address: logical block address + * @param buffer: transfer data buffer + * @retval status: usb_sts_type status + */ +static usb_sts_type usbh_cmd_write(msc_bot_trans_type *bot_trans, uint8_t *cmd, uint8_t lun, + uint32_t data_len, uint32_t address, uint8_t *buffer) +{ + cmd[0] = MSC_OPCODE_WRITE10; + cmd[1] = lun << 5; + cmd[2] = (uint8_t)(address >> 24); + cmd[3] = (uint8_t)(address >> 16); + cmd[4] = (uint8_t)(address >> 8); + cmd[5] = (uint8_t)(address & 0xFF); + + cmd[7] = data_len >> 8; + cmd[8] = data_len; + + bot_trans->data = buffer; + return USB_OK; +} + +/** + * @brief usb host msc command read + * @param bot_trans: to the structure of msc_bot_trans_type + * @param cmd: command buffer + * @param lun: logical unit number + * @param data_len: transfer data length + * @param address: logical block address + * @param buffer: transfer data buffer + * @retval status: usb_sts_type status + */ +static usb_sts_type usbh_cmd_read(msc_bot_trans_type *bot_trans, uint8_t *cmd, uint8_t lun, + uint32_t data_len, uint32_t address, uint8_t *buffer) +{ + cmd[0] = MSC_OPCODE_READ10; + cmd[1] = lun << 5; + cmd[2] = (uint8_t)(address >> 24); + cmd[3] = (uint8_t)(address >> 16); + cmd[4] = (uint8_t)(address >> 8); + cmd[5] = (uint8_t)(address & 0xFF); + + cmd[7] = data_len >> 8; + cmd[8] = data_len; + + bot_trans->data = buffer; + return USB_OK; +} + +/** + * @brief usb host csw check + * @param cbw: to the structure of msc_bot_cbw_type + * @param csw: to the structure of msc_bot_csw_type + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_check_csw(void *uhost, msc_bot_cbw_type *cbw, msc_bot_csw_type *csw) +{ + usb_sts_type status = USB_FAIL; + if(csw->dCBWSignature == MSC_CSW_SIGNATURE) + { + if(csw->dCBWTag == cbw->dCBWTag) + { + if(csw->bCSWStatus == 0) + { + status = USB_OK; + } + } + } + return status; +} + +/** + * @brief usb host msc bulk-only request + * @param uhost: to the structure of usbh_core_type + * @param bot_trans: to the structure of msc_bot_trans_type + * @retval status: usb_sts_type status + */ +usb_sts_type usb_bot_request(void *uhost, msc_bot_trans_type *bot_trans) +{ + usb_sts_type status = USB_WAIT; + urb_sts_type urb_status; + usb_sts_type clr_status; + usbh_core_type *puhost = (usbh_core_type *)uhost; + usbh_msc_type *msc_struct = (usbh_msc_type *)bot_trans->msc_struct; + switch(bot_trans->bot_state) + { + case BOT_STATE_SEND_CBW: + usbh_bulk_send(puhost, msc_struct->chout, (uint8_t *)(&bot_trans->cbw), MSC_CBW_LEN); + bot_trans->bot_state = BOT_STATE_SEND_CBW_WAIT; + break; + + case BOT_STATE_SEND_CBW_WAIT: + urb_status = usbh_get_urb_status(puhost, msc_struct->chout); + if(urb_status == URB_DONE) + { + if(bot_trans->cbw.dCBWDataTransferLength != 0) + { + if(bot_trans->cbw.bmCBWFlags == MSC_CBW_FLAG_IN) + { + bot_trans->bot_state = BOT_STATE_DATA_IN; + } + else + { + bot_trans->bot_state = BOT_STATE_DATA_OUT; + } + } + else + { + bot_trans->bot_state = BOT_STATE_RECV_CSW; + } + } + else if(urb_status == URB_NOTREADY) + { + bot_trans->bot_state = BOT_STATE_SEND_CBW; + } + else if(urb_status == URB_STALL) + { + bot_trans->bot_state = BOT_STATE_ERROR_OUT; + } + break; + + case BOT_STATE_DATA_IN: + usbh_bulk_recv(puhost, msc_struct->chin, bot_trans->data, + msc_struct->in_maxpacket); + bot_trans->bot_state = BOT_STATE_DATA_IN_WAIT; + break; + + case BOT_STATE_DATA_IN_WAIT: + urb_status = usbh_get_urb_status(puhost, msc_struct->chin); + if(urb_status == URB_DONE) + { + if(bot_trans->cbw.dCBWDataTransferLength > msc_struct->in_maxpacket) + { + bot_trans->data += msc_struct->in_maxpacket; + bot_trans->cbw.dCBWDataTransferLength -= msc_struct->in_maxpacket; + } + else + { + bot_trans->cbw.dCBWDataTransferLength = 0; + } + if(bot_trans->cbw.dCBWDataTransferLength > 0) + { + usbh_bulk_recv(puhost, msc_struct->chin, bot_trans->data, + msc_struct->in_maxpacket); + } + else + { + bot_trans->bot_state = BOT_STATE_RECV_CSW; + } + } + else if(urb_status == URB_STALL) + { + bot_trans->bot_state = BOT_STATE_ERROR_IN; + } + + break; + + case BOT_STATE_DATA_OUT: + usbh_bulk_send(puhost, msc_struct->chout, bot_trans->data, msc_struct->out_maxpacket); + bot_trans->bot_state = BOT_STATE_DATA_OUT_WAIT; + break; + + case BOT_STATE_DATA_OUT_WAIT: + urb_status = usbh_get_urb_status(puhost, msc_struct->chout); + if(urb_status == URB_DONE) + { + if(bot_trans->cbw.dCBWDataTransferLength > msc_struct->out_maxpacket) + { + bot_trans->data += msc_struct->out_maxpacket; + bot_trans->cbw.dCBWDataTransferLength -= msc_struct->out_maxpacket; + } + else + { + bot_trans->cbw.dCBWDataTransferLength = 0; + } + if(bot_trans->cbw.dCBWDataTransferLength > 0) + { + usbh_bulk_send(puhost, msc_struct->chout, bot_trans->data, msc_struct->out_maxpacket); + } + else + { + bot_trans->bot_state = BOT_STATE_RECV_CSW; + } + } + else if(urb_status == URB_NOTREADY) + { + bot_trans->bot_state = BOT_STATE_DATA_OUT; + } + else if(urb_status == URB_STALL) + { + bot_trans->bot_state = BOT_STATE_ERROR_OUT; + } + break; + + case BOT_STATE_RECV_CSW: + usbh_bulk_recv(puhost, msc_struct->chin, (uint8_t *)&bot_trans->csw, + MSC_CSW_LEN); + bot_trans->bot_state = BOT_STATE_RECV_CSW_WAIT; + + break; + case BOT_STATE_RECV_CSW_WAIT: + urb_status = usbh_get_urb_status(puhost, msc_struct->chin); + if(urb_status == URB_DONE) + { + bot_trans->bot_state = BOT_STATE_SEND_CBW; + bot_trans->cmd_state = CMD_STATE_SEND; + status = usbh_check_csw(uhost, &bot_trans->cbw, &bot_trans->csw); + } + else if(urb_status == URB_STALL) + { + bot_trans->bot_state = BOT_STATE_ERROR_IN; + } + + break; + case BOT_STATE_ERROR_IN: + clr_status = usbh_clear_ept_feature(puhost, msc_struct->eptin, msc_struct->chin); + if(clr_status == USB_OK) + { + bot_trans->bot_state = BOT_STATE_RECV_CSW; + usbh_set_toggle(puhost, msc_struct->chin, 0); + } + + break; + case BOT_STATE_ERROR_OUT: + clr_status = usbh_clear_ept_feature(puhost, msc_struct->eptout, msc_struct->chout); + if(clr_status == USB_OK) + { + usbh_set_toggle(puhost, msc_struct->chout, 1 - puhost->hch[msc_struct->chout].toggle_out); + usbh_set_toggle(puhost, msc_struct->chin, 0); + bot_trans->bot_state = BOT_STATE_ERROR_IN; + } + break; + case BOT_STATE_COMPLETE: + break; + + default: + break; + } + + return status; +} + +/** + * @brief usb host msc bulk-only get inquiry request + * @param uhost: to the structure of usbh_core_type + * @param bot_trans: to the structure of msc_bot_trans_type + * @param lun: logical unit number + * @param inquiry: to the structure of msc_scsi_data_inquiry + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_msc_bot_scsi_get_inquiry(void *uhost, msc_bot_trans_type *bot_trans, + uint8_t lun, msc_scsi_data_inquiry *inquiry) +{ + usb_sts_type status = USB_WAIT; + switch(bot_trans->cmd_state) + { + case CMD_STATE_SEND: + usbh_bot_cbw(&bot_trans->cbw, MSC_INQUIRY_DATA_LEN, MSC_INQUIRY_CMD_LEN, MSC_CBW_FLAG_IN); + bot_trans->cbw.bCBWLUN = lun; + usbh_cmd_inquiry(bot_trans, bot_trans->cbw.CBWCB, lun); + bot_trans->cmd_state = CMD_STATE_WAIT; + bot_trans->bot_state = BOT_STATE_SEND_CBW; + break; + + case CMD_STATE_WAIT: + status = usb_bot_request(uhost, bot_trans); + if(status == USB_OK) + { + bot_trans->cmd_state = CMD_STATE_SEND; + } + if(status == USB_FAIL) + { + bot_trans->cmd_state = CMD_STATE_SEND; + } + break; + default: + break; + } + return status; +} + +/** + * @brief usb host msc bulk-only capacity request + * @param uhost: to the structure of usbh_core_type + * @param bot_trans: to the structure of msc_bot_trans_type + * @param lun: logical unit number + * @param capacity: to the structure of msc_scsi_data_capacity + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_msc_bot_scsi_capacity(void *uhost, msc_bot_trans_type *bot_trans, + uint8_t lun, msc_scsi_data_capacity *capacity) +{ + usb_sts_type status = USB_WAIT; + switch(bot_trans->cmd_state) + { + case CMD_STATE_SEND: + usbh_bot_cbw(&bot_trans->cbw, MSC_CAPACITY10_DATA_LEN, MSC_CAPACITY10_CMD_LEN, MSC_CBW_FLAG_IN); + bot_trans->cbw.bCBWLUN = lun; + usbh_cmd_capacity10(bot_trans, bot_trans->cbw.CBWCB, lun); + bot_trans->cmd_state = CMD_STATE_WAIT; + bot_trans->bot_state = BOT_STATE_SEND_CBW; + break; + + case CMD_STATE_WAIT: + status = usb_bot_request(uhost, bot_trans); + if(status == USB_OK) + { + capacity->blk_nbr = bot_trans->buffer[3] | bot_trans->buffer[2] << 8 | + bot_trans->buffer[1] << 16 | bot_trans->buffer[0] << 24; + capacity->blk_size = bot_trans->buffer[7] | bot_trans->buffer[6] << 8 ; + bot_trans->cmd_state = CMD_STATE_SEND; + } + if(status == USB_FAIL) + { + bot_trans->cmd_state = CMD_STATE_SEND; + } + break; + default: + break; + } + return status; +} + +/** + * @brief usb host msc bulk-only tet unit ready request + * @param uhost: to the structure of usbh_core_type + * @param bot_trans: to the structure of msc_bot_trans_type + * @param lun: logical unit number + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_msc_bot_scsi_test_unit_ready(void *uhost, msc_bot_trans_type *bot_trans, + uint8_t lun) +{ + usb_sts_type status = USB_WAIT; + switch(bot_trans->cmd_state) + { + case CMD_STATE_SEND: + usbh_bot_cbw(&bot_trans->cbw, MSC_TEST_UNIT_READY_DATA_LEN, + MSC_TEST_UNIT_READY_CMD_LEN, MSC_CBW_FLAG_OUT); + bot_trans->cbw.bCBWLUN = lun; + usbh_cmd_test_unit_ready(bot_trans, bot_trans->cbw.CBWCB, lun); + bot_trans->cmd_state = CMD_STATE_WAIT; + bot_trans->bot_state = BOT_STATE_SEND_CBW; + break; + + case CMD_STATE_WAIT: + status = usb_bot_request(uhost, bot_trans); + if(status == USB_OK) + { + bot_trans->cmd_state = CMD_STATE_SEND; + } + if(status == USB_FAIL) + { + bot_trans->cmd_state = CMD_STATE_SEND; + } + break; + default: + break; + } + return status; +} + +/** + * @brief usb host msc bulk-only request sense request + * @param uhost: to the structure of usbh_core_type + * @param bot_trans: to the structure of msc_bot_trans_type + * @param lun: logical unit number + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_msc_bot_scsi_request_sense(void *uhost, msc_bot_trans_type *bot_trans, + uint8_t lun) +{ + usb_sts_type status = USB_WAIT; + switch(bot_trans->cmd_state) + { + case CMD_STATE_SEND: + usbh_bot_cbw(&bot_trans->cbw, MSC_REQUEST_SENSE_DATA_LEN, + MSC_REQUEST_SENSE_CMD_LEN, MSC_CBW_FLAG_IN); + bot_trans->cbw.bCBWLUN = lun; + usbh_cmd_requset_sense(bot_trans, bot_trans->cbw.CBWCB, lun); + bot_trans->cmd_state = CMD_STATE_WAIT; + bot_trans->bot_state = BOT_STATE_SEND_CBW; + break; + + case CMD_STATE_WAIT: + status = usb_bot_request(uhost, bot_trans); + if(status == USB_OK) + { + bot_trans->cmd_state = CMD_STATE_SEND; + } + if(status == USB_FAIL) + { + bot_trans->cmd_state = CMD_STATE_SEND; + } + break; + default: + break; + } + return status; +} + +/** + * @brief usb host msc bulk-only write request + * @param uhost: to the structure of usbh_core_type + * @param bot_trans: to the structure of msc_bot_trans_type + * @param address: logical block address + * @param write_data: write data buffer + * @param write_len: write data length + * @param lun: logical unit number + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_msc_bot_scsi_write(void *uhost, msc_bot_trans_type *bot_trans, + uint32_t address, uint8_t *write_data, + uint32_t write_len, uint8_t lun) +{ + usb_sts_type status = USB_WAIT; + switch(bot_trans->cmd_state) + { + case CMD_STATE_SEND: + usbh_bot_cbw(&bot_trans->cbw, write_len * 512, + MSC_WRITE_CMD_LEN, MSC_CBW_FLAG_OUT); + bot_trans->cbw.bCBWLUN = lun; + usbh_cmd_write(bot_trans, bot_trans->cbw.CBWCB, lun, write_len, address, write_data); + bot_trans->cmd_state = CMD_STATE_WAIT; + bot_trans->bot_state = BOT_STATE_SEND_CBW; + break; + + case CMD_STATE_WAIT: + status = usb_bot_request(uhost, bot_trans); + if(status == USB_OK) + { + bot_trans->cmd_state = CMD_STATE_SEND; + } + if(status == USB_FAIL) + { + bot_trans->cmd_state = CMD_STATE_SEND; + } + break; + default: + break; + } + return status; +} + +/** + * @brief usb host msc bulk-only read request + * @param uhost: to the structure of usbh_core_type + * @param bot_trans: to the structure of msc_bot_trans_type + * @param address: logical block address + * @param read_data: read data buffer + * @param read_len: read data length + * @param lun: logical unit number + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_msc_bot_scsi_read(void *uhost, msc_bot_trans_type *bot_trans, + uint32_t address, uint8_t *read_data, + uint32_t read_len, uint8_t lun) +{ + usb_sts_type status = USB_WAIT; + switch(bot_trans->cmd_state) + { + case CMD_STATE_SEND: + usbh_bot_cbw(&bot_trans->cbw, read_len * 512, + MSC_READ_CMD_LEN, MSC_CBW_FLAG_IN); + bot_trans->cbw.bCBWLUN = lun; + usbh_cmd_read(bot_trans, bot_trans->cbw.CBWCB, lun, read_len, address, read_data); + bot_trans->cmd_state = CMD_STATE_WAIT; + bot_trans->bot_state = BOT_STATE_SEND_CBW; + break; + + case CMD_STATE_WAIT: + status = usb_bot_request(uhost, bot_trans); + if(status == USB_OK) + { + bot_trans->cmd_state = CMD_STATE_SEND; + } + if(status == USB_FAIL) + { + bot_trans->cmd_state = CMD_STATE_SEND; + } + break; + default: + break; + } + return status; +} + +/** + * @brief usb host msc init + * @param msc_struct: to the structure of usbh_msc_type + * @retval status: usb_sts_type status + */ +usb_sts_type msc_bot_scsi_init(usbh_msc_type *msc_struct) +{ + msc_struct->state = USBH_MSC_INIT; + msc_struct->ctrl_state = USBH_MSC_STATE_IDLE; + msc_struct->error = MSC_OK; + msc_struct->cur_lun = 0; + msc_struct->max_lun = 0; + msc_struct->use_lun = 0; + msc_struct->bot_trans.msc_struct = &usbh_msc; + msc_struct->bot_trans.cmd_state = CMD_STATE_SEND; + msc_struct->bot_trans.bot_state = BOT_STATE_SEND_CBW; + return USB_OK; +} + + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + + + + diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_msc/usbh_msc_bot_scsi.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_msc/usbh_msc_bot_scsi.h new file mode 100644 index 0000000000..b62f0138f4 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_msc/usbh_msc_bot_scsi.h @@ -0,0 +1,239 @@ +/** + ************************************************************************** + * @file usbh_msc_bot_scsi.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb host msc bulk-only transfer and scsi header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USBH_MSC_BOT_SCSI_H +#define __USBH_MSC_BOT_SCSI_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "usbh_core.h" +#include "usb_conf.h" + +/** @addtogroup AT32F435_437_middlewares_usbh_class + * @{ + */ + +/** @addtogroup USBH_msc_bot_scsi_class + * @{ + */ + +/** @defgroup USBH_msc_bot_scsi_class_definition + * @{ + */ + +#define MSC_CBW_SIGNATURE 0x43425355 +#define MSC_CSW_SIGNATURE 0x53425355 +#define MSC_CBW_TAG 0x50607080 +#define MSC_CBW_FLAG_IN 0x80 +#define MSC_CBW_FLAG_OUT 0x00 + +#define MSC_CBW_LEN 31 +#define MSC_CSW_LEN 13 +#define MSC_CBW_CB_LEN 16 +#define MSC_TEST_UNIT_READY_CMD_LEN 12 +#define MSC_TEST_UNIT_READY_DATA_LEN 0 +#define MSC_INQUIRY_CMD_LEN 12 +#define MSC_INQUIRY_DATA_LEN 36 +#define MSC_CAPACITY10_CMD_LEN 12 +#define MSC_CAPACITY10_DATA_LEN 8 +#define MSC_REQUEST_SENSE_CMD_LEN 12 +#define MSC_REQUEST_SENSE_DATA_LEN 18 +#define MSC_WRITE_CMD_LEN 12 +#define MSC_READ_CMD_LEN 10 + +#define MSC_OPCODE_INQUIRY 0x12 +#define MSC_OPCODE_CAPACITY 0x25 +#define MSC_OPCODE_TEST_UNIT_READY 0x00 +#define MSC_OPCODE_REQUEST_SENSE 0x03 +#define MSC_OPCODE_WRITE10 0x2A +#define MSC_OPCODE_READ10 0x28 + +typedef enum +{ + BOT_STATE_IDLE, + BOT_STATE_SEND_CBW, + BOT_STATE_SEND_CBW_WAIT, + BOT_STATE_DATA_IN, + BOT_STATE_DATA_IN_WAIT, + BOT_STATE_DATA_OUT, + BOT_STATE_DATA_OUT_WAIT, + BOT_STATE_RECV_CSW, + BOT_STATE_RECV_CSW_WAIT, + BOT_STATE_ERROR_IN, + BOT_STATE_ERROR_OUT, + BOT_STATE_COMPLETE +}msc_bot_state_type; + +typedef enum +{ + CMD_STATE_SEND, + CMD_STATE_WAIT, +}msc_cmd_state_type; + +/** + * @brief usb msc process state + */ +typedef enum +{ + USBH_MSC_INIT, + USBH_MSC_INQUIRY, + USBH_MSC_TEST_UNIT_READY, + USBH_MSC_READ_CAPACITY10, + USBH_MSC_REQUEST_SENSE, + USBH_MSC_READ10, + USBH_MSC_WRITE, + USBH_MSC_BUSY, + USBH_MSC_ERROR, + USBH_MSC_IDLE +}msc_state_type; + +typedef enum +{ + MSC_OK, + MSC_NOT_READY, + MSC_ERROR +}msc_error_type; + + +/** + * @brief usb msc inquiry data type + */ +typedef struct +{ + uint8_t pdev_type; + uint8_t rmb; + uint8_t version; + uint8_t data_format; + uint8_t length; + uint8_t reserved[3]; + uint8_t vendor[8]; + uint8_t product[16]; + uint8_t revision[4]; +}msc_scsi_data_inquiry; + + +/** + * @brief usb msc capacity data type + */ +typedef struct +{ + uint32_t blk_nbr; + uint32_t blk_size; +}msc_scsi_data_capacity; + +/** + * @brief usb msc bulk-only command block wrapper type + */ +typedef struct +{ + uint32_t dCBWSignature; + uint32_t dCBWTag; + uint32_t dCBWDataTransferLength; + uint8_t bmCBWFlags; + uint8_t bCBWLUN; + uint8_t bCBWCBLength; + uint8_t CBWCB[MSC_CBW_CB_LEN]; +}msc_bot_cbw_type; + +/** + * @brief usb msc bulk-only command status wrapper type + */ +typedef struct +{ + uint32_t dCBWSignature; + uint32_t dCBWTag; + uint32_t dCSWDataResidue; + uint8_t bCSWStatus; +}msc_bot_csw_type; + +/** + * @brief usb msc bulk-only transfer control type + */ +typedef struct +{ + uint8_t buffer[32]; + msc_bot_cbw_type cbw; + msc_bot_csw_type csw; + msc_cmd_state_type cmd_state; + msc_bot_state_type bot_state; + uint8_t *data; + void *msc_struct; +}msc_bot_trans_type; + +/** + * @brief usb msc bank type + */ +typedef struct +{ + msc_scsi_data_inquiry inquiry; + msc_scsi_data_capacity capacity; + msc_state_type state; + msc_error_type ready; + usb_sts_type pre_state; + uint8_t change; +}usbh_msc_unit_type; + + +usb_sts_type usb_bot_request(void *uhost, msc_bot_trans_type *bot_trans); + +usb_sts_type usbh_msc_bot_scsi_get_inquiry(void *uhost, msc_bot_trans_type *bot_trans, + uint8_t lun, msc_scsi_data_inquiry *inquiry); + +usb_sts_type usbh_msc_bot_scsi_capacity(void *uhost, msc_bot_trans_type *bot_trans, + uint8_t lun, msc_scsi_data_capacity *capacity); + +usb_sts_type usbh_msc_bot_scsi_test_unit_ready(void *uhost, msc_bot_trans_type *bot_trans, + uint8_t lun); + +usb_sts_type usbh_msc_bot_scsi_request_sense(void *uhost, msc_bot_trans_type *bot_trans, + uint8_t lun); + +usb_sts_type usbh_msc_bot_scsi_write(void *uhost, msc_bot_trans_type *bot_trans, + uint32_t address, uint8_t *write_data, + uint32_t write_len, uint8_t lun); + +usb_sts_type usbh_msc_bot_scsi_read(void *uhost, msc_bot_trans_type *bot_trans, + uint32_t address, uint8_t *read_data, + uint32_t read_len, uint8_t lun); +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif + diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_msc/usbh_msc_class.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_msc/usbh_msc_class.c new file mode 100644 index 0000000000..fd2532746a --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_msc/usbh_msc_class.c @@ -0,0 +1,523 @@ +/** + ************************************************************************** + * @file usbh_msc_class.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb host msc class type + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +#include "usbh_msc_class.h" +#include "usb_conf.h" +#include "usbh_core.h" +#include "usbh_ctrl.h" + +/** @addtogroup AT32F435_437_middlewares_usbh_class + * @{ + */ + +/** @defgroup USBH_msc_class + * @brief usb host class msc demo + * @{ + */ + +/** @defgroup USBH_msc_class_private_functions + * @{ + */ + +static usb_sts_type uhost_init_handler(void *uhost); +static usb_sts_type uhost_reset_handler(void *uhost); +static usb_sts_type uhost_request_handler(void *uhost); +static usb_sts_type uhost_process_handler(void *uhost); + +static usb_sts_type usbh_msc_get_max_lun(void *uhost, uint8_t *lun); +static usb_sts_type usbh_msc_clear_feature(void *uhost, uint8_t ept_num); + + +usbh_msc_type usbh_msc; + +usbh_class_handler_type uhost_msc_class_handler = +{ + uhost_init_handler, + uhost_reset_handler, + uhost_request_handler, + uhost_process_handler, + &usbh_msc +}; + + + +/** + * @brief usb host class init handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +static usb_sts_type uhost_init_handler(void *uhost) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usb_sts_type status = USB_OK; + uint8_t if_x, eptidx = 0; + usbh_msc_type *pmsc = &usbh_msc; + puhost->class_handler->pdata = &usbh_msc; + + if_x = usbh_find_interface(puhost, USB_CLASS_CODE_MSC, MSC_SUBCLASS_SCSI_TRANS, MSC_PROTOCOL_BBB); + if(if_x == 0xFF) + { + USBH_DEBUG("Unsupport Device!"); + return USB_NOT_SUPPORT; + } + pmsc->protocol = puhost->dev.cfg_desc.interface[if_x].interface.bInterfaceProtocol; + + for(eptidx = 0; eptidx < puhost->dev.cfg_desc.interface[if_x].interface.bNumEndpoints; eptidx ++) + { + if(puhost->dev.cfg_desc.interface[if_x].endpoint[eptidx].bEndpointAddress & 0x80) + { + pmsc->eptin = puhost->dev.cfg_desc.interface[if_x].endpoint[eptidx].bEndpointAddress; + pmsc->in_maxpacket = puhost->dev.cfg_desc.interface[if_x].endpoint[eptidx].wMaxPacketSize; + pmsc->in_poll = puhost->dev.cfg_desc.interface[if_x].endpoint[eptidx].bInterval; + + pmsc->chin = usbh_alloc_channel(puhost, pmsc->eptin); + /* enable channel */ + usbh_hc_open(puhost, pmsc->chin, pmsc->eptin, + puhost->dev.address, EPT_BULK_TYPE, + pmsc->in_maxpacket, + puhost->dev.speed); + } + else + { + pmsc->eptout = puhost->dev.cfg_desc.interface[if_x].endpoint[eptidx].bEndpointAddress; + pmsc->out_maxpacket = puhost->dev.cfg_desc.interface[if_x].endpoint[eptidx].wMaxPacketSize; + pmsc->out_poll = puhost->dev.cfg_desc.interface[if_x].endpoint[eptidx].bInterval; + + pmsc->chout = usbh_alloc_channel(puhost, pmsc->eptout); + /* enable channel */ + usbh_hc_open(puhost, pmsc->chout,pmsc->eptout, + puhost->dev.address, EPT_BULK_TYPE, + pmsc->out_maxpacket, + puhost->dev.speed); + } + } + + msc_bot_scsi_init(pmsc); + usbh_set_toggle(puhost, pmsc->chout, 0); + usbh_set_toggle(puhost, pmsc->chin, 0); + return status; +} + +/** + * @brief usb host class reset handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +static usb_sts_type uhost_reset_handler(void *uhost) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usbh_msc_type *pmsc = (usbh_msc_type *)puhost->class_handler->pdata; + usb_sts_type status = USB_OK; + uint8_t i_index = 0; + + if(puhost->class_handler->pdata == NULL) + { + return status; + } + + for(i_index = 0; i_index < pmsc->max_lun ; i_index ++) + { + pmsc->l_unit_n[i_index].pre_state = USB_FAIL; + pmsc->l_unit_n[i_index].change = 0; + pmsc->l_unit_n[i_index].state = USBH_MSC_INIT; + pmsc->l_unit_n[i_index].ready = MSC_NOT_READY; + } + + if(pmsc->chin != 0 ) + { + usbh_free_channel(puhost, pmsc->chin); + usbh_ch_disable(puhost, pmsc->chin); + pmsc->chin = 0; + } + + if(pmsc->chout != 0 ) + { + usbh_free_channel(puhost, pmsc->chout); + usbh_ch_disable(puhost, pmsc->chout); + pmsc->chout = 0; + } + + return status; +} + +/** + * @brief usb host hid class request handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +static usb_sts_type uhost_request_handler(void *uhost) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usbh_msc_type *pmsc = (usbh_msc_type *)puhost->class_handler->pdata; + usb_sts_type status = USB_WAIT; + uint8_t i_index = 0; + + switch(pmsc->ctrl_state) + { + case USBH_MSC_STATE_IDLE: + pmsc->ctrl_state = USBH_MSC_STATE_GET_LUN; + break; + case USBH_MSC_STATE_GET_LUN: + if((status = usbh_msc_get_max_lun(uhost, (uint8_t *)&pmsc->max_lun)) == USB_OK) + { + pmsc->max_lun = (pmsc->max_lun & 0xFF) > USBH_SUPPORT_MAX_LUN ? USBH_SUPPORT_MAX_LUN:((pmsc->max_lun & 0xFF) + 1); + USBH_DEBUG("Support max lun %d", pmsc->max_lun); + for(i_index = 0; i_index < pmsc->max_lun ; i_index ++) + { + pmsc->l_unit_n[i_index].pre_state = USB_FAIL; + pmsc->l_unit_n[i_index].change = 0; + pmsc->l_unit_n[i_index].state = USBH_MSC_INIT; + } + } + break; + case USBH_MSC_STATE_ERROR: + if((usbh_msc_clear_feature(uhost, 0)) == USB_OK) + { + pmsc->ctrl_state = USBH_MSC_STATE_GET_LUN; + } + break; + default: + break; + } + + return status; +} + +/** + * @brief usb host class process handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +static usb_sts_type uhost_process_handler(void *uhost) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usbh_msc_type *pmsc = (usbh_msc_type *)puhost->class_handler->pdata; + uint64_t msize = 0; + usb_sts_type status; + switch(pmsc->state) + { + case USBH_MSC_INIT: + if(pmsc->cur_lun < pmsc->max_lun) + { + switch(pmsc->l_unit_n[pmsc->cur_lun].state) + { + case USBH_MSC_INIT: + pmsc->l_unit_n[pmsc->cur_lun].ready = MSC_NOT_READY; + pmsc->l_unit_n[pmsc->cur_lun].state = USBH_MSC_INQUIRY; + break; + case USBH_MSC_INQUIRY: + status = usbh_msc_bot_scsi_get_inquiry(uhost, &pmsc->bot_trans, pmsc->cur_lun, &pmsc->l_unit_n[pmsc->cur_lun].inquiry); + if(status == USB_OK) + { + pmsc->l_unit_n[pmsc->cur_lun].state = USBH_MSC_TEST_UNIT_READY; + } + else if(status == USB_FAIL) + { + pmsc->l_unit_n[pmsc->cur_lun].state = USBH_MSC_REQUEST_SENSE; + } + break; + case USBH_MSC_TEST_UNIT_READY: + status = usbh_msc_bot_scsi_test_unit_ready(uhost, &pmsc->bot_trans, pmsc->cur_lun); + if(status == USB_OK) + { + pmsc->l_unit_n[pmsc->cur_lun].state = USBH_MSC_READ_CAPACITY10; + pmsc->l_unit_n[pmsc->cur_lun].ready = MSC_OK; + } + else if(status == USB_FAIL) + { + pmsc->l_unit_n[pmsc->cur_lun].state = USBH_MSC_REQUEST_SENSE; + pmsc->l_unit_n[pmsc->cur_lun].ready = MSC_NOT_READY; + } + break; + + case USBH_MSC_READ_CAPACITY10: + status = usbh_msc_bot_scsi_capacity(uhost, &pmsc->bot_trans, pmsc->cur_lun, &pmsc->l_unit_n[pmsc->cur_lun].capacity); + if(status == USB_OK) + { + msize = (uint64_t)pmsc->l_unit_n[pmsc->cur_lun].capacity.blk_nbr * (uint64_t)pmsc->l_unit_n[pmsc->cur_lun].capacity.blk_size; + USBH_DEBUG("Device capacity: %llu Byte", msize); + USBH_DEBUG("Block num: %d ", pmsc->l_unit_n[pmsc->cur_lun].capacity.blk_nbr); + USBH_DEBUG("Block size: %d Byte", pmsc->l_unit_n[pmsc->cur_lun].capacity.blk_size); + pmsc->l_unit_n[pmsc->cur_lun].state = USBH_MSC_IDLE; + pmsc->cur_lun ++; + } + else if(status == USB_FAIL) + { + pmsc->l_unit_n[pmsc->cur_lun].state = USBH_MSC_REQUEST_SENSE; + } + break; + case USBH_MSC_REQUEST_SENSE: + status = usbh_msc_bot_scsi_request_sense(uhost, &pmsc->bot_trans, pmsc->cur_lun); + if(status == USB_OK) + { + pmsc->l_unit_n[pmsc->cur_lun].state = USBH_MSC_TEST_UNIT_READY; + } + else if(status == USB_FAIL) + { + pmsc->l_unit_n[pmsc->cur_lun].ready = MSC_NOT_READY; + pmsc->l_unit_n[pmsc->cur_lun].state = USBH_MSC_ERROR; + } + break; + + case USBH_MSC_BUSY: + break; + case USBH_MSC_ERROR: + break; + default: + break; + } + + } + else + { + pmsc->state = USBH_MSC_IDLE; + } + break; + case USBH_MSC_IDLE: + if(puhost->user_handler->user_application != NULL) + { + puhost->user_handler->user_application(); + } + default: + break; + } + return USB_OK; +} + + +/** + * @brief usb host msc get max lun + * @param uhost: to the structure of usbh_core_type + * @param lun: max lun buffer + * @retval status: usb_sts_type status + */ +static usb_sts_type usbh_msc_get_max_lun(void *uhost, uint8_t *lun) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usb_sts_type status = USB_WAIT; + if(puhost->ctrl.state == CONTROL_IDLE ) + { + puhost->ctrl.setup.bmRequestType = USB_DIR_D2H | USB_REQ_RECIPIENT_INTERFACE | USB_REQ_TYPE_CLASS; + puhost->ctrl.setup.bRequest = MSC_REQ_GET_MAX_LUN; + puhost->ctrl.setup.wValue = 0; + puhost->ctrl.setup.wIndex = 0; + puhost->ctrl.setup.wLength = 1; + usbh_ctrl_request(puhost, lun, 1); + } + else + { + status = usbh_ctrl_result_check(puhost, CONTROL_IDLE, ENUM_IDLE); + if(status == USB_OK || status == USB_NOT_SUPPORT) + { + status = USB_OK; + } + } + return status; +} + +/** + * @brief usb host msc clear feature + * @param uhost: to the structure of usbh_core_type + * @param ept_num: endpoint number + * @retval status: usb_sts_type status + */ +static usb_sts_type usbh_msc_clear_feature(void *uhost, uint8_t ept_num) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usb_sts_type status = USB_WAIT; + if(puhost->ctrl.state == CONTROL_IDLE ) + { + puhost->ctrl.setup.bmRequestType = USB_DIR_H2D | USB_REQ_RECIPIENT_ENDPOINT | USB_REQ_TYPE_STANDARD; + puhost->ctrl.setup.bRequest = USB_STD_REQ_CLEAR_FEATURE; + puhost->ctrl.setup.wValue = 0; + puhost->ctrl.setup.wIndex = ept_num; + puhost->ctrl.setup.wLength = 0; + usbh_ctrl_request(puhost, 0, 0); + } + else + { + status = usbh_ctrl_result_check(puhost, CONTROL_IDLE, ENUM_IDLE); + if(status == USB_OK || status == USB_NOT_SUPPORT) + { + status = USB_OK; + } + } + return status; +} + +/** + * @brief usb host msc clear feature + * @param lun: logical unit number + * @retval msc_error_type status + */ +msc_error_type usbh_msc_is_ready(void *uhost, uint8_t lun) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usbh_msc_type *pmsc = (usbh_msc_type *)puhost->class_handler->pdata; + return pmsc->l_unit_n[lun].ready; +} + + +/** + * @brief usb host msc read and write handle + * @param uhost: to the structure of usbh_core_type + * @param address: logical block address + * @param data_len: transfer data length + * @param buffer: transfer data buffer + * @param lun: logical unit number + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_msc_rw_handle(void *uhost, uint32_t address, uint32_t len, uint8_t *buffer, uint8_t lun) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usbh_msc_type *pmsc = (usbh_msc_type *)puhost->class_handler->pdata; + usb_sts_type status = USB_WAIT; + switch(pmsc->l_unit_n[lun].state) + { + case USBH_MSC_READ10: + status = usbh_msc_bot_scsi_read(uhost, &pmsc->bot_trans, address, buffer, len, lun); + if(status == USB_OK) + { + pmsc->l_unit_n[lun].state = USBH_MSC_IDLE; + } + else if(status == USB_FAIL) + { + pmsc->l_unit_n[lun].state = USBH_MSC_REQUEST_SENSE; + status = USB_WAIT; + } + break; + case USBH_MSC_WRITE: + status = usbh_msc_bot_scsi_write(uhost, &pmsc->bot_trans, address, buffer, len, lun); + if(status == USB_OK) + { + pmsc->l_unit_n[lun].state = USBH_MSC_IDLE; + } + else if(status == USB_FAIL) + { + pmsc->l_unit_n[lun].state = USBH_MSC_REQUEST_SENSE; + status = USB_WAIT; + } + break; + case USBH_MSC_REQUEST_SENSE: + status = usbh_msc_bot_scsi_request_sense(uhost, &pmsc->bot_trans, lun); + if(status == USB_OK) + { + pmsc->l_unit_n[lun].state = USBH_MSC_IDLE; + status = USB_FAIL; + } + else if(status == USB_FAIL) + { + USBH_DEBUG("device not support"); + } + break; + default: + break; + } + return status; +} + +/** + * @brief usb host msc read + * @param uhost: to the structure of usbh_core_type + * @param address: logical block address + * @param data_len: transfer data length + * @param buffer: transfer data buffer + * @param lun: logical unit number + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_msc_read(void *uhost, uint32_t address, uint32_t len, uint8_t *buffer, uint8_t lun) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usbh_msc_type *pmsc = (usbh_msc_type *)puhost->class_handler->pdata; + uint32_t timeout = 0; + if(puhost->conn_sts == 0 || puhost->global_state != USBH_CLASS + || pmsc->l_unit_n[lun].state != USBH_MSC_IDLE) + { + return USB_FAIL; + } + pmsc->bot_trans.msc_struct = &usbh_msc; + pmsc->l_unit_n[lun].state = USBH_MSC_READ10; + pmsc->use_lun = lun; + + timeout = puhost->timer; + + while(usbh_msc_rw_handle(uhost, address, len, buffer, lun) == USB_WAIT) + { + if(puhost->conn_sts == 0 || (puhost->timer - timeout) > (len * 10000)) + { + pmsc->l_unit_n[lun].state = USBH_MSC_IDLE; + return USB_FAIL; + } + } + return USB_OK; +} + +/** + * @brief usb host msc write + * @param uhost: to the structure of usbh_core_type + * @param address: logical block address + * @param data_len: transfer data length + * @param buffer: transfer data buffer + * @param lun: logical unit number + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_msc_write(void *uhost, uint32_t address, uint32_t len, uint8_t *buffer, uint8_t lun) +{ + usbh_core_type *puhost = (usbh_core_type *)uhost; + usbh_msc_type *pmsc = (usbh_msc_type *)puhost->class_handler->pdata; + uint32_t timeout = 0; + if(puhost->conn_sts == 0 || puhost->global_state != USBH_CLASS + || pmsc->l_unit_n[lun].state != USBH_MSC_IDLE) + { + return USB_FAIL; + } + + pmsc->bot_trans.msc_struct = &usbh_msc; + pmsc->l_unit_n[lun].state = USBH_MSC_WRITE; + pmsc->use_lun = lun; + + timeout = puhost->timer; + while(usbh_msc_rw_handle(uhost, address, len, buffer, lun) == USB_WAIT) + { + if(puhost->conn_sts == 0 || (puhost->timer - timeout) > (len * 10000)) + { + pmsc->l_unit_n[lun].state = USBH_MSC_IDLE; + return USB_FAIL; + } + } + return USB_OK; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_msc/usbh_msc_class.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_msc/usbh_msc_class.h new file mode 100644 index 0000000000..9435f0f1fa --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Class/usbh_class/usbh_msc/usbh_msc_class.h @@ -0,0 +1,143 @@ +/** + ************************************************************************** + * @file usbh_msc_class.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb host msc class header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USBH_MSC_CLASS_H +#define __USBH_MSC_CLASS_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "usbh_core.h" +#include "usb_conf.h" +#include "usbh_msc_bot_scsi.h" + +/** @addtogroup AT32F435_437_middlewares_usbh_class + * @{ + */ + +/** @addtogroup USBH_msc_class + * @{ + */ + +/** @defgroup USBH_msc_class_definition + * @{ + */ + +/** + * @brief usb msc subclass code + */ +#define MSC_SUBCLASS_SCSI_TRANS 0x06 + +/** + * @brief usb msc protocol code + */ +#define MSC_PROTOCOL_BBB 0x50 + +/** + * @brief usb msc request code + */ +#define MSC_REQ_GET_MAX_LUN 0xFE +#define MSC_REQ_BOMSR 0xFF + +/** + * @brief usb hid request code + */ +#define USB_HID_GET_REPORT 0x01 +#define USB_HID_GET_IDLE 0x02 +#define USB_HID_GET_PROTOCOL 0x03 +#define USB_HID_SET_REPORT 0x09 +#define USB_HID_SET_IDLE 0x0A +#define USB_HID_SET_PROTOCOL 0x0B + + +#define USBH_SUPPORT_MAX_LUN 0x2 + +/** + * @brief usb msc request state + */ +typedef enum +{ + USBH_MSC_STATE_IDLE, + USBH_MSC_STATE_GET_LUN, + USBH_MSC_STATE_ERROR, + USBH_MSC_STATE_COMPLETE, +}usbh_msc_ctrl_state_type; + +/** + * @brief usb msc struct + */ +typedef struct +{ + uint8_t chin; + uint8_t eptin; + uint16_t in_maxpacket; + uint8_t in_poll; + + uint8_t chout; + uint8_t eptout; + uint16_t out_maxpacket; + uint8_t out_poll; + uint8_t protocol; + + uint32_t max_lun; + uint32_t cur_lun; + uint32_t use_lun; + + + usbh_msc_ctrl_state_type ctrl_state; + msc_state_type state; + uint8_t error; + msc_bot_trans_type bot_trans; + usbh_msc_unit_type l_unit_n[USBH_SUPPORT_MAX_LUN]; + uint16_t poll_timer; + uint8_t buffer[64]; +}usbh_msc_type; + +extern usbh_class_handler_type uhost_msc_class_handler; +extern usbh_msc_type usbh_msc; +msc_error_type usbh_msc_is_ready(void *uhost, uint8_t lun); +usb_sts_type usbh_msc_write(void *uhost, uint32_t address, uint32_t len, uint8_t *buffer, uint8_t lun); +usb_sts_type usbh_msc_read(void *uhost, uint32_t address, uint32_t len, uint8_t *buffer, uint8_t lun); +usb_sts_type usbh_msc_rw_handle(void *uhost, uint32_t address, uint32_t len, uint8_t *buffer, uint8_t lun); +usb_sts_type msc_bot_scsi_init(usbh_msc_type *msc_struct); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usb_conf.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usb_conf.h new file mode 100644 index 0000000000..9bdf135cd6 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usb_conf.h @@ -0,0 +1,219 @@ +/** + ************************************************************************** + * @file usb_conf.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb config header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USB_CONF_H +#define __USB_CONF_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "at32f435_437_usb.h" +#include "at32f435_437.h" + +/** @addtogroup AT32F437_periph_examples + * @{ + */ + +/** @addtogroup 437_USB_device_hid_app_led3 + * @{ + */ + +/** + * @brief enable usb device mode + */ +#define USE_OTG_DEVICE_MODE + +/** + * @brief enable usb host mode + */ +/* #define USE_OTG_HOST_MODE */ + +/** + * @brief select otgfs1 or otgfs2 define + */ + +/* use otgfs1 */ +#define OTG_USB_ID 1 + +/* use otgfs2 */ +/* #define OTG_USB_ID 2 */ + +#if (OTG_USB_ID == 1) +#define USB_ID 0 +#define OTG_CLOCK CRM_OTGFS1_PERIPH_CLOCK +#define OTG_IRQ OTGFS1_IRQn +#define OTG_IRQ_HANDLER OTGFS1_IRQHandler +#define OTG_WKUP_IRQ OTGFS1_WKUP_IRQn +#define OTG_WKUP_HANDLER OTGFS1_WKUP_IRQHandler +#define OTG_WKUP_EXINT_LINE EXINT_LINE_18 + +#define OTG_PIN_GPIO GPIOA +#define OTG_PIN_GPIO_CLOCK CRM_GPIOA_PERIPH_CLOCK + +#define OTG_PIN_DP GPIO_PINS_12 +#define OTG_PIN_DP_SOURCE GPIO_PINS_SOURCE12 + +#define OTG_PIN_DM GPIO_PINS_11 +#define OTG_PIN_DM_SOURCE GPIO_PINS_SOURCE11 + +#define OTG_PIN_VBUS GPIO_PINS_9 +#define OTG_PIN_VBUS_SOURCE GPIO_PINS_SOURCE9 + +#define OTG_PIN_ID GPIO_PINS_10 +#define OTG_PIN_ID_SOURCE GPIO_PINS_SOURCE10 + +#define OTG_PIN_SOF_GPIO GPIOA +#define OTG_PIN_SOF_GPIO_CLOCK CRM_GPIOA_PERIPH_CLOCK +#define OTG_PIN_SOF GPIO_PINS_8 +#define OTG_PIN_SOF_SOURCE GPIO_PINS_SOURCE8 + +#define OTG_PIN_MUX GPIO_MUX_10 +#endif + +#if (OTG_USB_ID == 2) +#define USB_ID 1 +#define OTG_CLOCK CRM_OTGFS2_PERIPH_CLOCK +#define OTG_IRQ OTGFS2_IRQn +#define OTG_IRQ_HANDLER OTGFS2_IRQHandler +#define OTG_WKUP_IRQ OTGFS2_WKUP_IRQn +#define OTG_WKUP_HANDLER OTGFS2_WKUP_IRQHandler +#define OTG_WKUP_EXINT_LINE EXINT_LINE_20 + +#define OTG_PIN_GPIO GPIOB +#define OTG_PIN_GPIO_CLOCK CRM_GPIOB_PERIPH_CLOCK + +#define OTG_PIN_DP GPIO_PINS_15 +#define OTG_PIN_DP_SOURCE GPIO_PINS_SOURCE15 + +#define OTG_PIN_DM GPIO_PINS_14 +#define OTG_PIN_DM_SOURCE GPIO_PINS_SOURCE14 + +#define OTG_PIN_VBUS GPIO_PINS_13 +#define OTG_PIN_VBUS_SOURCE GPIO_PINS_SOURCE13 + +#define OTG_PIN_ID GPIO_PINS_12 +#define OTG_PIN_ID_SOURCE GPIO_PINS_SOURCE10 + +#define OTG_PIN_SOF_GPIO GPIOA +#define OTG_PIN_SOF_GPIO_CLOCK CRM_GPIOA_PERIPH_CLOCK +#define OTG_PIN_SOF GPIO_PINS_4 +#define OTG_PIN_SOF_SOURCE GPIO_PINS_SOURCE4 + +#define OTG_PIN_MUX GPIO_MUX_12 +#endif + +/** + * @brief usb device mode config + */ +#ifdef USE_OTG_DEVICE_MODE +/** + * @brief usb device mode fifo + */ +/* otg1 device fifo */ +#define USBD_RX_SIZE 128 +#define USBD_EP0_TX_SIZE 24 +#define USBD_EP1_TX_SIZE 20 +#define USBD_EP2_TX_SIZE 20 +#define USBD_EP3_TX_SIZE 20 +#define USBD_EP4_TX_SIZE 20 +#define USBD_EP5_TX_SIZE 20 +#define USBD_EP6_TX_SIZE 20 +#define USBD_EP7_TX_SIZE 20 + +/* otg2 device fifo */ +#define USBD2_RX_SIZE 128 +#define USBD2_EP0_TX_SIZE 24 +#define USBD2_EP1_TX_SIZE 20 +#define USBD2_EP2_TX_SIZE 20 +#define USBD2_EP3_TX_SIZE 20 +#define USBD2_EP4_TX_SIZE 20 +#define USBD2_EP5_TX_SIZE 20 +#define USBD2_EP6_TX_SIZE 20 +#define USBD2_EP7_TX_SIZE 20 + +/** + * @brief usb endpoint max num define + */ +#ifndef USB_EPT_MAX_NUM +#define USB_EPT_MAX_NUM 8 +#endif +#endif + +/** + * @brief usb host mode config + */ +#ifdef USE_OTG_HOST_MODE +#ifndef USB_HOST_CHANNEL_NUM +#define USB_HOST_CHANNEL_NUM 16 +#endif + +/** + * @brief usb host mode fifo + */ +/* otg1 host fifo */ +#define USBH_RX_FIFO_SIZE 128 +#define USBH_NP_TX_FIFO_SIZE 96 +#define USBH_P_TX_FIFO_SIZE 96 + +/* otg2 host fifo */ +#define USBH2_RX_FIFO_SIZE 128 +#define USBH2_NP_TX_FIFO_SIZE 96 +#define USBH2_P_TX_FIFO_SIZE 96 +#endif + +/** + * @brief usb sof output enable + */ +/* #define USB_SOF_OUTPUT_ENABLE */ + +/** + * @brief usb vbus ignore + */ +#define USB_VBUS_IGNORE + +/** + * @brief usb low power wakeup handler enable + */ +/* #define USB_LOW_POWER_WAKUP */ + +void usb_delay_ms(uint32_t ms); +void usb_delay_us(uint32_t us); + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usb_core.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usb_core.h new file mode 100644 index 0000000000..5ab69918cd --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usb_core.h @@ -0,0 +1,136 @@ +/** + ************************************************************************** + * @file usb_core.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb core header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USB_CORE_H +#define __USB_CORE_H + +#ifdef __cplusplus +extern "C" { +#endif + + +#include "usb_std.h" +#include "usb_conf.h" + +#ifdef USE_OTG_DEVICE_MODE +#include "usbd_core.h" +#endif +#ifdef USE_OTG_HOST_MODE +#include "usbh_core.h" +#endif + +/** @addtogroup AT32F435_437_middlewares_usb_drivers + * @{ + */ + +/** @addtogroup USB_drivers_core + * @{ + */ + +/** @defgroup USB_core_exported_types + * @{ + */ + +/** + * @brief usb core speed select + */ +typedef enum +{ + USB_LOW_SPEED_CORE_ID, /*!< usb low speed core id */ + USB_FULL_SPEED_CORE_ID, /*!< usb full speed core id */ + USB_HIGH_SPEED_CORE_ID, /*!< usb high speed core id */ +} usb_speed_type; + +/** + * @brief usb core cofig struct + */ +typedef struct +{ + uint8_t speed; /*!< otg speed */ + uint8_t dma_en; /*!< dma enable state, not use*/ + uint8_t hc_num; /*!< the otg host support number of channel */ + uint8_t ept_num; /*!< the otg device support number of endpoint */ + + uint16_t max_size; /*!< support max packet size */ + uint16_t fifo_size; /*!< the usb otg total file size */ + uint8_t phy_itface; /*!< usb phy select */ + uint8_t core_id; /*!< the usb otg core id */ + uint8_t low_power; /*!< the usb otg low power option */ + uint8_t sof_out; /*!< the sof signal output */ + uint8_t usb_id; /*!< select otgfs1 or otgfs2 */ + uint8_t vbusig; /*!< vbus ignore */ +} usb_core_cfg; + +/** + * @brief usb otg core struct type + */ +typedef struct +{ + usb_reg_type *usb_reg; /*!< the usb otg register type */ +#ifdef USE_OTG_DEVICE_MODE + usbd_core_type dev; /*!< the usb device core type */ +#endif + +#ifdef USE_OTG_HOST_MODE + usbh_core_type host; /*!< the usb host core type */ +#endif + + usb_core_cfg cfg; /*!< the usb otg core config type */ + +} otg_core_type; + +usb_sts_type usb_core_config(otg_core_type *otgdev, uint8_t core_id); +#ifdef USE_OTG_DEVICE_MODE +usb_sts_type usbd_init(otg_core_type *udev, + uint8_t core_id, uint8_t usb_id, + usbd_class_handler *class_handler, + usbd_desc_handler *desc_handler); +#endif + +#ifdef USE_OTG_HOST_MODE +usb_sts_type usbh_init(otg_core_type *hdev, + uint8_t core_id, uint8_t usb_id, + usbh_class_handler_type *class_handler, + usbh_user_handler_type *user_handler); +#endif +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif + diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usb_std.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usb_std.h new file mode 100644 index 0000000000..278edb259d --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usb_std.h @@ -0,0 +1,385 @@ +/** + ************************************************************************** + * @file usb_std.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb standard header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USB_STD_H +#define __USB_STD_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* includes ------------------------------------------------------------------*/ +#include "usb_conf.h" + +/** @addtogroup AT32F435_437_middlewares_usb_drivers + * @{ + */ + +/** @addtogroup USB_standard + * @{ + */ + +/** @defgroup USB_standard_define + * @{ + */ + +/** + * @brief usb request recipient + */ +#define USB_REQ_RECIPIENT_DEVICE 0x00 /*!< usb request recipient device */ +#define USB_REQ_RECIPIENT_INTERFACE 0x01 /*!< usb request recipient interface */ +#define USB_REQ_RECIPIENT_ENDPOINT 0x02 /*!< usb request recipient endpoint */ +#define USB_REQ_RECIPIENT_OTHER 0x03 /*!< usb request recipient other */ +#define USB_REQ_RECIPIENT_MASK 0x1F /*!< usb request recipient mask */ + +/** + * @brief usb request type + */ +#define USB_REQ_TYPE_STANDARD 0x00 /*!< usb request type standard */ +#define USB_REQ_TYPE_CLASS 0x20 /*!< usb request type class */ +#define USB_REQ_TYPE_VENDOR 0x40 /*!< usb request type vendor */ +#define USB_REQ_TYPE_RESERVED 0x60 /*!< usb request type reserved */ + +/** + * @brief usb request data transfer direction + */ +#define USB_REQ_DIR_HTD 0x00 /*!< usb request data transfer direction host to device */ +#define USB_REQ_DIR_DTH 0x80 /*!< usb request data transfer direction device to host */ + +/** + * @brief usb standard device requests codes + */ +#define USB_STD_REQ_GET_STATUS 0 /*!< usb request code status */ +#define USB_STD_REQ_CLEAR_FEATURE 1 /*!< usb request code clear feature */ +#define USB_STD_REQ_SET_FEATURE 3 /*!< usb request code feature */ +#define USB_STD_REQ_SET_ADDRESS 5 /*!< usb request code address */ +#define USB_STD_REQ_GET_DESCRIPTOR 6 /*!< usb request code get descriptor */ +#define USB_STD_REQ_SET_DESCRIPTOR 7 /*!< usb request code set descriptor */ +#define USB_STD_REQ_GET_CONFIGURATION 8 /*!< usb request code get configuration */ +#define USB_STD_REQ_SET_CONFIGURATION 9 /*!< usb request code set configuration */ +#define USB_STD_REQ_GET_INTERFACE 10 /*!< usb request code get interface */ +#define USB_STD_REQ_SET_INTERFACE 11 /*!< usb request code set interface */ +#define USB_STD_REQ_SYNCH_FRAME 12 /*!< usb request code synch frame */ + +/** + * @brief usb standard device type + */ +#define USB_DESCIPTOR_TYPE_DEVICE 1 /*!< usb standard device type device */ +#define USB_DESCIPTOR_TYPE_CONFIGURATION 2 /*!< usb standard device type configuration */ +#define USB_DESCIPTOR_TYPE_STRING 3 /*!< usb standard device type string */ +#define USB_DESCIPTOR_TYPE_INTERFACE 4 /*!< usb standard device type interface */ +#define USB_DESCIPTOR_TYPE_ENDPOINT 5 /*!< usb standard device type endpoint */ +#define USB_DESCIPTOR_TYPE_DEVICE_QUALIFIER 6 /*!< usb standard device type qualifier */ +#define USB_DESCIPTOR_TYPE_OTHER_SPEED 7 /*!< usb standard device type other speed */ +#define USB_DESCIPTOR_TYPE_INTERFACE_POWER 8 /*!< usb standard device type interface power */ + +/** + * @brief usb standard string type + */ +#define USB_LANGID_STRING 0 /*!< usb standard string type lang id */ +#define USB_MFC_STRING 1 /*!< usb standard string type mfc */ +#define USB_PRODUCT_STRING 2 /*!< usb standard string type product */ +#define USB_SERIAL_STRING 3 /*!< usb standard string type serial */ +#define USB_CONFIG_STRING 4 /*!< usb standard string type config */ +#define USB_INTERFACE_STRING 5 /*!< usb standard string type interface */ + +/** + * @brief usb configuration attributes + */ +#define USB_CONF_REMOTE_WAKEUP 2 /*!< usb configuration attributes remote wakeup */ +#define USB_CONF_SELF_POWERED 1 /*!< usb configuration attributes self powered */ + +/** + * @brief usb standard feature selectors + */ +#define USB_FEATURE_EPT_HALT 0 /*!< usb standard feature selectors endpoint halt */ +#define USB_FEATURE_REMOTE_WAKEUP 1 /*!< usb standard feature selectors remote wakeup */ +#define USB_FEATURE_TEST_MODE 2 /*!< usb standard feature selectors test mode */ + +/** + * @brief usb device connect state + */ +typedef enum +{ + USB_CONN_STATE_DEFAULT =1, /*!< usb device connect state default */ + USB_CONN_STATE_ADDRESSED, /*!< usb device connect state address */ + USB_CONN_STATE_CONFIGURED, /*!< usb device connect state configured */ + USB_CONN_STATE_SUSPENDED /*!< usb device connect state suspend */ +}usbd_conn_state; + +/** + * @brief endpoint 0 state + */ +#define USB_EPT0_IDLE 0 /*!< usb endpoint state idle */ +#define USB_EPT0_SETUP 1 /*!< usb endpoint state setup */ +#define USB_EPT0_DATA_IN 2 /*!< usb endpoint state data in */ +#define USB_EPT0_DATA_OUT 3 /*!< usb endpoint state data out */ +#define USB_EPT0_STATUS_IN 4 /*!< usb endpoint state status in */ +#define USB_EPT0_STATUS_OUT 5 /*!< usb endpoint state status out */ +#define USB_EPT0_STALL 6 /*!< usb endpoint state stall */ + +/** + * @brief usb descriptor length + */ +#define USB_DEVICE_QUALIFIER_DESC_LEN 0x0A /*!< usb qualifier descriptor length */ +#define USB_DEVICE_DESC_LEN 0x12 /*!< usb device descriptor length */ +#define USB_DEVICE_CFG_DESC_LEN 0x09 /*!< usb configuration descriptor length */ +#define USB_DEVICE_IF_DESC_LEN 0x09 /*!< usb interface descriptor length */ +#define USB_DEVICE_EPT_LEN 0x07 /*!< usb endpoint descriptor length */ +#define USB_DEVICE_OTG_DESC_LEN 0x03 /*!< usb otg descriptor length */ +#define USB_DEVICE_LANGID_STR_DESC_LEN 0x04 /*!< usb lang id string descriptor length */ +#define USB_DEVICE_OTHER_SPEED_DESC_SIZ_LEN 0x09 /*!< usb other speed descriptor length */ + +/** + * @brief usb class code + */ +#define USB_CLASS_CODE_AUDIO 0x01 /*!< usb class code audio */ +#define USB_CLASS_CODE_CDC 0x02 /*!< usb class code cdc */ +#define USB_CLASS_CODE_HID 0x03 /*!< usb class code hid */ +#define USB_CLASS_CODE_PRINTER 0x07 /*!< usb class code printer */ +#define USB_CLASS_CODE_MSC 0x08 /*!< usb class code msc */ +#define USB_CLASS_CODE_HUB 0x09 /*!< usb class code hub */ +#define USB_CLASS_CODE_CDCDATA 0x0A /*!< usb class code cdc data */ +#define USB_CLASS_CODE_CCID 0x0B /*!< usb class code ccid */ +#define USB_CLASS_CODE_VIDEO 0x0E /*!< usb class code video */ +#define USB_CLASS_CODE_VENDOR 0xFF /*!< usb class code vendor */ + +/** + * @brief usb endpoint type + */ +#define USB_EPT_DESC_CONTROL 0x00 /*!< usb endpoint description type control */ +#define USB_EPT_DESC_ISO 0x01 /*!< usb endpoint description type iso */ +#define USB_EPT_DESC_BULK 0x02 /*!< usb endpoint description type bulk */ +#define USB_EPT_DESC_INTERRUPT 0x03 /*!< usb endpoint description type interrupt */ + +#define USB_EPT_DESC_NSYNC 0x00 /*!< usb endpoint description nsync */ +#define USB_ETP_DESC_ASYNC 0x04 /*!< usb endpoint description async */ +#define USB_ETP_DESC_ADAPTIVE 0x08 /*!< usb endpoint description adaptive */ +#define USB_ETP_DESC_SYNC 0x0C /*!< usb endpoint description sync */ + +#define USB_EPT_DESC_DATA_EPT 0x00 /*!< usb endpoint description data */ +#define USB_EPT_DESC_FD_EPT 0x10 /*!< usb endpoint description fd */ +#define USB_EPT_DESC_FDDATA_EPT 0x20 /*!< usb endpoint description fddata */ + +/** + * @brief usb cdc class descriptor define + */ +#define USBD_CDC_CS_INTERFACE 0x24 +#define USBD_CDC_CS_ENDPOINT 0x25 + +/** + * @brief usb cdc class sub-type define + */ +#define USBD_CDC_SUBTYPE_HEADER 0x00 +#define USBD_CDC_SUBTYPE_CMF 0x01 +#define USBD_CDC_SUBTYPE_ACM 0x02 +#define USBD_CDC_SUBTYPE_UFD 0x06 + +/** + * @brief usb cdc class request code define + */ +#define SET_LINE_CODING 0x20 +#define GET_LINE_CODING 0x21 + +/** + * @brief usb cdc class set line coding struct + */ +typedef struct +{ + uint32_t bitrate; /* line coding baud rate */ + uint8_t format; /* line coding foramt */ + uint8_t parity; /* line coding parity */ + uint8_t data; /* line coding data bit */ +}linecoding_type; + +/** + * @brief usb hid class descriptor define + */ +#define HID_CLASS_DESC_HID 0x21 +#define HID_CLASS_DESC_REPORT 0x22 +#define HID_CLASS_DESC_PHYSICAL 0x23 + +/** + * @brief usb hid class request code define + */ +#define HID_REQ_SET_PROTOCOL 0x0B +#define HID_REQ_GET_PROTOCOL 0x03 +#define HID_REQ_SET_IDLE 0x0A +#define HID_REQ_GET_IDLE 0x02 +#define HID_REQ_SET_REPORT 0x09 +#define HID_REQ_GET_REPORT 0x01 +#define HID_DESCRIPTOR_TYPE 0x21 +#define HID_REPORT_DESC 0x22 + +/** + * @brief endpoint 0 max size + */ +#define USB_MAX_EP0_SIZE 64 /*!< usb endpoint 0 max size */ + +/** + * @brief usb swap address + */ +#define SWAPBYTE(addr) (uint16_t)(((uint16_t)(*((uint8_t *)(addr)))) + \ + (((uint16_t)(*(((uint8_t *)(addr)) + 1))) << 8)) /*!< swap address */ + +/** + * @brief min and max define + */ +#define MIN(a, b) (uint16_t)(((a) < (b)) ? (a) : (b)) /*!< min define*/ +#define MAX(a, b) (uint16_t)(((a) > (b)) ? (a) : (b)) /*!< max define*/ + +/** + * @brief low byte and high byte define + */ +#define LBYTE(x) ((uint8_t)(x & 0x00FF)) /*!< low byte define */ +#define HBYTE(x) ((uint8_t)((x & 0xFF00) >>8)) /*!< high byte define*/ + +/** + * @brief usb return status + */ +typedef enum +{ + USB_OK, /*!< usb status ok */ + USB_FAIL, /*!< usb status fail */ + USB_WAIT, /*!< usb status wait */ + USB_NOT_SUPPORT, /*!< usb status not support */ + USB_ERROR, /*!< usb status error */ +}usb_sts_type; + + +/** + * @brief format of usb setup data + */ +typedef struct +{ + uint8_t bmRequestType; /*!< characteristics of request */ + uint8_t bRequest; /*!< specific request */ + uint16_t wValue; /*!< word-sized field that varies according to request */ + uint16_t wIndex; /*!< word-sized field that varies according to request + typically used to pass an index or offset */ + uint16_t wLength; /*!< number of bytes to transfer if there is a data stage */ +} usb_setup_type; + +/** + * @brief format of standard device descriptor + */ +typedef struct +{ + uint8_t bLength; /*!< size of this descriptor in bytes */ + uint8_t bDescriptorType; /*!< device descriptor type */ + uint16_t bcdUSB; /*!< usb specification release number */ + uint8_t bDeviceClass; /*!< class code (assigned by the usb-if) */ + uint8_t bDeviceSubClass; /*!< subclass code (assigned by the usb-if) */ + uint8_t bDeviceProtocol; /*!< protocol code ((assigned by the usb-if)) */ + uint8_t bMaxPacketSize0; /*!< maximum packet size for endpoint zero */ + uint16_t idVendor; /*!< verndor id ((assigned by the usb-if)) */ + uint16_t idProduct; /*!< product id ((assigned by the usb-if)) */ + uint16_t bcdDevice; /*!< device release number in binary-coded decimal */ + uint8_t iManufacturer; /*!< index of string descriptor describing manufacturer */ + uint8_t iProduct; /*!< index of string descriptor describing product */ + uint8_t iSerialNumber; /*!< index of string descriptor describing serial number */ + uint8_t bNumConfigurations; /*!< number of possible configurations */ +} usb_device_desc_type; + +/** + * @brief format of standard configuration descriptor + */ +typedef struct +{ + uint8_t bLength; /*!< size of this descriptor in bytes */ + uint8_t bDescriptorType; /*!< configuration descriptor type */ + uint16_t wTotalLength; /*!< total length of data returned for this configuration */ + uint8_t bNumInterfaces; /*!< number of interfaces supported by this configuration */ + uint8_t bConfigurationValue; /*!< value to use as an argument to the SetConfiguration() request */ + uint8_t iConfiguration; /*!< index of string descriptor describing this configuration */ + uint8_t bmAttributes; /*!< configuration characteristics + D7 reserved + D6 self-powered + D5 remote wakeup + D4~D0 reserved */ + uint8_t bMaxPower; /*!< maximum power consumption of the usb device from the bus */ + + +}usb_configuration_desc_type; + +/** + * @brief format of standard interface descriptor + */ +typedef struct +{ + uint8_t bLength; /*!< size of this descriptor in bytes */ + uint8_t bDescriptorType; /*!< interface descriptor type */ + uint8_t bInterfaceNumber; /*!< number of this interface */ + uint8_t bAlternateSetting; /*!< value used to select this alternate setting for the interface */ + uint8_t bNumEndpoints; /*!< number of endpoints used by this interface */ + uint8_t bInterfaceClass; /*!< class code (assigned by the usb-if) */ + uint8_t bInterfaceSubClass; /*!< subclass code (assigned by the usb-if) */ + uint8_t bInterfaceProtocol; /*!< protocol code (assigned by the usb-if) */ + uint8_t iInterface; /*!< index of string descriptor describing this interface */ +} usb_interface_desc_type; + +/** + * @brief format of standard endpoint descriptor + */ +typedef struct +{ + uint8_t bLength; /*!< size of this descriptor in bytes */ + uint8_t bDescriptorType; /*!< endpoint descriptor type */ + uint8_t bEndpointAddress; /*!< the address of the endpoint on the usb device described by this descriptor */ + uint8_t bmAttributes; /*!< describes the endpoints attributes when it is configured using bConfiguration value */ + uint16_t wMaxPacketSize; /*!< maximum packet size this endpoint */ + uint8_t bInterval; /*!< interval for polling endpoint for data transfers */ +} usb_endpoint_desc_type; + +/** + * @brief format of header + */ +typedef struct +{ + uint8_t bLength; /*!< size of this descriptor in bytes */ + uint8_t bDescriptorType; /*!< descriptor type */ +} usb_header_desc_type; + + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif + diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbd_core.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbd_core.h new file mode 100644 index 0000000000..35bdddc2ce --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbd_core.h @@ -0,0 +1,187 @@ +/** + ************************************************************************** + * @file usbd_core.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb device core header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USBD_CORE_H +#define __USBD_CORE_H + +#ifdef __cplusplus +extern "C" { +#endif + + +#include "usb_conf.h" +#include "usb_std.h" + +/** @addtogroup AT32F435_437_middlewares_usbd_drivers + * @{ + */ + +/** @addtogroup USBD_drivers_core + * @{ + */ + +/** @defgroup USBD_core_exported_types + * @{ + */ + +#ifdef USE_OTG_DEVICE_MODE + +/** + * @brief usb device event + */ +typedef enum +{ + USBD_NOP_EVENT, /*!< usb device nop event */ + USBD_RESET_EVENT, /*!< usb device reset event */ + USBD_SUSPEND_EVENT, /*!< usb device suspend event */ + USBD_WAKEUP_EVENT, /*!< usb device wakeup event */ + USBD_DISCONNECT_EVNET, /*!< usb device disconnect event */ + USBD_INISOINCOM_EVENT, /*!< usb device inisoincom event */ + USBD_OUTISOINCOM_EVENT, /*!< usb device outisoincom event */ + USBD_ERR_EVENT /*!< usb device error event */ +}usbd_event_type; + +/** + * @brief usb device descriptor struct + */ +typedef struct +{ + uint16_t length; /*!< descriptor length */ + uint8_t *descriptor; /*!< descriptor string */ +}usbd_desc_t; + +/** + * @brief usb device descriptor handler + */ +typedef struct +{ + usbd_desc_t *(*get_device_descriptor)(void); /*!< get device descriptor callback */ + usbd_desc_t *(*get_device_qualifier)(void); /*!< get device qualifier callback */ + usbd_desc_t *(*get_device_configuration)(void); /*!< get device configuration callback */ + usbd_desc_t *(*get_device_other_speed)(void); /*!< get device other speed callback */ + usbd_desc_t *(*get_device_lang_id)(void); /*!< get device lang id callback */ + usbd_desc_t *(*get_device_manufacturer_string)(void); /*!< get device manufacturer callback */ + usbd_desc_t *(*get_device_product_string)(void); /*!< get device product callback */ + usbd_desc_t *(*get_device_serial_string)(void); /*!< get device serial callback */ + usbd_desc_t *(*get_device_interface_string)(void); /*!< get device interface string callback */ + usbd_desc_t *(*get_device_config_string)(void); /*!< get device device config callback */ +}usbd_desc_handler; + +/** + * @brief usb device class handler + */ +typedef struct +{ + usb_sts_type (*init_handler)(void *udev); /*!< usb class init handler */ + usb_sts_type (*clear_handler)(void *udev); /*!< usb class clear handler */ + usb_sts_type (*setup_handler)(void *udev, usb_setup_type *setup); /*!< usb class setup handler */ + usb_sts_type (*ept0_tx_handler)(void *udev); /*!< usb class endpoint 0 tx complete handler */ + usb_sts_type (*ept0_rx_handler)(void *udev); /*!< usb class endpoint 0 rx complete handler */ + usb_sts_type (*in_handler)(void *udev, uint8_t ept_num); /*!< usb class in transfer complete handler */ + usb_sts_type (*out_handler)(void *udev, uint8_t ept_num); /*!< usb class out transfer complete handler */ + usb_sts_type (*sof_handler)(void *udev); /*!< usb class sof handler */ + usb_sts_type (*event_handler)(void *udev, usbd_event_type event); /*!< usb class event handler */ + void *pdata; /*!< usb class data pointer */ +}usbd_class_handler; + +/** + * @brief usb device core struct type + */ +typedef struct +{ + usb_reg_type *usb_reg; /*!< usb register pointer */ + + usbd_class_handler *class_handler; /*!< usb device class handler pointer */ + usbd_desc_handler *desc_handler; /*!< usb device descriptor handler pointer */ + + usb_ept_info ept_in[USB_EPT_MAX_NUM]; /*!< usb in endpoint infomation struct */ + usb_ept_info ept_out[USB_EPT_MAX_NUM]; /*!< usb out endpoint infomation struct */ + + usb_setup_type setup; /*!< usb setup type struct */ + uint8_t setup_buffer[12]; /*!< usb setup request buffer */ + + uint8_t ept0_sts; /*!< usb control endpoint 0 state */ + uint8_t speed; /*!< usb speed */ + uint16_t ept0_wlength; /*!< usb endpoint 0 transfer length */ + + usbd_conn_state conn_state; /*!< usb current connect state */ + usbd_conn_state old_conn_state; /*!< usb save the previous connect state */ + + uint8_t device_addr; /*!< device address */ + uint8_t remote_wakup; /*!< remote wakeup state */ + uint8_t default_config; /*!< usb default config state */ + uint8_t dev_config; /*!< usb device config state */ + uint32_t config_status; /*!< usb configure status */ +}usbd_core_type; + +void usbd_core_in_handler(usbd_core_type *udev, uint8_t ept_num); +void usbd_core_out_handler(usbd_core_type *udev, uint8_t ept_num); +void usbd_core_setup_handler(usbd_core_type *udev, uint8_t ept_num); +void usbd_ctrl_unsupport(usbd_core_type *udev); +void usbd_ctrl_send(usbd_core_type *udev, uint8_t *buffer, uint16_t len); +void usbd_ctrl_recv(usbd_core_type *udev, uint8_t *buffer, uint16_t len); +void usbd_ctrl_send_status(usbd_core_type *udev); +void usbd_ctrl_recv_status(usbd_core_type *udev); +void usbd_set_stall(usbd_core_type *udev, uint8_t ept_addr); +void usbd_clear_stall(usbd_core_type *udev, uint8_t ept_addr); +void usbd_ept_open(usbd_core_type *udev, uint8_t ept_addr, uint8_t ept_type, uint16_t maxpacket); +void usbd_ept_close(usbd_core_type *udev, uint8_t ept_addr); +void usbd_ept_send(usbd_core_type *udev, uint8_t ept_num, uint8_t *buffer, uint16_t len); +void usbd_ept_recv(usbd_core_type *udev, uint8_t ept_num, uint8_t *buffer, uint16_t len); +void usbd_connect(usbd_core_type *udev); +void usbd_disconnect(usbd_core_type *udev); +void usbd_set_device_addr(usbd_core_type *udev, uint8_t address); +uint32_t usbd_get_recv_len(usbd_core_type *udev, uint8_t ept_addr); +void usb_ept_defaut_init(usbd_core_type *udev); +usbd_conn_state usbd_connect_state_get(usbd_core_type *udev); +void usbd_remote_wakeup(usbd_core_type *udev); +void usbd_enter_suspend(usbd_core_type *udev); +void usbd_flush_tx_fifo(usbd_core_type *udev, uint8_t ept_num); +void usbd_fifo_alloc(usbd_core_type *udev); +usb_sts_type usbd_core_init(usbd_core_type *udev, + usb_reg_type *usb_reg, + usbd_class_handler *class_handler, + usbd_desc_handler *desc_handler, + uint8_t core_id); +#endif + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbd_int.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbd_int.h new file mode 100644 index 0000000000..9387340d74 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbd_int.h @@ -0,0 +1,82 @@ +/** + ************************************************************************** + * @file usbd_int.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb interrupt header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USBD_INT_H +#define __USBD_INT_H + +#ifdef __cplusplus +extern "C" { +#endif + +/** @addtogroup AT32F435_437_middlewares_usbd_drivers + * @{ + */ + +/** @addtogroup USBD_drivers_int + * @{ + */ + +/** @defgroup USBD_interrupt_exported_types + * @{ + */ +/* includes ------------------------------------------------------------------*/ +#include "usbd_core.h" +#include "usb_core.h" + +void usbd_irq_handler(otg_core_type *udev); +void usbd_ept_handler(usbd_core_type *udev); +void usbd_reset_handler(usbd_core_type *udev); +void usbd_sof_handler(usbd_core_type *udev); +void usbd_suspend_handler(usbd_core_type *udev); +void usbd_wakeup_handler(usbd_core_type *udev); +void usbd_inept_handler(usbd_core_type *udev); +void usbd_outept_handler(usbd_core_type *udev); +void usbd_enumdone_handler(usbd_core_type *udev); +void usbd_rxflvl_handler(usbd_core_type *udev); +void usbd_incomisioin_handler(usbd_core_type *udev); +void usbd_discon_handler(usbd_core_type *udev); +void usbd_incomisoout_handler(usbd_core_type *udev); +void usb_write_empty_txfifo(usbd_core_type *udev, uint32_t ept_num); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif + diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbd_sdr.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbd_sdr.h new file mode 100644 index 0000000000..052f7d1a7b --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbd_sdr.h @@ -0,0 +1,73 @@ +/** + ************************************************************************** + * @file usb_sdr.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USB_SDR_H +#define __USB_SDR_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* includes ------------------------------------------------------------------*/ +#include "usb_conf.h" +#include "usb_core.h" +/** @addtogroup AT32F435_437_middlewares_usbd_drivers + * @{ + */ + +/** @addtogroup USBD_drivers_standard_request + * @{ + */ + +/** @defgroup USBD_sdr_exported_functions + * @{ + */ + + +void usbd_setup_request_parse(usb_setup_type *setup, uint8_t *buf); +usb_sts_type usbd_device_request(usbd_core_type *udev); +usb_sts_type usbd_interface_request(usbd_core_type *udev); +usb_sts_type usbd_endpoint_request(usbd_core_type *udev); + + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbh_core.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbh_core.h new file mode 100644 index 0000000000..10accd9743 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbh_core.h @@ -0,0 +1,375 @@ +/** + ************************************************************************** + * @file usbh_core.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb host core header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USBH_CORE_H +#define __USBH_CORE_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "usb_conf.h" +#include "usb_std.h" + +/** @addtogroup AT32F435_437_middlewares_usbh_drivers + * @{ + */ + +/** @addtogroup USBH_drivers_core + * @{ + */ + +/** @defgroup USBH_core_exported_types + * @{ + */ + + +#ifdef USE_OTG_HOST_MODE + +/** + * @brief usb channel flag + */ +typedef enum +{ + HCH_IDLE, /*!< usb host channel idle */ + HCH_XFRC, /*!< usb host channel transfer completed */ + HCH_HALTED, /*!< usb host channel halted */ + HCH_NAK, /*!< usb host channel nak */ + HCH_NYET, /*!< usb host channel nyet */ + HCH_STALL, /*!< usb host channel stall */ + HCH_XACTERR, /*!< usb host channel transaction error */ + HCH_BBLERR, /*!< usb host channel babble error */ + HCH_DATATGLERR /*!< usb host channel data toggle error */ +} hch_sts_type; + +/** + * @brief usb channel state + */ +typedef enum +{ + URB_IDLE = 0, /*!< usb request idle state */ + URB_DONE, /*!< usb request done state */ + URB_NOTREADY, /*!< usb request not ready state */ + URB_NYET, /*!< usb request nyet stat e*/ + URB_ERROR, /*!< usb request error state */ + URB_STALL /*!< usb request stall state */ +} urb_sts_type; + +/** + * @brief usb control channel flag + */ +typedef enum +{ + CTRL_START = 0, /*!< usb control request start */ + CTRL_XFERC, /*!< usb control request completed */ + CTRL_HALTED, /*!< usb control request halted */ + CTRL_NAK, /*!< usb control request nak */ + CTRL_STALL, /*!< usb control request stall */ + CTRL_XACTERR, /*!< usb control request transaction error */ + CTRL_BBLERR, /*!< usb control request babble error */ + CTRL_DATATGLERR, /*!< usb control request data toggle error */ + CTRL_FAIL /*!< usb control request failed */ +} ctrl_sts_type; + +/** + * @brief usb host control state machine + */ +typedef enum +{ + CONTROL_IDLE, /*!< usb control state idle */ + CONTROL_SETUP, /*!< usb control state setup */ + CONTROL_SETUP_WAIT, /*!< usb control state setup wait */ + CONTROL_DATA_IN, /*!< usb control state data in */ + CONTROL_DATA_IN_WAIT, /*!< usb control state data in wait */ + CONTROL_DATA_OUT, /*!< usb control state data out */ + CONTROL_DATA_OUT_WAIT, /*!< usb control state data out wait */ + CONTROL_STATUS_IN, /*!< usb control state status in */ + CONTROL_STATUS_IN_WAIT, /*!< usb control state status in wait */ + CONTROL_STATUS_OUT, /*!< usb control state out */ + CONTROL_STATUS_OUT_WAIT, /*!< usb control state out wait */ + CONTROL_ERROR, /*!< usb control state error */ + CONTROL_STALL, /*!< usb control state stall */ + CONTROL_COMPLETE /*!< usb control state complete */ +} ctrl_ept0_sts_type; + +/** + * @brief usb host enumration state machine + */ +typedef enum +{ + ENUM_IDLE, /*!< usb host enumration state idle */ + ENUM_GET_MIN_DESC, /*!< usb host enumration state get descriptor 8 byte*/ + ENUM_GET_FULL_DESC, /*!< usb host enumration state get descriptor 18 byte*/ + ENUM_SET_ADDR, /*!< usb host enumration state set address */ + ENUM_GET_CFG, /*!< usb host enumration state get configuration */ + ENUM_GET_FULL_CFG, /*!< usb host enumration state get full configuration */ + ENUM_GET_MFC_STRING, /*!< usb host enumration state get manufacturer string */ + ENUM_GET_PRODUCT_STRING, /*!< usb host enumration state get product string */ + ENUM_GET_SERIALNUM_STRING, /*!< usb host enumration state get serial number string */ + ENUM_SET_CONFIG, /*!< usb host enumration state set config */ + ENUM_COMPLETE, /*!< usb host enumration state complete */ +} usbh_enum_sts_type; + +/** + * @brief usb host global state machine + */ +typedef enum +{ + USBH_IDLE, /*!< usb host global state idle */ + USBH_PORT_EN, /*!< usb host global state port enable */ + USBH_ATTACHED, /*!< usb host global state attached */ + USBH_DISCONNECT, /*!< usb host global state disconnect */ + USBH_DEV_SPEED, /*!< usb host global state device speed */ + USBH_ENUMERATION, /*!< usb host global state enumeration */ + USBH_CLASS_REQUEST, /*!< usb host global state class request */ + USBH_CLASS, /*!< usb host global state class */ + USBH_CTRL_XFER, /*!< usb host global state control transfer */ + USBH_USER_HANDLER, /*!< usb host global state user handler */ + USBH_SUSPEND, /*!< usb host global state suspend */ + USBH_SUSPENDED, /*!< usb host have in suspend mode */ + USBH_WAKEUP, /*!< usb host global state wakeup */ + USBH_UNSUPPORT, /*!< usb host global unsupport device */ + USBH_ERROR_STATE, /*!< usb host global state error */ +} usbh_gstate_type; + +/** + * @brief usb host transfer state + */ +typedef enum +{ + CMD_IDLE, /*!< usb host transfer state idle */ + CMD_SEND, /*!< usb host transfer state send */ + CMD_WAIT /*!< usb host transfer state wait */ +} cmd_sts_type; + +/** + * @brief usb host channel malloc state + */ +#define HCH_OK 0x0000 /*!< usb channel malloc state ok */ +#define HCH_USED 0x8000 /*!< usb channel had used */ +#define HCH_ERROR 0xFFFF /*!< usb channel error */ +#define HCH_USED_MASK 0x7FFF /*!< usb channel use mask */ + +/** + * @brief channel pid + */ +#define HCH_PID_DATA0 0 /*!< usb channel pid data 0 */ +#define HCH_PID_DATA2 1 /*!< usb channel pid data 2 */ +#define HCH_PID_DATA1 2 /*!< usb channel pid data 1 */ +#define HCH_PID_SETUP 3 /*!< usb channel pid setup */ + +/** + * @brief channel data transfer direction + */ +#define USB_REQUEST_DIR_MASK 0x80 /*!< usb request direction mask */ +#define USB_DIR_H2D USB_REQ_DIR_HTD /*!< usb request direction host to device */ +#define USB_DIR_D2H USB_REQ_DIR_DTH /*!< usb request direction device to host */ + +/** + * @brief request timeout + */ +#define DATA_STAGE_TIMEOUT 5000 /*!< usb data stage timeout */ +#define NODATA_STAGE_TIMEOUT 50 /*!< usb no-data stage timeout */ + +/** + * @brief max interface and endpoint + */ +#define USBH_MAX_ERROR_COUNT 2 /*!< usb support maximum error */ +#define USBH_MAX_INTERFACE 5 /*!< usb support maximum interface */ +#define USBH_MAX_ENDPOINT 5 /*!< usb support maximum endpoint */ + +/** + * @brief interface descriptor + */ +typedef struct +{ + usb_interface_desc_type interface; /*!< usb device interface descriptor structure */ + usb_endpoint_desc_type endpoint[USBH_MAX_ENDPOINT]; /*!< usb device endpoint descriptor structure array */ +} usb_itf_desc_type; + +/** + * @brief configure descriptor + */ +typedef struct +{ + usb_configuration_desc_type cfg; /*!< usb device configuration descriptor structure */ + usb_itf_desc_type interface[USBH_MAX_INTERFACE]; /*!< usb device interface descriptor structure array*/ +} usb_cfg_desc_type; + +/** + * @brief device descriptor + */ +typedef struct +{ + uint8_t address; /*!< usb device address */ + uint8_t speed; /*!< usb device speed */ + usb_device_desc_type dev_desc; /*!< usb device descriptor */ + usb_cfg_desc_type cfg_desc; /*!< usb device configuration */ +} usbh_dev_desc_type; + +/** + * @brief usb host control struct type + */ +typedef struct +{ + uint8_t hch_in; /*!< in channel number */ + uint8_t hch_out; /*!< out channel number */ + uint8_t ept0_size; /*!< endpoint 0 size */ + uint8_t *buffer; /*!< endpoint 0 transfer buffer */ + usb_setup_type setup; /*!< control setup type */ + uint16_t len; /*!< transfer length */ + uint8_t err_cnt; /*!< error counter */ + uint32_t timer; /*!< transfer timer */ + ctrl_sts_type sts; /*!< control transfer status */ + ctrl_ept0_sts_type state; /*!< endpoint 0 state */ +} usbh_ctrl_type; + +/** + * @brief host class handler type + */ +typedef struct +{ + usb_sts_type (*init_handler)(void *uhost); /*!< usb host class init handler */ + usb_sts_type (*reset_handler)(void *uhost); /*!< usb host class reset handler */ + usb_sts_type (*request_handler)(void *uhost); /*!< usb host class request handler */ + usb_sts_type (*process_handler)(void *uhost); /*!< usb host class process handler */ + void *pdata; /*!< usb host class data */ +} usbh_class_handler_type; + +/** + * @brief host user handler type + */ +typedef struct +{ + usb_sts_type (*user_init)(void); /*!< usb host user init handler */ + usb_sts_type (*user_reset)(void); /*!< usb host user reset handler */ + usb_sts_type (*user_attached)(void); /*!< usb host user attached handler */ + usb_sts_type (*user_disconnect)(void); /*!< usb host user disconnect handler */ + usb_sts_type (*user_speed)(uint8_t speed); /*!< usb host user speed handler */ + usb_sts_type (*user_mfc_string)(void *); /*!< usb host user manufacturer string handler */ + usb_sts_type (*user_product_string)(void *); /*!< usb host user product string handler */ + usb_sts_type (*user_serial_string)(void *); /*!< usb host user serial handler */ + usb_sts_type (*user_enumeration_done)(void); /*!< usb host user enumeration done handler */ + usb_sts_type (*user_application)(void); /*!< usb host user application handler */ + usb_sts_type (*user_active_vbus)(void *uhost, confirm_state state); /*!< usb host user active vbus */ + usb_sts_type (*user_not_support)(void); /*!< usb host user not support handler */ +} usbh_user_handler_type; + +/** + * @brief host host core handler type + */ +typedef struct +{ + usb_reg_type *usb_reg; /*!< usb register pointer */ + + uint8_t global_state; /*!< usb host global state machine */ + uint8_t enum_state; /*!< usb host enumeration state machine */ + uint8_t req_state; /*!< usb host request state machine */ + + usbh_dev_desc_type dev; /*!< usb device descriptor */ + usbh_ctrl_type ctrl; /*!< usb host control transfer struct */ + + usbh_class_handler_type *class_handler; /*!< usb host class handler pointer */ + usbh_user_handler_type *user_handler; /*!< usb host user handler pointer */ + + usb_hch_type hch[USB_HOST_CHANNEL_NUM]; /*!< usb host channel array */ + uint8_t rx_buffer[USB_MAX_DATA_LENGTH]; /*!< usb host rx buffer */ + + uint32_t conn_sts; /*!< connect status */ + uint32_t port_enable; /*!< port enable status */ + uint32_t timer; /*!< sof timer */ + + uint32_t err_cnt[USB_HOST_CHANNEL_NUM]; /*!< error counter */ + uint32_t xfer_cnt[USB_HOST_CHANNEL_NUM]; /*!< xfer counter */ + hch_sts_type hch_state[USB_HOST_CHANNEL_NUM];/*!< channel state */ + urb_sts_type urb_state[USB_HOST_CHANNEL_NUM];/*!< usb request state */ + uint16_t channel[USB_HOST_CHANNEL_NUM]; /*!< channel array */ +} usbh_core_type; + + +void usbh_free_channel(usbh_core_type *uhost, uint8_t index); +uint16_t usbh_get_free_channel(usbh_core_type *uhost); +usb_sts_type usbh_set_toggle(usbh_core_type *uhost, uint8_t hc_num, uint8_t toggle); +usb_sts_type usbh_in_out_request(usbh_core_type *uhost, uint8_t hc_num); +usb_sts_type usbh_interrupt_recv(usbh_core_type *uhost, uint8_t hc_num, + uint8_t *buffer, uint16_t length); +usb_sts_type usbh_interrupt_send(usbh_core_type *uhost, uint8_t hc_num, + uint8_t *buffer, uint16_t length); +usb_sts_type usbh_bulk_recv(usbh_core_type *uhost, uint8_t hc_num, + uint8_t *buffer, uint16_t length); +usb_sts_type usbh_bulk_send(usbh_core_type *uhost, uint8_t hc_num, + uint8_t *buffer, uint16_t length); +usb_sts_type usbh_isoc_send(usbh_core_type *uhost, uint8_t hc_num, + uint8_t *buffer, uint16_t length); +usb_sts_type usbh_isoc_recv(usbh_core_type *uhost, uint8_t hc_num, + uint8_t *buffer, uint16_t length); +usb_sts_type usbh_cfg_default_init(usbh_core_type *uhost); +void usbh_enter_suspend(usbh_core_type *uhost); +void usbh_resume(usbh_core_type *uhost); + +uint16_t usbh_alloc_channel(usbh_core_type *uhost, uint8_t ept_addr); +urb_sts_type usbh_get_urb_status(usbh_core_type *uhost, uint8_t ch_num); +usb_sts_type usbh_ctrl_result_check(usbh_core_type *uhost, + ctrl_ept0_sts_type next_ctrl_state, + uint8_t next_enum_state); +uint8_t usbh_alloc_address(void); +void usbh_reset_port(usbh_core_type *uhost); +usb_sts_type usbh_loop_handler(usbh_core_type *uhost); +void usbh_ch_disable(usbh_core_type *uhost, uint8_t chn); +void usbh_hc_open(usbh_core_type *uhost, + uint8_t chn, + uint8_t ept_num, + uint8_t dev_address, + uint8_t type, + uint16_t maxpacket, + uint8_t speed); +void usbh_active_vbus(usbh_core_type *uhost, confirm_state state); + +usb_sts_type usbh_core_init(usbh_core_type *uhost, + usb_reg_type *usb_reg, + usbh_class_handler_type *class_handler, + usbh_user_handler_type *user_handler, + uint8_t core_id); +#endif + + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbh_ctrl.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbh_ctrl.h new file mode 100644 index 0000000000..c059e693e3 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbh_ctrl.h @@ -0,0 +1,109 @@ +/** + ************************************************************************** + * @file usbh_ctrl.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USBH_CTRL_H +#define __USBH_CTRL_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* includes ------------------------------------------------------------------*/ +#include "usb_conf.h" +#include "usbh_core.h" + +/** @addtogroup AT32F435_437_middlewares_usbh_drivers + * @{ + */ + +/** @addtogroup USBH_drivers_control + * @{ + */ + +/** @defgroup USBH_ctrl_exported_types + * @{ + */ + +usb_sts_type usbh_ctrl_send_setup(usbh_core_type *uhost, uint8_t *buffer, uint8_t hc_num); +usb_sts_type usbh_ctrl_recv_data(usbh_core_type *uhost, uint8_t *buffer, + uint16_t length, uint16_t hc_num); +usb_sts_type usbh_ctrl_send_data(usbh_core_type *uhost, uint8_t *buffer, + uint16_t length, uint16_t hc_num); +usb_sts_type usbh_ctrl_setup_handler(usbh_core_type *uhost); +usb_sts_type usbh_ctrl_setup_wait_handler(usbh_core_type *uhost, uint32_t *timeout); +usb_sts_type usbh_ctrl_data_in_handler(usbh_core_type *uhost); +usb_sts_type usbh_ctrl_data_in_wait_handler(usbh_core_type *uhost, uint32_t timeout); +usb_sts_type usbh_ctrl_data_out_handler(usbh_core_type *uhost); +usb_sts_type usbh_ctrl_data_out_wait_handler(usbh_core_type *uhost, uint32_t timeout); +usb_sts_type usbh_ctrl_status_in_handler(usbh_core_type *uhost); +usb_sts_type usbh_ctrl_status_in_wait_handler(usbh_core_type *uhost, uint32_t timeout); +usb_sts_type usbh_ctrl_status_out_handler(usbh_core_type *uhost); +usb_sts_type usbh_ctrl_status_out_wait_handler(usbh_core_type *uhost, uint32_t timeout); +usb_sts_type usbh_ctrl_error_handler(usbh_core_type *uhost); +usb_sts_type usbh_ctrl_stall_handler(usbh_core_type *uhost); +usb_sts_type usbh_ctrl_complete_handler(usbh_core_type *uhost); +usb_sts_type usbh_ctrl_transfer_loop(usbh_core_type *uhost); +usb_sts_type usbh_ctrl_request(usbh_core_type *uhost, uint8_t *buffer, uint16_t length); +usb_sts_type usbh_get_descriptor(usbh_core_type *uhost, uint16_t length, + uint8_t req_type, uint16_t wvalue, + uint8_t *buffer); +void usbh_parse_dev_desc(usbh_core_type *uhost, uint8_t *buffer, uint16_t length); +usb_header_desc_type *usbh_get_next_header(uint8_t *buf, uint16_t *index_len); +void usbh_parse_interface_desc(usb_interface_desc_type *intf, uint8_t *buf); +void usbh_parse_endpoint_desc(usb_endpoint_desc_type *ept_desc, uint8_t *buf); +usb_sts_type usbh_parse_configure_desc(usbh_core_type *uhost, + uint8_t *buffer, uint16_t length); +uint8_t usbh_find_interface(usbh_core_type *uhost, uint8_t class_code, uint8_t sub_class, uint8_t protocol); +void usbh_parse_string_desc(uint8_t *src, uint8_t *dest, uint16_t length); +usb_sts_type usbh_get_device_descriptor(usbh_core_type *uhost, uint16_t length); +usb_sts_type usbh_get_configure_descriptor(usbh_core_type *uhost, uint16_t length); +usb_sts_type usbh_get_sting_descriptor(usbh_core_type *uhost, uint8_t string_id, + uint8_t *buffer, uint16_t length); +usb_sts_type usbh_set_configuration(usbh_core_type *uhost, uint16_t config); +usb_sts_type usbh_set_address(usbh_core_type *uhost, uint8_t address); +usb_sts_type usbh_set_interface(usbh_core_type *uhost, uint8_t ept_num, uint8_t altsetting); +usb_sts_type usbh_set_feature(usbh_core_type *uhost, uint8_t feature, uint16_t index); +usb_sts_type usbh_clear_dev_feature(usbh_core_type *uhost, uint8_t feature, uint16_t index); +usb_sts_type usbh_clear_ept_feature(usbh_core_type *uhost, uint8_t ept_num, uint8_t hc_num); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#ifdef __cplusplus +} +#endif + +#endif diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbh_int.h b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbh_int.h new file mode 100644 index 0000000000..dcb2b31638 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Inc/usbh_int.h @@ -0,0 +1,77 @@ +/** + ************************************************************************** + * @file usbh_int.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/* define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USBH_INT_H +#define __USBH_INT_H + +#ifdef __cplusplus +extern "C" { +#endif + +/** @addtogroup AT32F435_437_middlewares_usbh_drivers + * @{ + */ + +/** @addtogroup USBH_drivers_int + * @{ + */ + +/** @defgroup USBH_interrupt_exported_types + * @{ + */ + +/* includes ------------------------------------------------------------------*/ +#include "usbh_core.h" +#include "usb_core.h" +void usbh_irq_handler(otg_core_type *hdev); +void usbh_hch_handler(usbh_core_type *uhost); +void usbh_port_handler(usbh_core_type *uhost); +void usbh_disconnect_handler(usbh_core_type *uhost); +void usbh_hch_in_handler(usbh_core_type *uhost, uint8_t chn); +void usbh_hch_out_handler(usbh_core_type *uhost, uint8_t chn); +void usbh_rx_qlvl_handler(usbh_core_type *uhost); +void usbh_wakeup_handler(usbh_core_type *uhost); +void usbh_sof_handler(usbh_core_type *uhost); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif + diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usb_core.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usb_core.c new file mode 100644 index 0000000000..4fb5655217 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usb_core.c @@ -0,0 +1,188 @@ +/** + ************************************************************************** + * @file usb_core.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb driver + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +#include "usb_core.h" + +/** @addtogroup AT32F435_437_middlewares_usb_drivers + * @{ + */ + +/** @defgroup USB_drivers_core + * @brief usb global drivers core + * @{ + */ + +/** @defgroup USB_core_private_functions + * @{ + */ + +usb_sts_type usb_core_config(otg_core_type *udev, uint8_t core_id); + +/** + * @brief usb core config + * @param otgdev: to the structure of otg_core_type + * @param core_id: usb core id number (USB_FULL_SPEED_CORE_ID) + * @retval usb_sts_type + */ +usb_sts_type usb_core_config(otg_core_type *otgdev, uint8_t core_id) +{ + /* set usb speed and core id */ + otgdev->cfg.speed = core_id; + otgdev->cfg.core_id = core_id; + + /* default sof out and vbus ignore */ + otgdev->cfg.sof_out = FALSE; + otgdev->cfg.vbusig = FALSE; + + /* set max size */ + otgdev->cfg.max_size = 64; + + /* set support number of channel and endpoint */ +#ifdef USE_OTG_HOST_MODE + otgdev->cfg.hc_num = USB_HOST_CHANNEL_NUM; +#endif +#ifdef USE_OTG_DEVICE_MODE + otgdev->cfg.ept_num = USB_EPT_MAX_NUM; +#endif + otgdev->cfg.fifo_size = OTG_FIFO_SIZE; + if(core_id == USB_FULL_SPEED_CORE_ID) + { + otgdev->cfg.phy_itface = 2; + } +#ifdef USB_SOF_OUTPUT_ENABLE + otgdev->cfg.sof_out = TRUE; +#endif + +#ifdef USB_VBUS_IGNORE + otgdev->cfg.vbusig = TRUE; +#endif + + return USB_OK; +} + +#ifdef USE_OTG_DEVICE_MODE +/** + * @brief usb device initialization + * @param otgdev: to the structure of otg_core_type + * @param core_id: usb core id number (USB_FULL_SPEED_CORE_ID) + * @param usb_id: select use OTG1 or OTG2 + * this parameter can be one of the following values: + * - USB_OTG1_ID + * - USB_OTG2_ID + * @param dev_handler: usb class callback handler + * @param desc_handler: device config callback handler + * @retval usb_sts_type + */ +usb_sts_type usbd_init(otg_core_type *otgdev, + uint8_t core_id, uint8_t usb_id, + usbd_class_handler *class_handler, + usbd_desc_handler *desc_handler) +{ + usb_sts_type usb_sts = USB_OK; + + /* select use OTG1 or OTG2 */ + otgdev->usb_reg = usb_global_select_core(usb_id); + + /* usb device core config */ + usb_core_config(otgdev, core_id); + + if(otgdev->cfg.sof_out) + { + otgdev->usb_reg->gccfg_bit.sofouten = TRUE; + } + + if(otgdev->cfg.vbusig) + { + otgdev->usb_reg->gccfg_bit.vbusig = TRUE; + } + + /* usb device core init */ + usbd_core_init(&(otgdev->dev), otgdev->usb_reg, + class_handler, + desc_handler, + core_id); + + return usb_sts; +} +#endif + +#ifdef USE_OTG_HOST_MODE + +/** + * @brief usb host initialization. + * @param otgdev: to the structure of otg_core_type + * @param core_id: usb core id number (USB_FULL_SPEED_CORE_ID) + * @param usb_id: select use OTG1 or OTG2 + * this parameter can be one of the following values: + * - USB_OTG1_ID + * - USB_OTG2_ID + * @param class_handler: usb class callback handler + * @param user_handler: user callback handler + * @retval usb_sts_type + */ +usb_sts_type usbh_init(otg_core_type *otgdev, + uint8_t core_id, uint8_t usb_id, + usbh_class_handler_type *class_handler, + usbh_user_handler_type *user_handler) +{ + usb_sts_type status = USB_OK; + + /* select use otg1 or otg2 */ + otgdev->usb_reg = usb_global_select_core(usb_id); + + /* usb core config */ + usb_core_config(otgdev, core_id); + + if(otgdev->cfg.sof_out) + { + otgdev->usb_reg->gccfg_bit.sofouten = TRUE; + } + + if(otgdev->cfg.vbusig) + { + otgdev->usb_reg->gccfg_bit.vbusig = TRUE; + } + + /* usb host core init */ + usbh_core_init(&otgdev->host, otgdev->usb_reg, + class_handler, + user_handler, + core_id); + + return status; +} +#endif + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbd_core.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbd_core.c new file mode 100644 index 0000000000..b64914a78d --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbd_core.c @@ -0,0 +1,884 @@ +/** + ************************************************************************** + * @file usbd_core.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb device driver + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "usb_core.h" +#include "usbd_core.h" +#include "usbd_sdr.h" + + +/** @addtogroup AT32F435_437_middlewares_usbd_drivers + * @{ + */ + +/** @defgroup USBD_drivers_core + * @brief usb device drivers core + * @{ + */ + +/** @defgroup USBD_core_private_functions + * @{ + */ + +/** + * @brief usb core in transfer complete handler + * @param udev: to the structure of usbd_core_type + * @param ept_addr: endpoint number + * @retval none + */ +void usbd_core_in_handler(usbd_core_type *udev, uint8_t ept_addr) +{ + /* get endpoint info*/ + usb_ept_info *ept_info = &udev->ept_in[ept_addr & 0x7F]; + + if(ept_addr == 0) + { + if(udev->ept0_sts == USB_EPT0_DATA_IN) + { + if(ept_info->rem0_len > ept_info->maxpacket) + { + ept_info->rem0_len -= ept_info->maxpacket; + usbd_ept_send(udev, 0, ept_info->trans_buf, + MIN(ept_info->rem0_len, ept_info->maxpacket)); + } + /* endpoint 0 */ + else if(ept_info->last_len == ept_info->maxpacket + && ept_info->ept0_slen >= ept_info->maxpacket + && ept_info->ept0_slen < udev->ept0_wlength) + { + ept_info->last_len = 0; + usbd_ept_send(udev, 0, 0, 0); + usbd_ept_recv(udev, ept_addr, 0, 0); + } + else + { + + if(udev->class_handler->ept0_tx_handler != 0 && + udev->conn_state == USB_CONN_STATE_CONFIGURED) + { + udev->class_handler->ept0_tx_handler(udev); + } + usbd_ctrl_recv_status(udev); + + } + } + } + else if(udev->class_handler->in_handler != 0 && + udev->conn_state == USB_CONN_STATE_CONFIGURED) + { + /* other user define endpoint */ + udev->class_handler->in_handler(udev, ept_addr); + } +} + +/** + * @brief usb core out transfer complete handler + * @param udev: to the structure of usbd_core_type + * @param ept_addr: endpoint number + * @retval none + */ +void usbd_core_out_handler(usbd_core_type *udev, uint8_t ept_addr) +{ + /* get endpoint info*/ + usb_ept_info *ept_info = &udev->ept_out[ept_addr & 0x7F]; + + if(ept_addr == 0) + { + /* endpoint 0 */ + if(udev->ept0_sts == USB_EPT0_DATA_OUT) + { + if(ept_info->rem0_len > ept_info->maxpacket) + { + ept_info->rem0_len -= ept_info->maxpacket; + usbd_ept_recv(udev, ept_addr, ept_info->trans_buf, + MIN(ept_info->rem0_len, ept_info->maxpacket)); + } + else + { + if(udev->class_handler->ept0_rx_handler != 0) + { + udev->class_handler->ept0_rx_handler(udev); + } + usbd_ctrl_send_status(udev); + } + } + } + else if(udev->class_handler->out_handler != 0 && + udev->conn_state == USB_CONN_STATE_CONFIGURED) + { + /* other user define endpoint */ + udev->class_handler->out_handler(udev, ept_addr); + } +} + +/** + * @brief usb core setup transfer complete handler + * @param udev: to the structure of usbd_core_type + * @param ept_addr: endpoint number + * @retval none + */ +void usbd_core_setup_handler(usbd_core_type *udev, uint8_t ept_num) +{ + UNUSED(ept_num); + /* setup parse */ + usbd_setup_request_parse(&udev->setup, udev->setup_buffer); + + /* set ept0 status */ + udev->ept0_sts = USB_EPT0_SETUP; + udev->ept0_wlength = udev->setup.wLength; + + switch(udev->setup.bmRequestType & USB_REQ_RECIPIENT_MASK) + { + case USB_REQ_RECIPIENT_DEVICE: + /* recipient device request */ + usbd_device_request(udev); + break; + case USB_REQ_RECIPIENT_INTERFACE: + /* recipient interface request */ + usbd_interface_request(udev); + break; + case USB_REQ_RECIPIENT_ENDPOINT: + /* recipient endpoint request */ + usbd_endpoint_request(udev); + break; + default: + break; + } +} + +/** + * @brief usb control endpoint send data + * @param udev: to the structure of usbd_core_type + * @param ept_addr: endpoint number + * @param buffer: send data buffer + * @param len: send data length + * @retval none + */ +void usbd_ctrl_send(usbd_core_type *udev, uint8_t *buffer, uint16_t len) +{ + usb_ept_info *ept_info = &udev->ept_in[0]; + + ept_info->ept0_slen = len; + ept_info->rem0_len = len; + udev->ept0_sts = USB_EPT0_DATA_IN; + + usbd_ept_send(udev, 0, buffer, len); +} + +/** + * @brief usb control endpoint recv data + * @param udev: to the structure of usbd_core_type + * @param ept_addr: endpoint number + * @param buffer: recv data buffer + * @param len: recv data length + * @retval none + */ +void usbd_ctrl_recv(usbd_core_type *udev, uint8_t *buffer, uint16_t len) +{ + usb_ept_info *ept_info = &udev->ept_out[0]; + + ept_info->ept0_slen = len; + ept_info->rem0_len = len; + udev->ept0_sts = USB_EPT0_DATA_OUT; + + usbd_ept_recv(udev, 0, buffer, len); +} + +/** + * @brief usb control endpoint send in status + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usbd_ctrl_send_status(usbd_core_type *udev) +{ + udev->ept0_sts = USB_EPT0_STATUS_IN; + + usbd_ept_send(udev, 0, 0, 0); +} + +/** + * @brief usb control endpoint send out status + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usbd_ctrl_recv_status(usbd_core_type *udev) +{ + udev->ept0_sts = USB_EPT0_STATUS_OUT; + + usbd_ept_recv(udev, 0, 0, 0); +} + +/** + * @brief clear endpoint stall + * @param udev: to the structure of usbd_core_type + * @param ept_addr: endpoint number + * @retval none + */ +void usbd_clear_stall(usbd_core_type *udev, uint8_t ept_addr) +{ + usb_ept_info *ept_info; + usb_reg_type *usbx = udev->usb_reg; + + if(ept_addr & 0x80) + { + /* in endpoint */ + ept_info = &udev->ept_in[ept_addr & 0x7F]; + } + else + { + /* out endpoint */ + ept_info = &udev->ept_out[ept_addr & 0x7F]; + } + usb_ept_clear_stall(usbx, ept_info); + ept_info->stall = 0; +} + +/** + * @brief usb set endpoint to stall status + * @param udev: to the structure of usbd_core_type + * @param ept_addr: endpoint number + * @retval none + */ +void usbd_set_stall(usbd_core_type *udev, uint8_t ept_addr) +{ + usb_ept_info *ept_info; + usb_reg_type *usbx = udev->usb_reg; + + if(ept_addr & 0x80) + { + /* in endpoint */ + ept_info = &udev->ept_in[ept_addr & 0x7F]; + } + else + { + /* out endpoint */ + ept_info = &udev->ept_out[ept_addr & 0x7F]; + } + usb_ept_stall(usbx, ept_info); + + ept_info->stall = 1; +} + +/** + * @brief un-support device request + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usbd_ctrl_unsupport(usbd_core_type *udev) +{ + /* return stall status */ + usbd_set_stall(udev, 0x00); + usbd_set_stall(udev, 0x80); +} + +/** + * @brief get endpoint receive data length + * @param udev: to the structure of usbd_core_type + * @param ept_addr: endpoint number + * @retval data receive len + */ +uint32_t usbd_get_recv_len(usbd_core_type *udev, uint8_t ept_addr) +{ + usb_ept_info *ept = &udev->ept_out[ept_addr & 0x7F]; + return ept->trans_len; +} + +/** + * @brief usb open endpoint + * @param udev: to the structure of usbd_core_type + * @param ept_addr: endpoint number + * @param ept_type: endpoint type + * @param maxpacket: endpoint support max buffer size + * @retval none + */ +void usbd_ept_open(usbd_core_type *udev, uint8_t ept_addr, uint8_t ept_type, uint16_t maxpacket) +{ + usb_reg_type *usbx = udev->usb_reg; + usb_ept_info *ept_info; + + if((ept_addr & 0x80) == 0) + { + /* out endpoint info */ + ept_info = &udev->ept_out[ept_addr & 0x7F]; + ept_info->inout = EPT_DIR_OUT; + } + else + { + /* in endpoint info */ + ept_info = &udev->ept_in[ept_addr & 0x7F]; + ept_info->inout = EPT_DIR_IN; + } + + /* set endpoint maxpacket and type */ + ept_info->maxpacket = maxpacket; + ept_info->trans_type = ept_type; + + /* open endpoint */ + usb_ept_open(usbx, ept_info); +} + +/** + * @brief usb close endpoint + * @param udev: to the structure of usbd_core_type + * @param ept_addr: endpoint number + * @retval none + */ +void usbd_ept_close(usbd_core_type *udev, uint8_t ept_addr) +{ + usb_ept_info *ept_info; + if(ept_addr & 0x80) + { + /* in endpoint */ + ept_info = &udev->ept_in[ept_addr & 0x7F]; + } + else + { + /* out endpoint */ + ept_info = &udev->ept_out[ept_addr & 0x7F]; + } + + /* close endpoint */ + usb_ept_close(udev->usb_reg, ept_info); +} + +/** + * @brief usb device connect to host + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usbd_connect(usbd_core_type *udev) +{ + usb_connect(udev->usb_reg); +} + +/** + * @brief usb device disconnect to host + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usbd_disconnect(usbd_core_type *udev) +{ + usb_disconnect(udev->usb_reg); +} + +/** + * @brief usb device set device address. + * @param udev: to the structure of usbd_core_type + * @param address: host assignment address + * @retval none + */ +void usbd_set_device_addr(usbd_core_type *udev, uint8_t address) +{ + usb_set_address(udev->usb_reg, address); +} + +/** + * @brief usb endpoint structure initialization + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usb_ept_default_init(usbd_core_type *udev) +{ + uint8_t i_index = 0; + /* init in endpoint info structure */ + for(i_index = 0; i_index < USB_EPT_MAX_NUM; i_index ++) + { + udev->ept_in[i_index].eptn = i_index; + udev->ept_in[i_index].ept_address = i_index; + udev->ept_in[i_index].inout = EPT_DIR_IN; + udev->ept_in[i_index].maxpacket = 0; + udev->ept_in[i_index].trans_buf = 0; + udev->ept_in[i_index].total_len = 0; + } + + /* init out endpoint info structure */ + for(i_index = 0; i_index < USB_EPT_MAX_NUM; i_index ++) + { + udev->ept_out[i_index].eptn = i_index; + udev->ept_out[i_index].ept_address = i_index; + udev->ept_out[i_index].inout = EPT_DIR_OUT; + udev->ept_out[i_index].maxpacket = 0; + udev->ept_out[i_index].trans_buf = 0; + udev->ept_out[i_index].total_len = 0; + } +} + +/** + * @brief endpoint send data + * @param udev: to the structure of usbd_core_type + * @param ept_addr: endpoint number + * @param buffer: send data buffer + * @param len: send data length + * @retval none + */ +void usbd_ept_send(usbd_core_type *udev, uint8_t ept_addr, uint8_t *buffer, uint16_t len) +{ + /* get endpoint info struct and register */ + usb_reg_type *usbx = udev->usb_reg; + usb_ept_info *ept_info = &udev->ept_in[ept_addr & 0x7F]; + otg_eptin_type *ept_in = USB_INEPT(usbx, ept_info->eptn); + otg_device_type *dev = OTG_DEVICE(usbx); + uint32_t pktcnt; + + /* set send data buffer and length */ + ept_info->trans_buf = buffer; + ept_info->total_len = len; + ept_info->trans_len = 0; + + /* transfer data len is zero */ + if(ept_info->total_len == 0) + { + ept_in->dieptsiz_bit.pktcnt = 1; + ept_in->dieptsiz_bit.xfersize = 0; + } + else + { + if((ept_addr & 0x7F) == 0) // endpoint 0 + { + /* endpoint 0 */ + if(ept_info->total_len > ept_info->maxpacket) + { + ept_info->total_len = ept_info->maxpacket; + } + + /* set transfer size */ + ept_in->dieptsiz_bit.xfersize = ept_info->total_len; + + /* set packet count */ + ept_in->dieptsiz_bit.pktcnt = 1; + + ept_info->last_len = ept_info->total_len; + } + else + { + /* other endpoint */ + + /* packet count */ + pktcnt = (ept_info->total_len + ept_info->maxpacket - 1) / ept_info->maxpacket; + + /* set transfer size */ + ept_in->dieptsiz_bit.xfersize = ept_info->total_len; + + /* set packet count */ + ept_in->dieptsiz_bit.pktcnt = pktcnt; + + if(ept_info->trans_type == EPT_ISO_TYPE) + { + ept_in->dieptsiz_bit.mc = 1; + } + } + } + + if(ept_info->trans_type != EPT_ISO_TYPE) + { + if(ept_info->total_len > 0) + { + /* set in endpoint tx fifo empty interrupt mask */ + dev->diepempmsk |= 1 << ept_info->eptn; + } + } + + if(ept_info->trans_type == EPT_ISO_TYPE) + { + if((dev->dsts_bit.soffn & 0x1) == 0) + { + ept_in->diepctl_bit.setd1pid = TRUE; + } + else + { + ept_in->diepctl_bit.setd0pid = TRUE; + } + } + + /* clear endpoint nak */ + ept_in->diepctl_bit.cnak = TRUE; + + /* endpoint enable */ + ept_in->diepctl_bit.eptena = TRUE; + + if(ept_info->trans_type == EPT_ISO_TYPE) + { + /* write data to fifo */ + usb_write_packet(usbx, ept_info->trans_buf, ept_info->eptn, ept_info->total_len); + } +} + +/** + * @brief endpoint receive data + * @param udev: to the structure of usbd_core_type + * @param ept_addr: endpoint number + * @param buffer: receive data buffer + * @param len: receive data length + * @retval none + */ +void usbd_ept_recv(usbd_core_type *udev, uint8_t ept_addr, uint8_t *buffer, uint16_t len) +{ + /* get endpoint info struct and register */ + usb_reg_type *usbx = udev->usb_reg; + usb_ept_info *ept_info = &udev->ept_out[ept_addr & 0x7F]; + otg_eptout_type *ept_out = USB_OUTEPT(usbx, ept_info->eptn); + otg_device_type *dev = OTG_DEVICE(usbx); + uint32_t pktcnt; + + /* set receive data buffer and length */ + ept_info->trans_buf = buffer; + ept_info->total_len = len; + ept_info->trans_len = 0; + + if((ept_addr & 0x7F) == 0) + { + /* endpoint 0 */ + ept_info->total_len = ept_info->maxpacket; + } + + if(ept_info->total_len == 0 || ((ept_addr & 0x7F) == 0)) + { + /* set transfer size */ + ept_out->doeptsiz_bit.xfersize = ept_info->maxpacket; + + /* set packet count */ + ept_out->doeptsiz_bit.pktcnt = 1; + } + else + { + pktcnt = (ept_info->total_len + ept_info->maxpacket - 1) / ept_info->maxpacket; + + /* set transfer size */ + ept_out->doeptsiz_bit.xfersize = ept_info->maxpacket * pktcnt; + + /* set packet count */ + ept_out->doeptsiz_bit.pktcnt = pktcnt; + } + + if(ept_info->trans_type == EPT_ISO_TYPE) + { + if((dev->dsts_bit.soffn & 0x01) == 0) + { + ept_out->doepctl_bit.setd1pid = TRUE; + } + else + { + ept_out->doepctl_bit.setd0pid = TRUE; + } + } + + /* clear endpoint nak */ + ept_out->doepctl_bit.cnak = TRUE; + + /* endpoint enable */ + ept_out->doepctl_bit.eptena = TRUE; +} + +/** + * @brief get usb connect state + * @param udev: to the structure of usbd_core_type + * @retval usb connect state + */ +usbd_conn_state usbd_connect_state_get(usbd_core_type *udev) +{ + return udev->conn_state; +} + +/** + * @brief usb device remote wakeup + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usbd_remote_wakeup(usbd_core_type *udev) +{ + /* check device is in suspend mode */ + if(usb_suspend_status_get(udev->usb_reg) == 1) + { + /* set connect state */ + udev->conn_state = udev->old_conn_state; + + /* open phy clock */ + usb_open_phy_clk(udev->usb_reg); + + /* set remote wakeup */ + usb_remote_wkup_set(udev->usb_reg); + + /* delay 10 ms */ + usb_delay_ms(10); + + /* clear remote wakup */ + usb_remote_wkup_clear(udev->usb_reg); + } +} + +/** + * @brief usb device enter suspend mode + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usbd_enter_suspend(usbd_core_type *udev) +{ + /* check device is in suspend mode */ + if(usb_suspend_status_get(udev->usb_reg) == 1) + { + /* stop phy clk */ + usb_stop_phy_clk(udev->usb_reg); + } +} + +/** + * @brief usb device flush in endpoint fifo + * @param udev: to the structure of usbd_core_type + * @param ept_num: endpoint number + * @retval none + */ +void usbd_flush_tx_fifo(usbd_core_type *udev, uint8_t ept_num) +{ + /* flush endpoint tx fifo */ + usb_flush_tx_fifo(udev->usb_reg, ept_num & 0x1F); +} + +/** + * @brief usb device endpoint fifo alloc + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usbd_fifo_alloc(usbd_core_type *udev) +{ + usb_reg_type *usbx = udev->usb_reg; + + if(usbx == OTG1_GLOBAL) + { + /* set receive fifo size */ + usb_set_rx_fifo(usbx, USBD_RX_SIZE); + + /* set endpoint0 tx fifo size */ + usb_set_tx_fifo(usbx, USB_EPT0, USBD_EP0_TX_SIZE); + + /* set endpoint1 tx fifo size */ + usb_set_tx_fifo(usbx, USB_EPT1, USBD_EP1_TX_SIZE); + + /* set endpoint2 tx fifo size */ + usb_set_tx_fifo(usbx, USB_EPT2, USBD_EP2_TX_SIZE); + + /* set endpoint3 tx fifo size */ + usb_set_tx_fifo(usbx, USB_EPT3, USBD_EP3_TX_SIZE); + + if(USB_EPT_MAX_NUM == 8) + { + /* set endpoint4 tx fifo size */ + usb_set_tx_fifo(usbx, USB_EPT4, USBD_EP4_TX_SIZE); + + /* set endpoint5 tx fifo size */ + usb_set_tx_fifo(usbx, USB_EPT5, USBD_EP5_TX_SIZE); + + /* set endpoint6 tx fifo size */ + usb_set_tx_fifo(usbx, USB_EPT6, USBD_EP6_TX_SIZE); + + /* set endpoint7 tx fifo size */ + usb_set_tx_fifo(usbx, USB_EPT7, USBD_EP7_TX_SIZE); + } + } +#ifdef OTG2_GLOBAL + if(usbx == OTG2_GLOBAL) + { + /* set receive fifo size */ + usb_set_rx_fifo(usbx, USBD2_RX_SIZE); + + /* set endpoint0 tx fifo size */ + usb_set_tx_fifo(usbx, USB_EPT0, USBD2_EP0_TX_SIZE); + + /* set endpoint1 tx fifo size */ + usb_set_tx_fifo(usbx, USB_EPT1, USBD2_EP1_TX_SIZE); + + /* set endpoint2 tx fifo size */ + usb_set_tx_fifo(usbx, USB_EPT2, USBD2_EP2_TX_SIZE); + + /* set endpoint3 tx fifo size */ + usb_set_tx_fifo(usbx, USB_EPT3, USBD2_EP3_TX_SIZE); + + if(USB_EPT_MAX_NUM == 8) + { + /* set endpoint4 tx fifo size */ + usb_set_tx_fifo(usbx, USB_EPT4, USBD2_EP4_TX_SIZE); + + /* set endpoint5 tx fifo size */ + usb_set_tx_fifo(usbx, USB_EPT5, USBD2_EP5_TX_SIZE); + + /* set endpoint6 tx fifo size */ + usb_set_tx_fifo(usbx, USB_EPT6, USBD2_EP6_TX_SIZE); + + /* set endpoint7 tx fifo size */ + usb_set_tx_fifo(usbx, USB_EPT7, USBD2_EP7_TX_SIZE); + } + } +#endif +} + +/** + * @brief usb device core initialization + * @param udev: to the structure of usbd_core_type + * @param usb_reg: usb otgfs peripheral global register + * this parameter can be one of the following values: + * OTG1_GLOBAL , OTG2_GLOBAL + * @param class_handler: usb class handler + * @param desc_handler: device config handler + * @param core_id: usb core id number + * @retval usb_sts_type + */ +usb_sts_type usbd_core_init(usbd_core_type *udev, + usb_reg_type *usb_reg, + usbd_class_handler *class_handler, + usbd_desc_handler *desc_handler, + uint8_t core_id) +{ + UNUSED(core_id); + usb_reg_type *usbx; + otg_device_type *dev; + otg_eptin_type *ept_in; + otg_eptout_type *ept_out; + uint32_t i_index; + + udev->usb_reg = usb_reg; + usbx = usb_reg; + dev = OTG_DEVICE(usbx); + + /* set connect state */ + udev->conn_state = USB_CONN_STATE_DEFAULT; + + /* device class config */ + udev->device_addr = 0; + udev->class_handler = class_handler; + udev->desc_handler = desc_handler; + /* set device disconnect */ + usbd_disconnect(udev); + + /* set endpoint to default status */ + usb_ept_default_init(udev); + + /* disable usb global interrupt */ + usb_interrupt_disable(usbx); + + /* init global register */ + usb_global_init(usbx); + + /* set device mode */ + usb_global_set_mode(usbx, OTG_DEVICE_MODE); + + /* open phy clock */ + usb_open_phy_clk(udev->usb_reg); + + /* set periodic frame interval */ + dev->dcfg_bit.perfrint = DCFG_PERFRINT_80; + + /* set device speed to full-speed */ + dev->dcfg_bit.devspd = USB_DCFG_FULL_SPEED; + + /* flush all tx fifo */ + usb_flush_tx_fifo(usbx, 16); + + /* flush share rx fifo */ + usb_flush_rx_fifo(usbx); + + /* clear all endpoint interrupt flag and mask */ + dev->daint = 0xFFFFFFFF; + dev->daintmsk = 0; + dev->diepmsk = 0; + dev->doepmsk = 0; + + for(i_index = 0; i_index < USB_EPT_MAX_NUM; i_index ++) + { + usbx->dieptxfn[i_index] = 0; + } + + /* endpoint fifo alloc */ + usbd_fifo_alloc(udev); + + /* disable all in endpoint */ + for(i_index = 0; i_index < USB_EPT_MAX_NUM; i_index ++) + { + ept_in = USB_INEPT(usbx, i_index); + if(ept_in->diepctl_bit.eptena) + { + ept_in->diepctl = 0; + ept_in->diepctl_bit.eptdis = TRUE; + ept_in->diepctl_bit.snak = TRUE; + } + else + { + ept_in->diepctl = 0; + } + ept_in->dieptsiz = 0; + ept_in->diepint = 0xFF; + } + + /* disable all out endpoint */ + for(i_index = 0; i_index < USB_EPT_MAX_NUM; i_index ++) + { + ept_out = USB_OUTEPT(usbx, i_index); + if(ept_out->doepctl_bit.eptena) + { + ept_out->doepctl = 0; + ept_out->doepctl_bit.eptdis = TRUE; + ept_out->doepctl_bit.snak = TRUE; + } + else + { + ept_out->doepctl = 0; + } + ept_out->doeptsiz = 0; + ept_out->doepint = 0xFF; + } + dev->diepmsk_bit.txfifoudrmsk = TRUE; + + /* clear global interrupt and mask */ + usbx->gintmsk = 0; + usbx->gintsts = 0xBFFFFFFF; + + /* enable global interrupt mask */ + usbx->gintmsk = USB_OTG_SOF_INT | USB_OTG_RXFLVL_INT | + USB_OTG_USBSUSP_INT | USB_OTG_USBRST_INT | + USB_OTG_ENUMDONE_INT | USB_OTG_IEPT_INT | + USB_OTG_OEPT_INT | USB_OTG_INCOMISOIN_INT | + USB_OTG_INCOMPIP_INCOMPISOOUT_INT | USB_OTG_WKUP_INT | + USB_OTG_OTGINT_INT; + + /* usb connect */ + usbd_connect(udev); + + /* enable global interrupt */ + usb_interrupt_enable(usbx); + + return USB_OK; + +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbd_int.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbd_int.c new file mode 100644 index 0000000000..fdb19c368c --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbd_int.c @@ -0,0 +1,538 @@ +/** + ************************************************************************** + * @file usbd_int.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb interrupt request + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +#include "usbd_int.h" + +/** @addtogroup AT32F435_437_middlewares_usbd_drivers + * @{ + */ + +/** @defgroup USBD_drivers_interrupt + * @brief usb device interrupt + * @{ + */ + +/** @defgroup USBD_int_private_functions + * @{ + */ + +/** + * @brief usb device interrput request handler. + * @param otgdev: to the structure of otg_core_type + * @retval none + */ +void usbd_irq_handler(otg_core_type *otgdev) +{ + otg_global_type *usbx = otgdev->usb_reg; + usbd_core_type *udev = &otgdev->dev; + uint32_t intsts = usb_global_get_all_interrupt(usbx); + + /* check current device mode */ + if(usbx->gintsts_bit.curmode == 0) + { + /* mode mismatch interrupt */ + if(intsts & USB_OTG_MODEMIS_FLAG) + { + usb_global_clear_interrupt(usbx, USB_OTG_MODEMIS_FLAG); + } + + /* in endpoint interrupt */ + if(intsts & USB_OTG_IEPT_FLAG) + { + usbd_inept_handler(udev); + } + + /* out endpoint interrupt */ + if(intsts & USB_OTG_OEPT_FLAG) + { + usbd_outept_handler(udev); + } + + /* usb reset interrupt */ + if(intsts & USB_OTG_USBRST_FLAG) + { + usbd_reset_handler(udev); + usb_global_clear_interrupt(usbx, USB_OTG_USBRST_FLAG); + } + + /* sof interrupt */ + if(intsts & USB_OTG_SOF_FLAG) + { + usbd_sof_handler(udev); + usb_global_clear_interrupt(usbx, USB_OTG_SOF_FLAG); + } + + /* enumeration done interrupt */ + if(intsts & USB_OTG_ENUMDONE_FLAG) + { + usbd_enumdone_handler(udev); + usb_global_clear_interrupt(usbx, USB_OTG_ENUMDONE_FLAG); + } + + /* rx non-empty interrupt, indicates that there is at least one + data packet pending to be read in rx fifo */ + if(intsts & USB_OTG_RXFLVL_FLAG) + { + usbd_rxflvl_handler(udev); + } + + /* incomplete isochronous in transfer interrupt */ + if(intsts & USB_OTG_INCOMISOIN_FLAG) + { + usbd_incomisioin_handler(udev); + usb_global_clear_interrupt(usbx, USB_OTG_INCOMISOIN_FLAG); + } + #ifndef USB_VBUS_IGNORE + /* disconnect detected interrupt */ + if(intsts & USB_OTG_OTGINT_FLAG) + { + uint32_t tmp = udev->usb_reg->gotgint; + if(udev->usb_reg->gotgint_bit.sesenddet) + usbd_discon_handler(udev); + udev->usb_reg->gotgint = tmp; + usb_global_clear_interrupt(usbx, USB_OTG_OTGINT_FLAG); + } +#endif + /* incomplete isochronous out transfer interrupt */ + if(intsts & USB_OTG_INCOMPIP_INCOMPISOOUT_FLAG) + { + usbd_incomisoout_handler(udev); + usb_global_clear_interrupt(usbx, USB_OTG_INCOMPIP_INCOMPISOOUT_FLAG); + } + + /* resume/remote wakeup interrupt */ + if(intsts & USB_OTG_WKUP_FLAG) + { + usbd_wakeup_handler(udev); + usb_global_clear_interrupt(usbx, USB_OTG_WKUP_FLAG); + } + + /* usb suspend interrupt */ + if(intsts & USB_OTG_USBSUSP_FLAG) + { + usbd_suspend_handler(udev); + usb_global_clear_interrupt(usbx, USB_OTG_USBSUSP_FLAG); + } + } +} + +/** + * @brief usb write tx fifo. + * @param udev: to the structure of usbd_core_type + * @param ept_num: endpoint number + * @retval none + */ +void usb_write_empty_txfifo(usbd_core_type *udev, uint32_t ept_num) +{ + otg_global_type *usbx = udev->usb_reg; + usb_ept_info *ept_info = &udev->ept_in[ept_num]; + uint32_t length = ept_info->total_len - ept_info->trans_len; + uint32_t wlen = 0; + + if(length > ept_info->maxpacket) + { + length = ept_info->maxpacket; + } + wlen = (length + 3) / 4; + + while((USB_INEPT(usbx, ept_num)->dtxfsts & USB_OTG_DTXFSTS_INEPTFSAV) > wlen && + (ept_info->trans_len < ept_info->total_len) && (ept_info->total_len != 0)) + { + length = ept_info->total_len - ept_info->trans_len; + if(length > ept_info->maxpacket) + { + length = ept_info->maxpacket; + } + wlen = (length + 3) / 4; + usb_write_packet(usbx, ept_info->trans_buf, ept_num, length); + + ept_info->trans_buf += length; + ept_info->trans_len += length; + + } + if(length <= 0) + { + OTG_DEVICE(usbx)->diepempmsk &= ~(0x1 << ept_num); + } +} + + +/** + * @brief usb in endpoint handler + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usbd_inept_handler(usbd_core_type *udev) +{ + otg_global_type *usbx = udev->usb_reg; + uint32_t ept_num = 0, ept_int; + uint32_t intsts; + + /*get all endpoint interrut */ + intsts = usb_get_all_in_interrupt(usbx); + while(intsts) + { + if(intsts & 0x1) + { + /* get endpoint interrupt flag */ + ept_int = usb_ept_in_interrupt(usbx, ept_num); + + /* transfer completed interrupt */ + if(ept_int & USB_OTG_DIEPINT_XFERC_FLAG) + { + OTG_DEVICE(usbx)->diepempmsk &= ~(1 << ept_num); + usb_ept_in_clear(usbx, ept_num , USB_OTG_DIEPINT_XFERC_FLAG); + usbd_core_in_handler(udev, ept_num); + } + + /* timeout condition interrupt */ + if(ept_int & USB_OTG_DIEPINT_TIMEOUT_FLAG) + { + usb_ept_in_clear(usbx, ept_num , USB_OTG_DIEPINT_TIMEOUT_FLAG); + } + + /* in token received when tx fifo is empty */ + if(ept_int & USB_OTG_DIEPINT_INTKNTXFEMP_FLAG) + { + usb_ept_in_clear(usbx, ept_num , USB_OTG_DIEPINT_INTKNTXFEMP_FLAG); + } + + /* in endpoint nak effective */ + if(ept_int & USB_OTG_DIEPINT_INEPTNAK_FLAG) + { + usb_ept_in_clear(usbx, ept_num , USB_OTG_DIEPINT_INEPTNAK_FLAG); + } + + /* endpoint disable interrupt */ + if(ept_int & USB_OTG_DIEPINT_EPTDISD_FLAG) + { + usb_ept_in_clear(usbx, ept_num , USB_OTG_DIEPINT_EPTDISD_FLAG); + } + + /* transmit fifo empty interrupt */ + if(ept_int & USB_OTG_DIEPINT_TXFEMP_FLAG) + { + usb_write_empty_txfifo(udev, ept_num); + } + } + ept_num ++; + intsts >>= 1; + } +} + +/** + * @brief usb out endpoint handler + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usbd_outept_handler(usbd_core_type *udev) +{ + otg_global_type *usbx = udev->usb_reg; + uint32_t ept_num = 0, ept_int; + uint32_t intsts; + + /* get all out endpoint interrupt */ + intsts = usb_get_all_out_interrupt(usbx); + + while(intsts) + { + if(intsts & 0x1) + { + /* get out endpoint interrupt */ + ept_int = usb_ept_out_interrupt(usbx, ept_num); + + /* transfer completed interrupt */ + if(ept_int & USB_OTG_DOEPINT_XFERC_FLAG) + { + usb_ept_out_clear(usbx, ept_num , USB_OTG_DOEPINT_XFERC_FLAG); + usbd_core_out_handler(udev, ept_num); + } + + /* setup phase done interrupt */ + if(ept_int & USB_OTG_DOEPINT_SETUP_FLAG) + { + usb_ept_out_clear(usbx, ept_num , USB_OTG_DOEPINT_SETUP_FLAG); + usbd_core_setup_handler(udev, ept_num); + if(udev->device_addr != 0) + { + OTG_DEVICE(udev->usb_reg)->dcfg_bit.devaddr = udev->device_addr; + udev->device_addr = 0; + } + } + + /* endpoint disable interrupt */ + if(ept_int & USB_OTG_DOEPINT_OUTTEPD_FLAG) + { + usb_ept_out_clear(usbx, ept_num , USB_OTG_DOEPINT_OUTTEPD_FLAG); + } + } + ept_num ++; + intsts >>= 1; + } +} + +/** + * @brief usb enumeration done handler + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usbd_enumdone_handler(usbd_core_type *udev) +{ + otg_global_type *usbx = udev->usb_reg; + + usb_ept0_setup(usbx); + + usbx->gusbcfg_bit.usbtrdtim = USB_TRDTIM_16; + + /* open endpoint 0 out */ + usbd_ept_open(udev, 0x00, EPT_CONTROL_TYPE, 0x40); + + /* open endpoint 0 in */ + usbd_ept_open(udev, 0x80, EPT_CONTROL_TYPE, 0x40); + + /* usb connect state set to default */ + udev->conn_state = USB_CONN_STATE_DEFAULT; + + /* clear callback */ + if(udev->class_handler->clear_handler != 0) + udev->class_handler->clear_handler(udev); +} + +/** + * @brief usb rx non-empty handler + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usbd_rxflvl_handler(usbd_core_type *udev) +{ + otg_global_type *usbx = udev->usb_reg; + uint32_t stsp; + uint32_t count; + uint32_t pktsts; + usb_ept_info *ept_info; + + /* disable rxflvl interrupt */ + usb_global_interrupt_enable(usbx, USB_OTG_RXFLVL_INT, FALSE); + + /* get rx status */ + stsp = usbx->grxstsp; + + /*get the byte count of receive */ + count = (stsp & USB_OTG_GRXSTSP_BCNT) >> 4; + + /* get packet status */ + pktsts = (stsp &USB_OTG_GRXSTSP_PKTSTS) >> 17; + + /* get endpoint infomation struct */ + ept_info = &udev->ept_out[stsp & USB_OTG_GRXSTSP_EPTNUM]; + + /* received out data packet */ + if(pktsts == USB_OUT_STS_DATA) + { + if(count != 0) + { + /* read packet to buffer */ + usb_read_packet(usbx, ept_info->trans_buf, (stsp & USB_OTG_GRXSTSP_EPTNUM), count); + ept_info->trans_buf += count; + ept_info->trans_len += count; + + } + } + /* setup data received */ + else if ( pktsts == USB_SETUP_STS_DATA) + { + /* read packet to buffer */ + usb_read_packet(usbx, udev->setup_buffer, (stsp & USB_OTG_GRXSTSP_EPTNUM), count); + ept_info->trans_len += count; + } + + /* enable rxflvl interrupt */ + usb_global_interrupt_enable(usbx, USB_OTG_RXFLVL_INT, TRUE); + +} + +/** + * @brief usb disconnect handler + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usbd_discon_handler(usbd_core_type *udev) +{ + /* disconnect callback handler */ + if(udev->class_handler->event_handler != 0) + udev->class_handler->event_handler(udev, USBD_DISCONNECT_EVNET); +} + + +/** + * @brief usb incomplete out handler + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usbd_incomisoout_handler(usbd_core_type *udev) +{ + if(udev->class_handler->event_handler != 0) + udev->class_handler->event_handler(udev, USBD_OUTISOINCOM_EVENT); +} + +/** + * @brief usb incomplete in handler + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usbd_incomisioin_handler(usbd_core_type *udev) +{ + if(udev->class_handler->event_handler != 0) + udev->class_handler->event_handler(udev, USBD_INISOINCOM_EVENT); +} + +/** + * @brief usb device reset interrupt request handler. + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usbd_reset_handler(usbd_core_type *udev) +{ + otg_global_type *usbx = udev->usb_reg; + otg_device_type *dev = OTG_DEVICE(usbx); + uint32_t i_index = 0; + + /* disable remote wakeup singal */ + dev->dctl_bit.rwkupsig = FALSE; + + /* endpoint fifo alloc */ + usbd_fifo_alloc(udev); + + /* flush all tx fifo */ + usb_flush_tx_fifo(usbx, 0x10); + + /* clear in and out endpoint interrupt flag */ + for(i_index = 0; i_index < USB_EPT_MAX_NUM; i_index ++) + { + USB_INEPT(usbx, i_index)->diepint = 0xFF; + USB_OUTEPT(usbx, i_index)->doepint = 0xFF; + } + + /* clear endpoint flag */ + dev->daint = 0xFFFFFFFF; + + /*clear endpoint interrupt mask */ + dev->daintmsk = 0x10001; + + /* enable out endpoint xfer, eptdis, setup interrupt mask */ + dev->doepmsk_bit.xfercmsk = TRUE; + dev->doepmsk_bit.eptdismsk = TRUE; + dev->doepmsk_bit.setupmsk = TRUE; + + /* enable in endpoint xfer, eptdis, timeout interrupt mask */ + dev->diepmsk_bit.xfercmsk = TRUE; + dev->diepmsk_bit.eptdismsk = TRUE; + dev->diepmsk_bit.timeoutmsk = TRUE; + + /* set device address to 0 */ + usb_set_address(usbx, 0); + + /* enable endpoint 0 */ + usb_ept0_start(usbx); + + /* usb connect state set to default */ + udev->conn_state = USB_CONN_STATE_DEFAULT; + + /* user define reset event */ + if(udev->class_handler->event_handler) + udev->class_handler->event_handler(udev, USBD_RESET_EVENT); +} + +/** + * @brief usb device sof interrupt request handler. + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usbd_sof_handler(usbd_core_type *udev) +{ + /* user sof handler in class define */ + if(udev->class_handler->sof_handler) + udev->class_handler->sof_handler(udev); +} + +/** + * @brief usb device suspend interrupt request handler. + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usbd_suspend_handler(usbd_core_type *udev) +{ + otg_global_type *usbx = udev->usb_reg; + + if(OTG_DEVICE(usbx)->dsts_bit.suspsts) + { + /* save connect state */ + udev->old_conn_state = udev->conn_state; + + /* set current state to suspend */ + udev->conn_state = USB_CONN_STATE_SUSPENDED; + + /* enter suspend mode */ + usbd_enter_suspend(udev); + + /* user suspend handler */ + if(udev->class_handler->event_handler != 0) + udev->class_handler->event_handler(udev, USBD_SUSPEND_EVENT); + } +} + +/** + * @brief usb device wakup interrupt request handler. + * @param udev: to the structure of usbd_core_type + * @retval none + */ +void usbd_wakeup_handler(usbd_core_type *udev) +{ + otg_global_type *usbx = udev->usb_reg; + + /* clear remote wakeup bit */ + OTG_DEVICE(usbx)->dctl_bit.rwkupsig = FALSE; + + /* exit suspend mode */ + usb_open_phy_clk(udev->usb_reg); + + /* restore connect state */ + udev->conn_state = udev->old_conn_state; + + /* user suspend handler */ + if(udev->class_handler->event_handler != 0) + udev->class_handler->event_handler(udev, USBD_WAKEUP_EVENT); +} +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbd_sdr.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbd_sdr.c new file mode 100644 index 0000000000..6191044974 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbd_sdr.c @@ -0,0 +1,535 @@ +/** + ************************************************************************** + * @file usbd_sdr.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb standard device request + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +#include "usbd_sdr.h" +#include + +/** @addtogroup AT32F435_437_middlewares_usbd_drivers + * @{ + */ + +/** @defgroup USBD_drivers_standard_request + * @brief usb device standard_request + * @{ + */ + +/** @defgroup USBD_sdr_private_functions + * @{ + */ + +static usb_sts_type usbd_get_descriptor(usbd_core_type *udev); +static usb_sts_type usbd_set_address(usbd_core_type *udev); +static usb_sts_type usbd_get_status(usbd_core_type *udev); +static usb_sts_type usbd_clear_feature(usbd_core_type *udev); +static usb_sts_type usbd_set_feature(usbd_core_type *udev); +static usb_sts_type usbd_get_configuration(usbd_core_type *udev); +static usb_sts_type usbd_set_configuration(usbd_core_type *udev); + +/** + * @brief usb parse standard setup request + * @param setup: setup structure + * @param buf: setup buffer + * @retval none + */ +void usbd_setup_request_parse(usb_setup_type *setup, uint8_t *buf) +{ + setup->bmRequestType = *(uint8_t *) buf; + setup->bRequest = *(uint8_t *) (buf + 1); + setup->wValue = SWAPBYTE(buf + 2); + setup->wIndex = SWAPBYTE(buf + 4); + setup->wLength = SWAPBYTE(buf + 6); +} + +/** + * @brief get usb standard device description request + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type usbd_get_descriptor(usbd_core_type *udev) +{ + usb_sts_type ret = USB_OK; + uint16_t len = 0; + usbd_desc_t *desc = NULL; + uint8_t desc_type = udev->setup.wValue >> 8; + switch(desc_type) + { + case USB_DESCIPTOR_TYPE_DEVICE: + desc = udev->desc_handler->get_device_descriptor(); + break; + case USB_DESCIPTOR_TYPE_CONFIGURATION: + desc = udev->desc_handler->get_device_configuration(); + break; + case USB_DESCIPTOR_TYPE_STRING: + { + uint8_t str_desc = (uint8_t)udev->setup.wValue; + switch(str_desc) + { + case USB_LANGID_STRING: + desc = udev->desc_handler->get_device_lang_id(); + break; + case USB_MFC_STRING: + desc = udev->desc_handler->get_device_manufacturer_string(); + break; + case USB_PRODUCT_STRING: + desc = udev->desc_handler->get_device_product_string(); + break; + case USB_SERIAL_STRING: + desc = udev->desc_handler->get_device_serial_string(); + break; + case USB_CONFIG_STRING: + desc = udev->desc_handler->get_device_config_string(); + break; + case USB_INTERFACE_STRING: + desc = udev->desc_handler->get_device_interface_string(); + break; + default: + udev->class_handler->setup_handler(udev, &udev->setup); + return ret; + } + break; + } + case USB_DESCIPTOR_TYPE_DEVICE_QUALIFIER: + usbd_ctrl_unsupport(udev); + break; + case USB_DESCIPTOR_TYPE_OTHER_SPEED: + usbd_ctrl_unsupport(udev); + return ret; + default: + usbd_ctrl_unsupport(udev); + return ret; + } + + if(desc != NULL) + { + if((desc->length != 0) && (udev->setup.wLength != 0)) + { + len = MIN(desc->length , udev->setup.wLength); + usbd_ctrl_send(udev, desc->descriptor, len); + } + } + return ret; +} + +/** + * @brief this request sets the device address + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type usbd_set_address(usbd_core_type *udev) +{ + usb_sts_type ret = USB_OK; + usb_setup_type *setup = &udev->setup; + uint8_t dev_addr; + + /* if wIndex or wLength are non-zero, then the behavior of + the device is not specified + */ + if(setup->wIndex == 0 && setup->wLength == 0) + { + dev_addr = (uint8_t)(setup->wValue) & 0x7f; + + /* device behavior when this request is received + while the device is in the configured state is not specified.*/ + if(udev->conn_state == USB_CONN_STATE_CONFIGURED ) + { + usbd_ctrl_unsupport(udev); + } + else + { + udev->device_addr = dev_addr; + + if(dev_addr != 0) + { + udev->conn_state = USB_CONN_STATE_ADDRESSED; + } + else + { + udev->conn_state = USB_CONN_STATE_DEFAULT; + } + usbd_ctrl_send_status(udev); + } + } + else + { + usbd_ctrl_unsupport(udev); + } + return ret; +} + +/** + * @brief get usb status request + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type usbd_get_status(usbd_core_type *udev) +{ + usb_sts_type ret = USB_OK; + switch(udev->conn_state) + { + case USB_CONN_STATE_ADDRESSED: + case USB_CONN_STATE_CONFIGURED: + if(udev->remote_wakup) + { + udev->config_status |= USB_CONF_REMOTE_WAKEUP; + } + usbd_ctrl_send(udev, (uint8_t *)(&udev->config_status), 2); + break; + default: + usbd_ctrl_unsupport(udev); + break; + } + return ret; +} + +/** + * @brief clear usb feature request + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type usbd_clear_feature(usbd_core_type *udev) +{ + usb_sts_type ret = USB_OK; + usb_setup_type *setup = &udev->setup; + switch(udev->conn_state) + { + case USB_CONN_STATE_ADDRESSED: + case USB_CONN_STATE_CONFIGURED: + if(setup->wValue == USB_FEATURE_REMOTE_WAKEUP) + { + udev->remote_wakup = 0; + udev->config_status &= ~USB_CONF_REMOTE_WAKEUP; + udev->class_handler->setup_handler(udev, &udev->setup); + usbd_ctrl_send_status(udev); + } + break; + default: + usbd_ctrl_unsupport(udev); + break; + } + return ret; +} + +/** + * @brief set usb feature request + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type usbd_set_feature(usbd_core_type *udev) +{ + usb_sts_type ret = USB_OK; + usb_setup_type *setup = &udev->setup; + if(setup->wValue == USB_FEATURE_REMOTE_WAKEUP) + { + udev->remote_wakup = 1; + udev->class_handler->setup_handler(udev, &udev->setup); + usbd_ctrl_send_status(udev); + } + return ret; +} + +/** + * @brief get usb configuration request + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type usbd_get_configuration(usbd_core_type *udev) +{ + usb_sts_type ret = USB_OK; + usb_setup_type *setup = &udev->setup; + if(setup->wLength != 1) + { + usbd_ctrl_unsupport(udev); + } + else + { + switch(udev->conn_state) + { + case USB_CONN_STATE_ADDRESSED: + udev->default_config = 0; + usbd_ctrl_send(udev, (uint8_t *)(&udev->default_config), 1); + break; + case USB_CONN_STATE_CONFIGURED: + usbd_ctrl_send(udev, (uint8_t *)(&udev->dev_config), 1); + break; + default: + usbd_ctrl_unsupport(udev); + break; + } + } + return ret; +} + +/** + * @brief sets the usb device configuration request + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +static usb_sts_type usbd_set_configuration(usbd_core_type *udev) +{ + usb_sts_type ret = USB_OK; + static uint8_t config_value; + usb_setup_type *setup = &udev->setup; + config_value = (uint8_t)setup->wValue; + + if(setup->wIndex == 0 && setup->wLength == 0) + { + switch(udev->conn_state) + { + case USB_CONN_STATE_ADDRESSED: + if(config_value) + { + udev->dev_config = config_value; + udev->conn_state = USB_CONN_STATE_CONFIGURED; + udev->class_handler->init_handler(udev); + usbd_ctrl_send_status(udev); + } + else + { + usbd_ctrl_send_status(udev); + } + + break; + case USB_CONN_STATE_CONFIGURED: + if(config_value == 0) + { + udev->conn_state = USB_CONN_STATE_ADDRESSED; + udev->dev_config = config_value; + udev->class_handler->clear_handler(udev); + usbd_ctrl_send_status(udev); + } + else if(config_value == udev->dev_config) + { + udev->class_handler->clear_handler(udev); + udev->dev_config = config_value; + udev->class_handler->init_handler(udev); + usbd_ctrl_send_status(udev); + } + else + { + usbd_ctrl_send_status(udev); + } + break; + default: + usbd_ctrl_unsupport(udev); + break; + } + } + else + { + usbd_ctrl_unsupport(udev); + } + return ret; +} + +/** + * @brief standard usb device requests + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +usb_sts_type usbd_device_request(usbd_core_type *udev) +{ + usb_sts_type ret = USB_OK; + usb_setup_type *setup = &udev->setup; + if((setup->bmRequestType & USB_REQ_TYPE_RESERVED) != USB_REQ_TYPE_STANDARD) + { + udev->class_handler->setup_handler(udev, &udev->setup); + return ret; + } + switch(udev->setup.bRequest) + { + case USB_STD_REQ_GET_STATUS: + usbd_get_status(udev); + break; + case USB_STD_REQ_CLEAR_FEATURE: + usbd_clear_feature(udev); + break; + case USB_STD_REQ_SET_FEATURE: + usbd_set_feature(udev); + break; + case USB_STD_REQ_SET_ADDRESS: + usbd_set_address(udev); + break; + case USB_STD_REQ_GET_DESCRIPTOR: + usbd_get_descriptor(udev); + break; + case USB_STD_REQ_GET_CONFIGURATION: + usbd_get_configuration(udev); + break; + case USB_STD_REQ_SET_CONFIGURATION: + usbd_set_configuration(udev); + break; + default: + usbd_ctrl_unsupport(udev); + break; + } + return ret; +} + +/** + * @brief standard usb interface requests + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +usb_sts_type usbd_interface_request(usbd_core_type *udev) +{ + usb_sts_type ret = USB_OK; + usb_setup_type *setup = &udev->setup; + switch(udev->conn_state) + { + case USB_CONN_STATE_CONFIGURED: + udev->class_handler->setup_handler(udev, &udev->setup); + if(setup->wLength == 0) + { + usbd_ctrl_send_status(udev); + } + break; + default: + usbd_ctrl_unsupport(udev); + break; + } + return ret; +} + +/** + * @brief standard usb endpoint requests + * @param udev: to the structure of usbd_core_type + * @retval status of usb_sts_type + */ +usb_sts_type usbd_endpoint_request(usbd_core_type *udev) +{ + usb_sts_type ret = USB_OK; + usb_setup_type *setup = &udev->setup; + uint8_t ept_addr = LBYTE(setup->wIndex); + usb_ept_info *ept_info; + + if((setup->bmRequestType & USB_REQ_TYPE_RESERVED) == USB_REQ_TYPE_CLASS) + { + udev->class_handler->setup_handler(udev, &udev->setup); + } + switch(setup->bRequest) + { + case USB_STD_REQ_GET_STATUS: + switch(udev->conn_state) + { + case USB_CONN_STATE_ADDRESSED: + if((ept_addr & 0x7F) != 0) + { + usbd_set_stall(udev, ept_addr); + } + break; + case USB_CONN_STATE_CONFIGURED: + { + if((ept_addr & 0x80) != 0) + { + ept_info = &udev->ept_in[ept_addr & 0x7F]; + } + else + { + ept_info = &udev->ept_out[ept_addr & 0x7F]; + } + if(ept_info->stall == 1) + { + ept_info->status = 0x0001; + } + else + { + ept_info->status = 0x0000; + } + usbd_ctrl_send(udev, (uint8_t *)(&ept_info->status), 2); + } + break; + default: + usbd_ctrl_unsupport(udev); + break; + } + break; + case USB_STD_REQ_CLEAR_FEATURE: + switch(udev->conn_state) + { + case USB_CONN_STATE_ADDRESSED: + if((ept_addr != 0x00) && (ept_addr != 0x80)) + { + usbd_set_stall(udev, ept_addr); + } + break; + case USB_CONN_STATE_CONFIGURED: + if(setup->wValue == USB_FEATURE_EPT_HALT) + { + if((ept_addr & 0x7F) != 0x00 ) + { + usbd_clear_stall(udev, ept_addr); + udev->class_handler->setup_handler(udev, &udev->setup); + } + usbd_ctrl_send_status(udev); + } + break; + default: + usbd_ctrl_unsupport(udev); + break; + } + break; + case USB_STD_REQ_SET_FEATURE: + switch(udev->conn_state) + { + case USB_CONN_STATE_ADDRESSED: + if((ept_addr != 0x00) && (ept_addr != 0x80)) + { + usbd_set_stall(udev, ept_addr); + } + break; + case USB_CONN_STATE_CONFIGURED: + if(setup->wValue == USB_FEATURE_EPT_HALT) + { + if((ept_addr != 0x00) && (ept_addr != 0x80)) + { + usbd_set_stall(udev, ept_addr); + } + } + udev->class_handler->setup_handler(udev, &udev->setup); + usbd_ctrl_send_status(udev); + break; + default: + usbd_ctrl_unsupport(udev); + break; + } + break; + default: + usbd_ctrl_unsupport(udev); + break; + } + return ret; +} +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbh_core.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbh_core.c new file mode 100644 index 0000000000..37ae05d014 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbh_core.c @@ -0,0 +1,1241 @@ +/** + ************************************************************************** + * @file usbh_core.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb host driver + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +#include "usbh_core.h" +#include "usb_core.h" +#include "usbh_ctrl.h" +#include "usb_conf.h" + +/** @addtogroup AT32F435_437_middlewares_usbh_drivers + * @{ + */ + +/** @defgroup USBH_drivers_core + * @brief usb host drivers core + * @{ + */ + +/** @defgroup USBH_core_private_functions + * @{ + */ + +static void usbh_attached(usbh_core_type *uhost); +static void usbh_enumeration(usbh_core_type *uhost); +static void usbh_class_request(usbh_core_type *uhost); +static void usbh_class(usbh_core_type *uhost); +static void usbh_suspend(usbh_core_type *uhost); +static void usbh_wakeup(usbh_core_type *uhost); +static void usbh_disconnect(usbh_core_type *uhost); +/** + * @brief usb host free channel + * @param uhost: to the structure of usbh_core_type + * @param index: channle number + * @retval none + */ +void usbh_free_channel(usbh_core_type *uhost, uint8_t index) +{ + if(index < USB_HOST_CHANNEL_NUM) + { + /* free host channel */ + uhost->channel[index] = 0x0; + } +} + +/** + * @brief get usb host free channel + * @param uhost: to the structure of usbh_core_type + * @retval channel index + */ +uint16_t usbh_get_free_channel(usbh_core_type *uhost) +{ + uint16_t i_index = 0; + for(i_index = 0; i_index < USB_HOST_CHANNEL_NUM; i_index ++) + { + /* find unuse channel */ + if((uhost->channel[i_index] & HCH_USED) == 0) + { + /* return channel index */ + return i_index; + } + } + return HCH_ERROR; +} + + +/** + * @brief usb host set toggle + * @param uhost: to the structure of usbh_core_type + * @param hc_num: channel number + * @param toggle: toggle value + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_set_toggle(usbh_core_type *uhost, uint8_t hc_num, uint8_t toggle) +{ + if(uhost->hch[hc_num].dir) + { + /* direction in */ + uhost->hch[hc_num].toggle_in = toggle; + } + else + { + /* direction out */ + uhost->hch[hc_num].toggle_out = toggle; + } + return USB_OK; +} + +/** + * @brief usb host in out request + * @param uhost: to the structure of usbh_core_type + * @param hc_num: channel number + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_in_out_request(usbh_core_type *uhost, uint8_t hc_num) +{ + usb_sts_type status = USB_OK; + uint32_t n_packet = 0; + uint32_t num_words = 0; + uint32_t tmp; + otg_global_type *usbx = uhost->usb_reg; + otg_hchannel_type *ch = USB_CHL(uhost->usb_reg, hc_num); + + /* set usb request block to idle */ + uhost->urb_state[hc_num] = URB_IDLE; + uhost->hch[hc_num].state = HCH_IDLE; + + /* set usb channel transmit count to zero */ + uhost->hch[hc_num].trans_count = 0; + + /* check transmit data len */ + if(uhost->hch[hc_num].trans_len > 0) + { + /* count how many packet need to send */ + n_packet = (uhost->hch[hc_num].trans_len + \ + uhost->hch[hc_num].maxpacket - 1) / \ + uhost->hch[hc_num].maxpacket; + + /* packet count max 256 */ + if(n_packet > 256) + { + n_packet = 256; + uhost->hch[hc_num].trans_len = n_packet * uhost->hch[hc_num].maxpacket; + } + } + else + { + /* zero data len */ + n_packet = 1; + } + + /* direction is in */ + if(uhost->hch[hc_num].dir) + { + uhost->hch[hc_num].trans_len = n_packet * uhost->hch[hc_num].maxpacket; + } + + /* set transfer information to channel register */ + ch->hctsiz = (uhost->hch[hc_num].trans_len & USB_OTG_HCTSIZ_XFERSIZE) | + ((n_packet << 19) & USB_OTG_HCTSIZ_PKTCNT) | + ((uhost->hch[hc_num].data_pid << 29) & USB_OTG_HCTSIZ_PID); + + /* set odd frame */ + ch->hcchar_bit.oddfrm = !(OTG_HOST(uhost->usb_reg)->hfnum & 0x1); + + /* clear channel disable bit and enable channel */ + tmp = ch->hcchar; + tmp &= ~(USB_OTG_HCCHAR_CHDIS); + tmp |= USB_OTG_HCCHAR_CHENA; + ch->hcchar = tmp; + + /* channel direction is out and transfer len > 0 */ + if((uhost->hch[hc_num].dir == 0) && + (uhost->hch[hc_num].trans_len > 0 )) + { + switch(uhost->hch[hc_num].ept_type) + { + case EPT_CONTROL_TYPE: + case EPT_BULK_TYPE: + num_words = (uhost->hch[hc_num].trans_len + 3) / 4; + + /* non-periodic transfer */ + if(num_words > usbx->gnptxsts_bit.nptxfspcavail) + { + usbx->gintmsk_bit.nptxfempmsk = 1; + } + break; + case EPT_ISO_TYPE: + case EPT_INT_TYPE: + num_words = (uhost->hch[hc_num].trans_len + 3) / 4; + + /* periodic transfer */ + if(num_words > OTG_HOST(usbx)->hptxsts_bit.ptxfspcavil) + { + usbx->gintmsk_bit.ptxfempmsk = 1; + } + break; + default: + break; + } + /* write data to fifo */ + usb_write_packet(usbx, uhost->hch[hc_num].trans_buf, + hc_num, uhost->hch[hc_num].trans_len); + } + + return status; +} + +/** + * @brief usb host interrupt receive request + * @param uhost: to the structure of usbh_core_type + * @param hc_num: channel number + * @param buffer: receive buffer + * @param length: receive length + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_interrupt_recv(usbh_core_type *uhost, uint8_t hc_num, + uint8_t *buffer, uint16_t length) +{ + /* set direction is in */ + uhost->hch[hc_num].dir = 1; + + /* set transfer buffer */ + uhost->hch[hc_num].trans_buf = buffer; + + /* set transfer len*/ + uhost->hch[hc_num].trans_len = length; + + if(uhost->hch[hc_num].toggle_in == 0) + { + /* pid: data0 */ + uhost->hch[hc_num].data_pid = HCH_PID_DATA0; + } + else + { + /* pid: data1 */ + uhost->hch[hc_num].data_pid = HCH_PID_DATA1; + } + + return usbh_in_out_request(uhost, hc_num); +} + +/** + * @brief usb host interrupt send request + * @param uhost: to the structure of usbh_core_type + * @param hc_num: channel number + * @param buffer: send buffer + * @param length: send length + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_interrupt_send(usbh_core_type *uhost, uint8_t hc_num, + uint8_t *buffer, uint16_t length) +{ + /* set direction is out */ + uhost->hch[hc_num].dir = 0; + + /* set transfer buffer */ + uhost->hch[hc_num].trans_buf = buffer; + + /* set transfer len*/ + uhost->hch[hc_num].trans_len = length; + + if(uhost->hch[hc_num].toggle_out == 0) + { + /* pid: data0 */ + uhost->hch[hc_num].data_pid = HCH_PID_DATA0; + } + else + { + /* pid: data1 */ + uhost->hch[hc_num].data_pid = HCH_PID_DATA1; + } + + return usbh_in_out_request(uhost, hc_num); +} + + +/** + * @brief usb host bulk receive request + * @param uhost: to the structure of usbh_core_type + * @param hc_num: channel number + * @param buffer: receive buffer + * @param length: receive length + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_bulk_recv(usbh_core_type *uhost, uint8_t hc_num, + uint8_t *buffer, uint16_t length) +{ + /* set direction is in */ + uhost->hch[hc_num].dir = 1; + + /* set transfer buffer */ + uhost->hch[hc_num].trans_buf = buffer; + + /* set transfer len*/ + uhost->hch[hc_num].trans_len = length; + + if(uhost->hch[hc_num].toggle_in == 0) + { + /* pid: data0 */ + uhost->hch[hc_num].data_pid = HCH_PID_DATA0; + } + else + { + /* pid: data1 */ + uhost->hch[hc_num].data_pid = HCH_PID_DATA1; + } + + return usbh_in_out_request(uhost, hc_num); +} + + +/** + * @brief usb host bulk send request + * @param uhost: to the structure of usbh_core_type + * @param hc_num: channel number + * @param buffer: receive buffer + * @param length: receive length + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_bulk_send(usbh_core_type *uhost, uint8_t hc_num, + uint8_t *buffer, uint16_t length) +{ + /* set direction is out */ + uhost->hch[hc_num].dir = 0; + + /* set transfer buffer */ + uhost->hch[hc_num].trans_buf = buffer; + + /* set transfer len*/ + uhost->hch[hc_num].trans_len = length; + + if(uhost->hch[hc_num].toggle_out == 0) + { + /* pid: data0 */ + uhost->hch[hc_num].data_pid = HCH_PID_DATA0; + } + else + { + /* pid: data1 */ + uhost->hch[hc_num].data_pid = HCH_PID_DATA1; + } + + return usbh_in_out_request(uhost, hc_num); +} + + +/** + * @brief usb host iso send request + * @param uhost: to the structure of usbh_core_type + * @param hc_num: channel number + * @param buffer: send buffer + * @param length: send length + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_isoc_send(usbh_core_type *uhost, uint8_t hc_num, + uint8_t *buffer, uint16_t length) +{ + /* set direction is out */ + uhost->hch[hc_num].dir = 0; + + /* set transfer buffer */ + uhost->hch[hc_num].trans_buf = buffer; + + /* set transfer len*/ + uhost->hch[hc_num].trans_len = length; + + /* pid: data0 */ + uhost->hch[hc_num].data_pid = HCH_PID_DATA0; + + return usbh_in_out_request(uhost, hc_num); +} + +/** + * @brief usb host iso receive request + * @param uhost: to the structure of usbh_core_type + * @param hc_num: channel number + * @param buffer: receive buffer + * @param length: receive length + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_isoc_recv(usbh_core_type *uhost, uint8_t hc_num, + uint8_t *buffer, uint16_t length) +{ + /* set direction is in */ + uhost->hch[hc_num].dir = 1; + + /* set transfer buffer */ + uhost->hch[hc_num].trans_buf = buffer; + + /* set transfer len*/ + uhost->hch[hc_num].trans_len = length; + + /* pid: data0 */ + uhost->hch[hc_num].data_pid = HCH_PID_DATA0; + + return usbh_in_out_request(uhost, hc_num); +} + +/** + * @brief usb host cfg default init + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_cfg_default_init(usbh_core_type *uhost) +{ + /* set global state to idle */ + uhost->global_state = USBH_IDLE; + + /* enumeration state to get description */ + uhost->enum_state = ENUM_GET_MIN_DESC; + + /* request state send */ + uhost->req_state = CMD_SEND; + + /* control transfer state is idle*/ + uhost->ctrl.state = CONTROL_IDLE; + + /* defaut endpoint 0 max size is 8byte */ + uhost->ctrl.ept0_size = 8; + + /* default device address is 0 */ + uhost->dev.address = 0; + + /* default speed is full speed */ + uhost->dev.speed = USB_FULL_SPEED_CORE_ID; + + uhost->timer = 0; + + uhost->ctrl.err_cnt = 0; + + /* free all channel */ + usbh_free_channel(uhost, uhost->ctrl.hch_in); + usbh_free_channel(uhost, uhost->ctrl.hch_out); + return USB_OK; +} + +/** + * @brief usb host enter suspend + * @param uhost: to the structure of usbh_core_type + * @retval none + */ +void usbh_enter_suspend(usbh_core_type *uhost) +{ + otg_host_type *host = OTG_HOST(uhost->usb_reg); + uint32_t hprt_val = host->hprt; + + hprt_val &= ~(USB_OTG_HPRT_PRTENA | USB_OTG_HPRT_PRTENCHNG | + USB_OTG_HPRT_PRTOVRCACT | USB_OTG_HPRT_PRTCONDET); + + /* set port suspend */ + host->hprt = hprt_val | USB_OTG_HPRT_PRTSUSP; + + /* stop phy clock */ + usb_stop_phy_clk(uhost->usb_reg); + +} + +/** + * @brief usb host resume + * @param uhost: to the structure of usbh_core_type + * @retval none + */ +void usbh_resume(usbh_core_type *uhost) +{ + otg_host_type *host = OTG_HOST(uhost->usb_reg); + uint32_t temp = host->hprt; + + /* open phy clock */ + usb_open_phy_clk(uhost->usb_reg); + + /* clear port suspend and set port resume*/ + temp &= ~(USB_OTG_HPRT_PRTENA | USB_OTG_HPRT_PRTENCHNG | + USB_OTG_HPRT_PRTOVRCACT | USB_OTG_HPRT_PRTCONDET + | USB_OTG_HPRT_PRTSUSP); + host->hprt = temp | USB_OTG_HPRT_PRTRES; + + /* delay 20 ms */ + usb_delay_ms(20); + + /*clear port resume */ + temp = host->hprt; + temp &= ~(USB_OTG_HPRT_PRTENA | USB_OTG_HPRT_PRTENCHNG | + USB_OTG_HPRT_PRTOVRCACT | USB_OTG_HPRT_PRTCONDET + | USB_OTG_HPRT_PRTRES); + host->hprt = temp; + usb_delay_ms(5); +} + +/** + * @brief usb host core initialize + * @param uhost: to the structure of usbh_core_type + * @param usb_reg: usb otgfs peripheral global register + * this parameter can be one of the following values: + * OTG1_GLOBAL , OTG2_GLOBAL + * @param class_handler: usb host class handler type pointer + * @param user_handler: usb host user handler type pointer + * @param core_id: usb core select id + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_core_init(usbh_core_type *uhost, + usb_reg_type *usb_reg, + usbh_class_handler_type *class_handler, + usbh_user_handler_type *user_handler, + uint8_t core_id) +{ + usb_sts_type status = USB_OK; + uint32_t i_index; + otg_global_type *usbx = usb_reg; + otg_host_type *host = OTG_HOST(usbx); + uhost->usb_reg = usb_reg; + + /* host class handler */ + uhost->class_handler = class_handler; + uhost->user_handler = user_handler; + + /* host user handler */ + uhost->user_handler->user_init(); + + uhost->timer = 0; + + /* usb host cfg default init */ + usbh_cfg_default_init(uhost); + + /* clear host config to default value */ + for(i_index = 0; i_index < USB_HOST_CHANNEL_NUM; i_index ++) + { + uhost->err_cnt[i_index] = 0; + uhost->xfer_cnt[i_index] = 0; + uhost->hch_state[i_index] = HCH_IDLE; + uhost->hch[0].maxpacket = 8; + } + + /* no device connect */ + uhost->conn_sts = 0; + + /* disable usb interrupt */ + usb_interrupt_disable(usbx); + + /* usb global init */ + usb_global_init(usbx); + + /* set usb host mode */ + usb_global_set_mode(usbx, OTG_HOST_MODE); + + /* open usb phy clock*/ + usb_open_phy_clk(usbx); + + /* clock select */ + usbh_fsls_clksel(usbx, USB_HCFG_CLK_48M); + + /* set support ls and fs device */ + host->hcfg_bit.fslssupp = 0; + + if(usbx == OTG1_GLOBAL) + { + /* set receive fifo size */ + usbx->grxfsiz = USBH_RX_FIFO_SIZE; + + /* set non-periodic transmit fifo start address and depth */ + usbx->gnptxfsiz_ept0tx_bit.nptxfstaddr = USBH_RX_FIFO_SIZE; + usbx->gnptxfsiz_ept0tx_bit.nptxfdep = USBH_NP_TX_FIFO_SIZE; + + /* set periodic transmit fifo start address and depth */ + usbx->hptxfsiz_bit.ptxfstaddr = USBH_RX_FIFO_SIZE + USBH_NP_TX_FIFO_SIZE; + usbx->hptxfsiz_bit.ptxfsize = USBH_P_TX_FIFO_SIZE; + } +#ifdef OTG2_GLOBAL + if(usbx == OTG2_GLOBAL) + { + /* set receive fifo size */ + usbx->grxfsiz = USBH2_RX_FIFO_SIZE; + + /* set non-periodic transmit fifo start address and depth */ + usbx->gnptxfsiz_ept0tx_bit.nptxfstaddr = USBH2_RX_FIFO_SIZE; + usbx->gnptxfsiz_ept0tx_bit.nptxfdep = USBH2_NP_TX_FIFO_SIZE; + + /* set periodic transmit fifo start address and depth */ + usbx->hptxfsiz_bit.ptxfstaddr = USBH2_RX_FIFO_SIZE + USBH2_NP_TX_FIFO_SIZE; + usbx->hptxfsiz_bit.ptxfsize = USBH2_P_TX_FIFO_SIZE; + } +#endif + /* flush tx fifo */ + usb_flush_tx_fifo(usbx, 16); + + /* flush rx fifo */ + usb_flush_rx_fifo(usbx); + + /* clear host channel interrut mask and status */ + for(i_index = 0; i_index < USB_HOST_CHANNEL_NUM; i_index ++) + { + USB_CHL(usbx, i_index)->hcintmsk = 0; + USB_CHL(usbx, i_index)->hcint = 0xFFFFFFFF; + } + + /* power on to this port */ + usb_port_power_on(usbx, TRUE); + + /* clear global interrupt mask and status */ + usbx->gintmsk = 0; + usbx->gintsts = 0xBFFFFFFF; + + /* set global interrut mask */ + usbx->gintmsk = USB_OTG_SOF_INT | USB_OTG_RXFLVL_INT | + USB_OTG_USBSUSP_INT | USB_OTG_PRT_INT | + USB_OTG_HCH_INT | USB_OTG_INCOMISOIN_INT | + USB_OTG_INCOMPIP_INCOMPISOOUT_INT | USB_OTG_WKUP_INT | + USB_OTG_DISCON_INT; + + /* enable usb global interrupt */ + usb_interrupt_enable(usbx); + + /* active vbus */ + usbh_active_vbus(uhost, TRUE); + return status; +} + +/** + * @brief usb host open channel + * @param uhost: to the structure of usbh_core_type + * @param chn: host channel number + * @param ept_num: devvice endpoint number + * @param dev_address: device address + * @param type: channel transfer type + * this parameter can be one of the following values: + * - EPT_CONTROL_TYPE + * - EPT_BULK_TYPE + * - EPT_INT_TYPE + * - EPT_ISO_TYPE + * @param maxpacket: support max packe size for this channel + * @param speed: device speed + * this parameter can be one of the following values: + * - USB_PRTSPD_FULL_SPEED + * - USB_PRTSPD_LOW_SPEED + * @param ept_addr: endpoint address + * @retval usb_sts_type + */ +void usbh_hc_open(usbh_core_type *uhost, + uint8_t chn, + uint8_t ept_num, + uint8_t dev_address, + uint8_t type, + uint16_t maxpacket, + uint8_t speed) +{ + /* device address */ + uhost->hch[chn].address = dev_address; + + /* device speed */ + uhost->hch[chn].speed = speed; + + /* endpoint transfer type */ + uhost->hch[chn].ept_type = type; + + /* endpoint support maxpacket */ + uhost->hch[chn].maxpacket = maxpacket; + + /* endpoint direction in or out */ + uhost->hch[chn].dir = (ept_num & 0x80)?1:0;; + + /* host channel number */ + uhost->hch[chn].ch_num = chn; + + /* device endpoint number */ + uhost->hch[chn].ept_num = ept_num; + + /* enable channel */ + usb_hc_enable(uhost->usb_reg, chn, + ept_num, dev_address, + type, maxpacket, speed + ); +} + +/** + * @brief disable host channel + * @param usbx: to select the otgfs peripheral. + * this parameter can be one of the following values: + * - OTG1_GLOBAL + * - OTG2_GLOBAL + * @param chn: channel number + * @retval none + */ +void usbh_ch_disable(usbh_core_type *uhost, uint8_t chn) +{ + usb_hch_halt(uhost->usb_reg, chn); +} + +/** + * @brief usb host alloc channel + * @param uhost: to the structure of usbh_core_type + * @param ept_addr: endpoint address + * @retval usb_sts_type + */ +uint16_t usbh_alloc_channel(usbh_core_type *uhost, uint8_t ept_addr) +{ + /* get one free channel */ + uint16_t ch_num = usbh_get_free_channel(uhost); + + if(ch_num == HCH_ERROR) + return USB_FAIL; + + /* set channel to used */ + uhost->channel[ch_num] = HCH_USED | ept_addr; + return ch_num; +} + +/** + * @brief usb host get urb status + * @param uhost: to the structure of usbh_core_type + * @param ch_num: channel number + * @retval urb_sts_type: urb status + */ +urb_sts_type usbh_get_urb_status(usbh_core_type *uhost, uint8_t ch_num) +{ + return uhost->urb_state[ch_num]; +} +/** + * @brief usb wait control setup complete + * @param uhost: to the structure of usbh_core_type + * @param next_ctrl_state: next ctrl state when setup complete + * @param next_enum_state: next enum state when setup complete + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_ctrl_result_check(usbh_core_type *uhost, ctrl_ept0_sts_type next_ctrl_state, uint8_t next_enum_state) +{ + usb_sts_type status; + + /* control transfer loop */ + status = usbh_ctrl_transfer_loop(uhost); + + if(status == USB_OK) + { + uhost->ctrl.state = next_ctrl_state; + uhost->enum_state = next_enum_state; + uhost->req_state = CMD_SEND; + } + else if(status == USB_ERROR) + { + uhost->ctrl.state = CONTROL_IDLE; + uhost->req_state = CMD_SEND; + } + else if(status == USB_NOT_SUPPORT) + { + uhost->ctrl.state = next_ctrl_state; + uhost->enum_state = next_enum_state; + uhost->req_state = CMD_SEND; + } + return status; +} + +/** + * @brief auto alloc address (1...20) + * @param none + * @retval address (1...20) + */ +uint8_t usbh_alloc_address(void) +{ + static uint8_t address = 1; + if(address == 20) + address = 1; + return address ++; +} + + +/** + * @brief usb host enumeration handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_enum_handler(usbh_core_type *uhost) +{ + usb_sts_type status = USB_WAIT; + switch(uhost->enum_state) + { + case ENUM_IDLE: + break; + case ENUM_GET_MIN_DESC: + /* get description */ + if(uhost->ctrl.state == CONTROL_IDLE) + { + usbh_get_device_descriptor(uhost, 8); + } + if(usbh_ctrl_result_check(uhost, CONTROL_IDLE, ENUM_GET_FULL_DESC) == USB_OK) + { + usbh_parse_dev_desc(uhost, uhost->rx_buffer, 8); + + /* set new control endpoint maxpacket size */ + uhost->ctrl.ept0_size = (uhost->dev).dev_desc.bMaxPacketSize0; + + /* enable channel */ + usbh_hc_open(uhost, uhost->ctrl.hch_in,0x80, + uhost->dev.address, EPT_CONTROL_TYPE, + uhost->ctrl.ept0_size, + uhost->dev.speed); + + /* enable channel */ + usbh_hc_open(uhost, uhost->ctrl.hch_out,0x00, + uhost->dev.address, EPT_CONTROL_TYPE, + uhost->ctrl.ept0_size, + uhost->dev.speed); + } + break; + + case ENUM_GET_FULL_DESC: + /* get description */ + if(uhost->ctrl.state == CONTROL_IDLE) + { + usbh_get_device_descriptor(uhost, 18); + } + if(usbh_ctrl_result_check(uhost, CONTROL_IDLE, ENUM_SET_ADDR) == USB_OK) + { + usbh_parse_dev_desc(uhost, uhost->rx_buffer, 18); + USBH_DEBUG("VID: %xh", uhost->dev.dev_desc.idVendor); + USBH_DEBUG("PID: %xh", uhost->dev.dev_desc.idProduct); + } + break; + + case ENUM_SET_ADDR: + /* set device address */ + if(uhost->ctrl.state == CONTROL_IDLE) + { + uhost->dev.address = usbh_alloc_address(); + USBH_DEBUG("Set Address: %d", uhost->dev.address); + usbh_set_address(uhost, uhost->dev.address); + } + if (usbh_ctrl_result_check(uhost, CONTROL_IDLE, ENUM_GET_CFG) == USB_OK) + { + /* enable channel */ + usbh_hc_open(uhost, uhost->ctrl.hch_in,0x80, + uhost->dev.address, EPT_CONTROL_TYPE, + uhost->ctrl.ept0_size, + uhost->dev.speed); + + /* enable channel */ + usbh_hc_open(uhost, uhost->ctrl.hch_out,0x00, + uhost->dev.address, EPT_CONTROL_TYPE, + uhost->ctrl.ept0_size, + uhost->dev.speed); + } + break; + + case ENUM_GET_CFG: + /* get device confiuration */ + if(uhost->ctrl.state == CONTROL_IDLE) + { + usbh_get_configure_descriptor(uhost, 9); + } + + if(usbh_ctrl_result_check(uhost, CONTROL_IDLE, ENUM_GET_FULL_CFG) == USB_OK) + { + usbh_parse_configure_desc(uhost, uhost->rx_buffer, 9); + } + break; + + case ENUM_GET_FULL_CFG: + /* get device confiuration */ + if(uhost->ctrl.state == CONTROL_IDLE) + { + usbh_get_configure_descriptor(uhost, uhost->dev.cfg_desc.cfg.wTotalLength); + } + + if(usbh_ctrl_result_check(uhost, CONTROL_IDLE, ENUM_GET_MFC_STRING) == USB_OK) + { + usbh_parse_configure_desc(uhost, uhost->rx_buffer, uhost->dev.cfg_desc.cfg.wTotalLength); + } + break; + + case ENUM_GET_MFC_STRING: + /* get device mfc string */ + if(uhost->ctrl.state == CONTROL_IDLE) + { + usbh_get_sting_descriptor(uhost, uhost->dev.dev_desc.iManufacturer, + uhost->rx_buffer, 0xFF); + } + + if(usbh_ctrl_result_check(uhost, CONTROL_IDLE, ENUM_GET_PRODUCT_STRING) == USB_OK) + { + usbh_parse_string_desc(uhost->rx_buffer, uhost->rx_buffer, 0xFF); + uhost->user_handler->user_mfc_string(uhost->rx_buffer); + } + break; + + case ENUM_GET_PRODUCT_STRING: + /* get device product string */ + if(uhost->ctrl.state == CONTROL_IDLE) + { + usbh_get_sting_descriptor(uhost, uhost->dev.dev_desc.iProduct, + uhost->rx_buffer, 0xFF); + } + + if(usbh_ctrl_result_check(uhost, CONTROL_IDLE, ENUM_GET_SERIALNUM_STRING) == USB_OK) + { + usbh_parse_string_desc(uhost->rx_buffer, uhost->rx_buffer, 0xFF); + uhost->user_handler->user_product_string(uhost->rx_buffer); + } + break; + + case ENUM_GET_SERIALNUM_STRING: + /* get device serial string */ + if(uhost->ctrl.state == CONTROL_IDLE) + { + usbh_get_sting_descriptor(uhost, uhost->dev.dev_desc.iSerialNumber, + uhost->rx_buffer, 0xFF); + } + + if(usbh_ctrl_result_check(uhost, CONTROL_IDLE, ENUM_SET_CONFIG) == USB_OK) + { + usbh_parse_string_desc(uhost->rx_buffer, uhost->rx_buffer, 0xFF); + uhost->user_handler->user_serial_string(uhost->rx_buffer); + } + break; + + case ENUM_SET_CONFIG: + /* set device config */ + if(uhost->ctrl.state == CONTROL_IDLE) + { + usbh_set_configuration(uhost, uhost->dev.cfg_desc.cfg.bConfigurationValue); + } + usbh_ctrl_result_check(uhost, CONTROL_IDLE, ENUM_COMPLETE); + + break; + + case ENUM_COMPLETE: + /* enum complete */ + status = USB_OK; + break; + default: + break; + } + return status; +} + +/** + * @brief active vbus. + * @param uhost: to the structure of usbh_core_type + * @param state: vbus state + * @retval none + */ +void usbh_active_vbus(usbh_core_type *uhost, confirm_state state) +{ + uhost->user_handler->user_active_vbus(uhost, state); +} + +/** + * @brief reset usb port + * @param usbx: to the structure of otg_global_type + * @retval none + */ +void usbh_reset_port(usbh_core_type *uhost) +{ + otg_host_type *usb_host = OTG_HOST(uhost->usb_reg); + uint32_t hprt_val = usb_host->hprt; + + hprt_val &= ~(USB_OTG_HPRT_PRTENA | USB_OTG_HPRT_PRTENCHNG | + USB_OTG_HPRT_PRTOVRCACT | USB_OTG_HPRT_PRTCONDET); + + /* set port reset */ + usb_host->hprt = hprt_val | USB_OTG_HPRT_PRTRST; + + usb_delay_ms(100); + + /* clear port reset */ + usb_host->hprt = hprt_val & (~USB_OTG_HPRT_PRTRST); + + usb_delay_ms(20); + +} + +/** + * @brief usb host attached + * @param uhost: to the structure of usbh_core_type + * @retval none + */ +static void usbh_attached(usbh_core_type *uhost) +{ + /* get free channel */ + uhost->ctrl.hch_in = usbh_alloc_channel(uhost, 0x80); + uhost->ctrl.hch_out = usbh_alloc_channel(uhost, 0x00); + + /* user reset callback handler */ + uhost->user_handler->user_reset(); + + /* get device speed */ + uhost->dev.speed = OTG_HOST(uhost->usb_reg)->hprt_bit.prtspd; + uhost->global_state = USBH_ENUMERATION; + uhost->user_handler->user_speed(uhost->dev.speed); + + /* enable channel */ + usbh_hc_open(uhost, uhost->ctrl.hch_in,0x80, + uhost->dev.address, EPT_CONTROL_TYPE, + uhost->ctrl.ept0_size, + uhost->dev.speed); + + /* enable channel */ + usbh_hc_open(uhost, uhost->ctrl.hch_out,0x00, + uhost->dev.address, EPT_CONTROL_TYPE, + uhost->ctrl.ept0_size, + uhost->dev.speed); + + usb_flush_tx_fifo(uhost->usb_reg, 0x10); + usb_flush_rx_fifo(uhost->usb_reg); + + /* user attached callback */ + uhost->user_handler->user_attached(); +} + + +/** + * @brief usb host enumeration + * @param uhost: to the structure of usbh_core_type + * @retval none + */ +static void usbh_enumeration(usbh_core_type *uhost) +{ + /* enumeration process */ + if(usbh_enum_handler(uhost) == USB_OK) + { + /* user enumeration done callback */ + uhost->user_handler->user_enumeration_done(); + uhost->global_state = USBH_USER_HANDLER; + } +} + +/** + * @brief usb host class request + * @param uhost: to the structure of usbh_core_type + * @retval none + */ +static void usbh_class_request(usbh_core_type *uhost) +{ + usb_sts_type status; + + /* class request callback */ + status = uhost->class_handler->request_handler((void *)uhost); + if(status == USB_OK) + { + uhost->global_state = USBH_CLASS; + } + else if(status == USB_ERROR || status == USB_FAIL) + { + uhost->global_state = USBH_ERROR_STATE; + } + else if(status == USB_NOT_SUPPORT) + { + uhost->global_state = USBH_ERROR_STATE; + } +} + +/** + * @brief usb host class handler + * @param uhost: to the structure of usbh_core_type + * @retval none + */ +static void usbh_class(usbh_core_type *uhost) +{ + /* process handler */ + if(uhost->class_handler->process_handler((void *)uhost) == USB_OK) + { + } +} + +/** + * @brief usb host suspend + * @param uhost: to the structure of usbh_core_type + * @retval none + */ +static void usbh_suspend(usbh_core_type *uhost) +{ + /* set device feature */ + if(uhost->ctrl.state == CONTROL_IDLE) + { + usbh_set_feature(uhost, 0x01, 0); + } + if(usbh_ctrl_result_check(uhost, CONTROL_IDLE, ENUM_IDLE) == USB_OK) + { + /* enter suspend mode */ + usb_delay_ms(3); + usbh_enter_suspend(uhost); + uhost->global_state = USBH_SUSPENDED; + + } +} + +/** + * @brief usb host wakeup + * @param uhost: to the structure of usbh_core_type + * @retval none + */ +static void usbh_wakeup(usbh_core_type *uhost) +{ + /* clear device feature */ + if(uhost->ctrl.state == CONTROL_IDLE) + { + /* usb host resume */ + usbh_resume(uhost); + usbh_clear_dev_feature(uhost, 0x01, 0); + } + if(usbh_ctrl_result_check(uhost, CONTROL_IDLE, ENUM_IDLE) == USB_OK) + { + uhost->global_state = USBH_CLASS_REQUEST; + USBH_DEBUG("Remote Wakeup"); + } +} + +/** + * @brief usb host disconnect + * @param uhost: to the structure of usbh_core_type + * @retval none + */ +static void usbh_disconnect(usbh_core_type *uhost) +{ + uint8_t i_index = 0; + + /* set host to default state */ + usbh_cfg_default_init(uhost); + + /* free host channel */ + for(i_index = 0; i_index < USB_HOST_CHANNEL_NUM; i_index ++) + { + usbh_free_channel(uhost, i_index); + } + + /* call class reset handler */ + if(uhost->class_handler->reset_handler != NULL) + { + uhost->class_handler->reset_handler(uhost); + } + + /* set global state to idle */ + uhost->global_state = USBH_IDLE; + + /*call user disconnect function */ + uhost->user_handler->user_disconnect(); +} + + +/** + * @brief usb host enum loop handler + * @param uhost: to the structure of usbh_core_type + * @retval none + */ +usb_sts_type usbh_loop_handler(usbh_core_type *uhost) +{ + usb_sts_type status = USB_FAIL; + + if(uhost->conn_sts == 0 && + uhost->global_state != USBH_IDLE && + uhost->global_state != USBH_DISCONNECT) + { + uhost->global_state = USBH_IDLE; + } + switch(uhost->global_state) + { + case USBH_IDLE: + if(uhost->conn_sts == 1) + { + uhost->global_state = USBH_PORT_EN; + + /* wait stable */ + usb_delay_ms(200); + + /* port reset */ + usbh_reset_port(uhost); + + /* user reset */ + uhost->user_handler->user_reset(); + } + break; + + case USBH_PORT_EN: + if(uhost->port_enable) + { + uhost->global_state = USBH_ATTACHED; + usb_delay_ms(50); + } + break; + + case USBH_ATTACHED: + usbh_attached(uhost); + break; + + case USBH_ENUMERATION: + usbh_enumeration(uhost); + break; + + case USBH_USER_HANDLER: + uhost->global_state = USBH_CLASS_REQUEST; + if( uhost->class_handler->init_handler(uhost) == USB_NOT_SUPPORT) + { + uhost->global_state = USBH_UNSUPPORT; + } + break; + + case USBH_CLASS_REQUEST: + usbh_class_request(uhost); + break; + + case USBH_CLASS: + usbh_class(uhost); + break; + + case USBH_SUSPEND: + usbh_suspend(uhost); + break; + + case USBH_SUSPENDED: + break; + + case USBH_WAKEUP: + usbh_wakeup(uhost); + break; + + case USBH_DISCONNECT: + usbh_disconnect(uhost); + break; + + case USBH_ERROR_STATE: + usbh_cfg_default_init(uhost); + uhost->class_handler->reset_handler(uhost); + uhost->user_handler->user_reset(); + break; + case USBH_UNSUPPORT: + break; + default: + break; + } + + return status; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbh_ctrl.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbh_ctrl.c new file mode 100644 index 0000000000..d60ae0a455 --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbh_ctrl.c @@ -0,0 +1,976 @@ +/** + ************************************************************************** + * @file usbh_ctrl.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb host control request + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +#include "usbh_ctrl.h" +#include "usbh_core.h" +#include "usb_std.h" + +/** @addtogroup AT32F435_437_middlewares_usbh_drivers + * @{ + */ + +/** @defgroup USBH_drivers_control + * @brief usb host drivers control + * @{ + */ + +/** @defgroup USBH_ctrl_private_functions + * @{ + */ + +/* control timeout 5s */ +#define CTRL_TIMEOUT 5000 + +/** + * @brief usb host control send setup packet + * @param uhost: to the structure of usbh_core_type + * @param buffer: usb control setup send buffer + * @param hc_num: channel number + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_ctrl_send_setup(usbh_core_type *uhost, uint8_t *buffer, uint8_t hc_num) +{ + uhost->hch[hc_num].dir = 0; + uhost->hch[hc_num].data_pid = HCH_PID_SETUP; + uhost->hch[hc_num].trans_buf = buffer; + uhost->hch[hc_num].trans_len = 8; /*setup */ + + return usbh_in_out_request(uhost, hc_num); +} + +/** + * @brief usb host control receive data from device + * @param uhost: to the structure of usbh_core_type + * @param buffer: usb control receive data buffer + * @param length: usb control receive data length + * @param hc_num: channel number + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_ctrl_recv_data(usbh_core_type *uhost, uint8_t *buffer, + uint16_t length, uint16_t hc_num) +{ + uhost->hch[hc_num].dir = 1; + uhost->hch[hc_num].data_pid = HCH_PID_DATA1; + uhost->hch[hc_num].trans_buf = buffer; + uhost->hch[hc_num].trans_len = length; + + return usbh_in_out_request(uhost, hc_num); +} + +/** + * @brief usb host control send data packet + * @param uhost: to the structure of usbh_core_type + * @param buffer: usb control send data buffer + * @param length: usb control send data length + * @param hc_num: channel number + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_ctrl_send_data(usbh_core_type *uhost, uint8_t *buffer, + uint16_t length, uint16_t hc_num) +{ + uhost->hch[hc_num].dir = 0; + uhost->hch[hc_num].trans_buf = buffer; + uhost->hch[hc_num].trans_len = length; + + if(length == 0) + { + uhost->hch[uhost->ctrl.hch_out].toggle_out = 1; + } + if(uhost->hch[uhost->ctrl.hch_out].toggle_out == 0) + { + uhost->hch[hc_num].data_pid = HCH_PID_DATA0; + } + else + { + uhost->hch[hc_num].data_pid = HCH_PID_DATA1; + } + return usbh_in_out_request(uhost, hc_num); +} + +/** + * @brief usb host control setup request handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_ctrl_setup_handler(usbh_core_type *uhost) +{ + usbh_ctrl_send_setup(uhost, (uint8_t *)(&uhost->ctrl.setup), + uhost->ctrl.hch_out); + uhost->ctrl.state = CONTROL_SETUP_WAIT; + return USB_OK; +} + +/** + * @brief usb host control setup request wait handler + * @param uhost: to the structure of usbh_core_type + * @param timeout: pointer of wait timeout + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_ctrl_setup_wait_handler(usbh_core_type *uhost, uint32_t *timeout) +{ + urb_sts_type urb_state; + usb_sts_type status = USB_WAIT; + uint8_t dir; + urb_state = uhost->urb_state[uhost->ctrl.hch_out]; + if(urb_state == URB_DONE) + { + dir = uhost->ctrl.setup.bmRequestType & USB_REQUEST_DIR_MASK; + if(uhost->ctrl.setup.wLength != 0) + { + *timeout = DATA_STAGE_TIMEOUT; + if(dir == USB_DIR_D2H) //in + { + uhost->ctrl.state = CONTROL_DATA_IN; + } + else //out + { + uhost->ctrl.state = CONTROL_DATA_OUT; + } + } + else + { + *timeout = NODATA_STAGE_TIMEOUT; + if(dir == USB_DIR_D2H) //no data, send status + { + uhost->ctrl.state = CONTROL_STATUS_OUT; + } + else //out + { + uhost->ctrl.state = CONTROL_STATUS_IN; + } + } + status = USB_OK; + } + else if(urb_state == URB_ERROR || urb_state == URB_NOTREADY) + { + uhost->ctrl.state = CONTROL_ERROR; + uhost->ctrl.sts = CTRL_XACTERR; + status = USB_ERROR; + } + else + { + /* wait nak timeout 5s*/ + if(uhost->timer - uhost->ctrl.timer > CTRL_TIMEOUT) + { + uhost->ctrl.state = CONTROL_ERROR; + uhost->ctrl.sts = CTRL_XACTERR; + status = USB_ERROR; + } + } + return status; +} + +/** + * @brief usb host control data in request handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_ctrl_data_in_handler(usbh_core_type *uhost) +{ + usb_sts_type status = USB_OK; + usbh_ctrl_recv_data(uhost, uhost->ctrl.buffer, + uhost->ctrl.len, + uhost->ctrl.hch_in); + uhost->ctrl.state = CONTROL_DATA_IN_WAIT; + + return status; +} + +/** + * @brief usb host control data in wait handler + * @param uhost: to the structure of usbh_core_type + * @param timeout: wait timeout + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_ctrl_data_in_wait_handler(usbh_core_type *uhost, uint32_t timeout) +{ + usb_sts_type status = USB_OK; + urb_sts_type urb_state; + urb_state = uhost->urb_state[uhost->ctrl.hch_in]; + + if(urb_state == URB_DONE) + { + uhost->ctrl.state = CONTROL_STATUS_OUT; + } + else if(urb_state == URB_STALL) + { + uhost->ctrl.state = CONTROL_STALL; + } + else if(urb_state == URB_ERROR) + { + uhost->ctrl.state = CONTROL_ERROR; + } + else + { + /* wait nak timeout 5s*/ + if(uhost->timer - uhost->ctrl.timer > CTRL_TIMEOUT) + { + uhost->ctrl.state = CONTROL_ERROR; + uhost->ctrl.sts = CTRL_XACTERR; + status = USB_ERROR; + } + + } + return status; +} + +/** + * @brief usb host control data out request handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_ctrl_data_out_handler(usbh_core_type *uhost) +{ + usb_sts_type status = USB_OK; + uhost->hch[uhost->ctrl.hch_out].toggle_out = 1; + + usbh_ctrl_send_data(uhost, uhost->ctrl.buffer, + uhost->ctrl.len, + uhost->ctrl.hch_out); + uhost->ctrl.state = CONTROL_DATA_OUT_WAIT; + + return status; +} + +/** + * @brief usb host control data out wait handler + * @param uhost: to the structure of usbh_core_type + * @param timeout: wait timeout + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_ctrl_data_out_wait_handler(usbh_core_type *uhost, uint32_t timeout) +{ + usb_sts_type status = USB_OK; + urb_sts_type urb_state; + urb_state = uhost->urb_state[uhost->ctrl.hch_out]; + if(urb_state == URB_DONE) + { + uhost->ctrl.state = CONTROL_STATUS_IN; + } + else if(urb_state == URB_STALL) + { + uhost->ctrl.state = CONTROL_STALL; + } + else if(urb_state == URB_ERROR) + { + uhost->ctrl.state = CONTROL_ERROR; + } + else if(urb_state == URB_NOTREADY) + { + uhost->ctrl.state = CONTROL_DATA_OUT; + } + else + { + /* wait nak timeout 5s*/ + if(uhost->timer - uhost->ctrl.timer > CTRL_TIMEOUT) + { + uhost->ctrl.state = CONTROL_ERROR; + uhost->ctrl.sts = CTRL_XACTERR; + status = USB_ERROR; + } + } + return status; +} + +/** + * @brief usb host control status data in handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_ctrl_status_in_handler(usbh_core_type *uhost) +{ + usb_sts_type status = USB_OK; + usbh_ctrl_recv_data(uhost, 0, 0, + uhost->ctrl.hch_in); + uhost->ctrl.state = CONTROL_STATUS_IN_WAIT; + + + return status; +} + +/** + * @brief usb host control status data in wait handler + * @param uhost: to the structure of usbh_core_type + * @param timeout: wait timeout + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_ctrl_status_in_wait_handler(usbh_core_type *uhost, uint32_t timeout) +{ + usb_sts_type status = USB_OK; + urb_sts_type urb_state; + urb_state = uhost->urb_state[uhost->ctrl.hch_in]; + if(urb_state == URB_DONE) + { + uhost->ctrl.state = CONTROL_COMPLETE; + } + else if(urb_state == URB_STALL) + { + uhost->ctrl.state = CONTROL_STALL; + status = USB_NOT_SUPPORT; + } + else if(urb_state == URB_ERROR) + { + uhost->ctrl.state = CONTROL_ERROR; + } + else + { + /* wait nak timeout 5s*/ + if(uhost->timer - uhost->ctrl.timer > CTRL_TIMEOUT) + { + uhost->ctrl.state = CONTROL_ERROR; + uhost->ctrl.sts = CTRL_XACTERR; + status = USB_ERROR; + } + } + return status; +} + +/** + * @brief usb host control status data out wait handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_ctrl_status_out_handler(usbh_core_type *uhost) +{ + usb_sts_type status = USB_OK; + uhost->hch[uhost->ctrl.hch_out].toggle_out ^= 1; + + usbh_ctrl_send_data(uhost, 0, 0, uhost->ctrl.hch_out); + uhost->ctrl.state = CONTROL_STATUS_OUT_WAIT; + + return status; +} + +/** + * @brief usb host control status data out wait handler + * @param uhost: to the structure of usbh_core_type + * @param timeout: wait timeout + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_ctrl_status_out_wait_handler(usbh_core_type *uhost, uint32_t timeout) +{ + usb_sts_type status = USB_OK; + urb_sts_type urb_state; + urb_state = uhost->urb_state[uhost->ctrl.hch_out]; + if(urb_state == URB_DONE) + { + uhost->ctrl.state = CONTROL_COMPLETE; + } + else if(urb_state == URB_STALL) + { + uhost->ctrl.state = CONTROL_STALL; + } + else if(urb_state == URB_ERROR) + { + uhost->ctrl.state = CONTROL_ERROR; + } + else if(urb_state == URB_NOTREADY) + { + uhost->ctrl.state = CONTROL_STATUS_OUT; + } + else + { + /* wait nak timeout 5s*/ + if(uhost->timer - uhost->ctrl.timer > CTRL_TIMEOUT) + { + uhost->ctrl.state = CONTROL_ERROR; + uhost->ctrl.sts = CTRL_XACTERR; + status = USB_ERROR; + } + } + return status; +} + +/** + * @brief usb host control error handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_ctrl_error_handler(usbh_core_type *uhost) +{ + usb_sts_type status = USB_WAIT; + if(++ uhost->ctrl.err_cnt <= USBH_MAX_ERROR_COUNT) + { + uhost->ctrl.state = CONTROL_SETUP; + } + else + { + uhost->ctrl.sts = CTRL_FAIL; + uhost->global_state = USBH_ERROR_STATE; + uhost->ctrl.err_cnt = 0; + USBH_DEBUG("control error: **** Device No Response ****"); + status = USB_ERROR; + } + return status; +} + +/** + * @brief usb host control stall handler + * @param uhost: to the structure of usbh_core_type + * @retval usb_sts_type + */ +usb_sts_type usbh_ctrl_stall_handler(usbh_core_type *uhost) +{ + return USB_NOT_SUPPORT; +} + +/** + * @brief usb host control complete handler + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_ctrl_complete_handler(usbh_core_type *uhost) +{ + return USB_OK; +} + +/** + * @brief usb host control transfer loop function + * @param uhost: to the structure of usbh_core_type + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_ctrl_transfer_loop(usbh_core_type *uhost) +{ + usb_sts_type status = USB_WAIT; + static uint32_t timeout = 0; + uhost->ctrl.sts = CTRL_START; + + switch(uhost->ctrl.state) + { + case CONTROL_SETUP: + usbh_ctrl_setup_handler(uhost); + uhost->ctrl.timer = uhost->timer; + break; + + case CONTROL_SETUP_WAIT: + usbh_ctrl_setup_wait_handler(uhost, &timeout); + break; + + case CONTROL_DATA_IN: + usbh_ctrl_data_in_handler(uhost); + uhost->ctrl.timer = uhost->timer; + break; + + case CONTROL_DATA_IN_WAIT: + usbh_ctrl_data_in_wait_handler(uhost, timeout); + break; + + case CONTROL_DATA_OUT: + usbh_ctrl_data_out_handler(uhost); + uhost->ctrl.timer = uhost->timer; + break; + + case CONTROL_DATA_OUT_WAIT: + usbh_ctrl_data_out_wait_handler(uhost, timeout); + break; + + case CONTROL_STATUS_IN: + usbh_ctrl_status_in_handler(uhost); + uhost->ctrl.timer = uhost->timer; + break; + + case CONTROL_STATUS_IN_WAIT: + usbh_ctrl_status_in_wait_handler(uhost, timeout); + break; + + case CONTROL_STATUS_OUT: + usbh_ctrl_status_out_handler(uhost); + uhost->ctrl.timer = uhost->timer; + break; + + case CONTROL_STATUS_OUT_WAIT: + usbh_ctrl_status_out_wait_handler(uhost, timeout); + break; + case CONTROL_STALL: + status = usbh_ctrl_stall_handler(uhost); + break; + case CONTROL_ERROR: + status = usbh_ctrl_error_handler(uhost); + break; + case CONTROL_COMPLETE: + status = usbh_ctrl_complete_handler(uhost); + break; + + default: + break; + } + + return status; +} + +/** + * @brief usb host control request + * @param uhost: to the structure of usbh_core_type + * @param buffer: usb request buffer + * @param length: usb request length + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_ctrl_request(usbh_core_type *uhost, uint8_t *buffer, uint16_t length) +{ + usb_sts_type status = USB_OK; + if(uhost->req_state == CMD_SEND) + { + uhost->req_state = CMD_WAIT; + uhost->ctrl.buffer = buffer; + uhost->ctrl.len = length; + uhost->ctrl.state = CONTROL_SETUP; + } + return status; +} + +/** + * @brief usb host get device descriptor + * @param uhost: to the structure of usbh_core_type + * @param length: get descriptor request length + * @param req_type: usb request type + * @param wvalue: usb wvalue + * @param buffer: request buffer + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_get_descriptor(usbh_core_type *uhost, uint16_t length, + uint8_t req_type, uint16_t wvalue, + uint8_t *buffer) +{ + usb_sts_type status; + uhost->ctrl.setup.bmRequestType = USB_DIR_D2H | req_type; + uhost->ctrl.setup.bRequest = USB_STD_REQ_GET_DESCRIPTOR; + uhost->ctrl.setup.wValue = wvalue; + uhost->ctrl.setup.wLength = length; + + if((wvalue & 0xFF00) == ((USB_DESCIPTOR_TYPE_STRING << 8) & 0xFF00)) + { + uhost->ctrl.setup.wIndex = 0x0409; + } + else + { + uhost->ctrl.setup.wIndex = 0; + } + + status = usbh_ctrl_request(uhost, buffer, length); + return status; +} + +/** + * @brief usb host parse device descriptor + * @param uhost: to the structure of usbh_core_type + * @param buffer: usb device descriptor buffer + * @param length: usb device descriptor length + * @retval status: usb_sts_type status + */ +void usbh_parse_dev_desc(usbh_core_type *uhost, uint8_t *buffer, uint16_t length) +{ + usbh_dev_desc_type *desc = &(uhost->dev); + + desc->dev_desc.bLength = *(uint8_t *)(buffer + 0); + desc->dev_desc.bDescriptorType = *(uint8_t *)(buffer + 1); + desc->dev_desc.bcdUSB = SWAPBYTE(buffer + 2); + desc->dev_desc.bDeviceClass = *(uint8_t *)(buffer + 4); + desc->dev_desc.bDeviceSubClass = *(uint8_t *)(buffer + 5); + desc->dev_desc.bDeviceProtocol = *(uint8_t *)(buffer + 6); + desc->dev_desc.bMaxPacketSize0 = *(uint8_t *)(buffer + 7); + + if(length > 8) + { + desc->dev_desc.idVendor = SWAPBYTE(buffer + 8); + desc->dev_desc.idProduct = SWAPBYTE(buffer + 10); + desc->dev_desc.bcdDevice = SWAPBYTE(buffer + 12); + desc->dev_desc.iManufacturer = *(uint8_t *)(buffer + 14); + desc->dev_desc.iProduct = *(uint8_t *)(buffer + 15); + desc->dev_desc.iSerialNumber = *(uint8_t *)(buffer + 16); + desc->dev_desc.bNumConfigurations = *(uint8_t *)(buffer + 17); + } +} + +/** + * @brief usb host get next header + * @param buffer: usb data buffer + * @param index_len: pointer of index len + * @retval status: usb_sts_type status + */ +usb_header_desc_type *usbh_get_next_header(uint8_t *buf, uint16_t *index_len) +{ + *index_len += ((usb_header_desc_type *)buf)->bLength; + return (usb_header_desc_type *) + ((uint8_t *)buf + ((usb_header_desc_type *)buf)->bLength); +} + +/** + * @brief usb host parse interface descriptor + * @param intf: usb interface description type + * @param buf: interface description data buffer + * @retval none + */ +void usbh_parse_interface_desc(usb_interface_desc_type *intf, uint8_t *buf) +{ + intf->bLength = *(uint8_t *)buf; + intf->bDescriptorType = *(uint8_t *)(buf + 1); + intf->bInterfaceNumber = *(uint8_t *)(buf + 2); + intf->bAlternateSetting = *(uint8_t *)(buf + 3); + intf->bNumEndpoints = *(uint8_t *)(buf + 4); + intf->bInterfaceClass = *(uint8_t *)(buf + 5); + intf->bInterfaceSubClass = *(uint8_t *)(buf + 6); + intf->bInterfaceProtocol = *(uint8_t *)(buf + 7); + intf->iInterface = *(uint8_t *)(buf + 8); +} + +/** + * @brief usb host parse endpoint descriptor + * @param ept_desc: endpoint type + * @param buf: endpoint description data buffer + * @retval none + */ +void usbh_parse_endpoint_desc(usb_endpoint_desc_type *ept_desc, uint8_t *buf) +{ + ept_desc->bLength = *(uint8_t *)(buf + 0); + ept_desc->bDescriptorType = *(uint8_t *)(buf + 1); + ept_desc->bEndpointAddress = *(uint8_t *)(buf + 2); + ept_desc->bmAttributes = *(uint8_t *)(buf + 3); + ept_desc->wMaxPacketSize = SWAPBYTE(buf + 4); + ept_desc->bInterval = *(uint8_t *)(buf + 6); +} + +/** + * @brief usb host parse configure descriptor + * @param uhost: to the structure of usbh_core_type + * @param buffer: configure buffer + * @param length: configure length + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_parse_configure_desc(usbh_core_type *uhost, + uint8_t *buffer, uint16_t length) +{ + usb_cfg_desc_type *cfg_desc = &(uhost->dev.cfg_desc); + usb_interface_desc_type *intf_desc; + usb_endpoint_desc_type *ept_desc; + usb_header_desc_type *desc; + uint16_t index_len; + uint8_t index_intf = 0; + uint8_t index_ept = 0; + + desc = (usb_header_desc_type *)buffer; + cfg_desc->cfg.bLength = *(uint8_t *)buffer; + cfg_desc->cfg.bDescriptorType = *(uint8_t *)(buffer + 1); + cfg_desc->cfg.wTotalLength = SWAPBYTE(buffer + 2); + cfg_desc->cfg.bNumInterfaces = *(uint8_t *)(buffer + 4); + cfg_desc->cfg.bConfigurationValue = *(uint8_t *)(buffer + 5); + cfg_desc->cfg.iConfiguration = *(uint8_t *)(buffer + 6); + cfg_desc->cfg.bmAttributes = *(uint8_t *)(buffer + 7); + cfg_desc->cfg.bMaxPower = *(uint8_t *)(buffer + 8); + + if(length > USB_DEVICE_CFG_DESC_LEN) + { + index_len = USB_DEVICE_CFG_DESC_LEN; + + while((index_intf < USBH_MAX_INTERFACE) && index_len < cfg_desc->cfg.wTotalLength) + { + desc = usbh_get_next_header((uint8_t *)desc, &index_len); + if(desc->bDescriptorType == USB_DESCIPTOR_TYPE_INTERFACE) + { + index_ept = 0; + intf_desc = &cfg_desc->interface[index_intf].interface; + usbh_parse_interface_desc(intf_desc, (uint8_t *)desc); + + while(index_ept < intf_desc->bNumEndpoints && index_len < cfg_desc->cfg.wTotalLength) + { + desc = usbh_get_next_header((uint8_t *)desc, &index_len); + if(desc->bDescriptorType == USB_DESCIPTOR_TYPE_ENDPOINT) + { + ept_desc = &(cfg_desc->interface[index_intf].endpoint[index_ept]); + usbh_parse_endpoint_desc(ept_desc, (uint8_t *)desc); + index_ept ++; + } + } + index_intf ++; + } + } + } + return USB_OK; +} + +/** + * @brief usb host find interface + * @param uhost: to the structure of usbh_core_type + * @param class_code: class code + * @param sub_class: subclass code + * @param protocol: prtocol code + * @retval idx: interface index + */ +uint8_t usbh_find_interface(usbh_core_type *uhost, uint8_t class_code, uint8_t sub_class, uint8_t protocol) +{ + uint8_t idx = 0; + usb_itf_desc_type *usbitf; + for(idx = 0; idx < uhost->dev.cfg_desc.cfg.bNumInterfaces; idx ++) + { + usbitf = &uhost->dev.cfg_desc.interface[idx]; + if(((usbitf->interface.bInterfaceClass == class_code) || (class_code == 0xFF)) && + ((usbitf->interface.bInterfaceSubClass == sub_class) || (sub_class == 0xFF)) && + ((usbitf->interface.bInterfaceProtocol == protocol) || (protocol == 0xFF)) + ) + { + return idx; + } + } + return 0xFF; +} + +/** + * @brief usbh parse string descriptor + * @param src: string source pointer + * @param dest: string destination pointer + * @param length: string length + * @retval none + */ +void usbh_parse_string_desc(uint8_t *src, uint8_t *dest, uint16_t length) +{ + uint16_t len; + uint16_t i_index; + + if(src[1] == USB_DESCIPTOR_TYPE_STRING) + { + len = ((src[0] - 2) <= length ? (src[0] - 2) : length); + src += 2; + for(i_index = 0; i_index < len; i_index += 2) + { + *dest = src[i_index]; + dest ++; + } + *dest = 0; + } +} + +/** + * @brief usb host get device descriptor + * @param uhost: to the structure of usbh_core_type + * @param length: get device descriptor length + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_get_device_descriptor(usbh_core_type *uhost, uint16_t length) +{ + usb_sts_type status = USB_WAIT; + uint8_t bm_req; + uint16_t wvalue; + + bm_req = USB_REQ_RECIPIENT_DEVICE | USB_REQ_TYPE_STANDARD; + wvalue = (USB_DESCIPTOR_TYPE_DEVICE << 8) & 0xFF00; + + status = usbh_get_descriptor(uhost, length, bm_req, + wvalue, uhost->rx_buffer); + return status; +} + +/** + * @brief usb host get configure descriptor + * @param uhost: to the structure of usbh_core_type + * @param length: get device configure length + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_get_configure_descriptor(usbh_core_type *uhost, uint16_t length) +{ + usb_sts_type status = USB_WAIT; + uint8_t bm_req; + uint16_t wvalue; + + bm_req = USB_REQ_RECIPIENT_DEVICE | USB_REQ_TYPE_STANDARD; + wvalue = (USB_DESCIPTOR_TYPE_CONFIGURATION << 8) & 0xFF00; + + status = usbh_get_descriptor(uhost, length, bm_req, + wvalue, uhost->rx_buffer); + + return status; +} + +/** + * @brief usb host get string descriptor + * @param uhost: to the structure of usbh_core_type + * @param string_id: string id + * @param buffer: receive data buffer + * @param length: get device string length + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_get_sting_descriptor(usbh_core_type *uhost, uint8_t string_id, + uint8_t *buffer, uint16_t length) +{ + usb_sts_type status = USB_WAIT; + uint8_t bm_req; + uint16_t wvalue; + + bm_req = USB_REQ_RECIPIENT_DEVICE | USB_REQ_TYPE_STANDARD; + wvalue = (USB_DESCIPTOR_TYPE_STRING << 8) | string_id; + + status = usbh_get_descriptor(uhost, length, bm_req, + wvalue, uhost->rx_buffer); + + return status; +} + +/** + * @brief usb host set configurtion + * @param uhost: to the structure of usbh_core_type + * @param config: usb configuration + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_set_configuration(usbh_core_type *uhost, uint16_t config) +{ + usb_sts_type status = USB_WAIT; + uint8_t bm_req; + bm_req = USB_REQ_RECIPIENT_DEVICE | USB_REQ_TYPE_STANDARD; + + uhost->ctrl.setup.bmRequestType = USB_DIR_H2D | bm_req; + uhost->ctrl.setup.bRequest = USB_STD_REQ_SET_CONFIGURATION; + uhost->ctrl.setup.wValue = config; + uhost->ctrl.setup.wLength = 0; + uhost->ctrl.setup.wIndex = 0; + status = usbh_ctrl_request(uhost, 0, 0); + return status; +} + +/** + * @brief usb host set device address + * @param uhost: to the structure of usbh_core_type + * @param address: device address + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_set_address(usbh_core_type *uhost, uint8_t address) +{ + usb_sts_type status = USB_WAIT; + uint8_t bm_req; + bm_req = USB_REQ_RECIPIENT_DEVICE | USB_REQ_TYPE_STANDARD; + + uhost->ctrl.setup.bmRequestType = USB_DIR_H2D | bm_req; + uhost->ctrl.setup.bRequest = USB_STD_REQ_SET_ADDRESS; + uhost->ctrl.setup.wValue = (uint16_t)address; + uhost->ctrl.setup.wLength = 0; + uhost->ctrl.setup.wIndex = 0; + status = usbh_ctrl_request(uhost, 0, 0); + return status; +} + +/** + * @brief usb host set interface + * @param uhost: to the structure of usbh_core_type + * @param ept_num: endpoint number + * @param altsetting: alter setting + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_set_interface(usbh_core_type *uhost, uint8_t ept_num, uint8_t altsetting) +{ + usb_sts_type status = USB_WAIT; + uint8_t bm_req; + bm_req = USB_REQ_RECIPIENT_INTERFACE | USB_REQ_TYPE_STANDARD; + + uhost->ctrl.setup.bmRequestType = USB_DIR_H2D | bm_req; + uhost->ctrl.setup.bRequest = USB_STD_REQ_SET_INTERFACE; + uhost->ctrl.setup.wValue = (uint16_t)altsetting; + uhost->ctrl.setup.wLength = 0; + uhost->ctrl.setup.wIndex = ept_num; + status = usbh_ctrl_request(uhost, 0, 0); + return status; +} + +/** + * @brief usb host set feature + * @param uhost: to the structure of usbh_core_type + * @param feature: feature number + * @param index: index number + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_set_feature(usbh_core_type *uhost, uint8_t feature, uint16_t index) +{ + usb_sts_type status = USB_WAIT; + uint8_t bm_req; + bm_req = USB_REQ_RECIPIENT_DEVICE | USB_REQ_TYPE_STANDARD; + + uhost->ctrl.setup.bmRequestType = USB_DIR_H2D | bm_req; + uhost->ctrl.setup.bRequest = USB_STD_REQ_SET_FEATURE; + uhost->ctrl.setup.wValue = (uint16_t)feature; + uhost->ctrl.setup.wLength = 0; + uhost->ctrl.setup.wIndex = index; + status = usbh_ctrl_request(uhost, 0, 0); + return status; +} + + +/** + * @brief usb host clear device feature + * @param uhost: to the structure of usbh_core_type + * @param feature: feature number + * @param index: index number + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_clear_dev_feature(usbh_core_type *uhost, uint8_t feature, uint16_t index) +{ + usb_sts_type status = USB_WAIT; + uint8_t bm_req; + bm_req = USB_REQ_RECIPIENT_DEVICE | USB_REQ_TYPE_STANDARD; + + uhost->ctrl.setup.bmRequestType = USB_DIR_H2D | bm_req; + uhost->ctrl.setup.bRequest = USB_STD_REQ_CLEAR_FEATURE; + uhost->ctrl.setup.wValue = (uint16_t)feature; + uhost->ctrl.setup.wLength = 0; + uhost->ctrl.setup.wIndex = index; + status = usbh_ctrl_request(uhost, 0, 0); + return status; +} + +/** + * @brief usb host clear endpoint feature + * @param uhost: to the structure of usbh_core_type + * @param ept_num: endpoint number + * @param hc_num: host channel number + * @retval status: usb_sts_type status + */ +usb_sts_type usbh_clear_ept_feature(usbh_core_type *uhost, uint8_t ept_num, uint8_t hc_num) +{ + usb_sts_type status = USB_WAIT; + uint8_t bm_req; + if(uhost->ctrl.state == CONTROL_IDLE ) + { + bm_req = USB_REQ_RECIPIENT_ENDPOINT | USB_REQ_TYPE_STANDARD; + + uhost->ctrl.setup.bmRequestType = USB_DIR_H2D | bm_req; + uhost->ctrl.setup.bRequest = USB_STD_REQ_CLEAR_FEATURE; + uhost->ctrl.setup.wValue = USB_FEATURE_EPT_HALT; + uhost->ctrl.setup.wLength = 0; + uhost->ctrl.setup.wIndex = ept_num; + usbh_ctrl_request(uhost, 0, 0); + } + if(usbh_ctrl_result_check(uhost, CONTROL_IDLE, ENUM_IDLE) == USB_OK) + { + status = USB_OK; + } + return status; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ diff --git a/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbh_int.c b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbh_int.c new file mode 100644 index 0000000000..81b37dc28c --- /dev/null +++ b/lib/main/AT32F43x/Middlewares/AT/AT32_USB_Device_Library/Core/Src/usbh_int.c @@ -0,0 +1,529 @@ +/** + ************************************************************************** + * @file usbh_int.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief usb host interrupt request + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ +#include "usbh_int.h" + + +/** @addtogroup AT32F435_437_middlewares_usbh_drivers + * @{ + */ + +/** @defgroup USBH_drivers_interrupt + * @brief usb host interrupt + * @{ + */ + +/** @defgroup USBH_int_private_functions + * @{ + */ + +/** + * @brief usb host interrupt handler + * @param otgdev: to the structure of otg_core_type + * @retval none + */ +void usbh_irq_handler(otg_core_type *otgdev) +{ + otg_global_type *usbx = otgdev->usb_reg; + usbh_core_type *uhost = &otgdev->host; + uint32_t intsts = usb_global_get_all_interrupt(usbx); + + if(usbx->gintsts_bit.curmode == 1) + { + if(intsts & USB_OTG_HCH_FLAG) + { + usbh_hch_handler(uhost); + usb_global_clear_interrupt(usbx, USB_OTG_HCH_FLAG); + } + if(intsts & USB_OTG_SOF_FLAG) + { + usbh_sof_handler(uhost); + usb_global_clear_interrupt(usbx, USB_OTG_SOF_FLAG); + } + if(intsts & USB_OTG_MODEMIS_FLAG) + { + usb_global_clear_interrupt(usbx, USB_OTG_MODEMIS_FLAG); + } + if(intsts & USB_OTG_WKUP_FLAG) + { + usbh_wakeup_handler(uhost); + usb_global_clear_interrupt(usbx, USB_OTG_WKUP_FLAG); + } + while(usbx->gintsts & USB_OTG_RXFLVL_FLAG) + { + usbh_rx_qlvl_handler(uhost); + usb_global_clear_interrupt(usbx, USB_OTG_RXFLVL_FLAG); + } + if(intsts & USB_OTG_DISCON_FLAG) + { + usbh_disconnect_handler(uhost); + usb_global_clear_interrupt(usbx, USB_OTG_DISCON_FLAG); + } + if(intsts & USB_OTG_PRT_FLAG) + { + usbh_port_handler(uhost); + } + if(intsts & USB_OTG_INCOMPIP_INCOMPISOOUT_FLAG) + { + usb_global_clear_interrupt(usbx, USB_OTG_INCOMPIP_INCOMPISOOUT_FLAG); + } + if(intsts & USB_OTG_INCOMISOIN_FLAG) + { + usb_global_clear_interrupt(usbx, USB_OTG_INCOMISOIN_FLAG); + } + if(intsts & USB_OTG_PTXFEMP_FLAG) + { + usb_global_clear_interrupt(usbx, USB_OTG_PTXFEMP_FLAG); + } + if(intsts & USB_OTG_ISOOUTDROP_FLAG) + { + usb_global_clear_interrupt(usbx, USB_OTG_ISOOUTDROP_FLAG); + } + + } +} + +/** + * @brief usb host wakeup handler + * @param uhost: to the structure of usbh_core_type + * @retval none + */ +void usbh_wakeup_handler(usbh_core_type *uhost) +{ + uhost->global_state = USBH_WAKEUP; +} + +/** + * @brief usb host sof handler + * @param uhost: to the structure of usbh_core_type + * @retval none + */ +void usbh_sof_handler(usbh_core_type *uhost) +{ + uhost->timer ++; +} + +/** + * @brief usb host disconnect handler + * @param uhost: to the structure of usbh_core_type + * @retval none + */ +void usbh_disconnect_handler(usbh_core_type *uhost) +{ + otg_global_type *usbx = uhost->usb_reg; + + uint8_t i_index; + + usb_host_disable(usbx); + + uhost->conn_sts = 0; + + uhost->global_state = USBH_DISCONNECT; + + for(i_index = 0; i_index < USB_HOST_CHANNEL_NUM; i_index ++) + { + usbh_free_channel(uhost, i_index); + } + usbh_fsls_clksel(usbx, USB_HCFG_CLK_48M); +} + +/** + * @brief usb host in transfer request handler + * @param uhost: to the structure of usbh_core_type + * @param chn: channel number + * @retval none + */ +void usbh_hch_in_handler(usbh_core_type *uhost, uint8_t chn) +{ + otg_global_type *usbx = uhost->usb_reg; + otg_hchannel_type *usb_chh = USB_CHL(usbx, chn); + uint32_t hcint_value = usb_chh->hcint & usb_chh->hcintmsk; + + if( hcint_value & USB_OTG_HC_ACK_FLAG) + { + usb_chh->hcint = USB_OTG_HC_ACK_FLAG; + } + else if(hcint_value & USB_OTG_HC_STALL_FLAG) + { + usb_chh->hcintmsk_bit.chhltdmsk = TRUE; + usb_chh->hcint = USB_OTG_HC_NAK_FLAG | USB_OTG_HC_STALL_FLAG; + uhost->hch[chn].state = HCH_STALL; + usb_hch_halt(usbx, chn); + } + else if(hcint_value & USB_OTG_HC_DTGLERR_FLAG) + { + usb_chh->hcintmsk_bit.chhltdmsk = TRUE; + usb_hch_halt(usbx, chn); + usb_chh->hcint = USB_OTG_HC_DTGLERR_FLAG | USB_OTG_HC_NAK_FLAG; + uhost->hch[chn].state = HCH_DATATGLERR; + } + + else if(hcint_value & USB_OTG_HC_FRMOVRRUN_FLAG) + { + usb_chh->hcintmsk_bit.chhltdmsk = TRUE; + usb_hch_halt(usbx, chn); + usb_chh->hcint = USB_OTG_HC_FRMOVRRUN_FLAG; + } + else if(hcint_value & USB_OTG_HC_XFERC_FLAG) + { + uhost->hch[chn].state = HCH_XFRC; + usb_chh->hcint = USB_OTG_HC_XFERC_FLAG; + + if(usb_chh->hcchar_bit.eptype == EPT_BULK_TYPE || usb_chh->hcchar_bit.eptype == EPT_CONTROL_TYPE) + { + usb_chh->hcintmsk_bit.chhltdmsk = TRUE; + usb_hch_halt(usbx, chn); + usb_chh->hcint = USB_OTG_HC_NAK_FLAG; + } + else if(usb_chh->hcchar_bit.eptype == EPT_INT_TYPE) + { + usb_chh->hcchar_bit.oddfrm = TRUE; + uhost->urb_state[chn] = URB_DONE; + } + else if(usb_chh->hcchar_bit.eptype == EPT_ISO_TYPE) + { + uhost->urb_state[chn] = URB_DONE; + } + uhost->hch[chn].toggle_in ^= 1; + } + else if(hcint_value & USB_OTG_HC_CHHLTD_FLAG) + { + usb_chh->hcintmsk_bit.chhltdmsk = FALSE; + if(uhost->hch[chn].state == HCH_XFRC ) + { + uhost->urb_state[chn] = URB_DONE; + } + else if(uhost->hch[chn].state == HCH_STALL) + { + uhost->urb_state[chn] = URB_STALL; + } + else if(uhost->hch[chn].state == HCH_XACTERR || + uhost->hch[chn].state == HCH_DATATGLERR) + { + uhost->err_cnt[chn] ++; + if(uhost->err_cnt[chn] > 3) + { + uhost->urb_state[chn] = URB_ERROR; + uhost->err_cnt[chn] = 0; + } + else + { + uhost->urb_state[chn] = URB_NOTREADY; + } + usb_chh->hcchar_bit.chdis = FALSE; + usb_chh->hcchar_bit.chena = TRUE; + } + else if(uhost->hch[chn].state == HCH_NAK) + { + usb_chh->hcchar_bit.chdis = FALSE; + usb_chh->hcchar_bit.chena = TRUE; + uhost->urb_state[chn] = URB_NOTREADY; + } + usb_chh->hcint = USB_OTG_HC_CHHLTD_FLAG; + } + else if(hcint_value & USB_OTG_HC_XACTERR_FLAG) + { + usb_chh->hcintmsk_bit.chhltdmsk = TRUE; + uhost->hch[chn].state = HCH_XACTERR; + usb_hch_halt(usbx, chn); + uhost->err_cnt[chn] ++; + usb_chh->hcint = USB_OTG_HC_XACTERR_FLAG; + } + else if(hcint_value & USB_OTG_HC_NAK_FLAG) + { + if(usb_chh->hcchar_bit.eptype == EPT_INT_TYPE) + { + uhost->err_cnt[chn] = 0; + usb_chh->hcintmsk_bit.chhltdmsk = TRUE; + usb_hch_halt(usbx, chn); + } + else if(usb_chh->hcchar_bit.eptype == EPT_BULK_TYPE || + usb_chh->hcchar_bit.eptype == EPT_CONTROL_TYPE) + { + uhost->err_cnt[chn] = 0; + usb_chh->hcintmsk_bit.chhltdmsk = TRUE; + usb_hch_halt(usbx, chn); + } + uhost->hch[chn].state = HCH_NAK; + usb_chh->hcint = USB_OTG_HC_NAK_FLAG; + } + else if(hcint_value & USB_OTG_HC_BBLERR_FLAG) + { + usb_chh->hcint = USB_OTG_HC_BBLERR_FLAG; + } +} + +/** + * @brief usb host out transfer request handler + * @param uhost: to the structure of usbh_core_type + * @param chn: channel number + * @retval none + */ +void usbh_hch_out_handler(usbh_core_type *uhost, uint8_t chn) +{ + otg_global_type *usbx = uhost->usb_reg; + otg_hchannel_type *usb_chh = USB_CHL(usbx, chn); + uint32_t hcint_value = usb_chh->hcint & usb_chh->hcintmsk; + + if( hcint_value & USB_OTG_HC_ACK_FLAG) + { + usb_chh->hcint = USB_OTG_HC_ACK_FLAG; + } + else if( hcint_value & USB_OTG_HC_FRMOVRRUN_FLAG) + { + usb_chh->hcintmsk_bit.chhltdmsk = TRUE; + usb_hch_halt(usbx, chn); + usb_chh->hcint = USB_OTG_HC_FRMOVRRUN_FLAG; + } + else if( hcint_value & USB_OTG_HC_XFERC_FLAG) + { + usb_chh->hcintmsk_bit.chhltdmsk = TRUE; + usb_hch_halt(usbx, chn); + uhost->hch[chn].state = HCH_XFRC; + usb_chh->hcint = USB_OTG_HC_XFERC_FLAG; + } + else if( hcint_value & USB_OTG_HC_STALL_FLAG) + { + usb_chh->hcintmsk_bit.chhltdmsk = TRUE; + usb_chh->hcint = USB_OTG_HC_STALL_FLAG; + uhost->hch[chn].state = HCH_STALL; + usb_hch_halt(usbx, chn); + } + else if( hcint_value & USB_OTG_HC_DTGLERR_FLAG) + { + usb_chh->hcintmsk_bit.chhltdmsk = TRUE; + usb_hch_halt(usbx, chn); + usb_chh->hcint = USB_OTG_HC_DTGLERR_FLAG | USB_OTG_HC_NAK_FLAG; + uhost->hch[chn].state = HCH_DATATGLERR; + } + else if( hcint_value & USB_OTG_HC_CHHLTD_FLAG) + { + usb_chh->hcintmsk_bit.chhltdmsk = FALSE; + if(uhost->hch[chn].state == HCH_XFRC) + { + uhost->urb_state[chn] = URB_DONE; + if(uhost->hch[chn].ept_type == EPT_BULK_TYPE || + uhost->hch[chn].ept_type == EPT_INT_TYPE) + { + uhost->hch[chn].toggle_out ^= 1; + } + } + else if(uhost->hch[chn].state == HCH_NAK) + { + uhost->urb_state[chn] = URB_NOTREADY; + } + else if(uhost->hch[chn].state == HCH_STALL) + { + uhost->hch[chn].urb_sts = URB_STALL; + } + else if(uhost->hch[chn].state == HCH_XACTERR || + uhost->hch[chn].state == HCH_DATATGLERR) + { + uhost->err_cnt[chn] ++; + if(uhost->err_cnt[chn] > 3) + { + uhost->urb_state[chn] = URB_ERROR; + uhost->err_cnt[chn] = 0; + } + else + { + uhost->urb_state[chn] = URB_NOTREADY; + } + + usb_chh->hcchar_bit.chdis = FALSE; + usb_chh->hcchar_bit.chena = TRUE; + } + usb_chh->hcint = USB_OTG_HC_CHHLTD_FLAG; + } + else if( hcint_value & USB_OTG_HC_XACTERR_FLAG) + { + usb_chh->hcintmsk_bit.chhltdmsk = TRUE; + uhost->err_cnt[chn] ++; + uhost->hch[chn].state = HCH_XACTERR; + usb_hch_halt(usbx, chn); + usb_chh->hcint = USB_OTG_HC_XACTERR_FLAG | USB_OTG_HC_NAK_FLAG; + } + else if( hcint_value & USB_OTG_HC_NAK_FLAG) + { + usb_chh->hcintmsk_bit.chhltdmsk = TRUE; + uhost->err_cnt[chn] = 0; + usb_hch_halt(usbx, chn); + uhost->hch[chn].state = HCH_NAK; + usb_chh->hcint = USB_OTG_HC_NAK_FLAG; + } +} + +/** + * @brief usb host channel request handler + * @param uhost: to the structure of usbh_core_type + * @retval none + */ +void usbh_hch_handler(usbh_core_type *uhost) +{ + otg_global_type *usbx = uhost->usb_reg; + otg_host_type *usb_host = OTG_HOST(usbx); + uint32_t intsts, i_index; + + intsts = usb_host->haint & 0xFFFF; + for(i_index = 0; i_index < 16; i_index ++) + { + if(intsts & (1 << i_index)) + { + if(USB_CHL(usbx, i_index)->hcchar_bit.eptdir) + { + //hc in + usbh_hch_in_handler(uhost, i_index); + } + else + { + //hc out + usbh_hch_out_handler(uhost, i_index); + } + } + } +} + +/** + * @brief usb host rx buffer not empty request handler + * @param uhost: to the structure of usbh_core_type + * @retval none + */ +void usbh_rx_qlvl_handler(usbh_core_type *uhost) +{ + uint8_t chn; + uint32_t pktsts; + uint32_t pktcnt; + uint32_t tmp; + otg_hchannel_type *ch; + otg_global_type *usbx = uhost->usb_reg; + + usbx->gintmsk_bit.rxflvlmsk = 0; + + tmp = usbx->grxstsp; + chn = tmp & 0xF; + pktsts = (tmp >> 17) & 0xF; + pktcnt = (tmp >> 4) & 0x7FF; + ch = USB_CHL(usbx, chn); + switch(pktsts) + { + case PKTSTS_IN_DATA_PACKET_RECV: + if(pktcnt > 0 && (uhost->hch[chn].trans_buf) != 0) + { + usb_read_packet(usbx, uhost->hch[chn].trans_buf, chn, pktcnt); + uhost->hch[chn].trans_buf += pktcnt; + uhost->hch[chn].trans_count += pktcnt; + + if(ch->hctsiz_bit.pktcnt > 0) + { + ch->hcchar_bit.chdis = FALSE; + ch->hcchar_bit.chena = TRUE; + uhost->hch[chn].toggle_in ^= 1; + } + } + break; + case PKTSTS_IN_TRANSFER_COMPLETE: + break; + case PKTSTS_DATA_BIT_ERROR: + break; + case PKTSTS_CHANNEL_STOP: + break; + default: + break; + + } + usbx->gintmsk_bit.rxflvlmsk = 1; +} + +/** + * @brief usb host port request handler + * @param uhost: to the structure of usbh_core_type + * @retval none + */ +void usbh_port_handler(usbh_core_type *uhost) +{ + otg_global_type *usbx = uhost->usb_reg; + otg_host_type *usb_host = OTG_HOST(usbx); + + uint32_t prt = 0, prt_0; + + prt = usb_host->hprt; + prt_0 = prt; + + prt_0 &= ~(USB_OTG_HPRT_PRTENA | USB_OTG_HPRT_PRTENCHNG | + USB_OTG_HPRT_PRTOVRCACT | USB_OTG_HPRT_PRTCONDET); + if(prt & USB_OTG_HPRT_PRTCONDET) + { + if(prt & USB_OTG_HPRT_PRTCONSTS) + { + /* connect callback */ + uhost->conn_sts = 1; + } + prt_0 |= USB_OTG_HPRT_PRTCONDET; + } + + if(prt & USB_OTG_HPRT_PRTENCHNG) + { + prt_0 |= USB_OTG_HPRT_PRTENCHNG; + + if(prt & USB_OTG_HPRT_PRTENA) + { + if((prt & USB_OTG_HPRT_PRTSPD) == (USB_PRTSPD_LOW_SPEED << 17)) + { + usbh_fsls_clksel(usbx, USB_HCFG_CLK_6M); + } + else + { + usbh_fsls_clksel(usbx, USB_HCFG_CLK_48M); + } + /* connect callback */ + uhost->port_enable = 1; + } + else + { + /* clean up hprt */ + uhost->port_enable = 0; + } + } + + if(prt & USB_OTG_HPRT_PRTOVRCACT) + { + prt_0 |= USB_OTG_HPRT_PRTOVRCACT; + } + + usb_host->hprt = prt_0; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + diff --git a/src/main/build/build_config.h b/src/main/build/build_config.h index 2ded047b05..d97e6d300c 100644 --- a/src/main/build/build_config.h +++ b/src/main/build/build_config.h @@ -51,7 +51,10 @@ #define EXTENDED_FASTRAM #endif -#ifdef STM32H7 +#if defined (STM32H7) +#define DMA_RAM __attribute__ ((section(".DMA_RAM"))) +#define SLOW_RAM __attribute__ ((section(".SLOW_RAM"))) +#elif defined (AT32F43x) #define DMA_RAM __attribute__ ((section(".DMA_RAM"))) #define SLOW_RAM __attribute__ ((section(".SLOW_RAM"))) #else diff --git a/src/main/navigation/navigation_fw_launch.c b/src/main/navigation/navigation_fw_launch.c index 134e649dfa..92a7967afb 100644 --- a/src/main/navigation/navigation_fw_launch.c +++ b/src/main/navigation/navigation_fw_launch.c @@ -52,7 +52,9 @@ #define SWING_LAUNCH_MIN_ROTATION_RATE DEGREES_TO_RADIANS(100) // expect minimum 100dps rotation rate #define LAUNCH_MOTOR_IDLE_SPINUP_TIME 1500 // ms +#ifndef UNUSED #define UNUSED(x) ((void)(x)) +#endif #define FW_LAUNCH_MESSAGE_TEXT_WAIT_THROTTLE "RAISE THE THROTTLE" #define FW_LAUNCH_MESSAGE_TEXT_WAIT_IDLE "WAITING FOR IDLE" #define FW_LAUNCH_MESSAGE_TEXT_WAIT_DETECTION "READY TO LAUNCH" diff --git a/src/main/platform.h b/src/main/platform.h index 42fa4ff938..8c4429746d 100644 --- a/src/main/platform.h +++ b/src/main/platform.h @@ -57,6 +57,19 @@ #define U_ID_2 (*(uint32_t*)0x1ff0f428) #endif +#elif defined(AT32F43x) +#include "at32f435_437.h" + +#define U_ID_0 (*(uint32_t*)0x1FFFF7E8) +#define U_ID_1 (*(uint32_t*)0x1FFFF7EC) +#define U_ID_2 (*(uint32_t*)0x1FFFF7F0) +typedef enum +{ + DISABLE = 0, + ENABLE = !DISABLE +} FunctionalState; +#define IS_FUNCTIONAL_STATE(STATE) (((STATE) == DISABLE) || ((STATE) == ENABLE)) + #elif defined(STM32F4) #include "stm32f4xx.h" diff --git a/src/main/startup/startup_at32f435_437.s b/src/main/startup/startup_at32f435_437.s new file mode 100644 index 0000000000..dc4fd4e582 --- /dev/null +++ b/src/main/startup/startup_at32f435_437.s @@ -0,0 +1,577 @@ +/** + ****************************************************************************** + * @file startup_at32f435_437.s + * @version v2.1.0 + * @date 2022-08-16 + * @brief at32f435_437 devices vector table for gcc toolchain. + * this module performs: + * - set the initial sp + * - set the initial pc == reset_handler, + * - set the vector table entries with the exceptions isr address + * - configure the clock system and the external sram to + * be used as data memory (optional, to be enabled by user) + * - branches to main in the c library (which eventually + * calls main()). + * after reset the cortex-m4 processor is in thread mode, + * priority is privileged, and the stack is set to main. + ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m4 + .fpu softvfp + .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: + +/* custom init */ + ldr sp, =_estack /* set stack pointer */ + + bl persistentObjectInit + bl checkForBootLoaderRequest + +/* 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 + +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call static constructors */ + bl __libc_init_array +/* Call the application's entry point.*/ + 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 + + /* External Interrupts */ + .word WWDT_IRQHandler /* Window Watchdog Timer */ + .word PVM_IRQHandler /* PVM through EXINT Line detect */ + .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXINT line */ + .word ERTC_WKUP_IRQHandler /* ERTC Wakeup through the EXINT line */ + .word FLASH_IRQHandler /* Flash */ + .word CRM_IRQHandler /* CRM */ + .word EXINT0_IRQHandler /* EXINT Line 0 */ + .word EXINT1_IRQHandler /* EXINT Line 1 */ + .word EXINT2_IRQHandler /* EXINT Line 2 */ + .word EXINT3_IRQHandler /* EXINT Line 3 */ + .word EXINT4_IRQHandler /* EXINT Line 4 */ + .word EDMA_Stream1_IRQHandler /* EDMA Stream 1 */ + .word EDMA_Stream2_IRQHandler /* EDMA Stream 2 */ + .word EDMA_Stream3_IRQHandler /* EDMA Stream 3 */ + .word EDMA_Stream4_IRQHandler /* EDMA Stream 4 */ + .word EDMA_Stream5_IRQHandler /* EDMA Stream 5 */ + .word EDMA_Stream6_IRQHandler /* EDMA Stream 6 */ + .word EDMA_Stream7_IRQHandler /* EDMA Stream 7 */ + .word ADC1_2_3_IRQHandler /* ADC1 & ADC2 & ADC3 */ + .word CAN1_TX_IRQHandler /* CAN1 TX */ + .word CAN1_RX0_IRQHandler /* CAN1 RX0 */ + .word CAN1_RX1_IRQHandler /* CAN1 RX1 */ + .word CAN1_SE_IRQHandler /* CAN1 SE */ + .word EXINT9_5_IRQHandler /* EXINT Line [9:5] */ + .word TMR1_BRK_TMR9_IRQHandler /* TMR1 Brake and TMR9 */ + .word TMR1_OVF_TMR10_IRQHandler /* TMR1 Overflow and TMR10 */ + .word TMR1_TRG_HALL_TMR11_IRQHandler /* TMR1 Trigger and hall and TMR11 */ + .word TMR1_CH_IRQHandler /* TMR1 Channel */ + .word TMR2_GLOBAL_IRQHandler /* TMR2 */ + .word TMR3_GLOBAL_IRQHandler /* TMR3 */ + .word TMR4_GLOBAL_IRQHandler /* TMR4 */ + .word I2C1_EVT_IRQHandler /* I2C1 Event */ + .word I2C1_ERR_IRQHandler /* I2C1 Error */ + .word I2C2_EVT_IRQHandler /* I2C2 Event */ + .word I2C2_ERR_IRQHandler /* I2C2 Error */ + .word SPI1_IRQHandler /* SPI1 */ + .word SPI2_I2S2EXT_IRQHandler /* SPI2 */ + .word USART1_IRQHandler /* USART1 */ + .word USART2_IRQHandler /* USART2 */ + .word USART3_IRQHandler /* USART3 */ + .word EXINT15_10_IRQHandler /* EXINT Line [15:10] */ + .word ERTCAlarm_IRQHandler /* RTC Alarm through EXINT Line */ + .word OTGFS1_WKUP_IRQHandler /* OTGFS1 Wakeup from suspend */ + .word TMR8_BRK_TMR12_IRQHandler /* TMR8 Brake and TMR12 */ + .word TMR8_OVF_TMR13_IRQHandler /* TMR8 Overflow and TMR13 */ + .word TMR8_TRG_HALL_TMR14_IRQHandler /* TMR8 Trigger and hall and TMR14 */ + .word TMR8_CH_IRQHandler /* TMR8 Channel */ + .word EDMA_Stream8_IRQHandler /* EDMA Stream 8 */ + .word XMC_IRQHandler /* XMC */ + .word SDIO1_IRQHandler /* SDIO1 */ + .word TMR5_GLOBAL_IRQHandler /* TMR5 */ + .word SPI3_I2S3EXT_IRQHandler /* SPI3 */ + .word UART4_IRQHandler /* UART4 */ + .word UART5_IRQHandler /* UART5 */ + .word TMR6_DAC_GLOBAL_IRQHandler /* TMR6 & DAC */ + .word TMR7_GLOBAL_IRQHandler /* TMR7 */ + .word DMA1_Channel1_IRQHandler /* DMA1 Channel 1 */ + .word DMA1_Channel2_IRQHandler /* DMA1 Channel 2 */ + .word DMA1_Channel3_IRQHandler /* DMA1 Channel 3 */ + .word DMA1_Channel4_IRQHandler /* DMA1 Channel 4 */ + .word DMA1_Channel5_IRQHandler /* DMA1 Channel 5 */ + .word EMAC_IRQHandler /* EMAC */ + .word EMAC_WKUP_IRQHandler /* EMAC Wakeup */ + .word CAN2_TX_IRQHandler /* CAN2 TX */ + .word CAN2_RX0_IRQHandler /* CAN2 RX0 */ + .word CAN2_RX1_IRQHandler /* CAN2 RX1 */ + .word CAN2_SE_IRQHandler /* CAN2 SE */ + .word OTGFS1_IRQHandler /* OTGFS1 */ + .word DMA1_Channel6_IRQHandler /* DMA1 Channel 6 */ + .word DMA1_Channel7_IRQHandler /* DMA1 Channel 7 */ + .word 0 /* Reserved */ + .word USART6_IRQHandler /* USART6 */ + .word I2C3_EVT_IRQHandler /* I2C3 Event */ + .word I2C3_ERR_IRQHandler /* I2C3 Error */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word OTGFS2_WKUP_IRQHandler /* OTGFS2 Wakeup from suspend */ + .word OTGFS2_IRQHandler /* OTGFS2 */ + .word DVP_IRQHandler /* DVP */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word FPU_IRQHandler /* FPU */ + .word UART7_IRQHandler /* UART7 */ + .word UART8_IRQHandler /* UART8 */ + .word SPI4_IRQHandler /* SPI4 */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word QSPI2_IRQHandler /* QSPI2 */ + .word QSPI1_IRQHandler /* QSPI1 */ + .word 0 /* Reserved */ + .word DMAMUX_IRQHandler /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word SDIO2_IRQHandler /* SDIO2 */ + .word ACC_IRQHandler /* ACC */ + .word TMR20_BRK_IRQHandler /* TMR20 Brake */ + .word TMR20_OVF_IRQHandler /* TMR20 Overflow */ + .word TMR20_TRG_HALL_IRQHandler /* TMR20 Trigger and hall */ + .word TMR20_CH_IRQHandler /* TMR20 Channel */ + .word DMA2_Channel1_IRQHandler /* DMA2 Channel 1 */ + .word DMA2_Channel2_IRQHandler /* DMA2 Channel 2 */ + .word DMA2_Channel3_IRQHandler /* DMA2 Channel 3 */ + .word DMA2_Channel4_IRQHandler /* DMA2 Channel 4 */ + .word DMA2_Channel5_IRQHandler /* DMA2 Channel 5 */ + .word DMA2_Channel6_IRQHandler /* DMA2 Channel 6 */ + .word DMA2_Channel7_IRQHandler /* DMA2 Channel 7 */ + +/******************************************************************************* +* +* 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. +* +*******************************************************************************/ + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDT_IRQHandler + .thumb_set WWDT_IRQHandler,Default_Handler + + .weak PVM_IRQHandler + .thumb_set PVM_IRQHandler,Default_Handler + + .weak TAMP_STAMP_IRQHandler + .thumb_set TAMP_STAMP_IRQHandler,Default_Handler + + .weak ERTC_WKUP_IRQHandler + .thumb_set ERTC_WKUP_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak CRM_IRQHandler + .thumb_set CRM_IRQHandler,Default_Handler + + .weak EXINT0_IRQHandler + .thumb_set EXINT0_IRQHandler,Default_Handler + + .weak EXINT1_IRQHandler + .thumb_set EXINT1_IRQHandler,Default_Handler + + .weak EXINT2_IRQHandler + .thumb_set EXINT2_IRQHandler,Default_Handler + + .weak EXINT3_IRQHandler + .thumb_set EXINT3_IRQHandler,Default_Handler + + .weak EXINT4_IRQHandler + .thumb_set EXINT4_IRQHandler,Default_Handler + + .weak EDMA_Stream1_IRQHandler + .thumb_set EDMA_Stream1_IRQHandler,Default_Handler + + .weak EDMA_Stream2_IRQHandler + .thumb_set EDMA_Stream2_IRQHandler,Default_Handler + + .weak EDMA_Stream3_IRQHandler + .thumb_set EDMA_Stream3_IRQHandler,Default_Handler + + .weak EDMA_Stream4_IRQHandler + .thumb_set EDMA_Stream4_IRQHandler,Default_Handler + + .weak EDMA_Stream5_IRQHandler + .thumb_set EDMA_Stream5_IRQHandler,Default_Handler + + .weak EDMA_Stream6_IRQHandler + .thumb_set EDMA_Stream6_IRQHandler,Default_Handler + + .weak EDMA_Stream7_IRQHandler + .thumb_set EDMA_Stream7_IRQHandler,Default_Handler + + .weak ADC1_2_3_IRQHandler + .thumb_set ADC1_2_3_IRQHandler,Default_Handler + + .weak CAN1_TX_IRQHandler + .thumb_set CAN1_TX_IRQHandler,Default_Handler + + .weak CAN1_RX0_IRQHandler + .thumb_set CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SE_IRQHandler + .thumb_set CAN1_SE_IRQHandler,Default_Handler + + .weak EXINT9_5_IRQHandler + .thumb_set EXINT9_5_IRQHandler,Default_Handler + + .weak TMR1_BRK_TMR9_IRQHandler + .thumb_set TMR1_BRK_TMR9_IRQHandler,Default_Handler + + .weak TMR1_OVF_TMR10_IRQHandler + .thumb_set TMR1_OVF_TMR10_IRQHandler,Default_Handler + + .weak TMR1_TRG_HALL_TMR11_IRQHandler + .thumb_set TMR1_TRG_HALL_TMR11_IRQHandler,Default_Handler + + .weak TMR1_CH_IRQHandler + .thumb_set TMR1_CH_IRQHandler,Default_Handler + + .weak TMR2_GLOBAL_IRQHandler + .thumb_set TMR2_GLOBAL_IRQHandler,Default_Handler + + .weak TMR3_GLOBAL_IRQHandler + .thumb_set TMR3_GLOBAL_IRQHandler,Default_Handler + + .weak TMR4_GLOBAL_IRQHandler + .thumb_set TMR4_GLOBAL_IRQHandler,Default_Handler + + .weak I2C1_EVT_IRQHandler + .thumb_set I2C1_EVT_IRQHandler,Default_Handler + + .weak I2C1_ERR_IRQHandler + .thumb_set I2C1_ERR_IRQHandler,Default_Handler + + .weak I2C2_EVT_IRQHandler + .thumb_set I2C2_EVT_IRQHandler,Default_Handler + + .weak I2C2_ERR_IRQHandler + .thumb_set I2C2_ERR_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_I2S2EXT_IRQHandler + .thumb_set SPI2_I2S2EXT_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXINT15_10_IRQHandler + .thumb_set EXINT15_10_IRQHandler,Default_Handler + + .weak ERTCAlarm_IRQHandler + .thumb_set ERTCAlarm_IRQHandler,Default_Handler + + .weak OTGFS1_WKUP_IRQHandler + .thumb_set OTGFS1_WKUP_IRQHandler,Default_Handler + + .weak TMR8_BRK_TMR12_IRQHandler + .thumb_set TMR8_BRK_TMR12_IRQHandler,Default_Handler + + .weak TMR8_OVF_TMR13_IRQHandler + .thumb_set TMR8_OVF_TMR13_IRQHandler,Default_Handler + + .weak TMR8_TRG_HALL_TMR14_IRQHandler + .thumb_set TMR8_TRG_HALL_TMR14_IRQHandler,Default_Handler + + .weak TMR8_CH_IRQHandler + .thumb_set TMR8_CH_IRQHandler,Default_Handler + + .weak EDMA_Stream8_IRQHandler + .thumb_set EDMA_Stream8_IRQHandler,Default_Handler + + .weak XMC_IRQHandler + .thumb_set XMC_IRQHandler,Default_Handler + + .weak SDIO1_IRQHandler + .thumb_set SDIO1_IRQHandler,Default_Handler + + .weak TMR5_GLOBAL_IRQHandler + .thumb_set TMR5_GLOBAL_IRQHandler,Default_Handler + + .weak SPI3_I2S3EXT_IRQHandler + .thumb_set SPI3_I2S3EXT_IRQHandler,Default_Handler + + .weak UART4_IRQHandler + .thumb_set UART4_IRQHandler,Default_Handler + + .weak UART5_IRQHandler + .thumb_set UART5_IRQHandler,Default_Handler + + .weak TMR6_DAC_GLOBAL_IRQHandler + .thumb_set TMR6_DAC_GLOBAL_IRQHandler,Default_Handler + + .weak TMR7_GLOBAL_IRQHandler + .thumb_set TMR7_GLOBAL_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak EMAC_IRQHandler + .thumb_set EMAC_IRQHandler,Default_Handler + + .weak EMAC_WKUP_IRQHandler + .thumb_set EMAC_WKUP_IRQHandler,Default_Handler + + .weak CAN2_TX_IRQHandler + .thumb_set CAN2_TX_IRQHandler,Default_Handler + + .weak CAN2_RX0_IRQHandler + .thumb_set CAN2_RX0_IRQHandler ,Default_Handler + + .weak CAN2_RX1_IRQHandler + .thumb_set CAN2_RX1_IRQHandler ,Default_Handler + + .weak CAN2_SE_IRQHandler + .thumb_set CAN2_SE_IRQHandler,Default_Handler + + .weak OTGFS1_IRQHandler + .thumb_set OTGFS1_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak USART6_IRQHandler + .thumb_set USART6_IRQHandler,Default_Handler + + .weak I2C3_EVT_IRQHandler + .thumb_set I2C3_EVT_IRQHandler,Default_Handler + + .weak I2C3_ERR_IRQHandler + .thumb_set I2C3_ERR_IRQHandler,Default_Handler + + .weak OTGFS2_WKUP_IRQHandler + .thumb_set OTGFS2_WKUP_IRQHandler,Default_Handler + + .weak OTGFS2_IRQHandler + .thumb_set OTGFS2_IRQHandler,Default_Handler + + .weak DVP_IRQHandler + .thumb_set DVP_IRQHandler,Default_Handler + + .weak FPU_IRQHandler + .thumb_set FPU_IRQHandler,Default_Handler + + .weak UART7_IRQHandler + .thumb_set UART7_IRQHandler,Default_Handler + + .weak UART8_IRQHandler + .thumb_set UART8_IRQHandler,Default_Handler + + .weak SPI4_IRQHandler + .thumb_set SPI4_IRQHandler,Default_Handler + + .weak QSPI2_IRQHandler + .thumb_set QSPI2_IRQHandler,Default_Handler + + .weak QSPI1_IRQHandler + .thumb_set QSPI1_IRQHandler,Default_Handler + + .weak DMAMUX_IRQHandler + .thumb_set DMAMUX_IRQHandler ,Default_Handler + + .weak SDIO2_IRQHandler + .thumb_set SDIO2_IRQHandler ,Default_Handler + + .weak ACC_IRQHandler + .thumb_set ACC_IRQHandler,Default_Handler + + .weak TMR20_BRK_IRQHandler + .thumb_set TMR20_BRK_IRQHandler,Default_Handler + + .weak TMR20_OVF_IRQHandler + .thumb_set TMR20_OVF_IRQHandler,Default_Handler + + .weak TMR20_TRG_HALL_IRQHandler + .thumb_set TMR20_TRG_HALL_IRQHandler,Default_Handler + + .weak TMR20_CH_IRQHandler + .thumb_set TMR20_CH_IRQHandler,Default_Handler + + .weak DMA2_Channel1_IRQHandler + .thumb_set DMA2_Channel1_IRQHandler,Default_Handler + + .weak DMA2_Channel2_IRQHandler + .thumb_set DMA2_Channel2_IRQHandler,Default_Handler + + .weak DMA2_Channel3_IRQHandler + .thumb_set DMA2_Channel3_IRQHandler,Default_Handler + + .weak DMA2_Channel4_IRQHandler + .thumb_set DMA2_Channel4_IRQHandler,Default_Handler + + .weak DMA2_Channel5_IRQHandler + .thumb_set DMA2_Channel5_IRQHandler,Default_Handler + + .weak DMA2_Channel6_IRQHandler + .thumb_set DMA2_Channel6_IRQHandler,Default_Handler + + .weak DMA2_Channel7_IRQHandler + .thumb_set DMA2_Channel7_IRQHandler,Default_Handler diff --git a/src/main/target/link/at32_flash_f43xG.ld b/src/main/target/link/at32_flash_f43xG.ld new file mode 100644 index 0000000000..7d43eae4e3 --- /dev/null +++ b/src/main/target/link/at32_flash_f43xG.ld @@ -0,0 +1,50 @@ +/* +***************************************************************************** +** +** File : at32_flash_f43xG.ld +** +** Abstract : Linker script for AT32F435/7xM Device with +** 1024 Byte FLASH, 384KByte RAM +** +** Set heap size, stack size and stack location according +** to application requirements. +** +** Set memory bank area and size if external memory is used. +** +** Target : Artery Tek AT32 +** +** Environment : Arm gcc toolchain +** +***************************************************************************** +*/ + + +/* + FLASH : 0x0800 0000 -- 0x083E FFFF + MEM : 0x2000 0000 -- 0x2007 FFFF + +*/ + + + +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 10K + FLASH_CUSTOM_DEFAULTS (r) : ORIGIN = 0x08002800, LENGTH = 6K + FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K + FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 976K : 992K + FLASH_CUSTOM_DEFAULTS_EXTENDED (r): ORIGIN = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 0x080FC000 : 0x08100000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 16K : 0K + + SYSTEM_MEMORY (rx) : ORIGIN = 0x1FFF0000, LENGTH = 16K + RAM1 (xrw) : ORIGIN = 0x10000000, LENGTH = 64K + RAM (xrw) : ORIGIN = 0x20010000, LENGTH = 128K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K /* external ram */ +} + +REGION_ALIAS("STACKRAM", RAM) +REGION_ALIAS("FASTRAM", RAM1) +REGION_ALIAS("VECTAB", RAM1) + +REGION_ALIAS("MOVABLE_FLASH", FLASH1) + +INCLUDE "at32_flash_f4_split.ld" \ No newline at end of file diff --git a/src/main/target/link/at32_flash_f43xM.ld b/src/main/target/link/at32_flash_f43xM.ld new file mode 100644 index 0000000000..2c8d11d0ba --- /dev/null +++ b/src/main/target/link/at32_flash_f43xM.ld @@ -0,0 +1,50 @@ +/* +***************************************************************************** +** +** File : at32_flash_f43xM.ld +** +** Abstract : Linker script for AT32F435/7xM Device with +** 4032KByte FLASH, 384KByte RAM +** +** Set heap size, stack size and stack location according +** to application requirements. +** +** Set memory bank area and size if external memory is used. +** +** Target : Artery Tek AT32 +** +** Environment : Arm gcc toolchain +** +***************************************************************************** +*/ + + +/* + FLASH : 0x0800 0000 -- 0x083E FFFF + MEM : 0x2000 0000 -- 0x2007 FFFF + +*/ + + + +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 10K + FLASH_CUSTOM_DEFAULTS (r) : ORIGIN = 0x08002800, LENGTH = 6K + FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K + FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 3984K: 4000K + FLASH_CUSTOM_DEFAULTS_EXTENDED (r): ORIGIN = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 0x083EC000 : 0x083F0000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 16K : 0K + + SYSTEM_MEMORY (rx) : ORIGIN = 0x1FFF0000, LENGTH = 16K + RAM1 (xrw) : ORIGIN = 0x10000000, LENGTH = 64K + RAM (xrw) : ORIGIN = 0x20010000, LENGTH = 128K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K /* external ram */ +} + +REGION_ALIAS("STACKRAM", RAM) +REGION_ALIAS("FASTRAM", RAM1) +REGION_ALIAS("VECTAB", RAM1) + +REGION_ALIAS("MOVABLE_FLASH", FLASH1) + +INCLUDE "at32_flash_f4_split.ld" \ No newline at end of file diff --git a/src/main/target/link/at32_flash_f43xM_bl.ld b/src/main/target/link/at32_flash_f43xM_bl.ld new file mode 100644 index 0000000000..f0be9d4a56 --- /dev/null +++ b/src/main/target/link/at32_flash_f43xM_bl.ld @@ -0,0 +1,52 @@ +/* +***************************************************************************** +** +** File : at32_flash_f43xM.ld +** +** Abstract : Linker script for AT32F435/7xM Device with +** 4032KByte FLASH, 384KByte RAM +** +** Set heap size, stack size and stack location according +** to application requirements. +** +** Set memory bank area and size if external memory is used. +** +** Target : Artery Tek AT32 +** +** Environment : Arm gcc toolchain +** +***************************************************************************** +*/ + + +/* + FLASH : 0x0800 0000 -- 0x083E FFFF + MEM : 0x2000 0000 -- 0x2007 FFFF + +*/ + + + +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 10K + FLASH_CUSTOM_DEFAULTS (r) : ORIGIN = 0x08002800, LENGTH = 6K + FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K + FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 3984K: 4000K + FLASH_CUSTOM_DEFAULTS_EXTENDED (r): ORIGIN = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 0x083EC000 : 0x083F0000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 16K : 0K + + SYSTEM_MEMORY (rx) : ORIGIN = 0x1FFF0000, LENGTH = 16K + RAM1 (xrw) : ORIGIN = 0x10000000, LENGTH = 64K + RAM (xrw) : ORIGIN = 0x20010000, LENGTH = 128K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K /* external ram */ +} + +REGION_ALIAS("STACKRAM", RAM) +REGION_ALIAS("FASTRAM", RAM1) +REGION_ALIAS("VECTAB", RAM1) + + +__firmware_start = ORIGIN(FLASH1); +REGION_ALIAS("MOVABLE_FLASH", FLASH1) + +INCLUDE "at32_flash_f4_split.ld" \ No newline at end of file diff --git a/src/main/target/link/at32_flash_f43xM_for_bl.ld b/src/main/target/link/at32_flash_f43xM_for_bl.ld new file mode 100644 index 0000000000..1f83b7f38f --- /dev/null +++ b/src/main/target/link/at32_flash_f43xM_for_bl.ld @@ -0,0 +1,52 @@ +/* +***************************************************************************** +** +** File : at32_flash_f43xM.ld +** +** Abstract : Linker script for AT32F435/7xM Device with +** 4032KByte FLASH, 384KByte RAM +** +** Set heap size, stack size and stack location according +** to application requirements. +** +** Set memory bank area and size if external memory is used. +** +** Target : Artery Tek AT32 +** +** Environment : Arm gcc toolchain +** +***************************************************************************** +*/ + + +/* + FLASH : 0x0800 0000 -- 0x083E FFFF + MEM : 0x2000 0000 -- 0x2007 FFFF + +*/ + + + +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08008000, LENGTH = 10K + FLASH_CUSTOM_DEFAULTS (r) : ORIGIN = 0x800A800, LENGTH = 6K + FLASH_CONFIG (r) : ORIGIN = 0x0800C000, LENGTH = 16K + FLASH1 (rx) : ORIGIN = 0x08010000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 3952K: 3968K + FLASH_CUSTOM_DEFAULTS_EXTENDED (r): ORIGIN = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 0x083E4000 : 0x083E8000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 16K : 0K + + SYSTEM_MEMORY (rx) : ORIGIN = 0x1FFF0000, LENGTH = 16K + RAM1 (xrw) : ORIGIN = 0x10000000, LENGTH = 64K + RAM (xrw) : ORIGIN = 0x20010000, LENGTH = 128K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K /* external ram */ +} + +REGION_ALIAS("STACKRAM", RAM) +REGION_ALIAS("FASTRAM", RAM1) +REGION_ALIAS("VECTAB", RAM1) + +__firmware_start = ORIGIN(FLASH); +REGION_ALIAS("MOVABLE_FLASH", FLASH1) + + +INCLUDE "at32_flash_f4_split.ld" \ No newline at end of file diff --git a/src/main/target/link/at32_flash_f4_split.ld b/src/main/target/link/at32_flash_f4_split.ld new file mode 100644 index 0000000000..5a24637974 --- /dev/null +++ b/src/main/target/link/at32_flash_f4_split.ld @@ -0,0 +1,267 @@ +/* +***************************************************************************** +** +** File : at32_flash_f4_split.ld +** +** Abstract : Common linker script for STM32 devices. +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_Hot_Reboot_Flags_Size = 16; +_estack = ORIGIN(STACKRAM) + LENGTH(STACKRAM) - _Hot_Reboot_Flags_Size; /* end of RAM */ + +/* Base address where the config is stored. */ +__config_start = ORIGIN(FLASH_CONFIG); +__config_end = ORIGIN(FLASH_CONFIG) + LENGTH(FLASH_CONFIG); + +/* Generate a link error if heap and stack don't fit into RAM */ +_Min_Heap_Size = 0x200; /* required amount of heap */ +_Min_Stack_Size = 0x400; /* required amount of stack */ + +/* Define output sections */ +SECTIONS +{ + /* + * The ISR vector table is loaded at the beginning of the FLASH, + * But it is linked (space reserved) at the beginning of the VECTAB region, + * which is aliased either to FLASH or RAM. + * When linked to RAM, the table can optionally be copied from FLASH to RAM + * for table relocation. + */ + + _isr_vector_table_flash_base = LOADADDR(.isr_vector); + PROVIDE (isr_vector_table_flash_base = _isr_vector_table_flash_base); + + .isr_vector : + { + . = ALIGN(4); + PROVIDE (isr_vector_table_base = .); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + PROVIDE (isr_vector_table_end = .); + } >FLASH + + + + /* System memory (read-only bootloader) interrupt vector */ + .system_isr_vector (NOLOAD) : + { + . = ALIGN(4); + PROVIDE (system_isr_vector_table_base = .); + KEEP(*(.system_isr_vector)) /* Bootloader code */ + . = ALIGN(4); + } >SYSTEM_MEMORY + + /* The program code and other data goes into FLASH */ + .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); + _etext = .; /* define a global symbols at end of code */ + } >FLASH1 + + + /* Critical program code goes into ZW RAM1 */ + /* Copy specific fast-executing code to ITCM RAM */ + tcm_code = LOADADDR(.tcm_code); + .tcm_code : + { + . = ALIGN(4); + tcm_code_start = .; + *(.tcm_code) + *(.tcm_code*) + . = ALIGN(4); + tcm_code_end = .; + } >RAM1 AT >FLASH1 + + + .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH + .ARM : { + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + } >MOVABLE_FLASH + + .busdev_registry : + { + PROVIDE_HIDDEN (__busdev_registry_start = .); + KEEP (*(.busdev_registry)) + KEEP (*(SORT(.busdev_registry.*))) + PROVIDE_HIDDEN (__busdev_registry_end = .); + } >MOVABLE_FLASH + .preinit_array : + { + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + } >MOVABLE_FLASH + .init_array : + { + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + } >MOVABLE_FLASH + .fini_array : + { + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(.fini_array*)) + KEEP (*(SORT(.fini_array.*))) + PROVIDE_HIDDEN (__fini_array_end = .); + } >MOVABLE_FLASH + .pg_registry : + { + PROVIDE_HIDDEN (__pg_registry_start = .); + KEEP (*(.pg_registry)) + KEEP (*(SORT(.pg_registry.*))) + PROVIDE_HIDDEN (__pg_registry_end = .); + } >MOVABLE_FLASH + .pg_resetdata : + { + PROVIDE_HIDDEN (__pg_resetdata_start = .); + KEEP (*(.pg_resetdata)) + PROVIDE_HIDDEN (__pg_resetdata_end = .); + } >FLASH1 + + /* Storage for the address for the configuration section so we can grab it out of the hex file */ + .custom_defaults : + { + . = ALIGN(4); + KEEP (*(.custom_defaults_start_address)) + . = ALIGN(4); + KEEP (*(.custom_defaults_end_address)) + . = ALIGN(4); + __custom_defaults_internal_start = .; + *(.custom_defaults); + } >FLASH_CUSTOM_DEFAULTS + + PROVIDE_HIDDEN (__custom_defaults_start = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? ORIGIN(FLASH_CUSTOM_DEFAULTS_EXTENDED) : __custom_defaults_internal_start); + PROVIDE_HIDDEN (__custom_defaults_end = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? ORIGIN(FLASH_CUSTOM_DEFAULTS_EXTENDED) + LENGTH(FLASH_CUSTOM_DEFAULTS_EXTENDED) : ORIGIN(FLASH_CUSTOM_DEFAULTS) + LENGTH(FLASH_CUSTOM_DEFAULTS)); + + /* used by the startup to initialize data */ + _sidata = LOADADDR(.data); + + /* Initialized data sections goes into RAM, load LMA copy after code */ + .data : + { + . = 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 AT> MOVABLE_FLASH + + /* Uninitialized data section */ + . = ALIGN(4); + .bss (NOLOAD) : + { + /* 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) + *(SORT_BY_ALIGNMENT(.bss*)) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* used during startup to initialized fastram_data */ + _sfastram_idata = LOADADDR(.fastram_data); + + /* Initialized FAST_DATA section for unsuspecting developers */ + /* init in startup/system_at32f43x.c */ + .fastram_data : + { + . = ALIGN(4); + _sfastram_data = .; /* create a global symbol at data start */ + *(.fastram_data) /* .data sections */ + *(.fastram_data*) /* .data* sections */ + + . = ALIGN(4); + _efastram_data = .; /* define a global symbol at data end */ + } >FASTRAM AT> FLASH1 + +/* define FAST_DATA_ZERO_INIT part Initialized in startup_at23f435_437_.S */ + . = ALIGN(4); + .fastram_bss (NOLOAD) : + { + _sfastram_bss = .; + __fastram_bss_start__ = _sfastram_bss; + *(.fastram_bss) + *(SORT_BY_ALIGNMENT(.fastram_bss*)) + + . = ALIGN(4); + _efastram_bss = .; + __fastram_bss_end__ = _efastram_bss; + } >FASTRAM + + .persistent_data (NOLOAD) : + { + __persistent_data_start__ = .; + *(.persistent_data) + . = ALIGN(4); + __persistent_data_end__ = .; + } >FASTRAM + + .DMA_RAM (NOLOAD) : + { + __dmaram_start__ = .; + *(.DMA_RAM) + . = ALIGN(32); + __dmaram_end__ = .; + } >FASTRAM + + /* User_heap_stack section, used to check that there is enough RAM left */ + _heap_stack_end = ORIGIN(STACKRAM) + LENGTH(STACKRAM) - _Hot_Reboot_Flags_Size; + _heap_stack_begin = _heap_stack_end - _Min_Stack_Size - _Min_Heap_Size; + . = _heap_stack_begin; + ._user_heap_stack : + { + . = ALIGN(4); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(4); + } >STACKRAM = 0xa5 + + /* MEMORY_bank1 section, code must be located here explicitly */ + /* Example: extern int foo(void) __attribute__ ((section (".mb1text"))); */ + .memory_b1_text : + { + *(.mb1text) /* .mb1text sections (code) */ + *(.mb1text*) /* .mb1text* sections (code) */ + *(.mb1rodata) /* read-only data (constants) */ + *(.mb1rodata*) + } >MEMORY_B1 + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} diff --git a/src/main/target/system_at32f435_437.c b/src/main/target/system_at32f435_437.c new file mode 100644 index 0000000000..259d511fb1 --- /dev/null +++ b/src/main/target/system_at32f435_437.c @@ -0,0 +1,186 @@ +/** + ************************************************************************** + * @file system_at32f435_437.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief contains all the functions for cmsis cortex-m4 system source file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup AT32F435_437_system + * @{ + */ + +#include "at32f435_437.h" +#include "drivers/system.h" +#include "platform.h" +#include "drivers/persistent.h" + +/** @addtogroup AT32F435_437_system_private_defines + * @{ + */ +#define VECT_TAB_OFFSET 0x0 /*!< vector table base offset field. this value must be a multiple of 0x200. */ +/** + * @} + */ + +/** @addtogroup AT32F435_437_system_private_variables + * @{ + */ +unsigned int system_core_clock = HICK_VALUE; /*!< system clock frequency (core clock) */ +/** + * @} + */ + +/** @addtogroup AT32F435_437_system_private_functions + * @{ + */ + +/** + * @brief setup the microcontroller system + * initialize the flash interface. + * @note this function should be used only after reset. + * @param none + * @retval none + */ +void SystemInit (void) +{ + initialiseMemorySections(); +#if defined (__FPU_USED) && (__FPU_USED == 1U) + SCB->CPACR |= ((3U << 10U * 2U) | /* set cp10 full access */ + (3U << 11U * 2U) ); /* set cp11 full access */ +#endif + + /* reset the crm clock configuration to the default reset state(for debug purpose) */ + /* set hicken bit */ + CRM->ctrl_bit.hicken = TRUE; + + /* wait hick stable */ + while(CRM->ctrl_bit.hickstbl != SET); + + /* hick used as system clock */ + CRM->cfg_bit.sclksel = CRM_SCLK_HICK; + + /* wait sclk switch status */ + while(CRM->cfg_bit.sclksts != CRM_SCLK_HICK); + + /* reset hexten, hextbyps, cfden and pllen bits */ + CRM->ctrl &= ~(0x010D0000U); + + /* reset cfg register, include sclk switch, ahbdiv, apb1div, apb2div, adcdiv, clkout bits */ + CRM->cfg = 0; + + /* reset pllms pllns pllfr pllrcs bits */ + CRM->pllcfg = 0x00033002U; + + /* reset clkout[3], usbbufs, hickdiv, clkoutdiv */ + CRM->misc1 = 0; + + /* disable all interrupts enable and clear pending bits */ + CRM->clkint = 0x009F0000U; +// todo set RAM +#ifdef VECT_TAB_SRAM + SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* vector table relocation in internal sram. */ +#else + SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* vector table relocation in internal flash. */ +#endif +} + +/** + * @brief update system_core_clock variable according to clock register values. + * the system_core_clock variable contains the core clock (hclk), it can + * be used by the user application to setup the systick timer or configure + * other parameters. + * @param none + * @retval none + */ +void system_core_clock_update(void) +{ + uint32_t pll_ns = 0, pll_ms = 0, pll_fr = 0, pll_clock_source = 0, pllrcsfreq = 0; + uint32_t temp = 0, div_value = 0; + crm_sclk_type sclk_source; + + static const uint8_t sys_ahb_div_table[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9}; + static const uint8_t pll_fr_table[6] = {1, 2, 4, 8, 16, 32}; + + /* get sclk source */ + sclk_source = crm_sysclk_switch_status_get(); + + switch(sclk_source) + { + case CRM_SCLK_HICK: + if(((CRM->misc1_bit.hick_to_sclk) != RESET) && ((CRM->misc1_bit.hickdiv) != RESET)) + system_core_clock = HICK_VALUE * 6; + else + system_core_clock = HICK_VALUE; + break; + case CRM_SCLK_HEXT: + system_core_clock = HEXT_VALUE; + break; + case CRM_SCLK_PLL: + /* get pll clock source */ + pll_clock_source = CRM->pllcfg_bit.pllrcs; + + /* get multiplication factor */ + pll_ns = CRM->pllcfg_bit.pllns; + pll_ms = CRM->pllcfg_bit.pllms; + pll_fr = pll_fr_table[CRM->pllcfg_bit.pllfr]; + + if (pll_clock_source == CRM_PLL_SOURCE_HICK) + { + /* hick selected as pll clock entry */ + pllrcsfreq = HICK_VALUE; + } + else + { + /* hext selected as pll clock entry */ + pllrcsfreq = HEXT_VALUE; + } + + system_core_clock = (uint32_t)(((uint64_t)pllrcsfreq * pll_ns) / (pll_ms * pll_fr)); + break; + default: + system_core_clock = HICK_VALUE; + break; + } + + /* compute sclk, ahbclk frequency */ + /* get ahb division */ + temp = CRM->cfg_bit.ahbdiv; + div_value = sys_ahb_div_table[temp]; + /* ahbclk frequency */ + system_core_clock = system_core_clock >> div_value; +} +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + diff --git a/src/main/target/system_at32f435_437.h b/src/main/target/system_at32f435_437.h new file mode 100644 index 0000000000..8bef4dbd98 --- /dev/null +++ b/src/main/target/system_at32f435_437.h @@ -0,0 +1,77 @@ +/** + ************************************************************************** + * @file system_at32f435_437.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief cmsis cortex-m4 system header file. + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#ifndef __SYSTEM_AT32F435_437_H +#define __SYSTEM_AT32F435_437_H + +#ifdef __cplusplus +extern "C" { +#endif + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup AT32F435_437_system + * @{ + */ + +#define SystemCoreClock system_core_clock + +/** @defgroup AT32F435_437_system_exported_variables + * @{ + */ +extern unsigned int system_core_clock; /*!< system clock frequency (core clock) */ + +/** + * @} + */ + +/** @defgroup AT32F435_437_system_exported_functions + * @{ + */ + +extern void SystemInit(void); +extern void system_core_clock_update(void); + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif + From a502106ddc50b6b2dc262e8770452a273e821cbe Mon Sep 17 00:00:00 2001 From: EMSR Date: Sun, 29 Jan 2023 23:27:22 +0800 Subject: [PATCH 044/130] add support for at32 chips Co-Authored-By: EMSR <10240646+shanggl@users.noreply.github.com> Co-Authored-By: carl <101383042+tcdddd@users.noreply.github.com> Co-Authored-By: Hugo Chiang --- src/bl/bl_main.c | 91 +- src/main/config/config_streamer_at32f43x.c | 65 + src/main/drivers/adc_at32f43x.c | 201 ++ src/main/drivers/adc_impl.h | 13 +- src/main/drivers/bus.c | 4 +- src/main/drivers/bus.h | 1 + src/main/drivers/bus_busdev_i2c.c | 13 + src/main/drivers/bus_busdev_spi.c | 33 + src/main/drivers/bus_i2c.h | 7 +- src/main/drivers/bus_i2c_at32f43x.c | 486 ++++ src/main/drivers/bus_spi.h | 44 +- src/main/drivers/bus_spi_at32f43x.c | 292 +++ src/main/drivers/dma.h | 92 +- src/main/drivers/dma_at32f43x.c | 174 ++ src/main/drivers/exti.c | 65 +- src/main/drivers/exti.h | 2 + src/main/drivers/i2c_application.c | 2332 ++++++++++++++++++ src/main/drivers/i2c_application.h | 197 ++ src/main/drivers/io.c | 103 +- src/main/drivers/io.h | 18 + src/main/drivers/io_def_generated.h | 333 ++- src/main/drivers/io_impl.h | 17 +- src/main/drivers/nvic.h | 16 +- src/main/drivers/persistent.c | 34 +- src/main/drivers/rcc.c | 188 +- src/main/drivers/rcc.h | 23 +- src/main/drivers/rcc_at32f43x_periph.h | 88 + src/main/drivers/sdcard/sdmmc_sdio.h | 11 +- src/main/drivers/serial_uart.h | 19 +- src/main/drivers/serial_uart_at32f43x.c | 431 ++++ src/main/drivers/serial_uart_hal_at32f43x.c | 269 ++ src/main/drivers/serial_usb_vcp_at32f43x.c | 566 +++++ src/main/drivers/serial_usb_vcp_at32f43x.h | 55 + src/main/drivers/system.c | 45 +- src/main/drivers/system_at32f43x.c | 148 ++ src/main/drivers/timer.c | 22 +- src/main/drivers/timer.h | 61 +- src/main/drivers/timer_at32f43x.c | 117 + src/main/drivers/timer_def.h | 25 + src/main/drivers/timer_def_at32f43x.h | 307 +++ src/main/drivers/timer_impl.h | 37 +- src/main/drivers/timer_impl_stdperiph_at32.c | 409 +++ src/main/drivers/uart_inverter.c | 5 +- src/main/drivers/uart_inverter.h | 4 + src/main/drivers/usb_msc_at32f43x.c | 299 +++ src/main/fc/cli.c | 11 + src/main/io/serial_4way.c | 2 + src/main/msc/at32_msc_diskio.c | 107 + src/main/msc/at32_msc_diskio.h | 43 + src/main/navigation/navigation_fw_launch.c | 2 +- src/main/target/SAGEATF4/CMakeLists.txt | 1 + src/main/target/SAGEATF4/target.c | 46 + src/main/target/SAGEATF4/target.h | 208 ++ src/main/target/system_at32f435_437.c | 2 +- 54 files changed, 7971 insertions(+), 213 deletions(-) create mode 100644 src/main/config/config_streamer_at32f43x.c create mode 100644 src/main/drivers/adc_at32f43x.c create mode 100644 src/main/drivers/bus_i2c_at32f43x.c create mode 100644 src/main/drivers/bus_spi_at32f43x.c create mode 100644 src/main/drivers/dma_at32f43x.c create mode 100644 src/main/drivers/i2c_application.c create mode 100644 src/main/drivers/i2c_application.h create mode 100644 src/main/drivers/rcc_at32f43x_periph.h create mode 100644 src/main/drivers/serial_uart_at32f43x.c create mode 100644 src/main/drivers/serial_uart_hal_at32f43x.c create mode 100644 src/main/drivers/serial_usb_vcp_at32f43x.c create mode 100644 src/main/drivers/serial_usb_vcp_at32f43x.h create mode 100644 src/main/drivers/system_at32f43x.c create mode 100644 src/main/drivers/timer_at32f43x.c create mode 100644 src/main/drivers/timer_def_at32f43x.h create mode 100644 src/main/drivers/timer_impl_stdperiph_at32.c create mode 100644 src/main/drivers/usb_msc_at32f43x.c create mode 100644 src/main/msc/at32_msc_diskio.c create mode 100644 src/main/msc/at32_msc_diskio.h create mode 100644 src/main/target/SAGEATF4/CMakeLists.txt create mode 100644 src/main/target/SAGEATF4/target.c create mode 100644 src/main/target/SAGEATF4/target.h diff --git a/src/bl/bl_main.c b/src/bl/bl_main.c index de86285628..6fddc7d72f 100644 --- a/src/bl/bl_main.c +++ b/src/bl/bl_main.c @@ -33,7 +33,9 @@ #include "drivers/persistent.h" #include "drivers/io.h" #include "drivers/light_led.h" + #include "drivers/sdcard/sdcard.h" + #include "drivers/system.h" #include "drivers/time.h" @@ -67,8 +69,17 @@ flashSectorDef_t flashSectors[] = { { 32, 4 }, { 128, 1 }, { 256, 3 }, { 0, 0 } #elif defined(STM32F765xI) #define SECTOR_COUNT 8 flashSectorDef_t flashSectors[] = { { 32, 4 }, { 128, 1 }, { 256, 7 }, { 0, 0 } }; + +#elif defined(AT32F437ZMT7) || defined(AT32F437VMT7) || defined(AT32F435RMT7) +#define SECTOR_COUNT 1007 +flashSectorDef_t flashSectors[] = { { 4, 1007 }, { 0, 0 } }; + +#elif defined(AT32F437ZGT7) ||defined(AT32F437VGT7) || defined(AT32F435RGT7) +#define SECTOR_COUNT 511 +flashSectorDef_t flashSectors[] = { { 2, 511 }, { 0, 0 } }; #else + #error Unsupported MCU #endif @@ -78,6 +89,9 @@ flashSectorDef_t flashSectors[] = { { 32, 4 }, { 128, 1 }, { 256, 7 }, { 0, 0 } #elif defined(STM32F7) #define flashLock() HAL_FLASH_Lock() #define flashUnlock() HAL_FLASH_Unlock() +#elif defined(AT32F43x) + #define flashLock() flash_lock() + #define flashUnlock() flash_unlock() #endif static bool dataBackEndInitialized = false; @@ -169,20 +183,49 @@ static void do_jump(uint32_t address) __set_MSP(bootloaderVector->stackEnd); bootloaderVector->resetHandler(); } - + void bootloader_jump_to_app(void) { - FLASH->ACR &= (~FLASH_ACR_PRFTEN); + #if defined(AT32F43x) + /*Close Peripherals Clock*/ + CRM->apb2rst = 0xFFFF; + CRM->apb2rst = 0; + CRM->apb1rst = 0xFFFF; + CRM->apb1rst = 0; + CRM->apb1en = 0; + CRM->apb2en = 0; + /*Close PLL*/ + /* Reset SW, AHBDIV, APB1DIV, APB2DIV, ADCDIV and CLKOUT_SEL bits */ + CRM->cfg_bit.sclksel = 0; + CRM->cfg_bit.ahbdiv = 0; + CRM->cfg_bit.apb1div = 0; + CRM->cfg_bit.apb2div = 0; + CRM->ctrl_bit.hexten = 0; + CRM->ctrl_bit.cfden = 0; + CRM->ctrl_bit.pllen = 0; + /* Disable all interrupts and clear pending bits */ + CRM->clkint_bit.lickstblfc = 0; + CRM->clkint_bit.lextstblfc = 0; + CRM->clkint_bit.hickstblfc = 0; + CRM->clkint_bit.hextstblfc = 0; + CRM->clkint_bit.pllstblfc = 0; + CRM->clkint_bit.cfdfc = 0; + /*Colse Systick*/ + SysTick->CTRL = 0; -#if defined(STM32F4) - RCC_APB1PeriphResetCmd(~0, DISABLE); - RCC_APB2PeriphResetCmd(~0, DISABLE); -#elif defined(STM32F7) - RCC->APB1ENR = 0; - RCC->APB1LPENR = 0; - RCC->APB2ENR = 0; - RCC->APB2LPENR = 0; -#endif + #else + FLASH->ACR &= (~FLASH_ACR_PRFTEN); + + #if defined(STM32F4) + RCC_APB1PeriphResetCmd(~0, DISABLE); + RCC_APB2PeriphResetCmd(~0, DISABLE); + #elif defined(STM32F7) + RCC->APB1ENR = 0; + RCC->APB1LPENR = 0; + RCC->APB2ENR = 0; + RCC->APB2LPENR = 0; + #endif + #endif __disable_irq(); @@ -200,7 +243,6 @@ int8_t mcuFlashAddressSectorIndex(uint32_t address) do { for (unsigned j = 0; j < sectorDef->count; ++j) { uint32_t sectorEndAddress = sectorStartAddress + sectorDef->size * 1024; - /*if ((CONFIG_START_ADDRESS >= sectorStartAddress) && (CONFIG_START_ADDRESS < sectorEndAddress) && (CONFIG_END_ADDRESS <= sectorEndAddress)) {*/ if ((address >= sectorStartAddress) && (address < sectorEndAddress)) { return sector; } @@ -223,6 +265,17 @@ uint32_t mcuFlashSectorID(uint8_t sectorIndex) } #elif defined(STM32F7) return sectorIndex; +#elif defined(AT32F437ZMT7) || defined(AT32F437VMT7) || defined(AT32F435RMT7) + if (sectorIndex < 512) + { + return FLASH_START_ADDRESS + sectorIndex * 4 * 1024; + } + else + { + return FLASH_START_ADDRESS + 0x200000 + (sectorIndex-512) * 4 * 1024; + } + #elif defined(AT32F437ZGT7) ||defined(AT32F437VGT7) || defined(AT32F435RGT7) + return FLASH_START_ADDRESS + sectorIndex * 2 * 1024; #endif } @@ -240,7 +293,10 @@ bool mcuFlashSectorErase(uint8_t sectorIndex) uint32_t SECTORError; const HAL_StatusTypeDef status = HAL_FLASHEx_Erase(&EraseInitStruct, &SECTORError); return (status == HAL_OK); +#elif defined(AT32F43x) + return (flash_sector_erase(mcuFlashSectorID(sectorIndex)) == FLASH_OPERATE_DONE); #else + #error Unsupported MCU #endif } @@ -278,6 +334,10 @@ bool mcuFlashWriteWord(uint32_t address, uint32_t data) #elif defined(STM32F7) const HAL_StatusTypeDef status = HAL_FLASH_Program(FLASH_TYPEPROGRAM_WORD, address, (uint64_t)data); return (status == HAL_OK); +#elif defined(AT32F43x) + flash_status_type status = FLASH_OPERATE_DONE; + status = flash_word_program(address, data); + return (status == FLASH_OPERATE_DONE); #else #error Unsupported MCU #endif @@ -350,7 +410,7 @@ bool flash(flashOperation_e flashOperation) if (afatfs_fseekSync(flashDataFile, sizeof(buffer), AFATFS_SEEK_SET) == AFATFS_OPERATION_FAILURE) { goto flashFailed; } - + // Write MCU flash while (!afatfs_feof(flashDataFile)) { if ((flashOperation == FLASH_OPERATION_UPDATE) && (flashDstAddress == CONFIG_START_ADDRESS)) { @@ -364,7 +424,7 @@ bool flash(flashOperation_e flashOperation) } afatfs_freadSync(flashDataFile, (uint8_t *)&buffer, sizeof(buffer)); - + // Write SD card files to MCU flash if (!mcuFlashWriteWord(flashDstAddress, buffer)) { goto flashFailed; } @@ -437,6 +497,7 @@ flashFailed: } #if defined(USE_FLASHFS) +// Erase falsh bool dataflashChipEraseUpdatePartition(void) { flashPartition_t *flashDataPartition = flashPartitionFindByType(FLASH_PARTITION_TYPE_UPDATE_FIRMWARE); @@ -461,7 +522,7 @@ bool dataflashChipEraseUpdatePartition(void) return true; } #endif - +// Refresh from SD or FLASH int main(void) { init(); diff --git a/src/main/config/config_streamer_at32f43x.c b/src/main/config/config_streamer_at32f43x.c new file mode 100644 index 0000000000..dce84dbd27 --- /dev/null +++ b/src/main/config/config_streamer_at32f43x.c @@ -0,0 +1,65 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include +#include "platform.h" +#include "drivers/system.h" +#include "config/config_streamer.h" + +#if defined(AT32F43x) && !defined(CONFIG_IN_RAM) && !defined(CONFIG_IN_EXTERNAL_FLASH) + + +#if defined(AT32F437ZMT7) || defined(AT32F437VMT7) || defined(AT32F435RMT7) + #define FLASH_PAGE_SIZE ((uint32_t)0x1000) +#elif defined(AT32F437ZGT7) || defined(AT32F437VGT7) || defined(AT32F435RGT7) + #define FLASH_PAGE_SIZE ((uint32_t)0x800) +#endif + +void config_streamer_impl_unlock(void) +{ + flash_unlock(); + flash_flag_clear(FLASH_ODF_FLAG|FLASH_PRGMERR_FLAG|FLASH_EPPERR_FLAG); +} + +void config_streamer_impl_lock(void) +{ + flash_lock(); +} + +int config_streamer_impl_write_word(config_streamer_t *c, config_streamer_buffer_align_type_t *buffer) +{ + if (c->err != 0) { + return c->err; + } + // Erases sectors from the start address + if (c->address % FLASH_PAGE_SIZE == 0) { + const flash_status_type status =flash_sector_erase(c->address); + if (status != FLASH_OPERATE_DONE) { + return -1; + } + } + + const flash_status_type status = flash_word_program(c->address, *buffer); + if (status != FLASH_OPERATE_DONE) { + return -2; + } + + c->address += CONFIG_STREAMER_BUFFER_SIZE; + return 0; +} + +#endif diff --git a/src/main/drivers/adc_at32f43x.c b/src/main/drivers/adc_at32f43x.c new file mode 100644 index 0000000000..1975a96e7b --- /dev/null +++ b/src/main/drivers/adc_at32f43x.c @@ -0,0 +1,201 @@ +/* + * This file is part of ATbetaflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include +#include +#include + +#include "platform.h" +#include "drivers/time.h" + +#include "drivers/io.h" +#include "io_impl.h" +#include "rcc.h" +#include "drivers/dma.h" + +#include "drivers/sensor.h" +#include "drivers/accgyro/accgyro.h" + +#include "adc.h" +#include "adc_impl.h" + +#if !defined(ADC1_DMA_STREAM) +#define ADC1_DMA_STREAM DMA2_CHANNEL1 +#endif + +static adcDevice_t adcHardware[ADCDEV_COUNT] = { + { .ADCx = ADC1, .rccADC = RCC_APB2(ADC1), .rccDMA = RCC_AHB1(DMA2), .DMAy_Channelx = ADC1_DMA_STREAM, .dmaMuxid= DMAMUX_DMAREQ_ID_ADC1,.enabled = false, .usedChannelCount = 0 }, +}; + +/* note these could be packed up for saving space */ +const adcTagMap_t adcTagMap[] = { + { DEFIO_TAG_E__PC0, ADC_CHANNEL_10 }, + { DEFIO_TAG_E__PC1, ADC_CHANNEL_11 }, + { DEFIO_TAG_E__PC2, ADC_CHANNEL_12 }, + { DEFIO_TAG_E__PC3, ADC_CHANNEL_13 }, + { DEFIO_TAG_E__PC4, ADC_CHANNEL_14 }, + { DEFIO_TAG_E__PC5, ADC_CHANNEL_15 }, + { DEFIO_TAG_E__PB0, ADC_CHANNEL_8 }, + { DEFIO_TAG_E__PB1, ADC_CHANNEL_9 }, + { DEFIO_TAG_E__PA0, ADC_CHANNEL_0 }, + { DEFIO_TAG_E__PA1, ADC_CHANNEL_1 }, + { DEFIO_TAG_E__PA2, ADC_CHANNEL_2 }, + { DEFIO_TAG_E__PA3, ADC_CHANNEL_3 }, + { DEFIO_TAG_E__PA4, ADC_CHANNEL_4 }, + { DEFIO_TAG_E__PA5, ADC_CHANNEL_5 }, + { DEFIO_TAG_E__PA6, ADC_CHANNEL_6 }, + { DEFIO_TAG_E__PA7, ADC_CHANNEL_7 }, +}; + +ADCDevice adcDeviceByInstance(adc_type *instance) +{ + if (instance == ADC1) + return ADCDEV_1; +/* + if (instance == ADC2) // TODO add ADC2 and 3 + return ADCDEV_2; +*/ + return ADCINVALID; +} + +/* + * Init the Config of the adc common \dma \adc base ,use the regular ordinary to init the ADC instance ,eg.ADC1. + * @param adcDevice ADCdevice + * + */ +static void adcInstanceInit(ADCDevice adcDevice) +{ + dma_init_type dma_init_struct; + adcDevice_t * adc = &adcHardware[adcDevice]; + // get dma channel, then assign the dma channel + DMA_t dmadac= dmaGetByRef(adc->DMAy_Channelx); + if(!dmadac) + { + return; + } + // dmadac->dmaMuxref = adc->dmaMuxid;//this cause an error + dmaInit(dmadac, OWNER_ADC, adcDevice); + // dma_channel_type + dma_reset(dmadac->ref); + + dma_default_para_init(&dma_init_struct); + dma_init_struct.peripheral_base_addr = (uint32_t)&adc->ADCx->odt; + // dma buffer_size= usedChannelCount*sanmple rate + dma_init_struct.buffer_size = adc->usedChannelCount * ADC_AVERAGE_N_SAMPLES; + dma_init_struct.peripheral_inc_enable = FALSE; + dma_init_struct.memory_inc_enable = ((adc->usedChannelCount > 1) || (ADC_AVERAGE_N_SAMPLES > 1)) ? TRUE : FALSE; + dma_init_struct.loop_mode_enable = TRUE; + dma_init_struct.direction = DMA_DIR_PERIPHERAL_TO_MEMORY; + dma_init_struct.memory_base_addr = (uint32_t)adcValues[adcDevice]; + dma_init_struct.memory_data_width = DMA_MEMORY_DATA_WIDTH_HALFWORD; + dma_init_struct.peripheral_data_width = DMA_PERIPHERAL_DATA_WIDTH_HALFWORD; + dma_init_struct.priority = DMA_PRIORITY_MEDIUM; + dma_init(dmadac->ref, &dma_init_struct); + //enable dma transfer and dma interrupt + dma_interrupt_enable(dmadac->ref, DMA_FDT_INT, TRUE); + //AT32 DMA MUX + dmaMuxEnable(dmadac, adc->dmaMuxid); + dma_channel_enable(dmadac->ref,TRUE); + //init adc common + adc_reset(); + adc_common_config_type adc_common_struct; + adc_common_default_para_init(&adc_common_struct); + adc_common_struct.combine_mode = ADC_INDEPENDENT_MODE; + adc_common_struct.div = ADC_HCLK_DIV_4; + adc_common_struct.common_dma_mode = ADC_COMMON_DMAMODE_DISABLE; + adc_common_struct.sampling_interval = ADC_SAMPLING_INTERVAL_5CYCLES; + adc_common_struct.tempervintrv_state = FALSE; + adc_common_struct.common_dma_request_repeat_state = FALSE; + adc_common_struct.vbat_state = FALSE; + adc_common_config(&adc_common_struct); + //enable adc RCC Clock + RCC_ClockCmd(adc->rccADC, ENABLE); + //config adc base + adc_base_config_type adc_base_struct; + adc_base_default_para_init(&adc_base_struct); + adc_base_struct.sequence_mode = TRUE; + adc_base_struct.repeat_mode = TRUE; + adc_base_struct.data_align = ADC_RIGHT_ALIGNMENT; + adc_base_struct.ordinary_channel_length = adc->usedChannelCount; //based on used channel count + adc_base_config(adc->ADCx, &adc_base_struct); + adc_resolution_set(adc->ADCx, ADC_RESOLUTION_12B); + + uint8_t rank = 1; + for (int i = ADC_CHN_1; i < ADC_CHN_COUNT; i++) { + if (!adcConfig[i].enabled || adcConfig[i].adcDevice != adcDevice) { + continue; + } + adc_ordinary_channel_set(adc->ADCx, adcConfig[i].adcChannel, rank++, adcConfig[i].sampleTime); + } + + // config dma repeat + adc_dma_request_repeat_enable(adc->ADCx, TRUE); + adc_dma_mode_enable(adc->ADCx, TRUE); + + //enable over flow interupt + adc_interrupt_enable(adc->ADCx, ADC_OCCO_INT, TRUE); + + adc_enable(adc->ADCx,TRUE); + + // wait ready to start adc calibration + while(adc_flag_get(adc->ADCx, ADC_RDY_FLAG) == RESET); + //start calibration + adc_calibration_init(adc->ADCx); + while(adc_calibration_init_status_get(adc->ADCx)); + adc_calibration_start(adc->ADCx); + while(adc_calibration_status_get(adc->ADCx)); + //start adc + adc_enable(adc->ADCx, TRUE); + adc_ordinary_software_trigger_enable(adc->ADCx, TRUE); +} + +/* + * ADC Hardware init ,config the GPIO Port and count the used ADC channel + *@parm init +*/ +void adcHardwareInit(drv_adc_config_t *init) +{ + UNUSED(init); + int configuredAdcChannels = 0; + + for (int i = ADC_CHN_1; i < ADC_CHN_COUNT; i++) { + if (!adcConfig[i].tag) + continue; + // only use adc1 for now + adcDevice_t * adc = &adcHardware[adcConfig[i].adcDevice]; + // init adc gpio port + IOInit(IOGetByTag(adcConfig[i].tag), OWNER_ADC, RESOURCE_ADC_CH1 + (i - ADC_CHN_1), 0); + IOConfigGPIO(IOGetByTag(adcConfig[i].tag), IO_CONFIG(GPIO_MODE_ANALOG, 0, GPIO_OUTPUT_OPEN_DRAIN, GPIO_PULL_NONE)); + + adcConfig[i].adcChannel = adcChannelByTag(adcConfig[i].tag); + adcConfig[i].dmaIndex = adc->usedChannelCount++; + adcConfig[i].sampleTime = ADC_SAMPLETIME_6_5; + adcConfig[i].enabled = true; + + adc->enabled = true; + configuredAdcChannels++; + } + + if (configuredAdcChannels == 0) + return; + // config adc instance + for (int i = 0; i < ADCDEV_COUNT; i++) { + if (adcHardware[i].enabled) { + adcInstanceInit(i); + } + } +} diff --git a/src/main/drivers/adc_impl.h b/src/main/drivers/adc_impl.h index 324f512aa7..32f4414e83 100644 --- a/src/main/drivers/adc_impl.h +++ b/src/main/drivers/adc_impl.h @@ -20,7 +20,7 @@ #include "drivers/io_types.h" #include "rcc_types.h" -#if defined(STM32F4) || defined(STM32F7) +#if defined(STM32F4) || defined(STM32F7) || defined(AT32F43x) #define ADC_TAG_MAP_COUNT 16 #elif defined(STM32H7) #define ADC_TAG_MAP_COUNT 28 @@ -53,12 +53,19 @@ typedef struct adcTagMap_s { } adcTagMap_t; typedef struct adcDevice_s { +#if defined(AT32F43x) + adc_type* ADCx; +#else ADC_TypeDef* ADCx; +#endif rccPeriphTag_t rccADC; rccPeriphTag_t rccDMA; #if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) DMA_Stream_TypeDef* DMAy_Streamx; uint32_t channel; +#elif defined(AT32F43x) + dma_channel_type* DMAy_Channelx; + uint32_t dmaMuxid; // dmamux request type #else DMA_Channel_TypeDef* DMAy_Channelx; #endif @@ -84,5 +91,9 @@ extern adc_config_t adcConfig[ADC_CHN_COUNT]; extern volatile ADC_VALUES_ALIGNMENT(uint16_t adcValues[ADCDEV_COUNT][ADC_CHN_COUNT * ADC_AVERAGE_N_SAMPLES]); void adcHardwareInit(drv_adc_config_t *init); +#if defined(AT32F43x) +ADCDevice adcDeviceByInstance(adc_type *instance); +#else ADCDevice adcDeviceByInstance(ADC_TypeDef *instance); +#endif uint32_t adcChannelByTag(ioTag_t ioTag); diff --git a/src/main/drivers/bus.c b/src/main/drivers/bus.c index f06e847d57..a6346f504b 100755 --- a/src/main/drivers/bus.c +++ b/src/main/drivers/bus.c @@ -396,9 +396,7 @@ bool busIsBusy(const busDevice_t * dev) return false; #endif case BUSTYPE_I2C: - // Not implemented for I2C, respond as always free - return false; - + return i2cBusBusy(dev,NULL); default: return false; } diff --git a/src/main/drivers/bus.h b/src/main/drivers/bus.h index 8218ce3455..b6a3d78e44 100755 --- a/src/main/drivers/bus.h +++ b/src/main/drivers/bus.h @@ -286,6 +286,7 @@ bool i2cBusWriteBuffer(const busDevice_t * dev, uint8_t reg, const uint8_t * dat bool i2cBusWriteRegister(const busDevice_t * dev, uint8_t reg, uint8_t data); bool i2cBusReadBuffer(const busDevice_t * dev, uint8_t reg, uint8_t * data, uint8_t length); bool i2cBusReadRegister(const busDevice_t * dev, uint8_t reg, uint8_t * data); +bool i2cBusBusy(const busDevice_t *dev, bool *error); bool spiBusInitHost(const busDevice_t * dev); bool spiBusIsBusy(const busDevice_t * dev); diff --git a/src/main/drivers/bus_busdev_i2c.c b/src/main/drivers/bus_busdev_i2c.c index 96c2cd3bd0..fb255278d5 100755 --- a/src/main/drivers/bus_busdev_i2c.c +++ b/src/main/drivers/bus_busdev_i2c.c @@ -23,6 +23,10 @@ #if defined(USE_I2C) +#if !defined(UNUSED) +#define UNUSED(x) ((void)(x)) +#endif + #include "drivers/bus.h" #include "drivers/bus_i2c.h" @@ -49,4 +53,13 @@ bool i2cBusReadRegister(const busDevice_t * dev, uint8_t reg, uint8_t * data) const bool allowRawAccess = (dev->flags & DEVFLAGS_USE_RAW_REGISTERS); return i2cRead(dev->busdev.i2c.i2cBus, dev->busdev.i2c.address, reg, 1, data, allowRawAccess); } +bool i2cBusBusy(const busDevice_t *dev, bool *error) +{ +#if defined(AT32F43x) + return i2cBusy(dev->busdev.i2c.i2cBus, error); +#endif + UNUSED(dev); + UNUSED(error); + return false; +} #endif diff --git a/src/main/drivers/bus_busdev_spi.c b/src/main/drivers/bus_busdev_spi.c index e206bdda02..51a30d8494 100755 --- a/src/main/drivers/bus_busdev_spi.c +++ b/src/main/drivers/bus_busdev_spi.c @@ -62,7 +62,12 @@ void spiBusDeselectDevice(const busDevice_t * dev) void spiBusSetSpeed(const busDevice_t * dev, busSpeed_e speed) { const SPIClockSpeed_e spiClock[] = { SPI_CLOCK_INITIALIZATON, SPI_CLOCK_SLOW, SPI_CLOCK_STANDARD, SPI_CLOCK_FAST, SPI_CLOCK_ULTRAFAST }; + +#if defined(AT32F43x) + spi_type * instance = spiInstanceByDevice(dev->busdev.spi.spiBus); +#else SPI_TypeDef * instance = spiInstanceByDevice(dev->busdev.spi.spiBus); +#endif #ifdef BUS_SPI_SPEED_MAX if (speed > BUS_SPI_SPEED_MAX) @@ -75,7 +80,11 @@ void spiBusSetSpeed(const busDevice_t * dev, busSpeed_e speed) bool spiBusTransfer(const busDevice_t * dev, uint8_t * rxBuf, const uint8_t * txBuf, int length) { +#if defined(AT32F43x) + spi_type * instance = spiInstanceByDevice(dev->busdev.spi.spiBus); +#else SPI_TypeDef * instance = spiInstanceByDevice(dev->busdev.spi.spiBus); +#endif if (!(dev->flags & DEVFLAGS_USE_MANUAL_DEVICE_SELECT)) { spiBusSelectDevice(dev); @@ -92,7 +101,11 @@ bool spiBusTransfer(const busDevice_t * dev, uint8_t * rxBuf, const uint8_t * tx bool spiBusTransferMultiple(const busDevice_t * dev, busTransferDescriptor_t * dsc, int count) { +#if defined(AT32F43x) + spi_type * instance = spiInstanceByDevice(dev->busdev.spi.spiBus); +#else SPI_TypeDef * instance = spiInstanceByDevice(dev->busdev.spi.spiBus); +#endif if (!(dev->flags & DEVFLAGS_USE_MANUAL_DEVICE_SELECT)) { spiBusSelectDevice(dev); @@ -111,7 +124,11 @@ bool spiBusTransferMultiple(const busDevice_t * dev, busTransferDescriptor_t * d bool spiBusWriteRegister(const busDevice_t * dev, uint8_t reg, uint8_t data) { +#if defined(AT32F43x) + spi_type * instance = spiInstanceByDevice(dev->busdev.spi.spiBus); +#else SPI_TypeDef * instance = spiInstanceByDevice(dev->busdev.spi.spiBus); +#endif if (!(dev->flags & DEVFLAGS_USE_MANUAL_DEVICE_SELECT)) { spiBusSelectDevice(dev); @@ -129,7 +146,11 @@ bool spiBusWriteRegister(const busDevice_t * dev, uint8_t reg, uint8_t data) bool spiBusWriteBuffer(const busDevice_t * dev, uint8_t reg, const uint8_t * data, uint8_t length) { +#if defined(AT32F43x) + spi_type * instance = spiInstanceByDevice(dev->busdev.spi.spiBus); +#else SPI_TypeDef * instance = spiInstanceByDevice(dev->busdev.spi.spiBus); +#endif if (!(dev->flags & DEVFLAGS_USE_MANUAL_DEVICE_SELECT)) { spiBusSelectDevice(dev); @@ -147,7 +168,11 @@ bool spiBusWriteBuffer(const busDevice_t * dev, uint8_t reg, const uint8_t * dat bool spiBusReadBuffer(const busDevice_t * dev, uint8_t reg, uint8_t * data, uint8_t length) { +#if defined(AT32F43x) + spi_type * instance = spiInstanceByDevice(dev->busdev.spi.spiBus); +#else SPI_TypeDef * instance = spiInstanceByDevice(dev->busdev.spi.spiBus); +#endif if (!(dev->flags & DEVFLAGS_USE_MANUAL_DEVICE_SELECT)) { spiBusSelectDevice(dev); @@ -165,7 +190,11 @@ bool spiBusReadBuffer(const busDevice_t * dev, uint8_t reg, uint8_t * data, uint bool spiBusReadRegister(const busDevice_t * dev, uint8_t reg, uint8_t * data) { +#if defined(AT32F43x) + spi_type * instance = spiInstanceByDevice(dev->busdev.spi.spiBus); +#else SPI_TypeDef * instance = spiInstanceByDevice(dev->busdev.spi.spiBus); +#endif if (!(dev->flags & DEVFLAGS_USE_MANUAL_DEVICE_SELECT)) { spiBusSelectDevice(dev); @@ -183,7 +212,11 @@ bool spiBusReadRegister(const busDevice_t * dev, uint8_t reg, uint8_t * data) bool spiBusIsBusy(const busDevice_t * dev) { +#if defined(AT32F43x) + spi_type * instance = spiInstanceByDevice(dev->busdev.spi.spiBus); +#else SPI_TypeDef * instance = spiInstanceByDevice(dev->busdev.spi.spiBus); +#endif return spiIsBusBusy(instance); } #endif diff --git a/src/main/drivers/bus_i2c.h b/src/main/drivers/bus_i2c.h index 16d49788a6..bf685b1bfa 100644 --- a/src/main/drivers/bus_i2c.h +++ b/src/main/drivers/bus_i2c.h @@ -47,12 +47,16 @@ typedef enum I2CDevice { } I2CDevice; typedef struct i2cDevice_s { +#if defined(AT32F43x) + i2c_type *dev; +#else I2C_TypeDef *dev; +#endif ioTag_t scl; ioTag_t sda; rccPeriphTag_t rcc; I2CSpeed speed; -#if defined(STM32F7) || defined(STM32H7) +#if defined(STM32F7) || defined(STM32H7) || defined(AT32F43x) uint8_t ev_irq; uint8_t er_irq; uint8_t af; @@ -64,5 +68,6 @@ void i2cInit(I2CDevice device); bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_, const uint8_t *data, bool allowRawAccess); bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t data, bool allowRawAccess); bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t len, uint8_t* buf, bool allowRawAccess); +bool i2cBusy(I2CDevice device, bool *error); uint16_t i2cGetErrorCounter(void); diff --git a/src/main/drivers/bus_i2c_at32f43x.c b/src/main/drivers/bus_i2c_at32f43x.c new file mode 100644 index 0000000000..97036b6186 --- /dev/null +++ b/src/main/drivers/bus_i2c_at32f43x.c @@ -0,0 +1,486 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include +#include + +#include +#include "io_impl.h" +#include "drivers/io.h" +#include "drivers/time.h" +#include "rcc.h" +#include "drivers/bus_i2c.h" +#include "drivers/nvic.h" +#include "drivers/i2c_application.h" + + +#if !defined(SOFT_I2C) && defined(USE_I2C) + +#define CLOCKSPEED 800000 // i2c clockspeed 400kHz default (conform specs), 800kHz and 1200kHz (Betaflight default) + +#define I2Cx_ADDRESS 0x00 +// Clock period in us during unstick transfer +#define UNSTICK_CLK_US 10 +// Allow 500us for clock strech to complete during unstick +#define UNSTICK_CLK_STRETCH (500/UNSTICK_CLK_US) + +static void i2cUnstick(IO_t scl, IO_t sda); + +#if defined(USE_I2C_PULLUP) +#define IOCFG_I2C IOCFG_AF_OD_UP +#else +#define IOCFG_I2C IOCFG_AF_OD +#endif + +#ifndef I2C1_SCL +#define I2C1_SCL PA9 +#endif + +#ifndef I2C1_SDA +#define I2C1_SDA PA10 +#endif + +#ifndef I2C2_SCL +#define I2C2_SCL PD12 +#endif +#ifndef I2C2_SDA +#define I2C2_SDA PD13 +#endif + +#ifndef I2C3_SCL +#define I2C3_SCL PC0 +#endif +#ifndef I2C3_SDA +#define I2C3_SDA PC1 +#endif + +//Define thi I2C hardware map +static i2cDevice_t i2cHardwareMap[I2CDEV_COUNT] = { + { .dev = I2C1, .scl = IO_TAG(I2C1_SCL), .sda = IO_TAG(I2C1_SDA), .rcc = RCC_APB1(I2C1), .speed = I2C_SPEED_400KHZ, .ev_irq = I2C1_EVT_IRQn, .er_irq = I2C1_ERR_IRQn, .af = GPIO_MUX_8 }, + { .dev = I2C2, .scl = IO_TAG(I2C2_SCL), .sda = IO_TAG(I2C2_SDA), .rcc = RCC_APB1(I2C2), .speed = I2C_SPEED_400KHZ, .ev_irq = I2C2_EVT_IRQn, .er_irq = I2C2_ERR_IRQn, .af = GPIO_MUX_4 }, + { .dev = I2C3, .scl = IO_TAG(I2C3_SCL), .sda = IO_TAG(I2C3_SDA), .rcc = RCC_APB1(I2C3), .speed = I2C_SPEED_400KHZ, .ev_irq = I2C3_EVT_IRQn, .er_irq = I2C3_ERR_IRQn, .af = GPIO_MUX_4 }, +}; + +static volatile uint16_t i2cErrorCount = 0; + +// Note that I2C_TIMEOUT is in us, while the HAL +// functions expect the timeout to be in ticks. +// Since we're setting up the ticks a 1khz, each +// tick equals 1ms. +// AT32F4 i2c TIMEOUT USING loop times +#define I2C_DEFAULT_TIMEOUT (I2C_TIMEOUT*288 / 1000 ) +//#define I2C_DEFAULT_TIMEOUT (0xD80) + +typedef struct { + bool initialised; + i2c_handle_type handle; +} i2cState_t; + +static i2cState_t i2cState[I2CDEV_COUNT]; + +void i2cSetSpeed(uint8_t speed) +{ + for (unsigned int i = 0; i < ARRAYLEN(i2cHardwareMap); i++) { + i2cHardwareMap[i].speed = speed; + } +} + +//I2C1_ERR_IRQHandler +void I2C1_ERR_IRQHandler(void) +{ + i2c_err_irq_handler(&i2cState[I2CDEV_1].handle); +} + +void I2C1_EVT_IRQHandler(void) +{ + i2c_evt_irq_handler(&i2cState[I2CDEV_1].handle); +} + +void I2C2_ERR_IRQHandler(void) +{ + i2c_err_irq_handler(&i2cState[I2CDEV_2].handle); +} + +void I2C2_EVT_IRQHandler(void) +{ + i2c_evt_irq_handler(&i2cState[I2CDEV_2].handle); +} + +void I2C3_ERR_IRQHandler(void) +{ + i2c_err_irq_handler(&i2cState[I2CDEV_3].handle); +} + +void I2C3_EVT_IRQHandler(void) +{ + i2c_evt_irq_handler(&i2cState[I2CDEV_3].handle); +} + +static bool i2cHandleHardwareFailure(I2CDevice device) +{ + (void)device; + i2cErrorCount++; + i2cInit(device); + return false; +} + +bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_, const uint8_t *data, bool allowRawAccess) +{ + if (device == I2CINVALID) + return false; + + i2cState_t * state = &(i2cState[device]); + + if (!state->initialised) + return false; + + i2c_status_type status; + + if ((reg_ == 0xFF || len_ == 0) && allowRawAccess) { + status = i2c_master_transmit(&state->handle, addr_ << 1, CONST_CAST(uint8_t*, data), len_, I2C_DEFAULT_TIMEOUT); + if(status != I2C_OK) + { + /* wait for the stop flag to be set */ + i2c_wait_flag(&state->handle, I2C_STOPF_FLAG, I2C_EVENT_CHECK_NONE, I2C_DEFAULT_TIMEOUT); + + /* clear stop flag */ + i2c_flag_clear(state->handle.i2cx, I2C_STOPF_FLAG); + } + } + else { + status = i2c_memory_write(&state->handle,I2C_MEM_ADDR_WIDIH_8, addr_ << 1, reg_, CONST_CAST(uint8_t*, data), len_, I2C_DEFAULT_TIMEOUT); + //status = i2c_memory_write_int(&state->handle,I2C_MEM_ADDR_WIDIH_8, addr_ << 1, reg_, data, len_, I2C_DEFAULT_TIMEOUT); + + if(status != I2C_OK) + { + /* wait for the stop flag to be set */ + i2c_wait_flag(&state->handle, I2C_STOPF_FLAG, I2C_EVENT_CHECK_NONE, I2C_DEFAULT_TIMEOUT); + + /* clear stop flag */ + i2c_flag_clear(state->handle.i2cx, I2C_STOPF_FLAG); + } + } + + if (status == I2C_ERR_STEP_1) {//BUSY + return false; + } + + if (status != I2C_OK) + return i2cHandleHardwareFailure(device); + + return true; +} + +bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t data, bool allowRawAccess) +{ + return i2cWriteBuffer(device, addr_, reg_, 1, &data, allowRawAccess); +} + +bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t* buf, bool allowRawAccess) +{ + if (device == I2CINVALID) + return false; + + i2cState_t * state = &(i2cState[device]); + + if (!state->initialised) + return false; + + //HAL_StatusTypeDef status; + i2c_status_type status; + if (reg_ == 0xFF && allowRawAccess) { + status = i2c_master_receive(&state->handle, addr_ << 1,buf, len, I2C_DEFAULT_TIMEOUT); + if(status != I2C_OK) + { + /* wait for the stop flag to be set */ + i2c_wait_flag(&state->handle, I2C_STOPF_FLAG, I2C_EVENT_CHECK_NONE, I2C_DEFAULT_TIMEOUT); + + /* clear stop flag */ + i2c_flag_clear(state->handle.i2cx, I2C_STOPF_FLAG); + } + + } + else { + status = i2c_memory_read(&state->handle, I2C_MEM_ADDR_WIDIH_8,addr_ << 1, reg_, buf, len, I2C_DEFAULT_TIMEOUT); + + if(status != I2C_OK) + { + /* wait for the stop flag to be set */ + i2c_wait_flag(&state->handle, I2C_STOPF_FLAG, I2C_EVENT_CHECK_NONE, I2C_DEFAULT_TIMEOUT); + + /* clear stop flag */ + i2c_flag_clear(state->handle.i2cx, I2C_STOPF_FLAG); + } + + } + + if (status != I2C_OK) + return i2cHandleHardwareFailure(device); + + return true; +} + +/* + * Compute SCLDEL, SDADEL, SCLH and SCLL for TIMINGR register according to reference manuals. + */ +static void i2cClockComputeRaw(uint32_t pclkFreq, int i2cFreqKhz, int presc, int dfcoeff, + uint8_t *scldel, uint8_t *sdadel, uint16_t *sclh, uint16_t *scll) +{ + // Values from I2C-SMBus specification + uint16_t trmax; // Rise time (max) + uint16_t tfmax; // Fall time (max) + uint8_t tsuDATmin; // SDA setup time (min) + uint8_t thdDATmin; // SDA hold time (min) + uint16_t tHIGHmin; // High period of SCL clock (min) + uint16_t tLOWmin; // Low period of SCL clock (min) + + // Silicon specific values, from datasheet + uint8_t tAFmin = 50; // Analog filter delay (min) + + // Actual (estimated) values + uint8_t tr = 100; // Rise time + uint8_t tf = 10; // Fall time + + if (i2cFreqKhz > 400) { + // Fm+ (Fast mode plus) + trmax = 120; + tfmax = 120; + tsuDATmin = 50; + thdDATmin = 0; + tHIGHmin = 260; + tLOWmin = 500; + } else { + // Fm (Fast mode) + trmax = 300; + tfmax = 300; + tsuDATmin = 100; + thdDATmin = 0; + tHIGHmin = 600; + tLOWmin = 1300; + } + + // Convert pclkFreq into nsec + float tI2cclk = 1000000000.0f / pclkFreq; + + // Convert target i2cFreq into cycle time (nsec) + float tSCL = 1000000.0f / i2cFreqKhz; + + uint32_t SCLDELmin = (trmax + tsuDATmin) / ((presc + 1) * tI2cclk) - 1; + uint32_t SDADELmin = (tfmax + thdDATmin - tAFmin - ((dfcoeff + 3) * tI2cclk)) / ((presc + 1) * tI2cclk); + + float tsync1 = tf + tAFmin + dfcoeff * tI2cclk + 2 * tI2cclk; + float tsync2 = tr + tAFmin + dfcoeff * tI2cclk + 2 * tI2cclk; + + float tSCLH = tHIGHmin * tSCL / (tHIGHmin + tLOWmin) - tsync2; + float tSCLL = tSCL - tSCLH - tsync1 - tsync2; + + uint32_t SCLH = tSCLH / ((presc + 1) * tI2cclk) - 1; + uint32_t SCLL = tSCLL / ((presc + 1) * tI2cclk) - 1; + + while (tsync1 + tsync2 + ((SCLH + 1) + (SCLL + 1)) * ((presc + 1) * tI2cclk) < tSCL) { + SCLH++; + } + + *scldel = SCLDELmin; + *sdadel = SDADELmin; + *sclh = SCLH; + *scll = SCLL; +} + +static uint32_t i2cClockTIMINGR(uint32_t pclkFreq, int i2cFreqKhz, int dfcoeff) +{ +#define TIMINGR(presc, scldel, sdadel, sclh, scll) \ + ((presc << 28)|(scldel << 20)|(sdadel << 16)|(sclh << 8)|(scll << 0)) + + uint8_t scldel; + uint8_t sdadel; + uint16_t sclh; + uint16_t scll; + + for (int presc = 1; presc < 15; presc++) { + i2cClockComputeRaw(pclkFreq, i2cFreqKhz, presc, dfcoeff, &scldel, &sdadel, &sclh, &scll); + + // If all fields are not overflowing, return TIMINGR. + // Otherwise, increase prescaler and try again. + if ((scldel < 16) && (sdadel < 16) && (sclh < 256) && (scll < 256)) { + return TIMINGR(presc, scldel, sdadel, sclh, scll); + } + } + return 0; // Shouldn't reach here +} + +void i2cInit(I2CDevice device) +{ + i2cDevice_t * hardware = &(i2cHardwareMap[device]); + i2cState_t * state = &(i2cState[device]); + + //I2C_HandleTypeDef * pHandle = &state->handle; + i2c_handle_type * pHandle = &state->handle; + + if (hardware->dev == NULL) + return; + + IO_t scl = IOGetByTag(hardware->scl); + IO_t sda = IOGetByTag(hardware->sda); + + IOInit(scl, OWNER_I2C, RESOURCE_I2C_SCL, RESOURCE_INDEX(device)); + IOInit(sda, OWNER_I2C, RESOURCE_I2C_SDA, RESOURCE_INDEX(device)); + // Enable RCC + RCC_ClockCmd(hardware->rcc, ENABLE); + + i2cUnstick(scl, sda); + + // Init pins + IOConfigGPIOAF(scl, IOCFG_I2C, hardware->af); + IOConfigGPIOAF(sda, IOCFG_I2C, hardware->af); + + // Init I2C peripheral + pHandle->i2cx = hardware->dev; + i2c_reset(pHandle->i2cx); + // Compute TIMINGR value based on peripheral clock for this device instance + uint32_t i2cPclk; + + #if defined(AT32F43x) + crm_clocks_freq_type clocks_struct; + crm_clocks_freq_get(&clocks_struct); + i2cPclk = clocks_struct.apb1_freq; + + #else + #error Unknown MCU type + #endif + + + // switch (hardware->speed) { + // case I2C_SPEED_400KHZ: + // default: + // i2c_init(pHandle->i2cx, 15, 0x10F03863); // 400kHz, Rise 100ns, Fall 10ns 0x10C03863 + // break; + + // case I2C_SPEED_800KHZ: + // i2c_init(pHandle->i2cx, 15, 0x00E03259); // 800khz, Rise 40, Fall 4 + // break; + + // case I2C_SPEED_100KHZ: + // i2c_init(pHandle->i2cx, 15, 0x30E0AEAE); // 100kHz, Rise 100ns, Fall 10ns 0x30607EE0 0x30607DDE + // break; + + // case I2C_SPEED_200KHZ: + // i2c_init(pHandle->i2cx, 15, 0x10F078D6); // 200kHz, Rise 100ns, Fall 10ns 0x10C078D6 + // break; + // } + + + switch (hardware->speed) { + case I2C_SPEED_400KHZ: + default: + i2c_init(pHandle->i2cx, 0x0f, i2cClockTIMINGR(i2cPclk, 400, 0)); + break; + + case I2C_SPEED_800KHZ: + i2c_init(pHandle->i2cx, 0x0f, i2cClockTIMINGR(i2cPclk, 800, 0)); + break; + + case I2C_SPEED_100KHZ: + i2c_init(pHandle->i2cx, 0x0f, i2cClockTIMINGR(i2cPclk, 100, 0)); + break; + + case I2C_SPEED_200KHZ: + i2c_init(pHandle->i2cx, 0x0f, i2cClockTIMINGR(i2cPclk, 200, 0)); + break; + } + + i2c_own_address1_set(pHandle->i2cx, I2C_ADDRESS_MODE_7BIT, 0x0); + //i2c_own_address2_enable(pHandle->i2cx, false); // enable or disable own address 2 + //i2c_own_address2_set(pHandle->i2cx, I2C_ADDRESS_MODE_7BIT, 0x0); + //i2c_general_call_enable(pHandle->i2cx, false); // enable or disable general call mode + //i2c_clock_stretch_enable(pHandle->i2cx, true); // enable or disable clock stretch + + nvic_irq_enable(hardware->er_irq,NVIC_PRIO_I2C_ER, 0); + nvic_irq_enable(hardware->ev_irq, NVIC_PRIO_I2C_EV,0); + + i2c_enable(pHandle->i2cx, TRUE); + + state->initialised = true; +} + +uint16_t i2cGetErrorCounter(void) +{ + return i2cErrorCount; +} + +static void i2cUnstick(IO_t scl, IO_t sda) +{ + int i; + + IOHi(scl); + IOHi(sda); + + IOConfigGPIO(scl, IOCFG_OUT_OD); + IOConfigGPIO(sda, IOCFG_OUT_OD); + + // Analog Devices AN-686 + // We need 9 clock pulses + STOP condition + for (i = 0; i < 9; i++) { + // Wait for any clock stretching to finish + int timeout = UNSTICK_CLK_STRETCH; + while (!IORead(scl) && timeout) { + delayMicroseconds(UNSTICK_CLK_US); + timeout--; + } + + // Pull low + IOLo(scl); // Set bus low + delayMicroseconds(UNSTICK_CLK_US/2); + IOHi(scl); // Set bus high + delayMicroseconds(UNSTICK_CLK_US/2); + } + + // Generate a stop condition in case there was none + IOLo(scl); + delayMicroseconds(UNSTICK_CLK_US/2); + IOLo(sda); + delayMicroseconds(UNSTICK_CLK_US/2); + + IOHi(scl); // Set bus scl high + delayMicroseconds(UNSTICK_CLK_US/2); + IOHi(sda); // Set bus sda high +} + +bool i2cBusy(I2CDevice device, bool *error) +{ + if (device == I2CINVALID) + return true; + + i2cState_t * state = &(i2cState[device]); + + if (error) { + *error = state->handle.error_code==I2C_OK?false:true; + } + + if(state->handle.error_code ==I2C_OK){ + + if (i2c_flag_get(state->handle.i2cx, I2C_BUSYF_FLAG) == SET) + { + return true; + } + return false; + } + + return true; +} + +#endif diff --git a/src/main/drivers/bus_spi.h b/src/main/drivers/bus_spi.h index 328118d1ef..e55119564c 100644 --- a/src/main/drivers/bus_spi.h +++ b/src/main/drivers/bus_spi.h @@ -32,6 +32,11 @@ #define SPI_IO_AF_SCK_CFG_LOW IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_PULLDOWN) #define SPI_IO_AF_MISO_CFG IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_PULLUP) #define SPI_IO_CS_CFG IO_CONFIG(GPIO_MODE_OUTPUT_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_NOPULL) +#elif defined(AT32F43x) +#define SPI_IO_AF_CFG IO_CONFIG(GPIO_MODE_MUX, GPIO_DRIVE_STRENGTH_STRONGER, GPIO_OUTPUT_PUSH_PULL, GPIO_PULL_NONE) +#define SPI_IO_AF_SCK_CFG IO_CONFIG(GPIO_MODE_MUX, GPIO_DRIVE_STRENGTH_STRONGER, GPIO_OUTPUT_PUSH_PULL, GPIO_PULL_DOWN) +#define SPI_IO_AF_MISO_CFG IO_CONFIG(GPIO_MODE_MUX, GPIO_DRIVE_STRENGTH_STRONGER, GPIO_OUTPUT_PUSH_PULL, GPIO_PULL_UP) +#define SPI_IO_CS_CFG IO_CONFIG(GPIO_MODE_OUTPUT, GPIO_DRIVE_STRENGTH_STRONGER, GPIO_OUTPUT_PUSH_PULL, GPIO_PULL_NONE) #endif /* @@ -56,14 +61,18 @@ typedef enum SPIDevice { #if defined(STM32F4) #define SPIDEV_COUNT 3 -#elif defined(STM32F7) || defined(STM32H7) +#elif defined(STM32F7) || defined(STM32H7)|| defined(AT32F43x) #define SPIDEV_COUNT 4 #else #define SPIDEV_COUNT 4 #endif typedef struct SPIDevice_s { - SPI_TypeDef *dev; +#if defined(AT32F43x) + spi_type *dev; +#else + SPI_TypeDef *dev; +#endif ioTag_t nss; ioTag_t sck; ioTag_t mosi; @@ -82,12 +91,27 @@ typedef struct SPIDevice_s { } spiDevice_t; bool spiInitDevice(SPIDevice device, bool leadingEdge); -bool spiIsBusBusy(SPI_TypeDef *instance); -void spiSetSpeed(SPI_TypeDef *instance, SPIClockSpeed_e speed); -uint8_t spiTransferByte(SPI_TypeDef *instance, uint8_t in); -bool spiTransfer(SPI_TypeDef *instance, uint8_t *rxData, const uint8_t *txData, int len); -uint16_t spiGetErrorCounter(SPI_TypeDef *instance); -void spiResetErrorCounter(SPI_TypeDef *instance); -SPIDevice spiDeviceByInstance(SPI_TypeDef *instance); -SPI_TypeDef * spiInstanceByDevice(SPIDevice device); \ No newline at end of file +#if defined(AT32F43x) + + bool spiIsBusBusy(spi_type *instance); + void spiSetSpeed(spi_type *instance, SPIClockSpeed_e speed); + uint8_t spiTransferByte(spi_type *instance, uint8_t in); + bool spiTransfer(spi_type *instance, uint8_t *rxData, const uint8_t *txData, int len); + + uint16_t spiGetErrorCounter(spi_type *instance); + void spiResetErrorCounter(spi_type *instance); + SPIDevice spiDeviceByInstance(spi_type *instance); + spi_type * spiInstanceByDevice(SPIDevice device); + +#else + bool spiIsBusBusy(SPI_TypeDef *instance); + void spiSetSpeed(SPI_TypeDef *instance, SPIClockSpeed_e speed); + uint8_t spiTransferByte(SPI_TypeDef *instance, uint8_t in); + bool spiTransfer(SPI_TypeDef *instance, uint8_t *rxData, const uint8_t *txData, int len); + + uint16_t spiGetErrorCounter(SPI_TypeDef *instance); + void spiResetErrorCounter(SPI_TypeDef *instance); + SPIDevice spiDeviceByInstance(SPI_TypeDef *instance); + SPI_TypeDef * spiInstanceByDevice(SPIDevice device); +#endif diff --git a/src/main/drivers/bus_spi_at32f43x.c b/src/main/drivers/bus_spi_at32f43x.c new file mode 100644 index 0000000000..55947c1913 --- /dev/null +++ b/src/main/drivers/bus_spi_at32f43x.c @@ -0,0 +1,292 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include +#include + +#include + +#ifdef USE_SPI + +#include "drivers/bus_spi.h" +#include "drivers/exti.h" +#include "drivers/io.h" +#include "drivers/io_impl.h" +#include "drivers/rcc.h" + +#ifndef SPI1_SCK_PIN +#define SPI1_NSS_PIN PA4 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 +#endif + +#ifndef SPI2_SCK_PIN +#define SPI2_NSS_PIN PB12 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 +#endif + +#ifndef SPI3_SCK_PIN +#define SPI3_NSS_PIN PA15 +#define SPI3_SCK_PIN PC10 +#define SPI3_MISO_PIN PC11 +#define SPI3_MOSI_PIN PC12 +#endif + +#ifndef SPI1_NSS_PIN +#define SPI1_NSS_PIN NONE +#endif +#ifndef SPI2_NSS_PIN +#define SPI2_NSS_PIN NONE +#endif +#ifndef SPI3_NSS_PIN +#define SPI3_NSS_PIN NONE +#endif + +#if defined(AT32F43x) + #if defined(USE_SPI_DEVICE_1) + static const uint32_t spiDivisorMapFast[] = { + SPI_MCLK_DIV_256, // SPI_CLOCK_INITIALIZATON 328.125 KBits/s + SPI_MCLK_DIV_128, // SPI_CLOCK_SLOW 656.25 KBits/s + SPI_MCLK_DIV_16, // SPI_CLOCK_STANDARD 10.5 MBits/s + SPI_MCLK_DIV_8, // SPI_CLOCK_FAST 21.0 MBits/s + SPI_MCLK_DIV_4 // SPI_CLOCK_ULTRAFAST 42.0 MBits/s + }; + #endif + + #if defined(USE_SPI_DEVICE_2) || defined(USE_SPI_DEVICE_3) + static const uint32_t spiDivisorMapSlow[] = { + SPI_MCLK_DIV_256, // SPI_CLOCK_INITIALIZATON 164.062 KBits/s + SPI_MCLK_DIV_128, // SPI_CLOCK_SLOW 656.25 KBits/s + SPI_MCLK_DIV_16, // SPI_CLOCK_STANDARD 10.5 MBits/s + SPI_MCLK_DIV_8, // SPI_CLOCK_FAST 21.0 MBits/s + SPI_MCLK_DIV_8 // SPI_CLOCK_ULTRAFAST 21.0 MBits/s + }; + #endif + + static spiDevice_t spiHardwareMap[] = { + #ifdef USE_SPI_DEVICE_1 + { .dev = SPI1, .nss = IO_TAG(SPI1_NSS_PIN), .sck = IO_TAG(SPI1_SCK_PIN), .miso = IO_TAG(SPI1_MISO_PIN), .mosi = IO_TAG(SPI1_MOSI_PIN), .rcc = RCC_APB2(SPI1), .af = GPIO_MUX_5, .divisorMap = spiDivisorMapFast }, + #else + { .dev = NULL }, // No SPI1 + #endif + #ifdef USE_SPI_DEVICE_2 + { .dev = SPI2, .nss = IO_TAG(SPI2_NSS_PIN), .sck = IO_TAG(SPI2_SCK_PIN), .miso = IO_TAG(SPI2_MISO_PIN), .mosi = IO_TAG(SPI2_MOSI_PIN), .rcc = RCC_APB1(SPI2), .af = GPIO_MUX_6, .divisorMap = spiDivisorMapSlow }, + #else + { .dev = NULL }, // No SPI2 + #endif + #ifdef USE_SPI_DEVICE_3 + { .dev = SPI3, .nss = IO_TAG(SPI3_NSS_PIN), .sck = IO_TAG(SPI3_SCK_PIN), .miso = IO_TAG(SPI3_MISO_PIN), .mosi = IO_TAG(SPI3_MOSI_PIN), .rcc = RCC_APB1(SPI3), .af = GPIO_MUX_6, .divisorMap = spiDivisorMapSlow }, + #else + { .dev = NULL }, // No SPI3 + #endif + { .dev = NULL }, // No SPI4 + }; +#else +#error "Invalid CPU" +#endif + +SPIDevice spiDeviceByInstance(spi_type *instance) +{ + if (instance == SPI1) + return SPIDEV_1; + + if (instance == SPI2) + return SPIDEV_2; + + if (instance == SPI3) + return SPIDEV_3; + + return SPIINVALID; +} + +bool spiInitDevice(SPIDevice device, bool leadingEdge) +{ + spiDevice_t *spi = &(spiHardwareMap[device]); + + if (!spi->dev) { + return false; + } + + if (spi->initDone) { + return true; + } + // Enable SPI clock + RCC_ClockCmd(spi->rcc, ENABLE); + RCC_ResetCmd(spi->rcc, ENABLE); + + IOInit(IOGetByTag(spi->sck), OWNER_SPI, RESOURCE_SPI_SCK, device + 1); + IOInit(IOGetByTag(spi->miso), OWNER_SPI, RESOURCE_SPI_MISO, device + 1); + IOInit(IOGetByTag(spi->mosi), OWNER_SPI, RESOURCE_SPI_MOSI, device + 1); + + IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_SCK_CFG, spi->af); + IOConfigGPIOAF(IOGetByTag(spi->miso), SPI_IO_AF_MISO_CFG, spi->af); + IOConfigGPIOAF(IOGetByTag(spi->mosi), SPI_IO_AF_CFG, spi->af); + + if (spi->nss) { + IOConfigGPIOAF(IOGetByTag(spi->nss), SPI_IO_CS_CFG, spi->af); + } + + spi_i2s_reset(spi->dev); + spi_init_type spi_init_struct; + spi_default_para_init (&spi_init_struct); + spi_init_struct.master_slave_mode = SPI_MODE_MASTER; + spi_init_struct.transmission_mode = SPI_TRANSMIT_FULL_DUPLEX; + spi_init_struct.first_bit_transmission = SPI_FIRST_BIT_MSB; + spi_init_struct.mclk_freq_division = SPI_MCLK_DIV_8; + spi_init_struct.frame_bit_num = SPI_FRAME_8BIT; + spi_init_struct.cs_mode_selection = SPI_CS_SOFTWARE_MODE; + + spi_init_struct.clock_polarity = SPI_CLOCK_POLARITY_HIGH; + spi_init_struct.clock_phase = SPI_CLOCK_PHASE_2EDGE; + + if (leadingEdge) { + // SPI_MODE0 + spi_init_struct.clock_polarity = SPI_CLOCK_POLARITY_LOW; + spi_init_struct.clock_phase = SPI_CLOCK_PHASE_1EDGE; + } else { + // SPI_MODE3 + spi_init_struct.clock_polarity = SPI_CLOCK_POLARITY_HIGH; + spi_init_struct.clock_phase = SPI_CLOCK_PHASE_2EDGE; + + } + spi_init(spi->dev, &spi_init_struct); + spi_crc_polynomial_set (spi->dev, 0x07); + spi_crc_enable (spi->dev, TRUE); // enable crc + spi_enable (spi->dev, TRUE); + + if (spi->nss) { + // Drive NSS high to disable connected SPI device. + IOHi(IOGetByTag(spi->nss)); + } + spi->initDone = true; + return true; +} + +uint32_t spiTimeoutUserCallback(spi_type *instance) +{ + SPIDevice device = spiDeviceByInstance(instance); + if (device == SPIINVALID) { + return -1; + } + spiHardwareMap[device].errorCount++; + return spiHardwareMap[device].errorCount; +} + +// return uint8_t value or -1 when failure +uint8_t spiTransferByte(spi_type *instance, uint8_t data) +{ + uint16_t spiTimeout = 1000; + + //while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_TXE) == RESET) + while (spi_i2s_flag_get(instance, SPI_I2S_TDBE_FLAG) == RESET) + if ((spiTimeout--) == 0) + return spiTimeoutUserCallback(instance); + + //SPI_I2S_SendData(instance, data); + spi_i2s_data_transmit(instance, data); + + spiTimeout = 1000; + //while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_RXNE) == RESET) + while (spi_i2s_flag_get(instance, SPI_I2S_RDBF_FLAG) == RESET) + if ((spiTimeout--) == 0) + return spiTimeoutUserCallback(instance); + + return ((uint8_t) spi_i2s_data_receive(instance)); +} + +/** + * Return true if the bus is currently in the middle of a transmission. + */ +bool spiIsBusBusy(spi_type *instance) +{ + //return SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_TXE) == RESET || SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_BSY) == SET; + return spi_i2s_flag_get(instance, SPI_I2S_TDBE_FLAG) == RESET || spi_i2s_flag_get(instance, SPI_I2S_BF_FLAG) == SET; +} + +bool spiTransfer(spi_type *instance, uint8_t *out, const uint8_t *in, int len) +{ + uint16_t spiTimeout = 1000; + + instance->dt; + while (len--) { + uint8_t b = in ? *(in++) : 0xFF; + while (spi_i2s_flag_get(instance, SPI_I2S_TDBE_FLAG) == RESET) { + if ((spiTimeout--) == 0) + return spiTimeoutUserCallback(instance); + } + spi_i2s_data_transmit(instance, b); + spiTimeout = 1000; + while (spi_i2s_flag_get(instance, SPI_I2S_RDBF_FLAG) == RESET) { + if ((spiTimeout--) == 0) + return spiTimeoutUserCallback(instance); + } + b = spi_i2s_data_receive(instance); + if (out) + *(out++) = b; + } + + return true; +} + +void spiSetSpeed(spi_type *instance, SPIClockSpeed_e speed) +{ + #define BR_CLEAR_MASK 0xFFC7 + SPIDevice device = spiDeviceByInstance(instance); + if (device == SPIINVALID) { + return; + } + + spi_enable (instance, FALSE); + + // #define BR_BITS ((BIT(5) | BIT(4) | BIT(3))) + // const uint16_t tempRegister = (instance->ctrl1 & ~BR_BITS); + // instance->ctrl1 = tempRegister | (spiHardwareMap[device].divisorMap[speed] << 3); + // #undef BR_BITS + + uint16_t tempRegister = instance->ctrl1; + tempRegister &= BR_CLEAR_MASK; + tempRegister |= (spiHardwareMap[device].divisorMap[speed] << 3); + instance->ctrl1 = tempRegister; + + spi_enable (instance, TRUE); +} + +uint16_t spiGetErrorCounter(spi_type *instance) +{ + SPIDevice device = spiDeviceByInstance(instance); + if (device == SPIINVALID) { + return 0; + } + return spiHardwareMap[device].errorCount; +} + +void spiResetErrorCounter(spi_type *instance) +{ + SPIDevice device = spiDeviceByInstance(instance); + if (device != SPIINVALID) { + spiHardwareMap[device].errorCount = 0; + } +} + +spi_type * spiInstanceByDevice( SPIDevice device ) +{ + return spiHardwareMap[device].dev; +} +#endif // USE_SPI diff --git a/src/main/drivers/dma.h b/src/main/drivers/dma.h index 4b820c5f17..10ece99925 100644 --- a/src/main/drivers/dma.h +++ b/src/main/drivers/dma.h @@ -27,7 +27,7 @@ typedef struct dmaChannelDescriptor_s * DMA_t; #if defined(UNIT_TEST) typedef uint32_t DMA_TypeDef; #endif - +// DMA Tag,contains DMA id\DMA stream\DMA channel #define DMA_TAG(dma, stream, channel) ( (((dma) & 0x03) << 12) | (((stream) & 0x0F) << 8) | (((channel) & 0xFF) << 0) ) #define DMA_NONE (0) @@ -37,21 +37,51 @@ typedef uint32_t DMA_TypeDef; typedef void (*dmaCallbackHandlerFuncPtr)(DMA_t channelDescriptor); -typedef struct dmaChannelDescriptor_s { - dmaTag_t tag; - DMA_TypeDef* dma; -#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) - DMA_Stream_TypeDef* ref; +#if defined(AT32F43x) + #define DMA_IT_TCIF ((uint32_t)0x00000002) /*!< dma full data transfer interrupt */ + #define DMA_IT_HTIF ((uint32_t)0x00000004) /*!< dma half data transfer interrupt */ + #define DMA_IT_DMEIF ((uint32_t)0x00000008) /*!< dma errorr interrupt */ + + //EDMA features are available for extended use + typedef struct dmaChannelDescriptor_s { + dmaTag_t tag; + dma_type* dma; + dma_channel_type* ref; + dmaCallbackHandlerFuncPtr irqHandlerCallback; + uint32_t flagsShift; + IRQn_Type irqNumber; + uint32_t userParam; + resourceOwner_e owner; + uint8_t resourceIndex; + dmamux_channel_type * dmaMuxref; //dmamux flag + } dmaChannelDescriptor_t; + #else - DMA_Channel_TypeDef* ref; + #define DMA_IT_TCIF ((uint32_t)0x00000020) + #define DMA_IT_HTIF ((uint32_t)0x00000010) + #define DMA_IT_TEIF ((uint32_t)0x00000008) + #define DMA_IT_DMEIF ((uint32_t)0x00000004) + #define DMA_IT_FEIF ((uint32_t)0x00000001) + + + typedef struct dmaChannelDescriptor_s { + dmaTag_t tag; + DMA_TypeDef* dma; + #if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) + DMA_Stream_TypeDef* ref; + #else + DMA_Channel_TypeDef* ref; + #endif + dmaCallbackHandlerFuncPtr irqHandlerCallback; + uint32_t flagsShift; + IRQn_Type irqNumber; + uint32_t userParam; + resourceOwner_e owner; + uint8_t resourceIndex; + } dmaChannelDescriptor_t; + #endif - dmaCallbackHandlerFuncPtr irqHandlerCallback; - uint32_t flagsShift; - IRQn_Type irqNumber; - uint32_t userParam; - resourceOwner_e owner; - uint8_t resourceIndex; -} dmaChannelDescriptor_t; + #if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) @@ -74,14 +104,38 @@ typedef struct dmaChannelDescriptor_s { #define DMA_GET_FLAG_STATUS(d, flag) (d->flagsShift > 31 ? d->dma->HISR & (flag << (d->flagsShift - 32)): d->dma->LISR & (flag << d->flagsShift)) -#define DMA_IT_TCIF ((uint32_t)0x00000020) -#define DMA_IT_HTIF ((uint32_t)0x00000010) -#define DMA_IT_TEIF ((uint32_t)0x00000008) -#define DMA_IT_DMEIF ((uint32_t)0x00000004) -#define DMA_IT_FEIF ((uint32_t)0x00000001) DMA_t dmaGetByRef(const DMA_Stream_TypeDef * ref); +#elif defined(AT32F43x) + +// DEFINE_DMA_CHANNEL(d, s, f) use DMA_TAG(d, s, 0) +#define DEFINE_DMA_CHANNEL(d, s, f) { \ + .tag = DMA_TAG(d, s, 0), \ + .dma = DMA##d, \ + .ref = DMA##d##_CHANNEL##s, \ + .irqHandlerCallback = NULL, \ + .flagsShift = f, \ + .irqNumber = DMA##d##_Channel##s##_IRQn, \ + .userParam = 0, \ + .dmaMuxref = (dmamux_channel_type *)DMA##d ## MUX_CHANNEL ##s \ + } + + +//DMA_IRQ Naming format DMA#_Channel#_IRQHandler +#define DEFINE_DMA_IRQ_HANDLER(d, s, i) void DMA ## d ## _Channel ## s ## _IRQHandler(void) {\ + if (dmaDescriptors[i].irqHandlerCallback)\ + dmaDescriptors[i].irqHandlerCallback(&dmaDescriptors[i]);\ + } + +//Same as dma_flag_clear/dma_flag_get +#define DMA_CLEAR_FLAG(d, flag) d->dma->clr = (flag << d->flagsShift) +#define DMA_GET_FLAG_STATUS(d, flag) (d->dma->sts & (flag << d->flagsShift)) + +DMA_t dmaGetByRef(const dma_channel_type * ref); + +void dmaMuxEnable(DMA_t dma, uint32_t dmaMuxid); + #endif DMA_t dmaGetByTag(dmaTag_t tag); diff --git a/src/main/drivers/dma_at32f43x.c b/src/main/drivers/dma_at32f43x.c new file mode 100644 index 0000000000..7f48af509e --- /dev/null +++ b/src/main/drivers/dma_at32f43x.c @@ -0,0 +1,174 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include +#include +#include + +#include + +#include "build/debug.h" +#include "common/utils.h" +#include "drivers/nvic.h" +#include "drivers/dma.h" +#include "drivers/rcc.h" + +/* + * DMA descriptors. + */ +static dmaChannelDescriptor_t dmaDescriptors[] = { + [0] = DEFINE_DMA_CHANNEL(1, 1, 0), // DMA1_ST1 + [1] = DEFINE_DMA_CHANNEL(1, 2, 4), // DMA1_ST2 + [2] = DEFINE_DMA_CHANNEL(1, 3, 8), // DMA1_ST3 + [3] = DEFINE_DMA_CHANNEL(1, 4, 12), // DMA1_ST4 + [4] = DEFINE_DMA_CHANNEL(1, 5, 16), // DMA1_ST5 + [5] = DEFINE_DMA_CHANNEL(1, 6, 20), // DMA1_ST6 + [6] = DEFINE_DMA_CHANNEL(1, 7, 24), // DMA1_ST7 + + [7] = DEFINE_DMA_CHANNEL(2, 1, 0), // DMA2_ST1 + [8] = DEFINE_DMA_CHANNEL(2, 2, 4), // DMA2_ST2 + [9] = DEFINE_DMA_CHANNEL(2, 3, 8), // DMA2_ST3 + [10] = DEFINE_DMA_CHANNEL(2, 4, 12), // DMA2_ST4 + [11] = DEFINE_DMA_CHANNEL(2, 5, 16), // DMA2_ST5 + [12] = DEFINE_DMA_CHANNEL(2, 6, 20), // DMA2_ST6 + [13] = DEFINE_DMA_CHANNEL(2, 7, 24) // DMA2_ST7 + /* + //EDMA + [14] = DEFINE_EDMA_CHANNEL(0, 1, 6), // EDMA_1 + [15] = DEFINE_EDMA_CHANNEL(0, 2, 12), // EDMA_2 + [16] = DEFINE_EDMA_CHANNEL(0, 3, 18), // EDMA_3 + [17] = DEFINE_EDMA_CHANNEL(0, 4, 24), // EDMA_4 + [18] = DEFINE_EDMA_CHANNEL(0, 5, 30), // EDMA_5 + [19] = DEFINE_EDMA_CHANNEL(0, 6, 36), // EDMA_6 + [20] = DEFINE_EDMA_CHANNEL(0, 7, 42) // EDMA_7 + [21] = DEFINE_EDMA_CHANNEL(0, 8, 48) // EDMA_8 + */ +}; + +/* + * DMA IRQ Handlers + */ + +DEFINE_DMA_IRQ_HANDLER(1, 1, 0) +DEFINE_DMA_IRQ_HANDLER(1, 2, 1) +DEFINE_DMA_IRQ_HANDLER(1, 3, 2) +DEFINE_DMA_IRQ_HANDLER(1, 4, 3) +DEFINE_DMA_IRQ_HANDLER(1, 5, 4) +DEFINE_DMA_IRQ_HANDLER(1, 6, 5) +DEFINE_DMA_IRQ_HANDLER(1, 7, 6) + +DEFINE_DMA_IRQ_HANDLER(2, 1, 7) +DEFINE_DMA_IRQ_HANDLER(2, 2, 8) +DEFINE_DMA_IRQ_HANDLER(2, 3, 9) +DEFINE_DMA_IRQ_HANDLER(2, 4, 10) +DEFINE_DMA_IRQ_HANDLER(2, 5, 11) +DEFINE_DMA_IRQ_HANDLER(2, 6, 12) +DEFINE_DMA_IRQ_HANDLER(2, 7, 13) +/* +// edma +DEFINE_EDMA_IRQ_HANDLER(0, 0, 16) +DEFINE_EDMA_IRQ_HANDLER(0, 1, 17) +DEFINE_EDMA_IRQ_HANDLER(0, 2, 18) +DEFINE_EDMA_IRQ_HANDLER(0, 3, 19) +DEFINE_EDMA_IRQ_HANDLER(0, 4, 20) +DEFINE_EDMA_IRQ_HANDLER(0, 5, 21) +DEFINE_EDMA_IRQ_HANDLER(0, 6, 22) +DEFINE_EDMA_IRQ_HANDLER(0, 7, 23) +DEFINE_EDMA_IRQ_HANDLER(0, 8, 24) +*/ +// Obtain DMA_t through DMA ID & DMA channel +DMA_t dmaGetByTag(dmaTag_t tag) +{ + for (unsigned i = 0; i < ARRAYLEN(dmaDescriptors); i++) { + // On F4/F7 we match only DMA and Stream. Channel is needed when connecting DMA to peripheral + if (DMATAG_GET_DMA(dmaDescriptors[i].tag) == DMATAG_GET_DMA(tag) && DMATAG_GET_STREAM(dmaDescriptors[i].tag) == DMATAG_GET_STREAM(tag)) { + return (DMA_t)&dmaDescriptors[i]; + } + } + + return (DMA_t) NULL; +} + +void dmaEnableClock(DMA_t dma) +{ + if (dma->dma == DMA1) { + RCC_ClockCmd(RCC_AHB1(DMA1), ENABLE); + } + else { + RCC_ClockCmd(RCC_AHB1(DMA2), ENABLE); + } + dmamux_enable(dma->dma,TRUE); +} + +void dmaMuxEnable(DMA_t dma, uint32_t dmaMuxid) +{ + dmamux_init(dma->dmaMuxref, dmaMuxid); +} + +resourceOwner_e dmaGetOwner(DMA_t dma) +{ + return dma->owner; +} + +void dmaInit(DMA_t dma, resourceOwner_e owner, uint8_t resourceIndex) +{ + dmaEnableClock(dma); + dma->owner = owner; + dma->resourceIndex = resourceIndex; +} + +void dmaSetHandler(DMA_t dma, dmaCallbackHandlerFuncPtr callback, uint32_t priority, uint32_t userParam) +{ + dmaEnableClock(dma); + + dma->irqHandlerCallback = callback; + dma->userParam = userParam; + nvic_irq_enable(dma->irqNumber, priority,0); + +} +// This function is not used , use ChannelByTag instead +uint32_t dmaGetChannelByTag(dmaTag_t tag) +{ + static const dma_channel_type * dmaChannel[14] = { DMA1_CHANNEL1, DMA1_CHANNEL2, DMA1_CHANNEL3, DMA1_CHANNEL4, DMA1_CHANNEL5, DMA1_CHANNEL6, DMA1_CHANNEL7, + DMA2_CHANNEL1, DMA2_CHANNEL2, DMA2_CHANNEL3, DMA2_CHANNEL4, DMA2_CHANNEL5, DMA2_CHANNEL6, DMA2_CHANNEL7, + }; + + return (uint32_t) dmaChannel[(DMATAG_GET_DMA(tag)-1)*7 + DMATAG_GET_STREAM(tag)-1]; +} + +// Obtain DMA_t through DMA channel +DMA_t dmaGetByRef(const dma_channel_type* ref) +{ + for (unsigned i = 0; i < ARRAYLEN(dmaDescriptors); i++) { + if (ref == dmaDescriptors[i].ref) { + return &dmaDescriptors[i]; + } + } + return NULL; +} + +/* +DMA_t dmaGetByRef(const edma_stream_type* ref) +{ + for (unsigned i = 0; i < ARRAYLEN(dmaDescriptors); i++) { + if (ref == dmaDescriptors[i].sref) { + return &dmaDescriptors[i]; + } + } + return NULL; +} +*/ \ No newline at end of file diff --git a/src/main/drivers/exti.c b/src/main/drivers/exti.c index bc7b3400f6..7cfb8afbc6 100644 --- a/src/main/drivers/exti.c +++ b/src/main/drivers/exti.c @@ -32,6 +32,16 @@ static const uint8_t extiGroupIRQn[EXTI_IRQ_GROUPS] = { EXTI9_5_IRQn, EXTI15_10_IRQn }; +#elif defined(AT32F43x) +static const uint8_t extiGroupIRQn[EXTI_IRQ_GROUPS] = { + EXINT0_IRQn, + EXINT1_IRQn, + EXINT2_IRQn, + EXINT3_IRQn, + EXINT4_IRQn, + EXINT9_5_IRQn, + EXINT15_10_IRQn +}; #else # warning "Unknown CPU" #endif @@ -40,6 +50,10 @@ static const uint8_t extiGroupIRQn[EXTI_IRQ_GROUPS] = { #if defined(STM32H7) #define EXTI_REG_IMR (EXTI_D1->IMR1) #define EXTI_REG_PR (EXTI_D1->PR1) +#elif defined(AT32F43x) +// Interrupt enable register & interrupt status register +#define EXTI_REG_IMR (EXINT->inten) +#define EXTI_REG_PR (EXINT->intsts) #else #define EXTI_REG_IMR (EXTI->IMR) #define EXTI_REG_PR (EXTI->PR) @@ -51,6 +65,8 @@ void EXTIInit(void) #if defined(STM32F4) /* Enable SYSCFG clock otherwise the EXTI irq handlers are not called */ RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE); +#elif defined(AT32F43x) + crm_periph_clock_enable(CRM_SCFG_PERIPH_CLOCK, TRUE); #endif memset(extiChannelRecs, 0, sizeof(extiChannelRecs)); memset(extiGroupPriority, 0xff, sizeof(extiGroupPriority)); @@ -91,8 +107,38 @@ void EXTIConfig(IO_t io, extiCallbackRec_t *cb, int irqPriority, ioConfig_t conf HAL_NVIC_EnableIRQ(extiGroupIRQn[group]); } } -#else +#elif defined(AT32F43x) +void EXTIConfig(IO_t io, extiCallbackRec_t *cb, int irqPriority, exint_polarity_config_type trigger) +{ + int chIdx; + chIdx = IO_GPIOPinIdx(io); + if (chIdx < 0) + return; + // we have only 16 extiChannelRecs + ASSERT(chIdx < 16); + extiChannelRec_t *rec = &extiChannelRecs[chIdx]; + int group = extiGroups[chIdx]; + rec->handler = cb; + scfg_exint_line_config(IO_EXTI_PortSourceGPIO(io), IO_EXTI_PinSource(io)); + uint32_t extiLine = IO_EXTI_Line(io); + exint_flag_clear(extiLine); + + exint_init_type EXTIInit; + exint_default_para_init(&EXTIInit); + EXTIInit.line_mode = EXINT_LINE_INTERRUPUT; + EXTIInit.line_select = extiLine; + EXTIInit.line_polarity = trigger; + EXTIInit.line_enable = TRUE; + exint_init(&EXTIInit); + + if (extiGroupPriority[group] > irqPriority) { + extiGroupPriority[group] = irqPriority; + nvic_priority_group_config(NVIC_PRIORITY_GROUPING); + nvic_irq_enable(extiGroupIRQn[group],irqPriority,0); + } +} +#else void EXTIConfig(IO_t io, extiCallbackRec_t *cb, int irqPriority, EXTITrigger_TypeDef trigger) { int chIdx; @@ -151,7 +197,7 @@ void EXTIRelease(IO_t io) void EXTIEnable(IO_t io, bool enable) { -#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) +#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7)|| defined(AT32F43x) uint32_t extiLine = IO_EXTI_Line(io); if (!extiLine) return; @@ -185,11 +231,20 @@ void EXTI_IRQHandler(void) /**/ +#if defined(AT32F43x) +_EXTI_IRQ_HANDLER(EXINT0_IRQHandler); +_EXTI_IRQ_HANDLER(EXINT1_IRQHandler); +_EXTI_IRQ_HANDLER(EXINT2_IRQHandler); +_EXTI_IRQ_HANDLER(EXINT3_IRQHandler); +_EXTI_IRQ_HANDLER(EXINT4_IRQHandler); +_EXTI_IRQ_HANDLER(EXINT9_5_IRQHandler); +_EXTI_IRQ_HANDLER(EXINT15_10_IRQHandler); +#else _EXTI_IRQ_HANDLER(EXTI0_IRQHandler); _EXTI_IRQ_HANDLER(EXTI1_IRQHandler); #if defined(STM32F7) || defined(STM32H7) _EXTI_IRQ_HANDLER(EXTI2_IRQHandler); -#elif defined(STM32F4) +#elif defined(STM32F4) || defined(AT32F43x) _EXTI_IRQ_HANDLER(EXTI2_TS_IRQHandler); #else # warning "Unknown CPU" @@ -197,4 +252,6 @@ _EXTI_IRQ_HANDLER(EXTI2_TS_IRQHandler); _EXTI_IRQ_HANDLER(EXTI3_IRQHandler); _EXTI_IRQ_HANDLER(EXTI4_IRQHandler); _EXTI_IRQ_HANDLER(EXTI9_5_IRQHandler); -_EXTI_IRQ_HANDLER(EXTI15_10_IRQHandler); \ No newline at end of file +_EXTI_IRQ_HANDLER(EXTI15_10_IRQHandler); +#endif + diff --git a/src/main/drivers/exti.h b/src/main/drivers/exti.h index 8abceb15f2..dbc5be1643 100644 --- a/src/main/drivers/exti.h +++ b/src/main/drivers/exti.h @@ -37,6 +37,8 @@ void EXTIInit(void); void EXTIHandlerInit(extiCallbackRec_t *cb, extiHandlerCallback *fn); #if defined(STM32F7) || defined(STM32H7) void EXTIConfig(IO_t io, extiCallbackRec_t *cb, int irqPriority, ioConfig_t config); +#elif defined(AT32F43x) +void EXTIConfig(IO_t io, extiCallbackRec_t *cb, int irqPriority, exint_polarity_config_type trigger); #else void EXTIConfig(IO_t io, extiCallbackRec_t *cb, int irqPriority, EXTITrigger_TypeDef trigger); #endif diff --git a/src/main/drivers/i2c_application.c b/src/main/drivers/i2c_application.c new file mode 100644 index 0000000000..ada893d65f --- /dev/null +++ b/src/main/drivers/i2c_application.c @@ -0,0 +1,2332 @@ +/** + ************************************************************************** + * @file i2c_application.c + * @version v2.1.0 + * @date 2022-08-16 + * @brief the driver library of the i2c peripheral + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +#include "i2c_application.h" + +/** @addtogroup AT32F435_437_middlewares_i2c_application_library + * @{ + */ + +/** + * @brief get the dma transfer direction flag through the channel + */ +#define DMA_GET_REQUEST(DMA_CHANNEL) \ +(((uint32_t)(DMA_CHANNEL) == ((uint32_t)hi2c->dma_tx_channel)) ? I2C_DMA_REQUEST_TX : I2C_DMA_REQUEST_RX) + +/** + * @brief get the dma transfer complete flag through the channel + */ +#define DMA_GET_TC_FLAG(DMA_CHANNEL) \ +(((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA1_CHANNEL1))? DMA1_FDT1_FLAG : \ + ((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA1_CHANNEL2))? DMA1_FDT2_FLAG : \ + ((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA1_CHANNEL3))? DMA1_FDT3_FLAG : \ + ((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA1_CHANNEL4))? DMA1_FDT4_FLAG : \ + ((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA1_CHANNEL5))? DMA1_FDT5_FLAG : \ + ((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA1_CHANNEL6))? DMA1_FDT6_FLAG : \ + ((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA1_CHANNEL7))? DMA1_FDT7_FLAG : \ + ((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA2_CHANNEL1))? DMA2_FDT1_FLAG : \ + ((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA2_CHANNEL2))? DMA2_FDT2_FLAG : \ + ((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA2_CHANNEL3))? DMA2_FDT3_FLAG : \ + ((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA2_CHANNEL4))? DMA2_FDT4_FLAG : \ + ((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA2_CHANNEL5))? DMA2_FDT5_FLAG : \ + ((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA2_CHANNEL6))? DMA2_FDT6_FLAG : \ + DMA2_FDT7_FLAG) + +/** + * @brief get the dma half transfer flag through the channel + */ +#define DMA_GET_HT_FLAG(DMA_CHANNEL) \ +(((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA1_CHANNEL1))? DMA1_HDT1_FLAG : \ + ((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA1_CHANNEL2))? DMA1_HDT2_FLAG : \ + ((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA1_CHANNEL3))? DMA1_HDT3_FLAG : \ + ((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA1_CHANNEL4))? DMA1_HDT4_FLAG : \ + ((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA1_CHANNEL5))? DMA1_HDT5_FLAG : \ + ((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA1_CHANNEL6))? DMA1_HDT6_FLAG : \ + ((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA1_CHANNEL7))? DMA1_HDT7_FLAG : \ + ((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA2_CHANNEL1))? DMA2_HDT1_FLAG : \ + ((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA2_CHANNEL2))? DMA2_HDT2_FLAG : \ + ((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA2_CHANNEL3))? DMA2_HDT3_FLAG : \ + ((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA2_CHANNEL4))? DMA2_HDT4_FLAG : \ + ((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA2_CHANNEL5))? DMA2_HDT5_FLAG : \ + ((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA2_CHANNEL6))? DMA2_HDT6_FLAG : \ + DMA2_HDT7_FLAG) + +/** + * @brief get the dma transfer error flag through the channel + */ +#define DMA_GET_TERR_FLAG(DMA_CHANNEL) \ +(((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA1_CHANNEL1))? DMA1_DTERR1_FLAG : \ + ((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA1_CHANNEL2))? DMA1_DTERR2_FLAG : \ + ((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA1_CHANNEL3))? DMA1_DTERR3_FLAG : \ + ((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA1_CHANNEL4))? DMA1_DTERR4_FLAG : \ + ((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA1_CHANNEL5))? DMA1_DTERR5_FLAG : \ + ((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA1_CHANNEL6))? DMA1_DTERR6_FLAG : \ + ((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA1_CHANNEL7))? DMA1_DTERR7_FLAG : \ + ((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA2_CHANNEL1))? DMA2_DTERR1_FLAG : \ + ((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA2_CHANNEL2))? DMA2_DTERR2_FLAG : \ + ((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA2_CHANNEL3))? DMA2_DTERR3_FLAG : \ + ((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA2_CHANNEL4))? DMA2_DTERR4_FLAG : \ + ((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA2_CHANNEL5))? DMA2_DTERR5_FLAG : \ + ((uint32_t)(DMA_CHANNEL) == ((uint32_t)DMA2_CHANNEL6))? DMA2_DTERR6_FLAG : \ + DMA2_DTERR7_FLAG) + +/** + * @brief i2c transmission status + */ +#define I2C_START 0 +#define I2C_END 1 + + +/** + * @brief i2c peripheral initialization. + * @param hi2c: the handle points to the operation information. + * @retval none. + */ +void i2c_config(i2c_handle_type* hi2c) +{ + /* reset i2c peripheral */ + i2c_reset(hi2c->i2cx); + + /* i2c peripheral initialization */ + i2c_lowlevel_init(hi2c); + + /* i2c peripheral enable */ + i2c_enable(hi2c->i2cx, TRUE); +} + +/** + * @brief refresh i2c register. + * @param hi2c: the handle points to the operation information. + * @retval none. + */ +void i2c_refresh_txdt_register(i2c_handle_type* hi2c) +{ + /* clear tdis flag */ + if (i2c_flag_get(hi2c->i2cx, I2C_TDIS_FLAG) != RESET) + { + hi2c->i2cx->txdt = 0x00; + } + + /* refresh txdt register*/ + if (i2c_flag_get(hi2c->i2cx, I2C_TDBE_FLAG) == RESET) + { + hi2c->i2cx->sts_bit.tdbe = 1; + } +} + +/** + * @brief reset ctrl2 register. + * @param hi2c: the handle points to the operation information. + * @retval none. + */ +void i2c_reset_ctrl2_register(i2c_handle_type* hi2c) +{ + hi2c->i2cx->ctrl2_bit.saddr = 0; + hi2c->i2cx->ctrl2_bit.readh10 = 0; + hi2c->i2cx->ctrl2_bit.cnt = 0; + hi2c->i2cx->ctrl2_bit.rlden = 0; + hi2c->i2cx->ctrl2_bit.dir = 0; +} + +/** + * @brief wait for the transfer to end. + * @param hi2c: the handle points to the operation information. + * @param timeout: maximum waiting time. + * @retval i2c status. + */ +i2c_status_type i2c_wait_end(i2c_handle_type* hi2c, uint32_t timeout) +{ + while(hi2c->status != I2C_END) + { + /* check timeout */ + if((timeout--) == 0) + { + return I2C_ERR_TIMEOUT; + } + } + + if(hi2c->error_code != I2C_OK) + { + return hi2c->error_code; + } + + return I2C_OK; +} + +/** + * @brief wait for the flag to be set or reset, only BUSYF flag + * is waiting to be reset, and other flags are waiting to be set + * @param hi2c: the handle points to the operation information. + * @param flag: specifies the flag to check. + * this parameter can be one of the following values: + * - I2C_TDBE_FLAG: transmit data buffer empty flag. + * - I2C_TDIS_FLAG: send interrupt status. + * - I2C_RDBF_FLAG: receive data buffer full flag. + * - I2C_ADDRF_FLAG: 0~7 bit address match flag. + * - I2C_ACKFAIL_FLAG: acknowledge failure flag. + * - I2C_STOPF_FLAG: stop condition generation complete flag. + * - I2C_TDC_FLAG: transmit data complete flag. + * - I2C_TCRLD_FLAG: transmission is complete, waiting to load data. + * - I2C_BUSERR_FLAG: bus error flag. + * - I2C_ARLOST_FLAG: arbitration lost flag. + * - I2C_OUF_FLAG: overflow or underflow flag. + * - I2C_PECERR_FLAG: pec receive error flag. + * - I2C_TMOUT_FLAG: smbus timeout flag. + * - I2C_ALERTF_FLAG: smbus alert flag. + * - I2C_BUSYF_FLAG: bus busy flag transmission mode. + * - I2C_SDIR_FLAG: slave data transmit direction. + * @param event_check: check other error flags while waiting for the flag. + * parameter as following values: + * - I2C_EVENT_CHECK_NONE + * - I2C_EVENT_CHECK_ACKFAIL + * - I2C_EVENT_CHECK_STOP + * @param timeout: maximum waiting time. + * @retval i2c status. + */ +i2c_status_type i2c_wait_flag(i2c_handle_type* hi2c, uint32_t flag, uint32_t event_check, uint32_t timeout) +{ + if(flag == I2C_BUSYF_FLAG) + { + while(i2c_flag_get(hi2c->i2cx, flag) != RESET) + { + /* check timeout */ + if((timeout--) == 0) + { + hi2c->error_code = I2C_ERR_TIMEOUT; + + return I2C_ERR_TIMEOUT; + } + } + } + else + { + while(i2c_flag_get(hi2c->i2cx, flag) == RESET) + { + /* check the ack fail flag */ + if(event_check & I2C_EVENT_CHECK_ACKFAIL) + { + if(i2c_flag_get(hi2c->i2cx, I2C_ACKFAIL_FLAG) != RESET) + { + /* clear ack fail flag */ + i2c_flag_clear(hi2c->i2cx, I2C_ACKFAIL_FLAG); + + hi2c->error_code = I2C_ERR_ACKFAIL; + + return I2C_ERR_ACKFAIL; + } + } + + /* check the stop flag */ + if(event_check & I2C_EVENT_CHECK_STOP) + { + if(i2c_flag_get(hi2c->i2cx, I2C_STOPF_FLAG) != RESET) + { + /* clear stop flag */ + i2c_flag_clear(hi2c->i2cx, I2C_STOPF_FLAG); + + i2c_reset_ctrl2_register(hi2c); + + hi2c->error_code = I2C_ERR_STOP; + + return I2C_ERR_STOP; + } + } + + /* check timeout */ + if((timeout--) == 0) + { + hi2c->error_code = I2C_ERR_TIMEOUT; + + return I2C_ERR_TIMEOUT; + } + } + } + + return I2C_OK; +} + +/** + * @brief dma transfer cofiguration. + * @param hi2c: the handle points to the operation information. + * @param dma_channelx: dma channel to be cofigured. + * @param pdata: data buffer. + * @param size: data size. + * @retval none. + */ +void i2c_dma_config(i2c_handle_type* hi2c, dma_channel_type* dma_channel, uint8_t* pdata, uint16_t size) +{ + /* disable the dma channel */ + dma_channel_enable(dma_channel, FALSE); + + /* disable the transfer complete interrupt */ + dma_interrupt_enable(dma_channel, DMA_FDT_INT, FALSE); + + /* configure the dma channel with the buffer address and the buffer size */ + hi2c->dma_init_struct.memory_base_addr = (uint32_t)pdata; + hi2c->dma_init_struct.direction = (dma_channel == hi2c->dma_tx_channel) ? DMA_DIR_MEMORY_TO_PERIPHERAL : DMA_DIR_PERIPHERAL_TO_MEMORY; + hi2c->dma_init_struct.peripheral_base_addr = (dma_channel == hi2c->dma_tx_channel) ? (uint32_t)&hi2c->i2cx->txdt : (uint32_t)&hi2c->i2cx->rxdt; + hi2c->dma_init_struct.buffer_size = (uint32_t)size; + dma_init(dma_channel, &hi2c->dma_init_struct); + + /* enable the transfer complete interrupt */ + dma_interrupt_enable(dma_channel, DMA_FDT_INT, TRUE); + + /* enable the dma channel */ + dma_channel_enable(dma_channel, TRUE); +} + +/** + * @brief start transfer in poll mode or interrupt mode. + * @param hi2c: the handle points to the operation information. + * @param address: slave address. + * @param start: config gen start condition mode. + * parameter as following values: + * - I2C_WITHOUT_START: transfer data without start condition. + * - I2C_GEN_START_READ: read data and generate start. + * - I2C_GEN_START_WRITE: send data and generate start. + * @retval i2c status. + */ +void i2c_start_transfer(i2c_handle_type* hi2c, uint16_t address, i2c_start_mode_type start) +{ + if (hi2c->pcount > MAX_TRANSFER_CNT) + { + hi2c->psize = MAX_TRANSFER_CNT; + + i2c_transmit_set(hi2c->i2cx, address, hi2c->psize, I2C_RELOAD_MODE, start); + } + else + { + hi2c->psize = hi2c->pcount; + + i2c_transmit_set(hi2c->i2cx, address, hi2c->psize, I2C_AUTO_STOP_MODE, start); + } +} + +/** + * @brief start transfer in dma mode. + * @param hi2c: the handle points to the operation information. + * @param address: slave address. + * @param start: config gen start condition mode. + * parameter as following values: + * - I2C_WITHOUT_START: transfer data without start condition. + * - I2C_GEN_START_READ: read data and generate start. + * - I2C_GEN_START_WRITE: send data and generate start. + * @retval i2c status. + */ +void i2c_start_transfer_dma(i2c_handle_type* hi2c, dma_channel_type* dma_channelx, uint16_t address, i2c_start_mode_type start) +{ + if (hi2c->pcount > MAX_TRANSFER_CNT) + { + hi2c->psize = MAX_TRANSFER_CNT; + + /* config dma */ + i2c_dma_config(hi2c, dma_channelx, hi2c->pbuff, hi2c->psize); + + i2c_transmit_set(hi2c->i2cx, address, hi2c->psize, I2C_RELOAD_MODE, start); + } + else + { + hi2c->psize = hi2c->pcount; + + /* config dma */ + i2c_dma_config(hi2c, dma_channelx, hi2c->pbuff, hi2c->psize); + + i2c_transmit_set(hi2c->i2cx, address, hi2c->psize, I2C_AUTO_STOP_MODE, start); + } +} + +/** + * @brief the master transmits data through polling mode. + * @param hi2c: the handle points to the operation information. + * @param address: slave address. + * @param pdata: data buffer. + * @param size: data size. + * @param timeout: maximum waiting time. + * @retval i2c status. + */ +i2c_status_type i2c_master_transmit(i2c_handle_type* hi2c, uint16_t address, uint8_t* pdata, uint16_t size, uint32_t timeout) +{ + /* initialization parameters */ + hi2c->pbuff = pdata; + hi2c->pcount = size; + + hi2c->error_code = I2C_OK; + + /* wait for the busy flag to be reset */ + if (i2c_wait_flag(hi2c, I2C_BUSYF_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + return I2C_ERR_STEP_1; + } + + /* start transfer */ + i2c_start_transfer(hi2c, address, I2C_GEN_START_WRITE); + + while (hi2c->pcount > 0) + { + /* wait for the tdis flag to be set */ + if(i2c_wait_flag(hi2c, I2C_TDIS_FLAG, I2C_EVENT_CHECK_ACKFAIL, timeout) != I2C_OK) + { + return I2C_ERR_STEP_2; + } + + /* send data */ + i2c_data_send(hi2c->i2cx, *hi2c->pbuff++); + hi2c->psize--; + hi2c->pcount--; + + if ((hi2c->psize == 0) && (hi2c->pcount != 0)) + { + /* wait for the tcrld flag to be set */ + if (i2c_wait_flag(hi2c, I2C_TCRLD_FLAG, I2C_EVENT_CHECK_ACKFAIL, timeout) != I2C_OK) + { + return I2C_ERR_STEP_3; + } + + /* continue transfer */ + i2c_start_transfer(hi2c, address, I2C_WITHOUT_START); + } + } + + /* wait for the stop flag to be set */ + if(i2c_wait_flag(hi2c, I2C_STOPF_FLAG, I2C_EVENT_CHECK_ACKFAIL, timeout) != I2C_OK) + { + return I2C_ERR_STEP_4; + } + + /* clear stop flag */ + i2c_flag_clear(hi2c->i2cx, I2C_STOPF_FLAG); + + /* reset ctrl2 register */ + i2c_reset_ctrl2_register(hi2c); + + return I2C_OK; +} + +/** + * @brief the slave receive data through polling mode. + * @param hi2c: the handle points to the operation information. + * @param pdata: data buffer. + * @param size: data size. + * @param timeout: maximum waiting time. + * @retval i2c status. + */ +i2c_status_type i2c_slave_receive(i2c_handle_type* hi2c, uint8_t* pdata, uint16_t size, uint32_t timeout) +{ + /* initialization parameters */ + hi2c->pbuff = pdata; + hi2c->pcount = size; + + hi2c->error_code = I2C_OK; + + /* wait for the busy flag to be reset */ + if(i2c_wait_flag(hi2c, I2C_BUSYF_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + return I2C_ERR_STEP_1; + } + + /* enable acknowledge */ + i2c_ack_enable(hi2c->i2cx, TRUE); + + /* wait for the addr flag to be set */ + if (i2c_wait_flag(hi2c, I2C_ADDRF_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + return I2C_ERR_STEP_2; + } + + /* clear addr flag */ + i2c_flag_clear(hi2c->i2cx, I2C_ADDRF_FLAG); + + while (hi2c->pcount > 0) + { + /* wait for the rdbf flag to be set */ + if(i2c_wait_flag(hi2c, I2C_RDBF_FLAG, I2C_EVENT_CHECK_STOP, timeout) != I2C_OK) + { + /* disable acknowledge */ + i2c_ack_enable(hi2c->i2cx, FALSE); + + /* if data is received, read data */ + if (i2c_flag_get(hi2c->i2cx, I2C_RDBF_FLAG) == SET) + { + /* read data */ + (*hi2c->pbuff++) = i2c_data_receive(hi2c->i2cx); + hi2c->pcount--; + } + + return I2C_ERR_STEP_4; + } + + /* read data */ + (*hi2c->pbuff++) = i2c_data_receive(hi2c->i2cx); + hi2c->pcount--; + } + + /* wait for the stop flag to be set */ + if(i2c_wait_flag(hi2c, I2C_STOPF_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + /* disable acknowledge */ + i2c_ack_enable(hi2c->i2cx, FALSE); + + return I2C_ERR_STEP_5; + } + + /* clear stop flag */ + i2c_flag_clear(hi2c->i2cx, I2C_STOPF_FLAG); + + /* wait for the busy flag to be reset */ + if (i2c_wait_flag(hi2c, I2C_BUSYF_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + /* disable acknowledge */ + i2c_ack_enable(hi2c->i2cx, FALSE); + + return I2C_ERR_STEP_6; + } + + return I2C_OK; +} + +/** + * @brief the master receive data through polling mode. + * @param hi2c: the handle points to the operation information. + * @param address: slave address. + * @param pdata: data buffer. + * @param size: data size. + * @param timeout: maximum waiting time. + * @retval i2c status. + */ +i2c_status_type i2c_master_receive(i2c_handle_type* hi2c, uint16_t address, uint8_t* pdata, uint16_t size, uint32_t timeout) +{ + /* initialization parameters */ + hi2c->pbuff = pdata; + hi2c->pcount = size; + + hi2c->error_code = I2C_OK; + + /* wait for the busy flag to be reset */ + if (i2c_wait_flag(hi2c, I2C_BUSYF_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + return I2C_ERR_STEP_1; + } + + /* start transfer */ + i2c_start_transfer(hi2c, address, I2C_GEN_START_READ); + + while (hi2c->pcount > 0) + { + /* wait for the rdbf flag to be set */ + if(i2c_wait_flag(hi2c, I2C_RDBF_FLAG, I2C_EVENT_CHECK_ACKFAIL, timeout) != I2C_OK) + { + return I2C_ERR_STEP_2; + } + + /* read data */ + (*hi2c->pbuff++) = i2c_data_receive(hi2c->i2cx); + hi2c->pcount--; + hi2c->psize--; + + if ((hi2c->psize == 0) && (hi2c->pcount != 0)) + { + /* wait for the tcrld flag to be set */ + if (i2c_wait_flag(hi2c, I2C_TCRLD_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + return I2C_ERR_STEP_3; + } + + /* continue transfer */ + i2c_start_transfer(hi2c, address, I2C_WITHOUT_START); + } + } + + /* wait for the stop flag to be set */ + if(i2c_wait_flag(hi2c, I2C_STOPF_FLAG, I2C_EVENT_CHECK_ACKFAIL, timeout) != I2C_OK) + { + return I2C_ERR_STEP_4; + } + + /* clear stop flag */ + i2c_flag_clear(hi2c->i2cx, I2C_STOPF_FLAG); + + /* reset ctrl2 register */ + i2c_reset_ctrl2_register(hi2c); + + return I2C_OK; +} + +/** + * @brief the slave transmits data through polling mode. + * @param hi2c: the handle points to the operation information. + * @param pdata: data buffer. + * @param size: data size. + * @param timeout: maximum waiting time. + * @retval i2c status. + */ +i2c_status_type i2c_slave_transmit(i2c_handle_type* hi2c, uint8_t* pdata, uint16_t size, uint32_t timeout) +{ + /* initialization parameters */ + hi2c->pbuff = pdata; + hi2c->pcount = size; + + hi2c->error_code = I2C_OK; + + /* wait for the busy flag to be reset */ + if(i2c_wait_flag(hi2c, I2C_BUSYF_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + return I2C_ERR_STEP_1; + } + + /* enable acknowledge */ + i2c_ack_enable(hi2c->i2cx, TRUE); + + /* wait for the addr flag to be set */ + if (i2c_wait_flag(hi2c, I2C_ADDRF_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + /* disable acknowledge */ + i2c_ack_enable(hi2c->i2cx, FALSE); + return I2C_ERR_STEP_2; + } + + /* clear addr flag */ + i2c_flag_clear(hi2c->i2cx, I2C_ADDRF_FLAG); + + /* if 10-bit address mode is used */ + if (hi2c->i2cx->ctrl2_bit.addr10 != RESET) + { + /* wait for the addr flag to be set */ + if (i2c_wait_flag(hi2c, I2C_ADDRF_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + /* disable acknowledge */ + i2c_ack_enable(hi2c->i2cx, FALSE); + + return I2C_ERR_STEP_3; + } + + /* clear addr flag */ + i2c_flag_clear(hi2c->i2cx, I2C_ADDRF_FLAG); + } + + while (hi2c->pcount > 0) + { + /* wait for the tdis flag to be set */ + if(i2c_wait_flag(hi2c, I2C_TDIS_FLAG, I2C_EVENT_CHECK_ACKFAIL, timeout) != I2C_OK) + { + /* disable acknowledge */ + i2c_ack_enable(hi2c->i2cx, FALSE); + + return I2C_ERR_STEP_5; + } + + /* send data */ + i2c_data_send(hi2c->i2cx, *hi2c->pbuff++); + hi2c->pcount--; + } + + /* wait for the ackfail flag to be set */ + if(i2c_wait_flag(hi2c, I2C_ACKFAIL_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + return I2C_ERR_STEP_6; + } + + /* clear ack fail flag */ + i2c_flag_clear(hi2c->i2cx, I2C_ACKFAIL_FLAG); + + /* wait for the stop flag to be set */ + if(i2c_wait_flag(hi2c, I2C_STOPF_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + /* disable acknowledge */ + i2c_ack_enable(hi2c->i2cx, FALSE); + + return I2C_ERR_STEP_7; + } + + /* clear stop flag */ + i2c_flag_clear(hi2c->i2cx, I2C_STOPF_FLAG); + + /* wait for the busy flag to be reset */ + if (i2c_wait_flag(hi2c, I2C_BUSYF_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + /* disable acknowledge */ + i2c_ack_enable(hi2c->i2cx, FALSE); + + return I2C_ERR_STEP_8; + } + + /* refresh tx dt register */ + i2c_refresh_txdt_register(hi2c); + + return I2C_OK; +} + +/** + * @brief the master transmits data through interrupt mode. + * @param hi2c: the handle points to the operation information. + * @param address: slave address. + * @param pdata: data buffer. + * @param size: data size. + * @param timeout: maximum waiting time. + * @retval i2c status. + */ +i2c_status_type i2c_master_transmit_int(i2c_handle_type* hi2c, uint16_t address, uint8_t* pdata, uint16_t size, uint32_t timeout) +{ + /* initialization parameters */ + hi2c->mode = I2C_INT_MA_TX; + hi2c->status = I2C_START; + + hi2c->pbuff = pdata; + hi2c->pcount = size; + + hi2c->error_code = I2C_OK; + + /* wait for the busy flag to be reset */ + if (i2c_wait_flag(hi2c, I2C_BUSYF_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + return I2C_ERR_STEP_1; + } + + /* start transfer */ + i2c_start_transfer(hi2c, address, I2C_GEN_START_WRITE); + + /* enable interrupt */ + i2c_interrupt_enable(hi2c->i2cx, I2C_ERR_INT | I2C_TDC_INT | I2C_STOP_INT | I2C_ACKFIAL_INT | I2C_TD_INT, TRUE); + + return I2C_OK; +} + +/** + * @brief the slave receive data through interrupt mode. + * @param hi2c: the handle points to the operation information. + * @param pdata: data buffer. + * @param size: data size. + * @param timeout: maximum waiting time. + * @retval i2c status. + */ +i2c_status_type i2c_slave_receive_int(i2c_handle_type* hi2c, uint8_t* pdata, uint16_t size, uint32_t timeout) +{ + /* initialization parameters */ + hi2c->mode = I2C_INT_SLA_RX; + hi2c->status = I2C_START; + + hi2c->pbuff = pdata; + hi2c->pcount = size; + + hi2c->error_code = I2C_OK; + + /* wait for the busy flag to be reset */ + if (i2c_wait_flag(hi2c, I2C_BUSYF_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + return I2C_ERR_STEP_1; + } + + /* enable acknowledge */ + i2c_ack_enable(hi2c->i2cx, TRUE); + + /* enable interrupt */ + i2c_interrupt_enable(hi2c->i2cx, I2C_ERR_INT | I2C_TDC_INT | I2C_STOP_INT | I2C_ACKFIAL_INT | I2C_ADDR_INT | I2C_RD_INT, TRUE); + + return I2C_OK; +} + +/** + * @brief the master receive data through interrupt mode. + * @param hi2c: the handle points to the operation information. + * @param address: slave address. + * @param pdata: data buffer. + * @param size: data size. + * @param timeout: maximum waiting time. + * @retval i2c status. + */ +i2c_status_type i2c_master_receive_int(i2c_handle_type* hi2c, uint16_t address, uint8_t* pdata, uint16_t size, uint32_t timeout) +{ + /* initialization parameters */ + hi2c->mode = I2C_INT_MA_RX; + hi2c->status = I2C_START; + + hi2c->pbuff = pdata; + hi2c->pcount = size; + + hi2c->error_code = I2C_OK; + + /* wait for the busy flag to be reset */ + if (i2c_wait_flag(hi2c, I2C_BUSYF_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + return I2C_ERR_STEP_1; + } + + /* start transfer */ + i2c_start_transfer(hi2c, address, I2C_GEN_START_READ); + + /* enable interrupt */ + i2c_interrupt_enable(hi2c->i2cx, I2C_ERR_INT | I2C_TDC_INT | I2C_STOP_INT | I2C_ACKFIAL_INT | I2C_RD_INT, TRUE); + + return I2C_OK; +} + +/** + * @brief the slave transmits data through interrupt mode. + * @param hi2c: the handle points to the operation information. + * @param pdata: data buffer. + * @param size: data size. + * @param timeout: maximum waiting time. + * @retval i2c status. + */ +i2c_status_type i2c_slave_transmit_int(i2c_handle_type* hi2c, uint8_t* pdata, uint16_t size, uint32_t timeout) +{ + /* initialization parameters */ + hi2c->mode = I2C_INT_SLA_TX; + hi2c->status = I2C_START; + + hi2c->pbuff = pdata; + hi2c->pcount = size; + + hi2c->error_code = I2C_OK; + + /* wait for the busy flag to be reset */ + if (i2c_wait_flag(hi2c, I2C_BUSYF_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + return I2C_ERR_STEP_1; + } + + /* enable acknowledge */ + i2c_ack_enable(hi2c->i2cx, TRUE); + + /* enable interrupt */ + i2c_interrupt_enable(hi2c->i2cx, I2C_ERR_INT | I2C_TDC_INT | I2C_STOP_INT | I2C_ACKFIAL_INT | I2C_ADDR_INT | I2C_TD_INT, TRUE); + + i2c_refresh_txdt_register(hi2c); + + return I2C_OK; +} + +/** + * @brief the master transmits data through dma mode. + * @param hi2c: the handle points to the operation information. + * @param address: slave address. + * @param pdata: data buffer. + * @param size: data size. + * @param timeout: maximum waiting time. + * @retval i2c status. + */ +i2c_status_type i2c_master_transmit_dma(i2c_handle_type* hi2c, uint16_t address, uint8_t* pdata, uint16_t size, uint32_t timeout) +{ + /* initialization parameters */ + hi2c->mode = I2C_DMA_MA_TX; + hi2c->status = I2C_START; + + hi2c->pbuff = pdata; + hi2c->pcount = size; + + hi2c->error_code = I2C_OK; + + /* wait for the busy flag to be reset */ + if(i2c_wait_flag(hi2c, I2C_BUSYF_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + return I2C_ERR_STEP_1; + } + + /* disable dma request */ + i2c_dma_enable(hi2c->i2cx, I2C_DMA_REQUEST_TX, FALSE); + + /* start transfer */ + i2c_start_transfer_dma(hi2c, hi2c->dma_tx_channel, address, I2C_GEN_START_WRITE); + + /* enable i2c interrupt */ + i2c_interrupt_enable(hi2c->i2cx, I2C_ERR_INT | I2C_ACKFIAL_INT, TRUE); + + /* enable dma request */ + i2c_dma_enable(hi2c->i2cx, I2C_DMA_REQUEST_TX, TRUE); + + return I2C_OK; +} + +/** + * @brief the slave receive data through dma mode. + * @param hi2c: the handle points to the operation information. + * @param pdata: data buffer. + * @param size: data size. + * @param timeout: maximum waiting time. + * @retval i2c status. + */ +i2c_status_type i2c_slave_receive_dma(i2c_handle_type* hi2c, uint8_t* pdata, uint16_t size, uint32_t timeout) +{ + /* initialization parameters */ + hi2c->mode = I2C_DMA_SLA_RX; + hi2c->status = I2C_START; + + hi2c->pbuff = pdata; + hi2c->pcount = size; + + hi2c->error_code = I2C_OK; + + /* wait for the busy flag to be reset */ + if(i2c_wait_flag(hi2c, I2C_BUSYF_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + return I2C_ERR_STEP_1; + } + + /* disable dma request */ + i2c_dma_enable(hi2c->i2cx, I2C_DMA_REQUEST_RX, FALSE); + + /* config dma */ + i2c_dma_config(hi2c, hi2c->dma_rx_channel, hi2c->pbuff, size); + + /* enable acknowledge */ + i2c_ack_enable(hi2c->i2cx, TRUE); + + /* enable i2c interrupt */ + i2c_interrupt_enable(hi2c->i2cx, I2C_ADDR_INT | I2C_STOP_INT | I2C_ACKFIAL_INT | I2C_ERR_INT, TRUE); + + /* enable dma request */ + i2c_dma_enable(hi2c->i2cx, I2C_DMA_REQUEST_RX, TRUE); + + return I2C_OK; +} + +/** + * @brief the master receive data through dma mode. + * @param hi2c: the handle points to the operation information. + * @param address: slave address. + * @param pdata: data buffer. + * @param size: data size. + * @param timeout: maximum waiting time. + * @retval i2c status. + */ +i2c_status_type i2c_master_receive_dma(i2c_handle_type* hi2c, uint16_t address, uint8_t* pdata, uint16_t size, uint32_t timeout) +{ + /* initialization parameters */ + hi2c->mode = I2C_DMA_MA_RX; + hi2c->status = I2C_START; + + hi2c->pbuff = pdata; + hi2c->pcount = size; + + hi2c->error_code = I2C_OK; + + /* wait for the busy flag to be reset */ + if(i2c_wait_flag(hi2c, I2C_BUSYF_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + return I2C_ERR_STEP_1; + } + + /* disable dma request */ + i2c_dma_enable(hi2c->i2cx, I2C_DMA_REQUEST_RX, FALSE); + + /* start transfer */ + i2c_start_transfer_dma(hi2c, hi2c->dma_rx_channel, address, I2C_GEN_START_READ); + + /* enable i2c interrupt */ + i2c_interrupt_enable(hi2c->i2cx, I2C_ERR_INT | I2C_ACKFIAL_INT, TRUE); + + /* enable dma request */ + i2c_dma_enable(hi2c->i2cx, I2C_DMA_REQUEST_RX, TRUE); + + return I2C_OK; +} + +/** + * @brief the slave transmits data through dma mode. + * @param hi2c: the handle points to the operation information. + * @param pdata: data buffer. + * @param size: data size. + * @param timeout: maximum waiting time. + * @retval i2c status. + */ +i2c_status_type i2c_slave_transmit_dma(i2c_handle_type* hi2c, uint8_t* pdata, uint16_t size, uint32_t timeout) +{ + /* initialization parameters */ + hi2c->mode = I2C_DMA_SLA_TX; + hi2c->status = I2C_START; + + hi2c->pbuff = pdata; + hi2c->pcount = size; + + hi2c->error_code = I2C_OK; + + /* wait for the busy flag to be reset */ + if(i2c_wait_flag(hi2c, I2C_BUSYF_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + return I2C_ERR_STEP_1; + } + + /* disable dma request */ + i2c_dma_enable(hi2c->i2cx, I2C_DMA_REQUEST_TX, FALSE); + + /* config dma */ + i2c_dma_config(hi2c, hi2c->dma_tx_channel, hi2c->pbuff, size); + + /* enable acknowledge */ + i2c_ack_enable(hi2c->i2cx, TRUE); + + /* enable i2c interrupt */ + i2c_interrupt_enable(hi2c->i2cx, I2C_ADDR_INT | I2C_STOP_INT | I2C_ACKFIAL_INT | I2C_ERR_INT, TRUE); + + /* enable dma request */ + i2c_dma_enable(hi2c->i2cx, I2C_DMA_REQUEST_TX, TRUE); + + return I2C_OK; +} + +/** + * @brief send memory address. + * @param hi2c: the handle points to the operation information. + * @param mem_address_width: memory address width. + * this parameter can be one of the following values: + * - I2C_MEM_ADDR_WIDIH_8: memory address is 8 bit + * - I2C_MEM_ADDR_WIDIH_16: memory address is 16 bit + * @param address: memory device address. + * @param mem_address: memory address. + * @param timeout: maximum waiting time. + * @retval i2c status. + */ +i2c_status_type i2c_memory_address_send(i2c_handle_type* hi2c, i2c_mem_address_width_type mem_address_width, uint16_t mem_address, int32_t timeout) +{ + i2c_status_type err_code; + + if(mem_address_width == I2C_MEM_ADDR_WIDIH_8) + { + /* send memory address */ + i2c_data_send(hi2c->i2cx, mem_address & 0xFF); + } + else + { + /* send memory address */ + i2c_data_send(hi2c->i2cx, (mem_address >> 8) & 0xFF); + + /* wait for the tdis flag to be set */ + err_code = i2c_wait_flag(hi2c, I2C_TDIS_FLAG, I2C_EVENT_CHECK_ACKFAIL, timeout); + + if(err_code != I2C_OK) + { + return err_code; + } + + /* send memory address */ + i2c_data_send(hi2c->i2cx, mem_address & 0xFF); + } + + return I2C_OK; +} + +/** + * @brief write data to the memory device through polling mode. + * @param hi2c: the handle points to the operation information. + * @param mem_address_width: memory address width. + * this parameter can be one of the following values: + * - I2C_MEM_ADDR_WIDIH_8: memory address is 8 bit + * - I2C_MEM_ADDR_WIDIH_16: memory address is 16 bit + * @param address: memory device address. + * @param mem_address: memory address. + * @param pdata: data buffer. + * @param size: data size. + * @param timeout: maximum waiting time. + * @retval i2c status. + */ +i2c_status_type i2c_memory_write(i2c_handle_type* hi2c, i2c_mem_address_width_type mem_address_width, uint16_t address, uint16_t mem_address, uint8_t* pdata, uint16_t size, uint32_t timeout) +{ + /* initialization parameters */ + hi2c->pbuff = pdata; + hi2c->pcount = size + mem_address_width; + + hi2c->error_code = I2C_OK; + + /* wait for the busy flag to be reset */ + if (i2c_wait_flag(hi2c, I2C_BUSYF_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + return I2C_ERR_STEP_1; + } + + /* start transfer */ + i2c_start_transfer(hi2c, address, I2C_GEN_START_WRITE); + + /* wait for the tdis flag to be set */ + if(i2c_wait_flag(hi2c, I2C_TDIS_FLAG, I2C_EVENT_CHECK_ACKFAIL, timeout) != I2C_OK) + { + return I2C_ERR_STEP_2; + } + + /* send memory address */ + if(i2c_memory_address_send(hi2c, mem_address_width, mem_address, timeout) != I2C_OK) + { + return I2C_ERR_STEP_3; + } + + hi2c->psize -= mem_address_width; + hi2c->pcount -= mem_address_width; + + while (hi2c->pcount > 0) + { + /* wait for the tdis flag to be set */ + if(i2c_wait_flag(hi2c, I2C_TDIS_FLAG, I2C_EVENT_CHECK_ACKFAIL, timeout) != I2C_OK) + { + return I2C_ERR_STEP_4; + } + + /* send data */ + i2c_data_send(hi2c->i2cx, *hi2c->pbuff++); + hi2c->psize--; + hi2c->pcount--; + + if ((hi2c->psize == 0) && (hi2c->pcount != 0)) + { + /* wait for the tcrld flag to be set */ + if (i2c_wait_flag(hi2c, I2C_TCRLD_FLAG, I2C_EVENT_CHECK_ACKFAIL, timeout) != I2C_OK) + { + return I2C_ERR_STEP_5; + } + + /* continue transfer */ + i2c_start_transfer(hi2c, address, I2C_WITHOUT_START); + } + } + + /* wait for the stop flag to be set */ + if(i2c_wait_flag(hi2c, I2C_STOPF_FLAG, I2C_EVENT_CHECK_ACKFAIL, timeout) != I2C_OK) + { + return I2C_ERR_STEP_6; + } + + /* clear stop flag */ + i2c_flag_clear(hi2c->i2cx, I2C_STOPF_FLAG); + + /* reset ctrl2 register */ + i2c_reset_ctrl2_register(hi2c); + + return I2C_OK; +} + +/** + * @brief read data from memory device through polling mode. + * @param hi2c: the handle points to the operation information. + * @param mem_address_width: memory address width. + * this parameter can be one of the following values: + * - I2C_MEM_ADDR_WIDIH_8: memory address is 8 bit + * - I2C_MEM_ADDR_WIDIH_16: memory address is 16 bit + * @param address: memory device address. + * @param mem_address: memory address. + * @param pdata: data buffer. + * @param size: data size. + * @param timeout: maximum waiting time. + * @retval i2c status. + */ +i2c_status_type i2c_memory_read(i2c_handle_type* hi2c, i2c_mem_address_width_type mem_address_width, uint16_t address, uint16_t mem_address, uint8_t* pdata, uint16_t size, uint32_t timeout) +{ + /* initialization parameters */ + hi2c->pbuff = pdata; + hi2c->pcount = size; + + hi2c->error_code = I2C_OK; + + /* wait for the busy flag to be reset */ + if(i2c_wait_flag(hi2c, I2C_BUSYF_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + return I2C_ERR_STEP_1; + } + + /* start transfer */ + i2c_transmit_set(hi2c->i2cx, address, mem_address_width, I2C_SOFT_STOP_MODE, I2C_GEN_START_WRITE); + + /* wait for the tdis flag to be set */ + if(i2c_wait_flag(hi2c, I2C_TDIS_FLAG, I2C_EVENT_CHECK_ACKFAIL, timeout) != I2C_OK) + { + return I2C_ERR_STEP_2; + } + + /* send memory address */ + if(i2c_memory_address_send(hi2c, mem_address_width, mem_address, timeout) != I2C_OK) + { + return I2C_ERR_STEP_3; + } + + /* wait for the tdc flag to be set */ + if (i2c_wait_flag(hi2c, I2C_TDC_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + return I2C_ERR_STEP_4; + } + + /* start transfer */ + i2c_start_transfer(hi2c, address, I2C_GEN_START_READ); + + while (hi2c->pcount > 0) + { + /* wait for the rdbf flag to be set */ + if (i2c_wait_flag(hi2c, I2C_RDBF_FLAG, I2C_EVENT_CHECK_ACKFAIL, timeout) != I2C_OK) + { + return I2C_ERR_STEP_5; + } + + /* read data */ + (*hi2c->pbuff++) = i2c_data_receive(hi2c->i2cx); + hi2c->pcount--; + hi2c->psize--; + + if ((hi2c->psize == 0) && (hi2c->pcount != 0)) + { + /* wait for the tcrld flag to be set */ + if (i2c_wait_flag(hi2c, I2C_TCRLD_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + return I2C_ERR_STEP_6; + } + + /* continue transfer */ + i2c_start_transfer(hi2c, address, I2C_WITHOUT_START); + } + } + + /* wait for the stop flag to be set */ + if (i2c_wait_flag(hi2c, I2C_STOPF_FLAG, I2C_EVENT_CHECK_ACKFAIL, timeout) != I2C_OK) + { + return I2C_ERR_STEP_7; + } + + /* clear stop flag */ + i2c_flag_clear(hi2c->i2cx, I2C_STOPF_FLAG); + + /* reset ctrl2 register */ + i2c_reset_ctrl2_register(hi2c); + + return I2C_OK; +} + +/** + * @brief write data to the memory device through interrupt mode. + * @param hi2c: the handle points to the operation information. + * @param mem_address_width: memory address width. + * this parameter can be one of the following values: + * - I2C_MEM_ADDR_WIDIH_8: memory address is 8 bit + * - I2C_MEM_ADDR_WIDIH_16: memory address is 16 bit + * @param address: memory device address. + * @param mem_address: memory address. + * @param pdata: data buffer. + * @param size: data size. + * @param timeout: maximum waiting time. + * @retval i2c status. + */ +i2c_status_type i2c_memory_write_int(i2c_handle_type* hi2c, i2c_mem_address_width_type mem_address_width, uint16_t address, uint16_t mem_address, uint8_t* pdata, uint16_t size, uint32_t timeout) +{ + /* initialization parameters */ + hi2c->mode = I2C_INT_MA_TX; + hi2c->status = I2C_START; + + hi2c->pbuff = pdata; + hi2c->pcount = size + mem_address_width; + + hi2c->error_code = I2C_OK; + + /* wait for the busy flag to be reset */ + if (i2c_wait_flag(hi2c, I2C_BUSYF_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + return I2C_ERR_STEP_1; + } + + /* start transfer */ + i2c_start_transfer(hi2c, address, I2C_GEN_START_WRITE); + + /* wait for the tdis flag to be set */ + if(i2c_wait_flag(hi2c, I2C_TDIS_FLAG, I2C_EVENT_CHECK_ACKFAIL, timeout) != I2C_OK) + { + return I2C_ERR_STEP_2; + } + + /* send memory address */ + if(i2c_memory_address_send(hi2c, mem_address_width, mem_address, timeout) != I2C_OK) + { + return I2C_ERR_STEP_3; + } + + hi2c->psize--; + hi2c->pcount--; + + /* enable interrupt */ + i2c_interrupt_enable(hi2c->i2cx, I2C_ERR_INT | I2C_TDC_INT | I2C_STOP_INT | I2C_ACKFIAL_INT | I2C_TD_INT, TRUE); + + return I2C_OK; +} + +/** + * @brief read data from memory device through interrupt mode. + * @param hi2c: the handle points to the operation information. + * @param mem_address_width: memory address width. + * this parameter can be one of the following values: + * - I2C_MEM_ADDR_WIDIH_8: memory address is 8 bit + * - I2C_MEM_ADDR_WIDIH_16: memory address is 16 bit + * @param address: memory device address. + * @param mem_address: memory address. + * @param pdata: data buffer. + * @param size: data size. + * @param timeout: maximum waiting time. + * @retval i2c status. + */ +i2c_status_type i2c_memory_read_int(i2c_handle_type* hi2c, i2c_mem_address_width_type mem_address_width, uint16_t address, uint16_t mem_address, uint8_t* pdata, uint16_t size, uint32_t timeout) +{ + /* initialization parameters */ + hi2c->mode = I2C_INT_MA_RX; + hi2c->status = I2C_START; + + hi2c->pbuff = pdata; + hi2c->pcount = size; + + hi2c->error_code = I2C_OK; + + /* wait for the busy flag to be reset */ + if(i2c_wait_flag(hi2c, I2C_BUSYF_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + return I2C_ERR_STEP_1; + } + + /* start transfer */ + i2c_transmit_set(hi2c->i2cx, address, mem_address_width, I2C_SOFT_STOP_MODE, I2C_GEN_START_WRITE); + + /* wait for the tdis flag to be set */ + if(i2c_wait_flag(hi2c, I2C_TDIS_FLAG, I2C_EVENT_CHECK_ACKFAIL, timeout) != I2C_OK) + { + return I2C_ERR_STEP_2; + } + + /* send memory address */ + if(i2c_memory_address_send(hi2c, mem_address_width, mem_address, timeout) != I2C_OK) + { + return I2C_ERR_STEP_3; + } + + /* wait for the tdc flag to be set */ + if (i2c_wait_flag(hi2c, I2C_TDC_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + return I2C_ERR_STEP_4; + } + + /* start transfer */ + i2c_start_transfer(hi2c, address, I2C_GEN_START_READ); + + /* enable i2c interrupt */ + i2c_interrupt_enable(hi2c->i2cx, I2C_ERR_INT | I2C_TDC_INT | I2C_STOP_INT | I2C_ACKFIAL_INT | I2C_RD_INT, TRUE); + + return I2C_OK; +} + +/** + * @brief write data to the memory device through dma mode. + * @param hi2c: the handle points to the operation information. + * @param mem_address_width: memory address width. + * this parameter can be one of the following values: + * - I2C_MEM_ADDR_WIDIH_8: memory address is 8 bit + * - I2C_MEM_ADDR_WIDIH_16: memory address is 16 bit + * @param address: memory device address. + * @param mem_address: memory address. + * @param pdata: data buffer. + * @param size: data size. + * @param timeout: maximum waiting time. + * @retval i2c status. + */ +i2c_status_type i2c_memory_write_dma(i2c_handle_type* hi2c, i2c_mem_address_width_type mem_address_width, uint16_t address, uint16_t mem_address, uint8_t* pdata, uint16_t size, uint32_t timeout) +{ + /* initialization parameters */ + hi2c->mode = I2C_DMA_MA_TX; + hi2c->status = I2C_START; + + hi2c->pbuff = pdata; + hi2c->pcount = size; + + hi2c->error_code = I2C_OK; + + /* disable dma request */ + i2c_dma_enable(hi2c->i2cx, I2C_DMA_REQUEST_TX, FALSE); + + /* wait for the busy flag to be reset */ + if(i2c_wait_flag(hi2c, I2C_BUSYF_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + return I2C_ERR_STEP_1; + } + + /* transfer config */ + i2c_transmit_set(hi2c->i2cx, address, mem_address_width, I2C_RELOAD_MODE, I2C_GEN_START_WRITE); + + /* wait for the tdis flag to be set */ + if(i2c_wait_flag(hi2c, I2C_TDIS_FLAG, I2C_EVENT_CHECK_ACKFAIL, timeout) != I2C_OK) + { + return I2C_ERR_STEP_2; + } + + /* send memory address */ + if(i2c_memory_address_send(hi2c, mem_address_width, mem_address, timeout) != I2C_OK) + { + return I2C_ERR_STEP_3; + } + + /* wait for the tcrld flag to be set */ + if (i2c_wait_flag(hi2c, I2C_TCRLD_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + return I2C_ERR_STEP_4; + } + + /* start transfer */ + i2c_start_transfer_dma(hi2c, hi2c->dma_tx_channel, address, I2C_WITHOUT_START); + + /* enable i2c interrupt */ + i2c_interrupt_enable(hi2c->i2cx, I2C_ERR_INT | I2C_ACKFIAL_INT, TRUE); + + /* enable dma request */ + i2c_dma_enable(hi2c->i2cx, I2C_DMA_REQUEST_TX, TRUE); + + return I2C_OK; +} + +/** + * @brief read data from memory device through polling mode. + * @param hi2c: the handle points to the operation information. + * @param mem_address_width: memory address width. + * this parameter can be one of the following values: + * - I2C_MEM_ADDR_WIDIH_8: memory address is 8 bit + * - I2C_MEM_ADDR_WIDIH_16: memory address is 16 bit + * @param address: memory device address. + * @param mem_address: memory address. + * @param pdata: data buffer. + * @param size: data size. + * @param timeout: maximum waiting time. + * @retval i2c status. + */ +i2c_status_type i2c_memory_read_dma(i2c_handle_type* hi2c, i2c_mem_address_width_type mem_address_width, uint16_t address, uint16_t mem_address, uint8_t* pdata, uint16_t size, uint32_t timeout) +{ + /* initialization parameters */ + hi2c->mode = I2C_DMA_MA_RX; + hi2c->status = I2C_START; + + hi2c->pbuff = pdata; + hi2c->pcount = size; + + hi2c->error_code = I2C_OK; + + /* wait for the busy flag to be reset */ + if(i2c_wait_flag(hi2c, I2C_BUSYF_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + return I2C_ERR_STEP_1; + } + + /* start transfer */ + i2c_transmit_set(hi2c->i2cx, address, mem_address_width, I2C_SOFT_STOP_MODE, I2C_GEN_START_WRITE); + + /* wait for the tdis flag to be set */ + if(i2c_wait_flag(hi2c, I2C_TDIS_FLAG, I2C_EVENT_CHECK_ACKFAIL, timeout) != I2C_OK) + { + return I2C_ERR_STEP_2; + } + + /* send memory address */ + if(i2c_memory_address_send(hi2c, mem_address_width, mem_address, timeout) != I2C_OK) + { + return I2C_ERR_STEP_3; + } + + /* wait for the tdc flag to be set */ + if (i2c_wait_flag(hi2c, I2C_TDC_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + return I2C_ERR_STEP_4; + } + + /* disable dma request */ + i2c_dma_enable(hi2c->i2cx, I2C_DMA_REQUEST_RX, FALSE); + + /* start transfer */ + i2c_start_transfer_dma(hi2c, hi2c->dma_rx_channel, address, I2C_GEN_START_READ); + + /* enable i2c interrupt */ + i2c_interrupt_enable(hi2c->i2cx, I2C_ERR_INT | I2C_ACKFIAL_INT, TRUE); + + /* enable dma request */ + i2c_dma_enable(hi2c->i2cx, I2C_DMA_REQUEST_RX, TRUE); + + return I2C_OK; +} + +/** + * @brief the master transmits data through SMBus mode. + * @param hi2c: the handle points to the operation information. + * @param address: slave address. + * @param pdata: data buffer. + * @param size: data size. + * @param timeout: maximum waiting time. + * @retval i2c status. + */ +i2c_status_type i2c_smbus_master_transmit(i2c_handle_type* hi2c, uint16_t address, uint8_t* pdata, uint16_t size, uint32_t timeout) +{ + /* initialization parameters */ + hi2c->pbuff = pdata; + hi2c->pcount = size; + + hi2c->error_code = I2C_OK; + + /* wait for the busy flag to be reset */ + if (i2c_wait_flag(hi2c, I2C_BUSYF_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + return I2C_ERR_STEP_1; + } + + /* enable pec calculation */ + i2c_pec_calculate_enable(hi2c->i2cx, TRUE); + + /* enable pec transmit request */ + i2c_pec_transmit_enable(hi2c->i2cx, TRUE); + + /* start transfer */ + i2c_start_transfer(hi2c, address, I2C_GEN_START_WRITE); + + hi2c->pcount--; + + while (hi2c->pcount > 0) + { + /* wait for the tdis flag to be set */ + if(i2c_wait_flag(hi2c, I2C_TDIS_FLAG, I2C_EVENT_CHECK_ACKFAIL, timeout) != I2C_OK) + { + return I2C_ERR_STEP_2; + } + + /* send data */ + i2c_data_send(hi2c->i2cx, *hi2c->pbuff++); + hi2c->psize--; + hi2c->pcount--; + + if ((hi2c->psize == 0) && (hi2c->pcount != 0)) + { + /* wait for the tcrld flag to be set */ + if (i2c_wait_flag(hi2c, I2C_TCRLD_FLAG, I2C_EVENT_CHECK_ACKFAIL, timeout) != I2C_OK) + { + return I2C_ERR_STEP_3; + } + + /* continue transfer */ + i2c_start_transfer(hi2c, address, I2C_WITHOUT_START); + } + } + + /* wait for the stop flag to be set */ + if(i2c_wait_flag(hi2c, I2C_STOPF_FLAG, I2C_EVENT_CHECK_ACKFAIL, timeout) != I2C_OK) + { + return I2C_ERR_STEP_4; + } + + /* clear stop flag */ + i2c_flag_clear(hi2c->i2cx, I2C_STOPF_FLAG); + + /* reset ctrl2 register */ + i2c_reset_ctrl2_register(hi2c); + + return I2C_OK; +} + +/** + * @brief the slave receive data through SMBus mode. + * @param hi2c: the handle points to the operation information. + * @param pdata: data buffer. + * @param size: data size. + * @param timeout: maximum waiting time. + * @retval i2c status. + */ +i2c_status_type i2c_smbus_slave_receive(i2c_handle_type* hi2c, uint8_t* pdata, uint16_t size, uint32_t timeout) +{ + /* initialization parameters */ + hi2c->pbuff = pdata; + hi2c->pcount = size; + + hi2c->error_code = I2C_OK; + + /* enable pec calculation */ + i2c_pec_calculate_enable(hi2c->i2cx, TRUE); + + /* enable slave data control mode */ + i2c_slave_data_ctrl_enable(hi2c->i2cx, TRUE); + + /* enable acknowledge */ + i2c_ack_enable(hi2c->i2cx, TRUE); + + /* wait for the addr flag to be set */ + if (i2c_wait_flag(hi2c, I2C_ADDRF_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + return I2C_ERR_STEP_1; + } + + /* enable pec transmit request */ + i2c_pec_transmit_enable(hi2c->i2cx, TRUE); + + /* configure the number of bytes to be transmitted */ + i2c_cnt_set(hi2c->i2cx, hi2c->pcount); + + /* clear addr flag */ + i2c_flag_clear(hi2c->i2cx, I2C_ADDRF_FLAG); + + while (hi2c->pcount > 0) + { + /* wait for the rdbf flag to be set */ + if(i2c_wait_flag(hi2c, I2C_RDBF_FLAG, I2C_EVENT_CHECK_STOP, timeout) != I2C_OK) + { + /* disable acknowledge */ + i2c_ack_enable(hi2c->i2cx, FALSE); + + /* if data is received, read data */ + if (i2c_flag_get(hi2c->i2cx, I2C_RDBF_FLAG) == SET) + { + /* read data */ + (*hi2c->pbuff++) = i2c_data_receive(hi2c->i2cx); + hi2c->pcount--; + } + + return I2C_ERR_STEP_3; + } + + /* read data */ + (*hi2c->pbuff++) = i2c_data_receive(hi2c->i2cx); + hi2c->pcount--; + } + + /* wait for the stop flag to be set */ + if(i2c_wait_flag(hi2c, I2C_STOPF_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + /* disable acknowledge */ + i2c_ack_enable(hi2c->i2cx, FALSE); + + return I2C_ERR_STEP_4; + } + + /* clear stop flag */ + i2c_flag_clear(hi2c->i2cx, I2C_STOPF_FLAG); + + /* wait for the busy flag to be reset */ + if (i2c_wait_flag(hi2c, I2C_BUSYF_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + /* disable acknowledge */ + i2c_ack_enable(hi2c->i2cx, FALSE); + + return I2C_ERR_STEP_5; + } + + /* disable slave data control mode */ + i2c_slave_data_ctrl_enable(hi2c->i2cx, FALSE); + + return I2C_OK; +} + +/** + * @brief the master receive data through SMBus mode. + * @param hi2c: the handle points to the operation information. + * @param address: slave address. + * @param pdata: data buffer. + * @param size: data size. + * @param timeout: maximum waiting time. + * @retval i2c status. + */ +i2c_status_type i2c_smbus_master_receive(i2c_handle_type* hi2c, uint16_t address, uint8_t* pdata, uint16_t size, uint32_t timeout) +{ + /* initialization parameters */ + hi2c->pbuff = pdata; + hi2c->pcount = size; + + hi2c->error_code = I2C_OK; + + /* wait for the busy flag to be reset */ + if (i2c_wait_flag(hi2c, I2C_BUSYF_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + return I2C_ERR_STEP_1; + } + + /* enable pec calculation */ + i2c_pec_calculate_enable(hi2c->i2cx, TRUE); + + /* enable pec transmit request */ + i2c_pec_transmit_enable(hi2c->i2cx, TRUE); + + /* start transfer */ + i2c_start_transfer(hi2c, address, I2C_GEN_START_READ); + + while (hi2c->pcount > 0) + { + /* wait for the rdbf flag to be set */ + if(i2c_wait_flag(hi2c, I2C_RDBF_FLAG, I2C_EVENT_CHECK_ACKFAIL, timeout) != I2C_OK) + { + return I2C_ERR_STEP_2; + } + + /* read data */ + (*hi2c->pbuff++) = i2c_data_receive(hi2c->i2cx); + hi2c->pcount--; + hi2c->psize--; + + if ((hi2c->psize == 0) && (hi2c->pcount != 0)) + { + /* wait for the tcrld flag to be set */ + if (i2c_wait_flag(hi2c, I2C_TCRLD_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + return I2C_ERR_STEP_3; + } + + /* continue transfer */ + i2c_start_transfer(hi2c, address, I2C_WITHOUT_START); + } + } + + /* wait for the stop flag to be set */ + if(i2c_wait_flag(hi2c, I2C_STOPF_FLAG, I2C_EVENT_CHECK_ACKFAIL, timeout) != I2C_OK) + { + return I2C_ERR_STEP_4; + } + + /* clear stop flag */ + i2c_flag_clear(hi2c->i2cx, I2C_STOPF_FLAG); + + /* reset ctrl2 register */ + i2c_reset_ctrl2_register(hi2c); + + return I2C_OK; +} + +/** + * @brief the slave transmits data through SMBus mode. + * @param hi2c: the handle points to the operation information. + * @param pdata: data buffer. + * @param size: data size. + * @param timeout: maximum waiting time. + * @retval i2c status. + */ +i2c_status_type i2c_smbus_slave_transmit(i2c_handle_type* hi2c, uint8_t* pdata, uint16_t size, uint32_t timeout) +{ + /* initialization parameters */ + hi2c->pbuff = pdata; + hi2c->pcount = size; + + hi2c->error_code = I2C_OK; + + /* enable pec calculation */ + i2c_pec_calculate_enable(hi2c->i2cx, TRUE); + + /* enable slave data control mode */ + i2c_slave_data_ctrl_enable(hi2c->i2cx, TRUE); + + /* enable acknowledge */ + i2c_ack_enable(hi2c->i2cx, TRUE); + + /* wait for the addr flag to be set */ + if (i2c_wait_flag(hi2c, I2C_ADDRF_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + /* disable acknowledge */ + i2c_ack_enable(hi2c->i2cx, FALSE); + return I2C_ERR_STEP_1; + } + + /* if 7-bit address mode is selected */ + if (hi2c->i2cx->ctrl2_bit.addr10 == 0) + { + /* enable pec transmit request */ + i2c_pec_transmit_enable(hi2c->i2cx, TRUE); + + /* configure the number of bytes to be transmitted */ + i2c_cnt_set(hi2c->i2cx, hi2c->pcount); + } + + /* clear addr flag */ + i2c_flag_clear(hi2c->i2cx, I2C_ADDRF_FLAG); + + /* if 10-bit address mode is used */ + if (hi2c->i2cx->ctrl2_bit.addr10 != RESET) + { + /* wait for the addr flag to be set */ + if (i2c_wait_flag(hi2c, I2C_ADDRF_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + /* disable acknowledge */ + i2c_ack_enable(hi2c->i2cx, FALSE); + + return I2C_ERR_STEP_2; + } + + /* enable pec transmit request */ + i2c_pec_transmit_enable(hi2c->i2cx, TRUE); + + /* configure the number of bytes to be transmitted */ + i2c_cnt_set(hi2c->i2cx, hi2c->pcount); + + /* clear addr flag */ + i2c_flag_clear(hi2c->i2cx, I2C_ADDRF_FLAG); + } + + hi2c->pcount--; + + while (hi2c->pcount > 0) + { + /* wait for the tdis flag to be set */ + if(i2c_wait_flag(hi2c, I2C_TDIS_FLAG, I2C_EVENT_CHECK_ACKFAIL, timeout) != I2C_OK) + { + /* disable acknowledge */ + i2c_ack_enable(hi2c->i2cx, FALSE); + + return I2C_ERR_STEP_4; + } + + /* send data */ + i2c_data_send(hi2c->i2cx, *hi2c->pbuff++); + hi2c->pcount--; + } + + /* wait for the ackfail flag to be set */ + if(i2c_wait_flag(hi2c, I2C_ACKFAIL_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + return I2C_ERR_STEP_5; + } + + /* clear ack fail flag */ + i2c_flag_clear(hi2c->i2cx, I2C_ACKFAIL_FLAG); + + /* wait for the stop flag to be set */ + if(i2c_wait_flag(hi2c, I2C_STOPF_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + /* disable acknowledge */ + i2c_ack_enable(hi2c->i2cx, FALSE); + + return I2C_ERR_STEP_6; + } + + /* clear stop flag */ + i2c_flag_clear(hi2c->i2cx, I2C_STOPF_FLAG); + + /* wait for the busy flag to be reset */ + if (i2c_wait_flag(hi2c, I2C_BUSYF_FLAG, I2C_EVENT_CHECK_NONE, timeout) != I2C_OK) + { + /* disable acknowledge */ + i2c_ack_enable(hi2c->i2cx, FALSE); + + return I2C_ERR_STEP_7; + } + + /* reset ctrl2 register */ + i2c_reset_ctrl2_register(hi2c); + + /* refresh tx dt register */ + i2c_refresh_txdt_register(hi2c); + + /* disable slave data control mode */ + i2c_slave_data_ctrl_enable(hi2c->i2cx, FALSE); + + return I2C_OK; +} + +/** + * @brief master interrupt processing function in interrupt mode. + * @param hi2c: the handle points to the operation information. + * @retval i2c status. + */ +i2c_status_type i2c_master_irq_handler_int(i2c_handle_type* hi2c) +{ + if (i2c_flag_get(hi2c->i2cx, I2C_ACKFAIL_FLAG) != RESET) + { + + /* clear ackfail flag */ + i2c_flag_clear(hi2c->i2cx, I2C_ACKFAIL_FLAG); + + /* refresh tx register */ + i2c_refresh_txdt_register(hi2c); + + if(hi2c->pcount != 0) + { + hi2c->error_code = I2C_ERR_ACKFAIL; + } + } + else if (i2c_flag_get(hi2c->i2cx, I2C_TDIS_FLAG) != RESET) + { + /* send data */ + i2c_data_send(hi2c->i2cx, *hi2c->pbuff++); + hi2c->pcount--; + hi2c->psize--; + } + else if (i2c_flag_get(hi2c->i2cx, I2C_TCRLD_FLAG) != RESET) + { + if ((hi2c->psize == 0) && (hi2c->pcount != 0)) + { + /* continue transfer */ + i2c_start_transfer(hi2c, i2c_transfer_addr_get(hi2c->i2cx), I2C_WITHOUT_START); + } + else + { + return I2C_ERR_TCRLD; + } + } + else if (i2c_flag_get(hi2c->i2cx, I2C_RDBF_FLAG) != RESET) + { + /* read data */ + (*hi2c->pbuff++) = i2c_data_receive(hi2c->i2cx); + hi2c->pcount--; + hi2c->psize--; + } + else if (i2c_flag_get(hi2c->i2cx, I2C_TDC_FLAG) != RESET) + { + if (hi2c->pcount == 0) + { + if (hi2c->i2cx->ctrl2_bit.astopen == 0) + { + /* generate stop condtion */ + i2c_stop_generate(hi2c->i2cx); + } + } + else + { + return I2C_ERR_TDC; + } + } + else if (i2c_flag_get(hi2c->i2cx, I2C_STOPF_FLAG) != RESET) + { + /* clear stop flag */ + i2c_flag_clear(hi2c->i2cx, I2C_STOPF_FLAG); + + /* reset ctrl2 register */ + i2c_reset_ctrl2_register(hi2c); + + if (i2c_flag_get(hi2c->i2cx, I2C_ACKFAIL_FLAG) != RESET) + { + /* clear ackfail flag */ + i2c_flag_clear(hi2c->i2cx, I2C_ACKFAIL_FLAG); + } + + /* refresh tx dt register */ + i2c_refresh_txdt_register(hi2c); + + /* disable interrupts */ + i2c_interrupt_enable(hi2c->i2cx, I2C_ERR_INT | I2C_TDC_INT | I2C_STOP_INT | I2C_ACKFIAL_INT | I2C_TD_INT | I2C_RD_INT, FALSE); + + /* transfer complete */ + hi2c->status = I2C_END; + } + + return I2C_OK; +} + +/** + * @brief slave interrupt processing function in interrupt mode. + * @param hi2c: the handle points to the operation information. + * @retval i2c status. + */ +i2c_status_type i2c_slave_irq_handler_int(i2c_handle_type* hi2c) +{ + if (i2c_flag_get(hi2c->i2cx, I2C_ACKFAIL_FLAG) != RESET) + { + /* transfer complete */ + if (hi2c->pcount == 0) + { + i2c_refresh_txdt_register(hi2c); + + /* clear ackfail flag */ + i2c_flag_clear(hi2c->i2cx, I2C_ACKFAIL_FLAG); + } + /* the transfer has not been completed */ + else + { + /* clear ackfail flag */ + i2c_flag_clear(hi2c->i2cx, I2C_ACKFAIL_FLAG); + } + } + else if (i2c_flag_get(hi2c->i2cx, I2C_ADDRF_FLAG) != RESET) + { + /* clear addr flag */ + i2c_flag_clear(hi2c->i2cx, I2C_ADDRF_FLAG); + } + else if (i2c_flag_get(hi2c->i2cx, I2C_TDIS_FLAG) != RESET) + { + if (hi2c->pcount > 0) + { + /* send data */ + hi2c->i2cx->txdt = (*(hi2c->pbuff++)); + hi2c->psize--; + hi2c->pcount--; + } + } + else if (i2c_flag_get(hi2c->i2cx, I2C_RDBF_FLAG) != RESET) + { + if (hi2c->pcount > 0) + { + /* read data */ + (*hi2c->pbuff++) = i2c_data_receive(hi2c->i2cx); + hi2c->pcount--; + hi2c->psize--; + } + } + else if (i2c_flag_get(hi2c->i2cx, I2C_STOPF_FLAG) != RESET) + { + /* clear stop flag */ + i2c_flag_clear(hi2c->i2cx, I2C_STOPF_FLAG); + + /* disable interrupts */ + i2c_interrupt_enable(hi2c->i2cx, I2C_ADDR_INT | I2C_STOP_INT | I2C_ACKFIAL_INT | I2C_ERR_INT | I2C_TDC_INT | I2C_TD_INT | I2C_RD_INT, FALSE); + + /* reset ctrl2 register */ + i2c_reset_ctrl2_register(hi2c); + + /* refresh tx dt register */ + i2c_refresh_txdt_register(hi2c); + + /* if data is received, read data */ + if (i2c_flag_get(hi2c->i2cx, I2C_RDBF_FLAG) != RESET) + { + /* read data */ + (*hi2c->pbuff++) = i2c_data_receive(hi2c->i2cx); + + if ((hi2c->psize > 0)) + { + hi2c->pcount--; + hi2c->psize--; + } + } + + /* transfer complete */ + hi2c->status = I2C_END; + } + + return I2C_OK; +} + +/** + * @brief master interrupt processing function in dma mode. + * @param hi2c: the handle points to the operation information. + * @retval i2c status. + */ +i2c_status_type i2c_master_irq_handler_dma(i2c_handle_type* hi2c) +{ + if (i2c_flag_get(hi2c->i2cx, I2C_ACKFAIL_FLAG) != RESET) + { + /* clear ackfail flag */ + i2c_flag_clear(hi2c->i2cx, I2C_ACKFAIL_FLAG); + + /* enable stop interrupt to wait for stop generate stop */ + i2c_interrupt_enable(hi2c->i2cx, I2C_STOP_INT, TRUE); + + /* refresh tx dt register */ + i2c_refresh_txdt_register(hi2c); + + if(hi2c->pcount != 0) + { + hi2c->error_code = I2C_ERR_ACKFAIL; + } + } + else if (i2c_flag_get(hi2c->i2cx, I2C_TCRLD_FLAG) != RESET) + { + /* disable tdc interrupt */ + i2c_interrupt_enable(hi2c->i2cx, I2C_TDC_INT, FALSE); + + if (hi2c->pcount != 0) + { + /* continue transfer */ + i2c_start_transfer(hi2c, i2c_transfer_addr_get(hi2c->i2cx), I2C_WITHOUT_START); + + /* enable dma request */ + if (hi2c->dma_init_struct.direction == DMA_DIR_MEMORY_TO_PERIPHERAL) + { + i2c_dma_enable(hi2c->i2cx, I2C_DMA_REQUEST_TX, TRUE); + } + else + { + i2c_dma_enable(hi2c->i2cx, I2C_DMA_REQUEST_RX, TRUE); + } + } + else + { + return I2C_ERR_TCRLD; + } + } + else if (i2c_flag_get(hi2c->i2cx, I2C_STOPF_FLAG) != RESET) + { + /* clear stop flag */ + i2c_flag_clear(hi2c->i2cx, I2C_STOPF_FLAG); + + /* reset ctrl2 register */ + i2c_reset_ctrl2_register(hi2c); + + if (i2c_flag_get(hi2c->i2cx, I2C_ACKFAIL_FLAG) != RESET) + { + /* clear ackfail flag */ + i2c_flag_clear(hi2c->i2cx, I2C_ACKFAIL_FLAG); + } + + /* refresh tx dt register */ + i2c_refresh_txdt_register(hi2c); + + /* disable interrupts */ + i2c_interrupt_enable(hi2c->i2cx, I2C_ERR_INT | I2C_TDC_INT | I2C_STOP_INT | I2C_ACKFIAL_INT | I2C_TD_INT | I2C_RD_INT, FALSE); + + /* transfer complete */ + hi2c->status = I2C_END; + } + + return I2C_OK; +} + +/** + * @brief slave interrupt processing function in dma mode. + * @param hi2c: the handle points to the operation information. + * @retval i2c status. + */ +i2c_status_type i2c_slave_irq_handler_dma(i2c_handle_type* hi2c) +{ + if (i2c_flag_get(hi2c->i2cx, I2C_ACKFAIL_FLAG) != RESET) + { + /* clear ackfail flag */ + i2c_flag_clear(hi2c->i2cx, I2C_ACKFAIL_FLAG); + } + else if (i2c_flag_get(hi2c->i2cx, I2C_ADDRF_FLAG) != RESET) + { + /* clear addr flag */ + i2c_flag_clear(hi2c->i2cx, I2C_ADDRF_FLAG); + } + else if (i2c_flag_get(hi2c->i2cx, I2C_STOPF_FLAG) != RESET) + { + /* clear stop flag */ + i2c_flag_clear(hi2c->i2cx, I2C_STOPF_FLAG); + + /* disable interrupts */ + i2c_interrupt_enable(hi2c->i2cx, I2C_ADDR_INT | I2C_STOP_INT | I2C_ACKFIAL_INT | I2C_ERR_INT | I2C_TDC_INT | I2C_TD_INT | I2C_RD_INT, FALSE); + + /* reset ctrl2 register */ + i2c_reset_ctrl2_register(hi2c); + + /* refresh tx dt register */ + i2c_refresh_txdt_register(hi2c); + + /* if data is received, read data */ + if (i2c_flag_get(hi2c->i2cx, I2C_RDBF_FLAG) != RESET) + { + /* read data */ + (*hi2c->pbuff++) = i2c_data_receive(hi2c->i2cx); + + if ((hi2c->psize > 0)) + { + hi2c->pcount--; + hi2c->psize--; + } + } + + /* transfer complete */ + hi2c->status = I2C_END; + } + + return I2C_OK; +} + +/** + * @brief dma processing function. + * @param hi2c: the handle points to the operation information. + * @retval none. + */ +void i2c_dma_tx_rx_irq_handler(i2c_handle_type* hi2c, dma_channel_type* dma_channel) +{ + /* transfer complete */ + if (dma_flag_get(DMA_GET_TC_FLAG(dma_channel)) != RESET) + { + /* disable the transfer complete interrupt */ + dma_interrupt_enable(dma_channel, DMA_FDT_INT, FALSE); + + /* clear the transfer complete flag */ + dma_flag_clear(DMA_GET_TC_FLAG(dma_channel)); + + /* disable dma request */ + i2c_dma_enable(hi2c->i2cx, DMA_GET_REQUEST(dma_channel), FALSE); + + /* disable dma channel */ + dma_channel_enable(dma_channel, FALSE); + + switch(hi2c->mode) + { + case I2C_DMA_MA_TX: + case I2C_DMA_MA_RX: + { + /* update the number of transfers */ + hi2c->pcount -= hi2c->psize; + + /* transfer complete */ + if (hi2c->pcount == 0) + { + /* enable stop interrupt */ + i2c_interrupt_enable(hi2c->i2cx, I2C_STOP_INT, TRUE); + } + /* the transfer has not been completed */ + else + { + /* update the buffer pointer of transfers */ + hi2c->pbuff += hi2c->psize; + + /* set the number to be transferred */ + if (hi2c->pcount > MAX_TRANSFER_CNT) + { + hi2c->psize = MAX_TRANSFER_CNT; + } + else + { + hi2c->psize = hi2c->pcount; + } + + /* config dma channel, continue to transfer data */ + i2c_dma_config(hi2c, dma_channel, hi2c->pbuff, hi2c->psize); + + /* enable tdc interrupt */ + i2c_interrupt_enable(hi2c->i2cx, I2C_TDC_INT, TRUE); + } + }break; + case I2C_DMA_SLA_TX: + case I2C_DMA_SLA_RX: + { + + }break; + + default:break; + } + } +} + +/** + * @brief dma transmission complete interrupt function. + * @param hi2c: the handle points to the operation information. + * @retval none. + */ +void i2c_dma_tx_irq_handler(i2c_handle_type* hi2c) +{ + i2c_dma_tx_rx_irq_handler(hi2c, hi2c->dma_tx_channel); +} + +/** + * @brief dma reveive complete interrupt function. + * @param hi2c: the handle points to the operation information. + * @retval none. + */ +void i2c_dma_rx_irq_handler(i2c_handle_type* hi2c) +{ + i2c_dma_tx_rx_irq_handler(hi2c, hi2c->dma_rx_channel); +} + +/** + * @brief interrupt procession function. + * @param hi2c: the handle points to the operation information. + * @retval none. + */ +void i2c_evt_irq_handler(i2c_handle_type* hi2c) +{ + switch(hi2c->mode) + { + case I2C_INT_MA_TX: + case I2C_INT_MA_RX: + { + i2c_master_irq_handler_int(hi2c); + }break; + case I2C_INT_SLA_TX: + case I2C_INT_SLA_RX: + { + i2c_slave_irq_handler_int(hi2c); + }break; + case I2C_DMA_MA_TX: + case I2C_DMA_MA_RX: + { + i2c_master_irq_handler_dma(hi2c); + }break; + case I2C_DMA_SLA_TX: + case I2C_DMA_SLA_RX: + { + i2c_slave_irq_handler_dma(hi2c); + }break; + + default:break; + } +} + +/** + * @brief dma reveive complete interrupt function. + * @param hi2c: the handle points to the operation information. + * @retval none. + */ +void i2c_err_irq_handler(i2c_handle_type* hi2c) +{ + /* buserr */ + if (i2c_flag_get(hi2c->i2cx, I2C_BUSERR_FLAG) != RESET) + { + hi2c->error_code = I2C_ERR_INTERRUPT; + + /* clear flag */ + i2c_flag_clear(hi2c->i2cx, I2C_BUSERR_FLAG); + + /* disable interrupts */ + i2c_interrupt_enable(hi2c->i2cx, I2C_ERR_INT, FALSE); + } + + /* arlost */ + if (i2c_flag_get(hi2c->i2cx, I2C_ARLOST_FLAG) != RESET) + { + hi2c->error_code = I2C_ERR_INTERRUPT; + + /* clear flag */ + i2c_flag_clear(hi2c->i2cx, I2C_ARLOST_FLAG); + + /* disable interrupts */ + i2c_interrupt_enable(hi2c->i2cx, I2C_ERR_INT, FALSE); + } + + /* ouf */ + if (i2c_flag_get(hi2c->i2cx, I2C_OUF_FLAG) != RESET) + { + hi2c->error_code = I2C_ERR_INTERRUPT; + + /* clear flag */ + i2c_flag_clear(hi2c->i2cx, I2C_OUF_FLAG); + + /* disable interrupts */ + i2c_interrupt_enable(hi2c->i2cx, I2C_ERR_INT, FALSE); + } + + /* pecerr */ + if (i2c_flag_get(hi2c->i2cx, I2C_PECERR_FLAG) != RESET) + { + hi2c->error_code = I2C_ERR_INTERRUPT; + + /* clear flag */ + i2c_flag_clear(hi2c->i2cx, I2C_PECERR_FLAG); + + /* disable interrupts */ + i2c_interrupt_enable(hi2c->i2cx, I2C_ERR_INT, FALSE); + + } + + /* timeout */ + if (i2c_flag_get(hi2c->i2cx, I2C_TMOUT_FLAG) != RESET) + { + hi2c->error_code = I2C_ERR_INTERRUPT; + + /* clear flag */ + i2c_flag_clear(hi2c->i2cx, I2C_TMOUT_FLAG); + + /* disable interrupts */ + i2c_interrupt_enable(hi2c->i2cx, I2C_ERR_INT, FALSE); + } + + /* alertf */ + if (i2c_flag_get(hi2c->i2cx, I2C_ALERTF_FLAG) != RESET) + { + hi2c->error_code = I2C_ERR_INTERRUPT; + + /* clear flag */ + i2c_flag_clear(hi2c->i2cx, I2C_ALERTF_FLAG); + + /* disable interrupts */ + i2c_interrupt_enable(hi2c->i2cx, I2C_ERR_INT, FALSE); + } +} + +/** + * @} + */ diff --git a/src/main/drivers/i2c_application.h b/src/main/drivers/i2c_application.h new file mode 100644 index 0000000000..d63abaa4a4 --- /dev/null +++ b/src/main/drivers/i2c_application.h @@ -0,0 +1,197 @@ +/** + ************************************************************************** + * @file i2c_application.h + * @version v2.1.0 + * @date 2022-08-16 + * @brief i2c application libray header file + ************************************************************************** + * Copyright notice & Disclaimer + * + * The software Board Support Package (BSP) that is made available to + * download from Artery official website is the copyrighted work of Artery. + * Artery authorizes customers to use, copy, and distribute the BSP + * software and its related documentation for the purpose of design and + * development in conjunction with Artery microcontrollers. Use of the + * software is governed by this copyright notice and the following disclaimer. + * + * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES, + * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS, + * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR + * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS, + * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT. + * + ************************************************************************** + */ + +/*!< define to prevent recursive inclusion -------------------------------------*/ +#ifndef __I2C_APPLICATION_H +#define __I2C_APPLICATION_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* includes ------------------------------------------------------------------*/ +#include "at32f435_437.h" + +/** @addtogroup AT32F435_437_middlewares_i2c_application_library + * @{ + */ + + +/** @defgroup I2C_library_event_check_flag + * @{ + */ + +#define I2C_EVENT_CHECK_NONE ((uint32_t)0x00000000) /*!< check flag none */ +#define I2C_EVENT_CHECK_ACKFAIL ((uint32_t)0x00000001) /*!< check flag ackfail */ +#define I2C_EVENT_CHECK_STOP ((uint32_t)0x00000002) /*!< check flag stop */ + +/** + * @} + */ + +/** @defgroup I2C_library_memory_address_width_mode + * @{ + */ + +typedef enum +{ + I2C_MEM_ADDR_WIDIH_8 = 0x01, /*!< memory address is 8 bit */ + I2C_MEM_ADDR_WIDIH_16 = 0x02, /*!< memory address is 16 bit */ +} i2c_mem_address_width_type; + +/** + * @} + */ + +/** @defgroup I2C_library_transmission_mode + * @{ + */ + +typedef enum +{ + I2C_INT_MA_TX = 0, + I2C_INT_MA_RX, + I2C_INT_SLA_TX, + I2C_INT_SLA_RX, + I2C_DMA_MA_TX, + I2C_DMA_MA_RX, + I2C_DMA_SLA_TX, + I2C_DMA_SLA_RX, +} i2c_mode_type; + +/** + * @} + */ + +/** @defgroup I2C_library_status_code + * @{ + */ + +typedef enum +{ + I2C_OK = 0, /*!< no error */ + I2C_ERR_STEP_1, /*!< step 1 error */ + I2C_ERR_STEP_2, /*!< step 2 error */ + I2C_ERR_STEP_3, /*!< step 3 error */ + I2C_ERR_STEP_4, /*!< step 4 error */ + I2C_ERR_STEP_5, /*!< step 5 error */ + I2C_ERR_STEP_6, /*!< step 6 error */ + I2C_ERR_STEP_7, /*!< step 7 error */ + I2C_ERR_STEP_8, /*!< step 8 error */ + I2C_ERR_STEP_9, /*!< step 9 error */ + I2C_ERR_STEP_10, /*!< step 10 error */ + I2C_ERR_STEP_11, /*!< step 11 error */ + I2C_ERR_STEP_12, /*!< step 12 error */ + I2C_ERR_TCRLD, /*!< tcrld error */ + I2C_ERR_TDC, /*!< tdc error */ + I2C_ERR_ADDR, /*!< addr error */ + I2C_ERR_STOP, /*!< stop error */ + I2C_ERR_ACKFAIL, /*!< ackfail error */ + I2C_ERR_TIMEOUT, /*!< timeout error */ + I2C_ERR_INTERRUPT, /*!< interrupt error */ +} i2c_status_type; + +/** + * @} + */ + +/** @defgroup I2C_library_handler + * @{ + */ + +typedef struct +{ + i2c_type *i2cx; /*!< i2c registers base address */ + uint8_t *pbuff; /*!< pointer to i2c transfer buffer */ + __IO uint16_t psize; /*!< i2c transfer size */ + __IO uint16_t pcount; /*!< i2c transfer counter */ + __IO uint32_t mode; /*!< i2c communication mode */ + __IO uint32_t status; /*!< i2c communication status */ + __IO i2c_status_type error_code; /*!< i2c error code */ + dma_channel_type *dma_tx_channel; /*!< dma transmit channel */ + dma_channel_type *dma_rx_channel; /*!< dma receive channel */ + dma_init_type dma_init_struct; /*!< dma init parameters */ +} i2c_handle_type; + +/** + * @} + */ + +/** @defgroup I2C_library_exported_functions + * @{ + */ + +void i2c_config (i2c_handle_type* hi2c); +void i2c_lowlevel_init (i2c_handle_type* hi2c); +void i2c_reset_ctrl2_register (i2c_handle_type* hi2c); +i2c_status_type i2c_wait_end (i2c_handle_type* hi2c, uint32_t timeout); +i2c_status_type i2c_wait_flag (i2c_handle_type* hi2c, uint32_t flag, uint32_t event_check, uint32_t timeout); + +i2c_status_type i2c_master_transmit (i2c_handle_type* hi2c, uint16_t address, uint8_t* pdata, uint16_t size, uint32_t timeout); +i2c_status_type i2c_master_receive (i2c_handle_type* hi2c, uint16_t address, uint8_t* pdata, uint16_t size, uint32_t timeout); +i2c_status_type i2c_slave_transmit (i2c_handle_type* hi2c, uint8_t* pdata, uint16_t size, uint32_t timeout); +i2c_status_type i2c_slave_receive (i2c_handle_type* hi2c, uint8_t* pdata, uint16_t size, uint32_t timeout); + +i2c_status_type i2c_master_transmit_int (i2c_handle_type* hi2c, uint16_t address, uint8_t* pdata, uint16_t size, uint32_t timeout); +i2c_status_type i2c_master_receive_int (i2c_handle_type* hi2c, uint16_t address, uint8_t* pdata, uint16_t size, uint32_t timeout); +i2c_status_type i2c_slave_transmit_int (i2c_handle_type* hi2c, uint8_t* pdata, uint16_t size, uint32_t timeout); +i2c_status_type i2c_slave_receive_int (i2c_handle_type* hi2c, uint8_t* pdata, uint16_t size, uint32_t timeout); + +i2c_status_type i2c_master_transmit_dma (i2c_handle_type* hi2c, uint16_t address, uint8_t* pdata, uint16_t size, uint32_t timeout); +i2c_status_type i2c_master_receive_dma (i2c_handle_type* hi2c, uint16_t address, uint8_t* pdata, uint16_t size, uint32_t timeout); +i2c_status_type i2c_slave_transmit_dma (i2c_handle_type* hi2c, uint8_t* pdata, uint16_t size, uint32_t timeout); +i2c_status_type i2c_slave_receive_dma (i2c_handle_type* hi2c, uint8_t* pdata, uint16_t size, uint32_t timeout); + +i2c_status_type i2c_smbus_master_transmit (i2c_handle_type* hi2c, uint16_t address, uint8_t* pdata, uint16_t size, uint32_t timeout); +i2c_status_type i2c_smbus_master_receive (i2c_handle_type* hi2c, uint16_t address, uint8_t* pdata, uint16_t size, uint32_t timeout); +i2c_status_type i2c_smbus_slave_transmit (i2c_handle_type* hi2c, uint8_t* pdata, uint16_t size, uint32_t timeout); +i2c_status_type i2c_smbus_slave_receive (i2c_handle_type* hi2c, uint8_t* pdata, uint16_t size, uint32_t timeout); + +i2c_status_type i2c_memory_write (i2c_handle_type* hi2c, i2c_mem_address_width_type mem_address_width, uint16_t address, uint16_t mem_address, uint8_t* pdata, uint16_t size, uint32_t timeout); +i2c_status_type i2c_memory_write_int (i2c_handle_type* hi2c, i2c_mem_address_width_type mem_address_width, uint16_t address, uint16_t mem_address, uint8_t* pdata, uint16_t size, uint32_t timeout); +i2c_status_type i2c_memory_write_dma (i2c_handle_type* hi2c, i2c_mem_address_width_type mem_address_width, uint16_t address, uint16_t mem_address, uint8_t* pdata, uint16_t size, uint32_t timeout); +i2c_status_type i2c_memory_read (i2c_handle_type* hi2c, i2c_mem_address_width_type mem_address_width, uint16_t address, uint16_t mem_address, uint8_t* pdata, uint16_t size, uint32_t timeout); +i2c_status_type i2c_memory_read_int (i2c_handle_type* hi2c, i2c_mem_address_width_type mem_address_width, uint16_t address, uint16_t mem_address, uint8_t* pdata, uint16_t size, uint32_t timeout); +i2c_status_type i2c_memory_read_dma (i2c_handle_type* hi2c, i2c_mem_address_width_type mem_address_width, uint16_t address, uint16_t mem_address, uint8_t* pdata, uint16_t size, uint32_t timeout); + +void i2c_evt_irq_handler (i2c_handle_type* hi2c); +void i2c_err_irq_handler (i2c_handle_type* hi2c); +void i2c_dma_tx_irq_handler (i2c_handle_type* hi2c); +void i2c_dma_rx_irq_handler (i2c_handle_type* hi2c); + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/src/main/drivers/io.c b/src/main/drivers/io.c index fe89596317..6d7aa4d5e2 100644 --- a/src/main/drivers/io.c +++ b/src/main/drivers/io.c @@ -60,6 +60,17 @@ const struct ioPortDef_s ioPortDefs[] = { { RCC_AHB4(GPIOH) }, { RCC_AHB4(GPIOI) }, }; +#elif defined(AT32F43x) +const struct ioPortDef_s ioPortDefs[] = { + { RCC_AHB1(GPIOA) }, + { RCC_AHB1(GPIOB) }, + { RCC_AHB1(GPIOC) }, + { RCC_AHB1(GPIOD) }, + { RCC_AHB1(GPIOE) }, + { RCC_AHB1(GPIOF) }, + { RCC_AHB1(GPIOG) }, + { RCC_AHB1(GPIOH) }, +}; # endif ioRec_t* IO_Rec(IO_t io) @@ -71,12 +82,20 @@ ioRec_t* IO_Rec(IO_t io) return io; } -GPIO_TypeDef* IO_GPIO(IO_t io) +#if defined(AT32F43x) +gpio_type * IO_GPIO(IO_t io) { const ioRec_t *ioRec = IO_Rec(io); return ioRec->gpio; } - +#else +GPIO_TypeDef * IO_GPIO(IO_t io) +{ + const ioRec_t *ioRec = IO_Rec(io); + return ioRec->gpio; +} +# endif + uint16_t IO_Pin(IO_t io) { const ioRec_t *ioRec = IO_Rec(io); @@ -126,7 +145,7 @@ uint32_t IO_EXTI_Line(IO_t io) if (!io) { return 0; } -#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) +#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(AT32F43x) return 1 << IO_GPIOPinIdx(io); #else # error "Unknown target type" @@ -140,6 +159,8 @@ bool IORead(IO_t io) } #if defined(USE_HAL_DRIVER) return !! HAL_GPIO_ReadPin(IO_GPIO(io),IO_Pin(io)); +#elif defined(AT32F43x) + return !! (IO_GPIO(io)->idt & IO_Pin(io)); #else return !! (IO_GPIO(io)->IDR & IO_Pin(io)); #endif @@ -156,14 +177,16 @@ void IOWrite(IO_t io, bool hi) } else { HAL_GPIO_WritePin(IO_GPIO(io),IO_Pin(io),GPIO_PIN_RESET); } -#elif defined(STM32F4) +#elif defined(STM32F4) if (hi) { - IO_GPIO(io)->BSRRL = IO_Pin(io); + IO_GPIO(io)->BSRRL = IO_Pin(io); } else { - IO_GPIO(io)->BSRRH = IO_Pin(io); + IO_GPIO(io)->BSRRH = IO_Pin(io); } +#elif defined(AT32F43x) + IO_GPIO(io)->scr = IO_Pin(io) << (hi ? 0 : 16); #else - IO_GPIO(io)->BSRR = IO_Pin(io) << (hi ? 0 : 16); + IO_GPIO(io)->BSRR = IO_Pin(io) << (hi ? 0 : 16); #endif } @@ -176,6 +199,8 @@ void IOHi(IO_t io) HAL_GPIO_WritePin(IO_GPIO(io),IO_Pin(io),GPIO_PIN_SET); #elif defined(STM32F4) IO_GPIO(io)->BSRRL = IO_Pin(io); +#elif defined(AT32F43x) + IO_GPIO(io)->scr = IO_Pin(io); #else IO_GPIO(io)->BSRR = IO_Pin(io); #endif @@ -188,8 +213,10 @@ void IOLo(IO_t io) } #if defined(USE_HAL_DRIVER) HAL_GPIO_WritePin(IO_GPIO(io),IO_Pin(io),GPIO_PIN_RESET); -#elif defined(STM32F4) +#elif defined(STM32F4) IO_GPIO(io)->BSRRH = IO_Pin(io); +#elif defined(AT32F43x) + IO_GPIO(io)->clr = IO_Pin(io); #else IO_GPIO(io)->BRR = IO_Pin(io); #endif @@ -214,10 +241,15 @@ void IOToggle(IO_t io) } else { IO_GPIO(io)->BSRRL = mask; } +#elif defined(AT32F43x) + if (IO_GPIO(io)->odt & mask) + mask <<= 16; // bit is set, shift mask to reset half + + IO_GPIO(io)->scr = IO_Pin(io); #else if (IO_GPIO(io)->ODR & mask) mask <<= 16; // bit is set, shift mask to reset half - + IO_GPIO(io)->BSRR = mask; #endif } @@ -332,6 +364,47 @@ void IOConfigGPIOAF(IO_t io, ioConfig_t cfg, uint8_t af) }; GPIO_Init(IO_GPIO(io), &init); } +#elif defined(AT32F43x) + +void IOConfigGPIO(IO_t io, ioConfig_t cfg) +{ + if (!io) { + return; + } + const rccPeriphTag_t rcc = ioPortDefs[IO_GPIOPortIdx(io)].rcc; + RCC_ClockCmd(rcc, ENABLE); + + gpio_init_type init = { + .gpio_pins = IO_Pin(io), + .gpio_out_type = (cfg >> 4) & 0x01, + .gpio_pull = (cfg >> 5) & 0x03, + .gpio_mode = (cfg >> 0) & 0x03, + .gpio_drive_strength = (cfg >> 2) & 0x03, + }; + + gpio_init(IO_GPIO(io), &init); +} + +void IOConfigGPIOAF(IO_t io, ioConfig_t cfg, uint8_t af) +{ + if (!io) { + return; + } + const rccPeriphTag_t rcc = ioPortDefs[IO_GPIOPortIdx(io)].rcc; + RCC_ClockCmd(rcc, ENABLE); + // Must run configure the pin's muxing function + gpio_pin_mux_config(IO_GPIO(io), IO_GPIO_PinSource(io), af); + + gpio_init_type init = { + .gpio_pins = IO_Pin(io), + .gpio_out_type = (cfg >> 4) & 0x01, + .gpio_pull = (cfg >> 5) & 0x03, + .gpio_mode = (cfg >> 0) & 0x03, + .gpio_drive_strength = (cfg >> 2) & 0x03, + }; + gpio_init(IO_GPIO(io), &init); +} + #endif static const uint16_t ioDefUsedMask[DEFIO_PORT_USED_COUNT] = { DEFIO_PORT_USED_LIST }; @@ -347,7 +420,11 @@ void IOInitGlobal(void) for (unsigned port = 0; port < ARRAYLEN(ioDefUsedMask); port++) { for (unsigned pin = 0; pin < sizeof(ioDefUsedMask[0]) * 8; pin++) { if (ioDefUsedMask[port] & (1 << pin)) { - ioRec->gpio = (GPIO_TypeDef *)(GPIOA_BASE + (port << 10)); // ports are 0x400 apart +#if defined(AT32F43x) + ioRec->gpio = (gpio_type *)(GPIOA_BASE + (port << 10)); // ports are 0x400 apart +#else + ioRec->gpio = (GPIO_TypeDef *)(GPIOA_BASE + (port << 10)); // ports are 0x400 apart +# endif ioRec->pin = 1 << pin; ioRec++; } @@ -363,13 +440,13 @@ IO_t IOGetByTag(ioTag_t tag) if (portIdx < 0 || portIdx >= DEFIO_PORT_USED_COUNT) { return NULL; } - // check if pin exists + // Check if pin exists if (!(ioDefUsedMask[portIdx] & (1 << pinIdx))) { return NULL; } - // count bits before this pin on single port + // Count bits before this pin on single port int offset = __builtin_popcount(((1 << pinIdx) - 1) & ioDefUsedMask[portIdx]); - // and add port offset + // Add port offset offset += ioDefUsedOffset[portIdx]; return ioRecs + offset; } diff --git a/src/main/drivers/io.h b/src/main/drivers/io.h index 27c0b3827b..8d7ed1b7de 100644 --- a/src/main/drivers/io.h +++ b/src/main/drivers/io.h @@ -70,6 +70,24 @@ #define IOCFG_IN_FLOATING IO_CONFIG(GPIO_Mode_IN, 0, 0, GPIO_PuPd_NOPULL) #define IOCFG_IPU_25 IO_CONFIG(GPIO_Mode_IN, GPIO_Speed_25MHz, 0, GPIO_PuPd_UP) +#elif defined(AT32F43x) + +#define IO_CONFIG(mode, speed, otype, pupd) ((mode) | ((speed) << 2) | ((otype) << 4) | ((pupd) << 5)) + +#define IOCFG_OUT_PP IO_CONFIG(GPIO_MODE_OUTPUT, GPIO_DRIVE_STRENGTH_STRONGER, GPIO_OUTPUT_PUSH_PULL, GPIO_PULL_NONE) // TODO +#define IOCFG_OUT_PP_25 IO_CONFIG(GPIO_MODE_OUTPUT, GPIO_DRIVE_STRENGTH_MODERATE, GPIO_OUTPUT_PUSH_PULL, GPIO_PULL_NONE) +#define IOCFG_OUT_OD IO_CONFIG(GPIO_MODE_OUTPUT, GPIO_DRIVE_STRENGTH_MODERATE, GPIO_OUTPUT_OPEN_DRAIN, GPIO_PULL_NONE) +#define IOCFG_AF_PP_FAST IO_CONFIG(GPIO_MODE_MUX, GPIO_DRIVE_STRENGTH_STRONGER, GPIO_OUTPUT_PUSH_PULL, GPIO_PULL_DOWN) +#define IOCFG_AF_PP IO_CONFIG(GPIO_MODE_MUX, GPIO_DRIVE_STRENGTH_STRONGER, GPIO_OUTPUT_PUSH_PULL, GPIO_PULL_NONE) +#define IOCFG_AF_PP_PD IO_CONFIG(GPIO_MODE_MUX, GPIO_DRIVE_STRENGTH_STRONGER, GPIO_OUTPUT_PUSH_PULL, GPIO_PULL_DOWN) +#define IOCFG_AF_PP_UP IO_CONFIG(GPIO_MODE_MUX, GPIO_DRIVE_STRENGTH_STRONGER, GPIO_OUTPUT_PUSH_PULL, GPIO_PULL_UP) +#define IOCFG_AF_OD IO_CONFIG(GPIO_MODE_MUX, GPIO_DRIVE_STRENGTH_STRONGER, GPIO_OUTPUT_OPEN_DRAIN, GPIO_PULL_NONE) +#define IOCFG_AF_OD_UP IO_CONFIG(GPIO_MODE_MUX, GPIO_DRIVE_STRENGTH_STRONGER, GPIO_OUTPUT_OPEN_DRAIN, GPIO_PULL_UP) +#define IOCFG_IPD IO_CONFIG(GPIO_MODE_INPUT, GPIO_DRIVE_STRENGTH_MODERATE, GPIO_OUTPUT_PUSH_PULL, GPIO_PULL_DOWN) +#define IOCFG_IPU IO_CONFIG(GPIO_MODE_INPUT, GPIO_DRIVE_STRENGTH_MODERATE, GPIO_OUTPUT_PUSH_PULL, GPIO_PULL_UP) +#define IOCFG_IN_FLOATING IO_CONFIG(GPIO_MODE_INPUT, GPIO_DRIVE_STRENGTH_MODERATE, GPIO_OUTPUT_PUSH_PULL, GPIO_PULL_NONE) +#define IOCFG_IPU_25 IO_CONFIG(GPIO_MODE_INPUT, GPIO_DRIVE_STRENGTH_MODERATE, GPIO_OUTPUT_PUSH_PULL, GPIO_PULL_UP) + #elif defined(UNIT_TEST) # define IOCFG_OUT_PP 0 diff --git a/src/main/drivers/io_def_generated.h b/src/main/drivers/io_def_generated.h index a1f0fc3114..80348c59ab 100644 --- a/src/main/drivers/io_def_generated.h +++ b/src/main/drivers/io_def_generated.h @@ -1,5 +1,6 @@ #pragma once -// this file is automatically generated by def_generated.pl script + +// this file is automatically generated by src/utils/def_generated.pl script // do not modify this file directly, your changes will be lost // DEFIO_PORT__USED_MASK is bitmask of used pins on target @@ -68,6 +69,24 @@ #endif #define DEFIO_PORT_G_OFFSET (DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT) +#if defined(TARGET_IO_PORTH) +# define DEFIO_PORT_H_USED_MASK TARGET_IO_PORTH +# define DEFIO_PORT_H_USED_COUNT BITCOUNT(DEFIO_PORT_H_USED_MASK) +#else +# define DEFIO_PORT_H_USED_MASK 0 +# define DEFIO_PORT_H_USED_COUNT 0 +#endif +#define DEFIO_PORT_H_OFFSET (DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT) + +#if defined(TARGET_IO_PORTI) +# define DEFIO_PORT_I_USED_MASK TARGET_IO_PORTI +# define DEFIO_PORT_I_USED_COUNT BITCOUNT(DEFIO_PORT_I_USED_MASK) +#else +# define DEFIO_PORT_I_USED_MASK 0 +# define DEFIO_PORT_I_USED_COUNT 0 +#endif +#define DEFIO_PORT_I_OFFSET (DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT+DEFIO_PORT_H_USED_COUNT) + // DEFIO_GPIOID__ maps to port index @@ -78,8 +97,11 @@ #define DEFIO_GPIOID__E 4 #define DEFIO_GPIOID__F 5 #define DEFIO_GPIOID__G 6 +#define DEFIO_GPIOID__H 7 +#define DEFIO_GPIOID__I 8 -// DEFIO_TAG__P will expand to TAG if defined for target +// DEFIO_TAG__P will expand to TAG if defined for target, error is triggered otherwise +// DEFIO_TAG_E__P will expand to TAG if defined, to NONE otherwise (usefull for tables that are CPU-specific) // DEFIO_REC__P will expand to ioRec* (using DEFIO_REC_INDEX(idx)) #if DEFIO_PORT_A_USED_MASK & BIT(0) @@ -1090,13 +1112,311 @@ # define DEFIO_TAG_E__PG15 DEFIO_TAG_E__NONE # define DEFIO_REC__PG15 defio_error_PG15_is_not_supported_on_TARGET #endif +#if DEFIO_PORT_H_USED_MASK & BIT(0) +# define DEFIO_TAG__PH0 DEFIO_TAG_MAKE(DEFIO_GPIOID__H, 0) +# define DEFIO_TAG_E__PH0 DEFIO_TAG_MAKE(DEFIO_GPIOID__H, 0) +# define DEFIO_REC__PH0 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_H_USED_MASK & (BIT(0) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT) +#else +# define DEFIO_TAG__PH0 defio_error_PH0_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PH0 DEFIO_TAG_E__NONE +# define DEFIO_REC__PH0 defio_error_PH0_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_H_USED_MASK & BIT(1) +# define DEFIO_TAG__PH1 DEFIO_TAG_MAKE(DEFIO_GPIOID__H, 1) +# define DEFIO_TAG_E__PH1 DEFIO_TAG_MAKE(DEFIO_GPIOID__H, 1) +# define DEFIO_REC__PH1 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_H_USED_MASK & (BIT(1) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT) +#else +# define DEFIO_TAG__PH1 defio_error_PH1_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PH1 DEFIO_TAG_E__NONE +# define DEFIO_REC__PH1 defio_error_PH1_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_H_USED_MASK & BIT(2) +# define DEFIO_TAG__PH2 DEFIO_TAG_MAKE(DEFIO_GPIOID__H, 2) +# define DEFIO_TAG_E__PH2 DEFIO_TAG_MAKE(DEFIO_GPIOID__H, 2) +# define DEFIO_REC__PH2 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_H_USED_MASK & (BIT(2) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT) +#else +# define DEFIO_TAG__PH2 defio_error_PH2_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PH2 DEFIO_TAG_E__NONE +# define DEFIO_REC__PH2 defio_error_PH2_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_H_USED_MASK & BIT(3) +# define DEFIO_TAG__PH3 DEFIO_TAG_MAKE(DEFIO_GPIOID__H, 3) +# define DEFIO_TAG_E__PH3 DEFIO_TAG_MAKE(DEFIO_GPIOID__H, 3) +# define DEFIO_REC__PH3 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_H_USED_MASK & (BIT(3) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT) +#else +# define DEFIO_TAG__PH3 defio_error_PH3_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PH3 DEFIO_TAG_E__NONE +# define DEFIO_REC__PH3 defio_error_PH3_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_H_USED_MASK & BIT(4) +# define DEFIO_TAG__PH4 DEFIO_TAG_MAKE(DEFIO_GPIOID__H, 4) +# define DEFIO_TAG_E__PH4 DEFIO_TAG_MAKE(DEFIO_GPIOID__H, 4) +# define DEFIO_REC__PH4 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_H_USED_MASK & (BIT(4) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT) +#else +# define DEFIO_TAG__PH4 defio_error_PH4_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PH4 DEFIO_TAG_E__NONE +# define DEFIO_REC__PH4 defio_error_PH4_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_H_USED_MASK & BIT(5) +# define DEFIO_TAG__PH5 DEFIO_TAG_MAKE(DEFIO_GPIOID__H, 5) +# define DEFIO_TAG_E__PH5 DEFIO_TAG_MAKE(DEFIO_GPIOID__H, 5) +# define DEFIO_REC__PH5 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_H_USED_MASK & (BIT(5) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT) +#else +# define DEFIO_TAG__PH5 defio_error_PH5_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PH5 DEFIO_TAG_E__NONE +# define DEFIO_REC__PH5 defio_error_PH5_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_H_USED_MASK & BIT(6) +# define DEFIO_TAG__PH6 DEFIO_TAG_MAKE(DEFIO_GPIOID__H, 6) +# define DEFIO_TAG_E__PH6 DEFIO_TAG_MAKE(DEFIO_GPIOID__H, 6) +# define DEFIO_REC__PH6 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_H_USED_MASK & (BIT(6) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT) +#else +# define DEFIO_TAG__PH6 defio_error_PH6_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PH6 DEFIO_TAG_E__NONE +# define DEFIO_REC__PH6 defio_error_PH6_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_H_USED_MASK & BIT(7) +# define DEFIO_TAG__PH7 DEFIO_TAG_MAKE(DEFIO_GPIOID__H, 7) +# define DEFIO_TAG_E__PH7 DEFIO_TAG_MAKE(DEFIO_GPIOID__H, 7) +# define DEFIO_REC__PH7 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_H_USED_MASK & (BIT(7) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT) +#else +# define DEFIO_TAG__PH7 defio_error_PH7_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PH7 DEFIO_TAG_E__NONE +# define DEFIO_REC__PH7 defio_error_PH7_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_H_USED_MASK & BIT(8) +# define DEFIO_TAG__PH8 DEFIO_TAG_MAKE(DEFIO_GPIOID__H, 8) +# define DEFIO_TAG_E__PH8 DEFIO_TAG_MAKE(DEFIO_GPIOID__H, 8) +# define DEFIO_REC__PH8 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_H_USED_MASK & (BIT(8) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT) +#else +# define DEFIO_TAG__PH8 defio_error_PH8_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PH8 DEFIO_TAG_E__NONE +# define DEFIO_REC__PH8 defio_error_PH8_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_H_USED_MASK & BIT(9) +# define DEFIO_TAG__PH9 DEFIO_TAG_MAKE(DEFIO_GPIOID__H, 9) +# define DEFIO_TAG_E__PH9 DEFIO_TAG_MAKE(DEFIO_GPIOID__H, 9) +# define DEFIO_REC__PH9 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_H_USED_MASK & (BIT(9) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT) +#else +# define DEFIO_TAG__PH9 defio_error_PH9_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PH9 DEFIO_TAG_E__NONE +# define DEFIO_REC__PH9 defio_error_PH9_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_H_USED_MASK & BIT(10) +# define DEFIO_TAG__PH10 DEFIO_TAG_MAKE(DEFIO_GPIOID__H, 10) +# define DEFIO_TAG_E__PH10 DEFIO_TAG_MAKE(DEFIO_GPIOID__H, 10) +# define DEFIO_REC__PH10 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_H_USED_MASK & (BIT(10) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT) +#else +# define DEFIO_TAG__PH10 defio_error_PH10_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PH10 DEFIO_TAG_E__NONE +# define DEFIO_REC__PH10 defio_error_PH10_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_H_USED_MASK & BIT(11) +# define DEFIO_TAG__PH11 DEFIO_TAG_MAKE(DEFIO_GPIOID__H, 11) +# define DEFIO_TAG_E__PH11 DEFIO_TAG_MAKE(DEFIO_GPIOID__H, 11) +# define DEFIO_REC__PH11 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_H_USED_MASK & (BIT(11) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT) +#else +# define DEFIO_TAG__PH11 defio_error_PH11_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PH11 DEFIO_TAG_E__NONE +# define DEFIO_REC__PH11 defio_error_PH11_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_H_USED_MASK & BIT(12) +# define DEFIO_TAG__PH12 DEFIO_TAG_MAKE(DEFIO_GPIOID__H, 12) +# define DEFIO_TAG_E__PH12 DEFIO_TAG_MAKE(DEFIO_GPIOID__H, 12) +# define DEFIO_REC__PH12 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_H_USED_MASK & (BIT(12) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT) +#else +# define DEFIO_TAG__PH12 defio_error_PH12_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PH12 DEFIO_TAG_E__NONE +# define DEFIO_REC__PH12 defio_error_PH12_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_H_USED_MASK & BIT(13) +# define DEFIO_TAG__PH13 DEFIO_TAG_MAKE(DEFIO_GPIOID__H, 13) +# define DEFIO_TAG_E__PH13 DEFIO_TAG_MAKE(DEFIO_GPIOID__H, 13) +# define DEFIO_REC__PH13 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_H_USED_MASK & (BIT(13) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT) +#else +# define DEFIO_TAG__PH13 defio_error_PH13_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PH13 DEFIO_TAG_E__NONE +# define DEFIO_REC__PH13 defio_error_PH13_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_H_USED_MASK & BIT(14) +# define DEFIO_TAG__PH14 DEFIO_TAG_MAKE(DEFIO_GPIOID__H, 14) +# define DEFIO_TAG_E__PH14 DEFIO_TAG_MAKE(DEFIO_GPIOID__H, 14) +# define DEFIO_REC__PH14 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_H_USED_MASK & (BIT(14) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT) +#else +# define DEFIO_TAG__PH14 defio_error_PH14_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PH14 DEFIO_TAG_E__NONE +# define DEFIO_REC__PH14 defio_error_PH14_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_H_USED_MASK & BIT(15) +# define DEFIO_TAG__PH15 DEFIO_TAG_MAKE(DEFIO_GPIOID__H, 15) +# define DEFIO_TAG_E__PH15 DEFIO_TAG_MAKE(DEFIO_GPIOID__H, 15) +# define DEFIO_REC__PH15 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_H_USED_MASK & (BIT(15) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT) +#else +# define DEFIO_TAG__PH15 defio_error_PH15_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PH15 DEFIO_TAG_E__NONE +# define DEFIO_REC__PH15 defio_error_PH15_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_I_USED_MASK & BIT(0) +# define DEFIO_TAG__PI0 DEFIO_TAG_MAKE(DEFIO_GPIOID__I, 0) +# define DEFIO_TAG_E__PI0 DEFIO_TAG_MAKE(DEFIO_GPIOID__I, 0) +# define DEFIO_REC__PI0 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_I_USED_MASK & (BIT(0) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT+DEFIO_PORT_H_USED_COUNT) +#else +# define DEFIO_TAG__PI0 defio_error_PI0_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PI0 DEFIO_TAG_E__NONE +# define DEFIO_REC__PI0 defio_error_PI0_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_I_USED_MASK & BIT(1) +# define DEFIO_TAG__PI1 DEFIO_TAG_MAKE(DEFIO_GPIOID__I, 1) +# define DEFIO_TAG_E__PI1 DEFIO_TAG_MAKE(DEFIO_GPIOID__I, 1) +# define DEFIO_REC__PI1 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_I_USED_MASK & (BIT(1) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT+DEFIO_PORT_H_USED_COUNT) +#else +# define DEFIO_TAG__PI1 defio_error_PI1_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PI1 DEFIO_TAG_E__NONE +# define DEFIO_REC__PI1 defio_error_PI1_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_I_USED_MASK & BIT(2) +# define DEFIO_TAG__PI2 DEFIO_TAG_MAKE(DEFIO_GPIOID__I, 2) +# define DEFIO_TAG_E__PI2 DEFIO_TAG_MAKE(DEFIO_GPIOID__I, 2) +# define DEFIO_REC__PI2 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_I_USED_MASK & (BIT(2) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT+DEFIO_PORT_H_USED_COUNT) +#else +# define DEFIO_TAG__PI2 defio_error_PI2_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PI2 DEFIO_TAG_E__NONE +# define DEFIO_REC__PI2 defio_error_PI2_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_I_USED_MASK & BIT(3) +# define DEFIO_TAG__PI3 DEFIO_TAG_MAKE(DEFIO_GPIOID__I, 3) +# define DEFIO_TAG_E__PI3 DEFIO_TAG_MAKE(DEFIO_GPIOID__I, 3) +# define DEFIO_REC__PI3 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_I_USED_MASK & (BIT(3) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT+DEFIO_PORT_H_USED_COUNT) +#else +# define DEFIO_TAG__PI3 defio_error_PI3_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PI3 DEFIO_TAG_E__NONE +# define DEFIO_REC__PI3 defio_error_PI3_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_I_USED_MASK & BIT(4) +# define DEFIO_TAG__PI4 DEFIO_TAG_MAKE(DEFIO_GPIOID__I, 4) +# define DEFIO_TAG_E__PI4 DEFIO_TAG_MAKE(DEFIO_GPIOID__I, 4) +# define DEFIO_REC__PI4 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_I_USED_MASK & (BIT(4) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT+DEFIO_PORT_H_USED_COUNT) +#else +# define DEFIO_TAG__PI4 defio_error_PI4_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PI4 DEFIO_TAG_E__NONE +# define DEFIO_REC__PI4 defio_error_PI4_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_I_USED_MASK & BIT(5) +# define DEFIO_TAG__PI5 DEFIO_TAG_MAKE(DEFIO_GPIOID__I, 5) +# define DEFIO_TAG_E__PI5 DEFIO_TAG_MAKE(DEFIO_GPIOID__I, 5) +# define DEFIO_REC__PI5 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_I_USED_MASK & (BIT(5) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT+DEFIO_PORT_H_USED_COUNT) +#else +# define DEFIO_TAG__PI5 defio_error_PI5_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PI5 DEFIO_TAG_E__NONE +# define DEFIO_REC__PI5 defio_error_PI5_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_I_USED_MASK & BIT(6) +# define DEFIO_TAG__PI6 DEFIO_TAG_MAKE(DEFIO_GPIOID__I, 6) +# define DEFIO_TAG_E__PI6 DEFIO_TAG_MAKE(DEFIO_GPIOID__I, 6) +# define DEFIO_REC__PI6 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_I_USED_MASK & (BIT(6) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT+DEFIO_PORT_H_USED_COUNT) +#else +# define DEFIO_TAG__PI6 defio_error_PI6_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PI6 DEFIO_TAG_E__NONE +# define DEFIO_REC__PI6 defio_error_PI6_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_I_USED_MASK & BIT(7) +# define DEFIO_TAG__PI7 DEFIO_TAG_MAKE(DEFIO_GPIOID__I, 7) +# define DEFIO_TAG_E__PI7 DEFIO_TAG_MAKE(DEFIO_GPIOID__I, 7) +# define DEFIO_REC__PI7 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_I_USED_MASK & (BIT(7) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT+DEFIO_PORT_H_USED_COUNT) +#else +# define DEFIO_TAG__PI7 defio_error_PI7_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PI7 DEFIO_TAG_E__NONE +# define DEFIO_REC__PI7 defio_error_PI7_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_I_USED_MASK & BIT(8) +# define DEFIO_TAG__PI8 DEFIO_TAG_MAKE(DEFIO_GPIOID__I, 8) +# define DEFIO_TAG_E__PI8 DEFIO_TAG_MAKE(DEFIO_GPIOID__I, 8) +# define DEFIO_REC__PI8 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_I_USED_MASK & (BIT(8) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT+DEFIO_PORT_H_USED_COUNT) +#else +# define DEFIO_TAG__PI8 defio_error_PI8_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PI8 DEFIO_TAG_E__NONE +# define DEFIO_REC__PI8 defio_error_PI8_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_I_USED_MASK & BIT(9) +# define DEFIO_TAG__PI9 DEFIO_TAG_MAKE(DEFIO_GPIOID__I, 9) +# define DEFIO_TAG_E__PI9 DEFIO_TAG_MAKE(DEFIO_GPIOID__I, 9) +# define DEFIO_REC__PI9 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_I_USED_MASK & (BIT(9) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT+DEFIO_PORT_H_USED_COUNT) +#else +# define DEFIO_TAG__PI9 defio_error_PI9_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PI9 DEFIO_TAG_E__NONE +# define DEFIO_REC__PI9 defio_error_PI9_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_I_USED_MASK & BIT(10) +# define DEFIO_TAG__PI10 DEFIO_TAG_MAKE(DEFIO_GPIOID__I, 10) +# define DEFIO_TAG_E__PI10 DEFIO_TAG_MAKE(DEFIO_GPIOID__I, 10) +# define DEFIO_REC__PI10 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_I_USED_MASK & (BIT(10) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT+DEFIO_PORT_H_USED_COUNT) +#else +# define DEFIO_TAG__PI10 defio_error_PI10_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PI10 DEFIO_TAG_E__NONE +# define DEFIO_REC__PI10 defio_error_PI10_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_I_USED_MASK & BIT(11) +# define DEFIO_TAG__PI11 DEFIO_TAG_MAKE(DEFIO_GPIOID__I, 11) +# define DEFIO_TAG_E__PI11 DEFIO_TAG_MAKE(DEFIO_GPIOID__I, 11) +# define DEFIO_REC__PI11 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_I_USED_MASK & (BIT(11) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT+DEFIO_PORT_H_USED_COUNT) +#else +# define DEFIO_TAG__PI11 defio_error_PI11_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PI11 DEFIO_TAG_E__NONE +# define DEFIO_REC__PI11 defio_error_PI11_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_I_USED_MASK & BIT(12) +# define DEFIO_TAG__PI12 DEFIO_TAG_MAKE(DEFIO_GPIOID__I, 12) +# define DEFIO_TAG_E__PI12 DEFIO_TAG_MAKE(DEFIO_GPIOID__I, 12) +# define DEFIO_REC__PI12 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_I_USED_MASK & (BIT(12) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT+DEFIO_PORT_H_USED_COUNT) +#else +# define DEFIO_TAG__PI12 defio_error_PI12_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PI12 DEFIO_TAG_E__NONE +# define DEFIO_REC__PI12 defio_error_PI12_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_I_USED_MASK & BIT(13) +# define DEFIO_TAG__PI13 DEFIO_TAG_MAKE(DEFIO_GPIOID__I, 13) +# define DEFIO_TAG_E__PI13 DEFIO_TAG_MAKE(DEFIO_GPIOID__I, 13) +# define DEFIO_REC__PI13 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_I_USED_MASK & (BIT(13) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT+DEFIO_PORT_H_USED_COUNT) +#else +# define DEFIO_TAG__PI13 defio_error_PI13_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PI13 DEFIO_TAG_E__NONE +# define DEFIO_REC__PI13 defio_error_PI13_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_I_USED_MASK & BIT(14) +# define DEFIO_TAG__PI14 DEFIO_TAG_MAKE(DEFIO_GPIOID__I, 14) +# define DEFIO_TAG_E__PI14 DEFIO_TAG_MAKE(DEFIO_GPIOID__I, 14) +# define DEFIO_REC__PI14 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_I_USED_MASK & (BIT(14) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT+DEFIO_PORT_H_USED_COUNT) +#else +# define DEFIO_TAG__PI14 defio_error_PI14_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PI14 DEFIO_TAG_E__NONE +# define DEFIO_REC__PI14 defio_error_PI14_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_I_USED_MASK & BIT(15) +# define DEFIO_TAG__PI15 DEFIO_TAG_MAKE(DEFIO_GPIOID__I, 15) +# define DEFIO_TAG_E__PI15 DEFIO_TAG_MAKE(DEFIO_GPIOID__I, 15) +# define DEFIO_REC__PI15 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_I_USED_MASK & (BIT(15) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT+DEFIO_PORT_H_USED_COUNT) +#else +# define DEFIO_TAG__PI15 defio_error_PI15_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PI15 DEFIO_TAG_E__NONE +# define DEFIO_REC__PI15 defio_error_PI15_is_not_supported_on_TARGET +#endif // DEFIO_IO_USED_COUNT is number of io pins supported on target -#define DEFIO_IO_USED_COUNT (DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT) +#define DEFIO_IO_USED_COUNT (DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT+DEFIO_PORT_H_USED_COUNT+DEFIO_PORT_I_USED_COUNT) // DEFIO_PORT_USED_LIST - comma separated list of bitmask for all used ports. // DEFIO_PORT_OFFSET_LIST - comma separated list of port offsets (count of pins before this port) // unused ports on end of list are skipped +#if !defined DEFIO_PORT_USED_LIST && DEFIO_PORT_I_USED_COUNT > 0 +# define DEFIO_PORT_USED_COUNT 9 +# define DEFIO_PORT_USED_LIST DEFIO_PORT_A_USED_MASK,DEFIO_PORT_B_USED_MASK,DEFIO_PORT_C_USED_MASK,DEFIO_PORT_D_USED_MASK,DEFIO_PORT_E_USED_MASK,DEFIO_PORT_F_USED_MASK,DEFIO_PORT_G_USED_MASK,DEFIO_PORT_H_USED_MASK,DEFIO_PORT_I_USED_MASK +# define DEFIO_PORT_OFFSET_LIST DEFIO_PORT_A_OFFSET,DEFIO_PORT_B_OFFSET,DEFIO_PORT_C_OFFSET,DEFIO_PORT_D_OFFSET,DEFIO_PORT_E_OFFSET,DEFIO_PORT_F_OFFSET,DEFIO_PORT_G_OFFSET,DEFIO_PORT_H_OFFSET,DEFIO_PORT_I_OFFSET +#endif +#if !defined DEFIO_PORT_USED_LIST && DEFIO_PORT_H_USED_COUNT > 0 +# define DEFIO_PORT_USED_COUNT 8 +# define DEFIO_PORT_USED_LIST DEFIO_PORT_A_USED_MASK,DEFIO_PORT_B_USED_MASK,DEFIO_PORT_C_USED_MASK,DEFIO_PORT_D_USED_MASK,DEFIO_PORT_E_USED_MASK,DEFIO_PORT_F_USED_MASK,DEFIO_PORT_G_USED_MASK,DEFIO_PORT_H_USED_MASK +# define DEFIO_PORT_OFFSET_LIST DEFIO_PORT_A_OFFSET,DEFIO_PORT_B_OFFSET,DEFIO_PORT_C_OFFSET,DEFIO_PORT_D_OFFSET,DEFIO_PORT_E_OFFSET,DEFIO_PORT_F_OFFSET,DEFIO_PORT_G_OFFSET,DEFIO_PORT_H_OFFSET +#endif #if !defined DEFIO_PORT_USED_LIST && DEFIO_PORT_G_USED_COUNT > 0 # define DEFIO_PORT_USED_COUNT 7 # define DEFIO_PORT_USED_LIST DEFIO_PORT_A_USED_MASK,DEFIO_PORT_B_USED_MASK,DEFIO_PORT_C_USED_MASK,DEFIO_PORT_D_USED_MASK,DEFIO_PORT_E_USED_MASK,DEFIO_PORT_F_USED_MASK,DEFIO_PORT_G_USED_MASK @@ -1133,10 +1453,11 @@ # define DEFIO_PORT_OFFSET_LIST DEFIO_PORT_A_OFFSET #endif -#if !defined DEFIO_PORT_USED_LIST -# warning "No pins are defined. Maybe you forgot to define TARGET_IO_PORTx in target_io.h" +#if !defined(DEFIO_PORT_USED_LIST) +# if !defined DEFIO_NO_PORTS // supress warnings if we really don't want any pins +# warning "No pins are defined. Maybe you forgot to define TARGET_IO_PORTx in target.h" +# endif # define DEFIO_PORT_USED_COUNT 0 # define DEFIO_PORT_USED_LIST /* empty */ # define DEFIO_PORT_OFFSET_LIST /* empty */ #endif - diff --git a/src/main/drivers/io_impl.h b/src/main/drivers/io_impl.h index 6bee6842fd..fe499d0dc1 100644 --- a/src/main/drivers/io_impl.h +++ b/src/main/drivers/io_impl.h @@ -8,6 +8,16 @@ typedef struct ioDef_s { ioTag_t tag; } ioDef_t; +#if defined(AT32F43x) +typedef struct ioRec_s { + gpio_type *gpio; + uint16_t pin; + resourceOwner_e owner; + resourceType_e resource; + uint8_t index; +} ioRec_t; +gpio_type* IO_GPIO(IO_t io); +#else typedef struct ioRec_s { GPIO_TypeDef *gpio; uint16_t pin; @@ -15,6 +25,9 @@ typedef struct ioRec_s { resourceType_e resource; uint8_t index; } ioRec_t; +GPIO_TypeDef* IO_GPIO(IO_t io); + +#endif extern ioRec_t ioRecs[DEFIO_IO_USED_COUNT]; @@ -24,12 +37,12 @@ int IO_GPIOPinIdx(IO_t io); int IO_GPIO_PinSource(IO_t io); int IO_GPIO_PortSource(IO_t io); -#if defined(STM32F4) +#if defined(STM32F4) || defined(AT32F43x) int IO_EXTI_PortSourceGPIO(IO_t io); int IO_EXTI_PinSource(IO_t io); #endif -GPIO_TypeDef* IO_GPIO(IO_t io); + uint16_t IO_Pin(IO_t io); #define IO_GPIOBYTAG(tag) IO_GPIO(IOGetByTag(tag)) diff --git a/src/main/drivers/nvic.h b/src/main/drivers/nvic.h index 42dfaa8d38..5a501fbc5e 100644 --- a/src/main/drivers/nvic.h +++ b/src/main/drivers/nvic.h @@ -14,10 +14,16 @@ #define NVIC_PRIO_SDIO 3 #define NVIC_PRIO_USB 5 #define NVIC_PRIO_SERIALUART 5 +#define NVIC_PRIO_VCP 7 -// Use all available bits for priority and zero bits to sub-priority -#ifdef USE_HAL_DRIVER -#define NVIC_PRIORITY_GROUPING NVIC_PRIORITYGROUP_4 -#else -#define NVIC_PRIORITY_GROUPING NVIC_PriorityGroup_4 + +#if defined(AT32F43x) + #define NVIC_PRIORITY_GROUPING NVIC_PRIORITY_GROUP_4 +#else //STM32 + // Use all available bits for priority and zero bits to sub-priority + #ifdef USE_HAL_DRIVER + #define NVIC_PRIORITY_GROUPING NVIC_PRIORITYGROUP_4 + #else + #define NVIC_PRIORITY_GROUPING NVIC_PriorityGroup_4 + #endif #endif diff --git a/src/main/drivers/persistent.c b/src/main/drivers/persistent.c index 43a1b1d0a5..cdb7c69fd7 100644 --- a/src/main/drivers/persistent.c +++ b/src/main/drivers/persistent.c @@ -31,7 +31,35 @@ #define PERSISTENT_OBJECT_MAGIC_VALUE (('i' << 24)|('N' << 16)|('a' << 8)|('v' << 0)) -#ifdef USE_HAL_DRIVER +#if defined(AT32F43x) + + uint32_t persistentObjectRead(persistentObjectId_e id) + { + uint32_t value = ertc_bpr_data_read((ertc_dt_type)id); + return value; + + } + + void persistentObjectWrite(persistentObjectId_e id, uint32_t value) + { + ertc_bpr_data_write((ertc_dt_type)id,value); + } + // examples ertc + void persistentObjectRTCEnable(void) + { + /* enable the pwc clock interface */ + crm_periph_clock_enable(CRM_PWC_PERIPH_CLOCK, TRUE); + + /* allow access to bpr domain */ + pwc_battery_powered_domain_access(TRUE); + + // We don't need a clock source for RTC itself. Skip it. + ertc_write_protect_enable(); + ertc_write_protect_disable(); + + } + +#elif defined(USE_HAL_DRIVER) uint32_t persistentObjectRead(persistentObjectId_e id) { @@ -104,7 +132,9 @@ void persistentObjectInit(void) uint32_t wasSoftReset; -#ifdef STM32H7 +#if defined(AT32F43x) + wasSoftReset = crm_flag_get(CRM_SW_RESET_FLAG); +#elif defined(STM32H7) wasSoftReset = RCC->RSR & RCC_RSR_SFTRSTF; #else wasSoftReset = RCC->CSR & RCC_CSR_SFTRSTF; diff --git a/src/main/drivers/rcc.c b/src/main/drivers/rcc.c index 16a38aed8e..3ca5b153e1 100644 --- a/src/main/drivers/rcc.c +++ b/src/main/drivers/rcc.c @@ -9,55 +9,73 @@ void RCC_ClockCmd(rccPeriphTag_t periphTag, FunctionalState NewState) { int tag = periphTag >> 5; uint32_t mask = 1 << (periphTag & 0x1f); + switch (tag) + { - switch (tag) { + #if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) + case RCC_AHB1: + RCC_BIT_CMD(RCC->AHB1ENR, mask, NewState); + break; -#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) - case RCC_AHB1: - RCC_BIT_CMD(RCC->AHB1ENR, mask, NewState); - break; + case RCC_AHB2: + RCC_BIT_CMD(RCC->AHB2ENR, mask, NewState); + break; + #endif - case RCC_AHB2: - RCC_BIT_CMD(RCC->AHB2ENR, mask, NewState); - break; -#endif + #if defined(STM32H7) + case RCC_AHB3: + RCC_BIT_CMD(RCC->AHB3ENR, mask, NewState); + break; -#if defined(STM32H7) - case RCC_AHB3: - RCC_BIT_CMD(RCC->AHB3ENR, mask, NewState); - break; + case RCC_AHB4: + RCC_BIT_CMD(RCC->AHB4ENR, mask, NewState); + break; - case RCC_AHB4: - RCC_BIT_CMD(RCC->AHB4ENR, mask, NewState); - break; + case RCC_APB1L: + RCC_BIT_CMD(RCC->APB1LENR, mask, NewState); + break; - case RCC_APB1L: - RCC_BIT_CMD(RCC->APB1LENR, mask, NewState); - break; + case RCC_APB1H: + RCC_BIT_CMD(RCC->APB1HENR, mask, NewState); + break; - case RCC_APB1H: - RCC_BIT_CMD(RCC->APB1HENR, mask, NewState); - break; + case RCC_APB3: + RCC_BIT_CMD(RCC->APB3ENR, mask, NewState); + break; - case RCC_APB3: - RCC_BIT_CMD(RCC->APB3ENR, mask, NewState); - break; + case RCC_APB4: + RCC_BIT_CMD(RCC->APB4ENR, mask, NewState); + break; + #endif - case RCC_APB4: - RCC_BIT_CMD(RCC->APB4ENR, mask, NewState); - break; -#endif + #if defined(AT32F43x) + case RCC_AHB1: + RCC_BIT_CMD(CRM->ahben1, mask, NewState); + break; -#if !(defined(STM32H7) || defined(STM32G4)) - case RCC_APB1: - RCC_BIT_CMD(RCC->APB1ENR, mask, NewState); - break; -#endif + case RCC_AHB2: + RCC_BIT_CMD(CRM->ahben2, mask, NewState); + break; - case RCC_APB2: - RCC_BIT_CMD(RCC->APB2ENR, mask, NewState); - break; + case RCC_APB1: + RCC_BIT_CMD(CRM->apb1en, mask, NewState); + break; + case RCC_APB2: + RCC_BIT_CMD(CRM->apb2en, mask, NewState); + break; + #else + #if !(defined(STM32H7) || defined(STM32G4)) + case RCC_APB1: + RCC_BIT_CMD(RCC->APB1ENR, mask, NewState); + break; + #endif + + case RCC_APB2: + RCC_BIT_CMD(RCC->APB2ENR, mask, NewState); + break; + + #endif } } @@ -66,52 +84,70 @@ void RCC_ResetCmd(rccPeriphTag_t periphTag, FunctionalState NewState) int tag = periphTag >> 5; uint32_t mask = 1 << (periphTag & 0x1f); - switch (tag) { + switch (tag) + { + + #if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) + case RCC_AHB1: + RCC_BIT_CMD(RCC->AHB1RSTR, mask, NewState); + break; -#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) - case RCC_AHB1: - RCC_BIT_CMD(RCC->AHB1RSTR, mask, NewState); - break; + case RCC_AHB2: + RCC_BIT_CMD(RCC->AHB2RSTR, mask, NewState); + break; + #endif - case RCC_AHB2: - RCC_BIT_CMD(RCC->AHB2RSTR, mask, NewState); - break; -#endif + #if defined(STM32H7) + case RCC_AHB3: + RCC_BIT_CMD(RCC->AHB3RSTR, mask, NewState); + break; -#if defined(STM32H7) - case RCC_AHB3: - RCC_BIT_CMD(RCC->AHB3RSTR, mask, NewState); - break; + case RCC_AHB4: + RCC_BIT_CMD(RCC->AHB4RSTR, mask, NewState); + break; - case RCC_AHB4: - RCC_BIT_CMD(RCC->AHB4RSTR, mask, NewState); - break; + case RCC_APB1L: + RCC_BIT_CMD(RCC->APB1LRSTR, mask, NewState); + break; - case RCC_APB1L: - RCC_BIT_CMD(RCC->APB1LRSTR, mask, NewState); - break; + case RCC_APB1H: + RCC_BIT_CMD(RCC->APB1HRSTR, mask, NewState); + break; - case RCC_APB1H: - RCC_BIT_CMD(RCC->APB1HRSTR, mask, NewState); - break; + case RCC_APB3: + RCC_BIT_CMD(RCC->APB3RSTR, mask, NewState); + break; - case RCC_APB3: - RCC_BIT_CMD(RCC->APB3RSTR, mask, NewState); - break; + case RCC_APB4: + RCC_BIT_CMD(RCC->APB4RSTR, mask, NewState); + break; + #endif + + #if defined(AT32F43x) + case RCC_AHB1: + RCC_BIT_CMD(CRM->ahbrst1, mask, NewState); + break; + case RCC_AHB2: + RCC_BIT_CMD(CRM->ahbrst2, mask, NewState); + break; + case RCC_APB1: + RCC_BIT_CMD(CRM->apb1rst, mask, NewState); + break; + case RCC_APB2: + RCC_BIT_CMD(CRM->apb2rst, mask, NewState); + break; - case RCC_APB4: - RCC_BIT_CMD(RCC->APB4RSTR, mask, NewState); - break; -#endif - -#if !(defined(STM32H7) || defined(STM32G4)) - case RCC_APB1: - RCC_BIT_CMD(RCC->APB1RSTR, mask, NewState); - break; -#endif - - case RCC_APB2: - RCC_BIT_CMD(RCC->APB2RSTR, mask, NewState); - break; + #else + #if !(defined(STM32H7) || defined(STM32G4)) + case RCC_APB1: + RCC_BIT_CMD(RCC->APB1RSTR, mask, NewState); + break; + #endif + + + case RCC_APB2: + RCC_BIT_CMD(RCC->APB2RSTR, mask, NewState); + break; + #endif } } diff --git a/src/main/drivers/rcc.h b/src/main/drivers/rcc.h index 2f8c8928bf..8e97286b3e 100644 --- a/src/main/drivers/rcc.h +++ b/src/main/drivers/rcc.h @@ -1,14 +1,14 @@ #pragma once #include "rcc_types.h" +#include "rcc_at32f43x_periph.h" enum rcc_reg { RCC_EMPTY = 0, // make sure that default value (0) does not enable anything - - RCC_AHB, - RCC_APB2, - RCC_APB1, - RCC_AHB1, + RCC_AHB, //0x20 + RCC_APB2, //0x40 CRM->apb2en + RCC_APB1, //0x60 CRM->apb1en end AT32 + RCC_AHB1, //0x80 RCC_AHB2, RCC_APB1L, RCC_APB1H, @@ -17,12 +17,23 @@ enum rcc_reg { RCC_AHB4, RCC_APB4 }; - + #define RCC_ENCODE(reg, mask) (((reg) << 5) | LOG2_32BIT(mask)) + +#ifdef AT32F43x + +#define RCC_AHB1(periph) RCC_ENCODE(RCC_AHB1, CRM_AHB1_ ## periph ## _PER_MASK) +#define RCC_AHB2(periph) RCC_ENCODE(RCC_AHB2, CRM_AHB2_ ## periph ## _PER_MASK) +#define RCC_AHB3(periph) RCC_ENCODE(RCC_AHB3, CRM_AHB3_ ## periph ## _PER_MASK) +#define RCC_APB1(periph) RCC_ENCODE(RCC_APB1, CRM_APB1_ ## periph ## _PER_MASK) +#define RCC_APB2(periph) RCC_ENCODE(RCC_APB2, CRM_APB2_ ## periph ## _PER_MASK) + +#else #define RCC_AHB(periph) RCC_ENCODE(RCC_AHB, RCC_AHBENR_ ## periph ## EN) #define RCC_AHB1(periph) RCC_ENCODE(RCC_AHB1, RCC_AHB1ENR_ ## periph ## EN) #define RCC_APB1(periph) RCC_ENCODE(RCC_APB1, RCC_APB1ENR_ ## periph ## EN) #define RCC_APB2(periph) RCC_ENCODE(RCC_APB2, RCC_APB2ENR_ ## periph ## EN) +#endif #ifdef STM32H7 #define RCC_AHB2(periph) RCC_ENCODE(RCC_AHB2, RCC_AHB2ENR_ ## periph ## EN) diff --git a/src/main/drivers/rcc_at32f43x_periph.h b/src/main/drivers/rcc_at32f43x_periph.h new file mode 100644 index 0000000000..3452904380 --- /dev/null +++ b/src/main/drivers/rcc_at32f43x_periph.h @@ -0,0 +1,88 @@ +/* + * rcc_at32f43x_periph.h + * + * Created on: 2022/3/19 + * Author: emsr (shanggl@wo.cn) + * + * The corresponding enable and reset bits are defined for each peripheral of at32, modeled after hal library + * offset= log2(mask) + */ + +#ifndef MAIN_DRIVERS_RCC_AT32F43X_PERIPH_H_ +#define MAIN_DRIVERS_RCC_AT32F43X_PERIPH_H_ + + +/******************** Bit definition for AT32F437 CRM PERIPH MASK ***************/ +/* AHB offset 0x30 */ +#define CRM_AHB1_GPIOA_PER_MASK ((uint32_t)0x00000001) /*!< gpiob periph clock */ +#define CRM_AHB1_GPIOB_PER_MASK ((uint32_t)0x00000002) /*!< gpiob periph clock */ +#define CRM_AHB1_GPIOC_PER_MASK ((uint32_t)0x00000004) /*!< gpioc periph clock */ +#define CRM_AHB1_GPIOD_PER_MASK ((uint32_t)0x00000008) /*!< gpiod periph clock */ +#define CRM_AHB1_GPIOE_PER_MASK ((uint32_t)0x00000010) /*!< gpioe periph clock */ +#define CRM_AHB1_GPIOF_PER_MASK ((uint32_t)0x00000020) /*!< gpiof periph clock */ +#define CRM_AHB1_GPIOG_PER_MASK ((uint32_t)0x00000040) /*!< gpiog periph clock */ +#define CRM_AHB1_GPIOH_PER_MASK ((uint32_t)0x00000080) /*!< gpioh periph clock */ +#define CRM_AHB1_CRC_PER_MASK ((uint32_t)0x00001000) /*!< crc periph clock */ +#define CRM_AHB1_EDMA_PER_MASK ((uint32_t)0x00200000) /*!< edma periph clock */ +#define CRM_AHB1_DMA1_PER_MASK ((uint32_t)0x00400000) /*!< dma1 periph clock */ +#define CRM_AHB1_DMA2_PER_MASK ((uint32_t)0x01000000) /*!< dma2 periph clock */ +#define CRM_AHB1_EMAC_PER_MASK ((uint32_t)0x02000000) /*!< emac periph clock */ +#define CRM_AHB1_EMACTX_PER_MASK ((uint32_t)0x04000000) /*!< emac tx periph clock */ +#define CRM_AHB1_EMACRX_PER_MASK ((uint32_t)0x08000000) /*!< emac rx periph clock */ +#define CRM_AHB1_EMACPTP_PER_MASK ((uint32_t)0x10000000) /*!< emac ptp periph clock */ +#define CRM_AHB1_OTGFS2_PER_MASK ((uint32_t)0x20000000) /*!< otgfs2 periph clock */ + /* ahb periph2 offset 0x34*/ +#define CRM_AHB2_DVP_PER_MASK ((uint32_t)0x00000001) /*!< dvp periph clock */ +#define CRM_AHB2_OTGFS1_PER_MASK ((uint32_t)0x00000080) /*!< otgfs1 periph clock */ +#define CRM_AHB2_SDIO1_PER_MASK ((uint32_t)0x00008000) /*!< sdio1 periph clock */ + /* ahb periph3 offset 0x38 */ +#define CRM_AHB3_XMC_PER_MASK ((uint32_t)0x00000001) /*!< xmc periph clock */ +#define CRM_AHB3_QSPI1_PER_MASK ((uint32_t)0x00000002) /*!< qspi1 periph clock */ +#define CRM_AHB3_QSPI2_PER_MASK ((uint32_t)0x00004000) /*!< qspi2 periph clock */ +#define CRM_AHB3_SDIO2_PER_MASK ((uint32_t)0x00008000) /*!< sdio2 periph clock */ + /* apb1 periph offset 0x40 */ +#define CRM_APB1_TMR2_PER_MASK ((uint32_t)0x00000001) /*!< tmr2 periph clock */ +#define CRM_APB1_TMR3_PER_MASK ((uint32_t)0x00000002) /*!< tmr3 periph clock */ +#define CRM_APB1_TMR4_PER_MASK ((uint32_t)0x00000004) /*!< tmr4 periph clock */ +#define CRM_APB1_TMR5_PER_MASK ((uint32_t)0x00000008) /*!< tmr5 periph clock */ +#define CRM_APB1_TMR6_PER_MASK ((uint32_t)0x00000010) /*!< tmr6 periph clock */ +#define CRM_APB1_TMR7_PER_MASK ((uint32_t)0x00000020) /*!< tmr7 periph clock */ +#define CRM_APB1_TMR12_PER_MASK ((uint32_t)0x00000040) /*!< tmr12 periph clock */ +#define CRM_APB1_TMR13_PER_MASK ((uint32_t)0x00000080) /*!< tmr13 periph clock */ +#define CRM_APB1_TMR14_PER_MASK ((uint32_t)0x00000100) /*!< tmr14 periph clock */ +#define CRM_APB1_WWDT_PER_MASK ((uint32_t)0x00000800) /*!< wwdt periph clock */ +#define CRM_APB1_SPI2_PER_MASK ((uint32_t)0x00004000) /*!< spi2 periph clock */ +#define CRM_APB1_SPI3_PER_MASK ((uint32_t)0x00008000) /*!< spi3 periph clock */ +#define CRM_APB1_USART2_PER_MASK ((uint32_t)0x00020000) /*!< usart2 periph clock */ +#define CRM_APB1_USART3_PER_MASK ((uint32_t)0x00040000) /*!< usart3 periph clock */ +#define CRM_APB1_UART4_PER_MASK ((uint32_t)0x00080000) /*!< uart4 periph clock */ +#define CRM_APB1_UART5_PER_MASK ((uint32_t)0x00100000) /*!< uart5 periph clock */ +#define CRM_APB1_I2C1_PER_MASK ((uint32_t)0x00200000) /*!< i2c1 periph clock */ +#define CRM_APB1_I2C2_PER_MASK ((uint32_t)0x00400000) /*!< i2c2 periph clock */ +#define CRM_APB1_I2C3_PER_MASK ((uint32_t)0x00800000) /*!< i2c3 periph clock */ +#define CRM_APB1_CAN1_PER_MASK ((uint32_t)0x02000000) /*!< can1 periph clock */ +#define CRM_APB1_CAN2_PER_MASK ((uint32_t)0x04000000) /*!< can2 periph clock */ +#define CRM_APB1_PWC_PER_MASK ((uint32_t)0x10000000) /*!< pwc periph clock */ +#define CRM_APB1_DAC_PER_MASK ((uint32_t)0x20000000) /*!< dac periph clock */ +#define CRM_APB1_UART7_PER_MASK ((uint32_t)0x40000000) /*!< uart7 periph clock */ +#define CRM_APB1_UART8_PER_MASK ((uint32_t)0x80000000) /*!< uart8 periph clock */ + /* apb2 periph offset 0x44 */ +#define CRM_APB2_TMR1_PER_MASK ((uint32_t)0x00000001) /*!< tmr1 periph clock */ +#define CRM_APB2_TMR8_PER_MASK ((uint32_t)0x00000002) /*!< tmr8 periph clock */ +#define CRM_APB2_USART1_PER_MASK ((uint32_t)0x00000010) /*!< usart1 periph clock */ +#define CRM_APB2_USART6_PER_MASK ((uint32_t)0x00000020) /*!< usart6 periph clock */ +#define CRM_APB2_ADC1_PER_MASK ((uint32_t)0x00000100) /*!< adc1 periph clock */ +#define CRM_APB2_ADC2_PER_MASK ((uint32_t)0x00000200) /*!< adc2 periph clock */ +#define CRM_APB2_ADC3_PER_MASK ((uint32_t)0x00000400) /*!< adc3 periph clock */ +#define CRM_APB2_SPI1_PER_MASK ((uint32_t)0x00001000) /*!< spi1 periph clock */ +#define CRM_APB2_SPI4_PER_MASK ((uint32_t)0x00002000) /*!< spi4 periph clock */ +#define CRM_APB2_SCFG_PER_MASK ((uint32_t)0x00004000) /*!< scfg periph clock */ +#define CRM_APB2_TMR9_PER_MASK ((uint32_t)0x00010000) /*!< tmr9 periph clock */ +#define CRM_APB2_TMR10_PER_MASK ((uint32_t)0x00020000) /*!< tmr10 periph clock */ +#define CRM_APB2_TMR11_PER_MASK ((uint32_t)0x00040000) /*!< tmr11 periph clock */ +#define CRM_APB2_TMR20_PER_MASK ((uint32_t)0x00100000) /*!< tmr20 periph clock */ +#define CRM_APB2_ACC_PER_MASK ((uint32_t)0x20000000) /*!< acc periph clock */ + + + +#endif /* MAIN_DRIVERS_RCC_AT32F43X_PERIPH_H_ */ diff --git a/src/main/drivers/sdcard/sdmmc_sdio.h b/src/main/drivers/sdcard/sdmmc_sdio.h index fe36410d09..f488d334f9 100644 --- a/src/main/drivers/sdcard/sdmmc_sdio.h +++ b/src/main/drivers/sdcard/sdmmc_sdio.h @@ -42,6 +42,10 @@ #ifdef STM32H7 #include "stm32h7xx.h" +#endif + +#ifdef AT32F43x +#include "at32f435_437.h" #endif /* SDCARD pinouts @@ -215,7 +219,12 @@ typedef struct extern SD_CardInfo_t SD_CardInfo; extern SD_CardType_t SD_CardType; -bool SD_Initialize_LL(DMA_Stream_TypeDef * dmaRef); +#ifdef AT32F43x +// TODO:AT32 TARGES NOT USE SD CARD ANT TF CARD FOR NOW +void SD_Initialize_LL (dma_channel_type *dma); +#else +bool SD_Initialize_LL (DMA_Stream_TypeDef *dma); +#endif bool SD_Init(void); bool SD_IsDetected(void); bool SD_GetState(void); diff --git a/src/main/drivers/serial_uart.h b/src/main/drivers/serial_uart.h index 75d04a6d69..b8e7202612 100644 --- a/src/main/drivers/serial_uart.h +++ b/src/main/drivers/serial_uart.h @@ -56,17 +56,24 @@ typedef enum { typedef struct { serialPort_t port; -#ifdef USE_HAL_DRIVER - UART_HandleTypeDef Handle; -#endif - - USART_TypeDef *USARTx; + #if defined(AT32F43x) + usart_type *USARTx; + #else + #ifdef USE_HAL_DRIVER + UART_HandleTypeDef Handle; + #endif + USART_TypeDef *USARTx; + #endif + } uartPort_t; void uartGetPortPins(UARTDevice_e device, serialPortPins_t * pins); void uartClearIdleFlag(uartPort_t *s); +#if defined(AT32F43x) +serialPort_t *uartOpen(usart_type *USARTx, serialReceiveCallbackPtr rxCallback, void *rxCallbackData, uint32_t baudRate, portMode_t mode, portOptions_t options); +#else serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr rxCallback, void *rxCallbackData, uint32_t baudRate, portMode_t mode, portOptions_t options); - +#endif // serialPort API void uartWrite(serialPort_t *instance, uint8_t ch); uint32_t uartTotalRxBytesWaiting(const serialPort_t *instance); diff --git a/src/main/drivers/serial_uart_at32f43x.c b/src/main/drivers/serial_uart_at32f43x.c new file mode 100644 index 0000000000..354ea6c934 --- /dev/null +++ b/src/main/drivers/serial_uart_at32f43x.c @@ -0,0 +1,431 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include +#include + +#include "platform.h" + +#include "drivers/time.h" +#include "drivers/io.h" +#include "rcc.h" +#include "drivers/nvic.h" + +#include "serial.h" +#include "serial_uart.h" +#include "serial_uart_impl.h" + +#define UART_RX_BUFFER_SIZE UART1_RX_BUFFER_SIZE +#define UART_TX_BUFFER_SIZE UART1_RX_BUFFER_SIZE + +typedef struct uartDevice_s { + usart_type* dev; + uartPort_t port; + ioTag_t rx; + ioTag_t tx; + volatile uint8_t rxBuffer[UART_RX_BUFFER_SIZE]; + volatile uint8_t txBuffer[UART_TX_BUFFER_SIZE]; + uint32_t rcc_ahb1; + rccPeriphTag_t rcc_apb2; + rccPeriphTag_t rcc_apb1; + uint8_t af; + uint8_t irq; + uint32_t irqPriority; +} uartDevice_t; + +#ifdef USE_UART1 +static uartDevice_t uart1 = +{ + .dev = USART1, + .rx = IO_TAG(UART1_RX_PIN), + .tx = IO_TAG(UART1_TX_PIN), + .af = GPIO_MUX_7, +#ifdef UART1_AHB1_PERIPHERALS + .rcc_ahb1 = UART1_AHB1_PERIPHERALS, +#endif + .rcc_apb2 = RCC_APB2(USART1), + .irq = USART1_IRQn, + .irqPriority = NVIC_PRIO_SERIALUART +}; +#endif + +#ifdef USE_UART2 +static uartDevice_t uart2 = +{ + .dev = USART2, + .rx = IO_TAG(UART2_RX_PIN), + .tx = IO_TAG(UART2_TX_PIN), + .af = GPIO_MUX_7, +#ifdef UART2_AHB1_PERIPHERALS + .rcc_ahb1 = UART2_AHB1_PERIPHERALS, +#endif + .rcc_apb1 = RCC_APB1(USART2), + .irq = USART2_IRQn, + .irqPriority = NVIC_PRIO_SERIALUART +}; +#endif + +#ifdef USE_UART3 +static uartDevice_t uart3 = +{ + .dev = USART3, + .rx = IO_TAG(UART3_RX_PIN), + .tx = IO_TAG(UART3_TX_PIN), + .af = GPIO_MUX_7, +#ifdef UART3_AHB1_PERIPHERALS + .rcc_ahb1 = UART3_AHB1_PERIPHERALS, +#endif + .rcc_apb1 = RCC_APB1(USART3), + .irq = USART3_IRQn, + .irqPriority = NVIC_PRIO_SERIALUART +}; +#endif + +#ifdef USE_UART4 +static uartDevice_t uart4 = +{ + .dev = UART4, + .rx = IO_TAG(UART4_RX_PIN), + .tx = IO_TAG(UART4_TX_PIN), + .af = GPIO_MUX_8, +#ifdef UART4_AHB1_PERIPHERALS + .rcc_ahb1 = UART4_AHB1_PERIPHERALS, +#endif + .rcc_apb1 = RCC_APB1(UART4), + .irq = UART4_IRQn, + .irqPriority = NVIC_PRIO_SERIALUART +}; +#endif + +#ifdef USE_UART5 +static uartDevice_t uart5 = +{ + .dev = UART5, + .rx = IO_TAG(UART5_RX_PIN), + .tx = IO_TAG(UART5_TX_PIN), + .af = GPIO_MUX_8, +#ifdef UART5_AHB1_PERIPHERALS + .rcc_ahb1 = UART5_AHB1_PERIPHERALS, +#endif + .rcc_apb1 = RCC_APB1(UART5), + .irq = UART5_IRQn, + .irqPriority = NVIC_PRIO_SERIALUART +}; +#endif + +#ifdef USE_UART6 +static uartDevice_t uart6 = +{ + .dev = USART6, + .rx = IO_TAG(UART6_RX_PIN), + .tx = IO_TAG(UART6_TX_PIN), + .af = GPIO_MUX_8, +#ifdef UART6_AHB1_PERIPHERALS + .rcc_ahb1 = UART6_AHB1_PERIPHERALS, +#endif + .rcc_apb2 = RCC_APB2(USART6), + .irq = USART6_IRQn, + .irqPriority = NVIC_PRIO_SERIALUART +}; +#endif + +#ifdef USE_UART7 +static uartDevice_t uart7 = +{ + .dev = UART7, + .rx = IO_TAG(UART7_RX_PIN), + .tx = IO_TAG(UART7_TX_PIN), + .af = GPIO_MUX_8, + .rcc_apb1 = RCC_APB1(UART7), + .irq = UART7_IRQn, + .irqPriority = NVIC_PRIO_SERIALUART +}; +#endif + +#ifdef USE_UART8 +static uartDevice_t uart8 = +{ + .dev = UART8, + .rx = IO_TAG(UART8_RX_PIN), + .tx = IO_TAG(UART8_TX_PIN), + .af = GPIO_MUX_8, + .rcc_apb1 = RCC_APB1(UART8), + .irq = UART8_IRQn, + .irqPriority = NVIC_PRIO_SERIALUART +}; +#endif + +static uartDevice_t* uartHardwareMap[] = { +#ifdef USE_UART1 + &uart1, +#else + NULL, +#endif +#ifdef USE_UART2 + &uart2, +#else + NULL, +#endif +#ifdef USE_UART3 + &uart3, +#else + NULL, +#endif +#ifdef USE_UART4 + &uart4, +#else + NULL, +#endif +#ifdef USE_UART5 + &uart5, +#else + NULL, +#endif +#ifdef USE_UART6 + &uart6, +#else + NULL, +#endif +#ifdef USE_UART7 + &uart7, +#else + NULL, +#endif +#ifdef USE_UART8 + &uart8, +#else + NULL, +#endif + }; + +void uartIrqHandler(uartPort_t *s) +{ + if (usart_flag_get(s->USARTx, USART_RDBF_FLAG) == SET) { + if (s->port.rxCallback) { + s->port.rxCallback(s->USARTx->dt, s->port.rxCallbackData); + } else { + s->port.rxBuffer[s->port.rxBufferHead] = s->USARTx->dt; + s->port.rxBufferHead = (s->port.rxBufferHead + 1) % s->port.rxBufferSize; + } + } + + if (usart_flag_get(s->USARTx, USART_TDBE_FLAG) == SET) { + if (s->port.txBufferTail != s->port.txBufferHead) { + usart_data_transmit(s->USARTx, s->port.txBuffer[s->port.txBufferTail]); + s->port.txBufferTail = (s->port.txBufferTail + 1) % s->port.txBufferSize; + } else { + usart_interrupt_enable (s->USARTx, USART_TDBE_INT, FALSE); + } + } + + if (usart_flag_get(s->USARTx, USART_ROERR_FLAG) == SET) + { + usart_flag_clear(s->USARTx, USART_ROERR_FLAG); + } +} + +void uartGetPortPins(UARTDevice_e device, serialPortPins_t * pins) +{ + uartDevice_t *uart = uartHardwareMap[device]; + + if (uart) { + pins->txPin = uart->tx; + pins->rxPin = uart->rx; + } + else { + pins->txPin = IO_TAG(NONE); + pins->rxPin = IO_TAG(NONE); + } +} + +void uartClearIdleFlag(uartPort_t *s) +{ + (void) s->USARTx->sts; + (void) s->USARTx->dt; +} + +uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_t mode, portOptions_t options) +{ + uartPort_t *s; + + uartDevice_t *uart = uartHardwareMap[device]; + if (!uart) return NULL; + + s = &(uart->port); + s->port.vTable = uartVTable; + + s->port.baudRate = baudRate; + + s->port.rxBuffer = uart->rxBuffer; + s->port.txBuffer = uart->txBuffer; + s->port.rxBufferSize = sizeof(uart->rxBuffer); + s->port.txBufferSize = sizeof(uart->txBuffer); + + s->USARTx = uart->dev; + + IO_t tx = IOGetByTag(uart->tx); + IO_t rx = IOGetByTag(uart->rx); + + if (uart->rcc_apb2) + RCC_ClockCmd(uart->rcc_apb2, ENABLE); + + if (uart->rcc_apb1) + RCC_ClockCmd(uart->rcc_apb1, ENABLE); + + if (uart->rcc_ahb1) + RCC_ClockCmd(uart->rcc_apb1, ENABLE); + + if (options & SERIAL_BIDIR) { + IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TXRX, RESOURCE_INDEX(device)); + if (options & SERIAL_BIDIR_PP) { + IOConfigGPIOAF(tx, IOCFG_AF_PP, uart->af); + } else { + IOConfigGPIOAF(tx, + (options & SERIAL_BIDIR_NOPULL) ? IOCFG_AF_OD : IOCFG_AF_OD_UP, + uart->af); + } + } + else { + if (mode & MODE_TX) { + IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TX, RESOURCE_INDEX(device)); + IOConfigGPIOAF(tx, IOCFG_AF_PP, uart->af); + } + + if (mode & MODE_RX) { + IOInit(rx, OWNER_SERIAL, RESOURCE_UART_RX, RESOURCE_INDEX(device)); + IOConfigGPIOAF(rx, IOCFG_AF_PP, uart->af); + } + } + + nvic_irq_enable(uart->irq, uart->irqPriority, 0); + + + return s; +} + +#ifdef USE_UART1 +uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t options) +{ + return serialUART(UARTDEV_1, baudRate, mode, options); +} + +// USART1 Rx/Tx IRQ Handler +void USART1_IRQHandler(void) +{ + uartPort_t *s = &(uartHardwareMap[UARTDEV_1]->port); + uartIrqHandler(s); +} + +#endif + +#ifdef USE_UART2 +// USART2 (RX + TX by IRQ) +uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t options) +{ + return serialUART(UARTDEV_2, baudRate, mode, options); +} + +void USART2_IRQHandler(void) +{ + uartPort_t *s = &(uartHardwareMap[UARTDEV_2]->port); + uartIrqHandler(s); +} +#endif + +#ifdef USE_UART3 +// USART3 +uartPort_t *serialUART3(uint32_t baudRate, portMode_t mode, portOptions_t options) +{ + return serialUART(UARTDEV_3, baudRate, mode, options); +} + +void USART3_IRQHandler(void) +{ + uartPort_t *s = &(uartHardwareMap[UARTDEV_3]->port); + uartIrqHandler(s); +} +#endif + +#ifdef USE_UART4 +// USART4 +uartPort_t *serialUART4(uint32_t baudRate, portMode_t mode, portOptions_t options) +{ + return serialUART(UARTDEV_4, baudRate, mode, options); +} + +void UART4_IRQHandler(void) +{ + uartPort_t *s = &(uartHardwareMap[UARTDEV_4]->port); + uartIrqHandler(s); +} +#endif + +#ifdef USE_UART5 +// USART5 +uartPort_t *serialUART5(uint32_t baudRate, portMode_t mode, portOptions_t options) +{ + return serialUART(UARTDEV_5, baudRate, mode, options); +} + +void UART5_IRQHandler(void) +{ + uartPort_t *s = &(uartHardwareMap[UARTDEV_5]->port); + uartIrqHandler(s); +} +#endif + +#ifdef USE_UART6 +// USART6 +uartPort_t *serialUART6(uint32_t baudRate, portMode_t mode, portOptions_t options) +{ + return serialUART(UARTDEV_6, baudRate, mode, options); +} + +void USART6_IRQHandler(void) +{ + uartPort_t *s = &(uartHardwareMap[UARTDEV_6]->port); + uartIrqHandler(s); +} +#endif + +#ifdef USE_UART7 +uartPort_t *serialUART7(uint32_t baudRate, portMode_t mode, portOptions_t options) +{ + return serialUART(UARTDEV_7, baudRate, mode, options); +} + +// UART7 Rx/Tx IRQ Handler +void UART7_IRQHandler(void) +{ + uartPort_t *s = &(uartHardwareMap[UARTDEV_7]->port); + uartIrqHandler(s); +} +#endif + +#ifdef USE_UART8 +uartPort_t *serialUART8(uint32_t baudRate, portMode_t mode, portOptions_t options) +{ + return serialUART(UARTDEV_8, baudRate, mode, options); +} + +// UART8 Rx/Tx IRQ Handler +void UART8_IRQHandler(void) +{ + uartPort_t *s = &(uartHardwareMap[UARTDEV_8]->port); + uartIrqHandler(s); +} +#endif diff --git a/src/main/drivers/serial_uart_hal_at32f43x.c b/src/main/drivers/serial_uart_hal_at32f43x.c new file mode 100644 index 0000000000..0e0f11b1c1 --- /dev/null +++ b/src/main/drivers/serial_uart_hal_at32f43x.c @@ -0,0 +1,269 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +/* + * Authors: + * Dominic Clifton - Serial port abstraction, Separation of common STM32 code for cleanflight, various cleanups. + * Hamasaki/Timecop - Initial baseflight code +*/ +#include +#include + +#include "platform.h" + +#include "build/build_config.h" + +#include "common/utils.h" + +#include "drivers/uart_inverter.h" + +#include "serial.h" +#include "serial_uart.h" +#include "serial_uart_impl.h" + +static void usartConfigurePinInversion(uartPort_t *uartPort) { +#if !defined(USE_UART_INVERTER) + UNUSED(uartPort); +#else + bool inverted = uartPort->port.options & SERIAL_INVERTED; + +#ifdef USE_UART_INVERTER + uartInverterLine_e invertedLines = UART_INVERTER_LINE_NONE; + if (uartPort->port.mode & MODE_RX) { + invertedLines |= UART_INVERTER_LINE_RX; + } + if (uartPort->port.mode & MODE_TX) { + invertedLines |= UART_INVERTER_LINE_TX; + } + uartInverterSet(uartPort->USARTx, invertedLines, inverted); +#endif + +#endif +} + +static void uartReconfigure(uartPort_t *uartPort) +{ + usart_enable(uartPort->USARTx, FALSE); + uint32_t baud_rate = 115200; + usart_data_bit_num_type data_bit = USART_DATA_8BITS; + usart_stop_bit_num_type stop_bit = USART_STOP_1_BIT; + usart_parity_selection_type parity_type = USART_PARITY_EVEN; + + baud_rate = uartPort->port.baudRate; + stop_bit = (uartPort->port.options & SERIAL_STOPBITS_2) ? USART_STOP_2_BIT : USART_STOP_1_BIT; + + // according to the stm32 documentation wordlen has to be 9 for parity bits + // this does not seem to matter for rx but will give bad data on tx! + if (uartPort->port.options & SERIAL_PARITY_EVEN) { + data_bit = USART_DATA_9BITS; + } else { + data_bit = USART_DATA_8BITS; + } + usart_init(uartPort->USARTx, baud_rate, data_bit, stop_bit); + + parity_type = (uartPort->port.options & SERIAL_PARITY_EVEN) ? USART_PARITY_EVEN : USART_PARITY_NONE; + usart_parity_selection_config(uartPort->USARTx, parity_type); + usart_hardware_flow_control_set (uartPort->USARTx, USART_HARDWARE_FLOW_NONE); + + if (uartPort->port.mode & MODE_RX) + usart_receiver_enable(uartPort->USARTx, TRUE); + if (uartPort->port.mode & MODE_TX) + usart_transmitter_enable(uartPort->USARTx, TRUE); + + usartConfigurePinInversion(uartPort); + + if (uartPort->port.options & SERIAL_BIDIR) + usart_single_line_halfduplex_select(uartPort->USARTx, TRUE); + else + usart_single_line_halfduplex_select(uartPort->USARTx, FALSE); + + usart_enable(uartPort->USARTx, TRUE); +} + +serialPort_t *uartOpen(usart_type *USARTx, serialReceiveCallbackPtr rxCallback, void *rxCallbackData, uint32_t baudRate, portMode_t mode, portOptions_t options) +{ + uartPort_t *s = NULL; + + if (false) { +#ifdef USE_UART1 + } else if (USARTx == USART1) { + s = serialUART1(baudRate, mode, options); + +#endif +#ifdef USE_UART2 + } else if (USARTx == USART2) { + s = serialUART2(baudRate, mode, options); +#endif +#ifdef USE_UART3 + } else if (USARTx == USART3) { + s = serialUART3(baudRate, mode, options); +#endif +#ifdef USE_UART4 + } else if (USARTx == UART4) { + s = serialUART4(baudRate, mode, options); +#endif +#ifdef USE_UART5 + } else if (USARTx == UART5) { + s = serialUART5(baudRate, mode, options); +#endif +#ifdef USE_UART6 + } else if (USARTx == USART6) { + s = serialUART6(baudRate, mode, options); +#endif +#ifdef USE_UART7 + } else if (USARTx == UART7) { + s = serialUART7(baudRate, mode, options); +#endif +#ifdef USE_UART8 + } else if (USARTx == UART8) { + s = serialUART8(baudRate, mode, options); +#endif + + } else { + return (serialPort_t *)s; + } + + // common serial initialisation code should move to serialPort::init() + s->port.rxBufferHead = s->port.rxBufferTail = 0; + s->port.txBufferHead = s->port.txBufferTail = 0; + // callback works for IRQ-based RX ONLY + s->port.rxCallback = rxCallback; + s->port.rxCallbackData = rxCallbackData; + s->port.mode = mode; + s->port.baudRate = baudRate; + s->port.options = options; + + uartReconfigure(s); + + if (mode & MODE_RX) { + usart_flag_clear(s->USARTx, USART_RDBF_FLAG); + usart_interrupt_enable (s->USARTx, USART_RDBF_INT, TRUE); + + } + + if (mode & MODE_TX) { + usart_interrupt_enable (s->USARTx, USART_TDBE_INT, TRUE); + + } + usart_enable(s->USARTx, TRUE); + + return (serialPort_t *)s; +} + +void uartSetBaudRate(serialPort_t *instance, uint32_t baudRate) +{ + uartPort_t *uartPort = (uartPort_t *)instance; + uartPort->port.baudRate = baudRate; + uartReconfigure(uartPort); +} + +void uartSetMode(serialPort_t *instance, portMode_t mode) +{ + uartPort_t *uartPort = (uartPort_t *)instance; + uartPort->port.mode = mode; + uartReconfigure(uartPort); +} + +uint32_t uartTotalRxBytesWaiting(const serialPort_t *instance) +{ + const uartPort_t *s = (const uartPort_t*)instance; + + if (s->port.rxBufferHead >= s->port.rxBufferTail) { + return s->port.rxBufferHead - s->port.rxBufferTail; + } else { + return s->port.rxBufferSize + s->port.rxBufferHead - s->port.rxBufferTail; + } +} + +uint32_t uartTotalTxBytesFree(const serialPort_t *instance) +{ + const uartPort_t *s = (const uartPort_t*)instance; + + uint32_t bytesUsed; + + if (s->port.txBufferHead >= s->port.txBufferTail) { + bytesUsed = s->port.txBufferHead - s->port.txBufferTail; + } else { + bytesUsed = s->port.txBufferSize + s->port.txBufferHead - s->port.txBufferTail; + } + + return (s->port.txBufferSize - 1) - bytesUsed; +} + +bool isUartTransmitBufferEmpty(const serialPort_t *instance) +{ + const uartPort_t *s = (const uartPort_t *)instance; + return s->port.txBufferTail == s->port.txBufferHead; +} + +uint8_t uartRead(serialPort_t *instance) +{ + uint8_t ch; + uartPort_t *s = (uartPort_t *)instance; + + ch = s->port.rxBuffer[s->port.rxBufferTail]; + if (s->port.rxBufferTail + 1 >= s->port.rxBufferSize) { + s->port.rxBufferTail = 0; + } else { + s->port.rxBufferTail++; + } + + return ch; +} + +void uartWrite(serialPort_t *instance, uint8_t ch) +{ + uartPort_t *s = (uartPort_t *)instance; + s->port.txBuffer[s->port.txBufferHead] = ch; + if (s->port.txBufferHead + 1 >= s->port.txBufferSize) { + s->port.txBufferHead = 0; + } else { + s->port.txBufferHead++; + } + + usart_interrupt_enable (s->USARTx, USART_TDBE_INT, TRUE); + +} + +bool isUartIdle(serialPort_t *instance) +{ + uartPort_t *s = (uartPort_t *)instance; + if(usart_flag_get(s->USARTx, USART_IDLEF_FLAG)) { + + uartClearIdleFlag(s); + return true; + } else { + return false; + } +} + +const struct serialPortVTable uartVTable[] = { + { + .serialWrite = uartWrite, + .serialTotalRxWaiting = uartTotalRxBytesWaiting, + .serialTotalTxFree = uartTotalTxBytesFree, + .serialRead = uartRead, + .serialSetBaudRate = uartSetBaudRate, + .isSerialTransmitBufferEmpty = isUartTransmitBufferEmpty, + .setMode = uartSetMode, + .isConnected = NULL, + .writeBuf = NULL, + .beginWrite = NULL, + .endWrite = NULL, + .isIdle = isUartIdle, + } +}; diff --git a/src/main/drivers/serial_usb_vcp_at32f43x.c b/src/main/drivers/serial_usb_vcp_at32f43x.c new file mode 100644 index 0000000000..03e071cadb --- /dev/null +++ b/src/main/drivers/serial_usb_vcp_at32f43x.c @@ -0,0 +1,566 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + * author : emsr (shanggl@wo.cn) + * hw_config is more modified and is implemented using emsr's VCP code + * (implemented using timers) + */ + +#include + +#include + +#include "platform.h" + +#ifdef USE_VCP + +#include "build/build_config.h" + +#include "common/utils.h" +#include "drivers/io.h" +#include "build/atomic.h" + +#include "usb_conf.h" +#include "usb_core.h" +#include "usbd_int.h" +#include "cdc_class.h" +#include "cdc_desc.h" +#include "usb_io.h" + +#include "drivers/time.h" +#include "at32f435_437_clock.h" +#include "serial.h" +#include "serial_usb_vcp_at32f43x.h" +#include "nvic.h" +#include "at32f435_437_tmr.h" +#include "stddef.h" + +otg_core_type otg_core_struct; +#define USB_TIMEOUT 50 + +static vcpPort_t vcpPort; + +/** + * @brief usb 48M clock select + * @param clk_s:USB_CLK_HICK, USB_CLK_HEXT + * @retval none + */ +void usb_clock48m_select(usb_clk48_s clk_s) +{ + if(clk_s == USB_CLK_HICK) + { + crm_usb_clock_source_select(CRM_USB_CLOCK_SOURCE_HICK); + + /* enable the acc calibration ready interrupt */ + crm_periph_clock_enable(CRM_ACC_PERIPH_CLOCK, TRUE); + + /* update the c1\c2\c3 value */ + acc_write_c1(7980); + acc_write_c2(8000); + acc_write_c3(8020); +#if (USB_ID == 0) + acc_sof_select(ACC_SOF_OTG1); +#else + acc_sof_select(ACC_SOF_OTG2); +#endif + /* open acc calibration */ + acc_calibration_mode_enable(ACC_CAL_HICKTRIM, TRUE); + } + else + { + switch(system_core_clock) + { + /* 48MHz */ + case 48000000: + crm_usb_clock_div_set(CRM_USB_DIV_1); + break; + + /* 72MHz */ + case 72000000: + crm_usb_clock_div_set(CRM_USB_DIV_1_5); + break; + + /* 96MHz */ + case 96000000: + crm_usb_clock_div_set(CRM_USB_DIV_2); + break; + + /* 120MHz */ + case 120000000: + crm_usb_clock_div_set(CRM_USB_DIV_2_5); + break; + + /* 144MHz */ + case 144000000: + crm_usb_clock_div_set(CRM_USB_DIV_3); + break; + + /* 168MHz */ + case 168000000: + crm_usb_clock_div_set(CRM_USB_DIV_3_5); + break; + + /* 192MHz */ + case 192000000: + crm_usb_clock_div_set(CRM_USB_DIV_4); + break; + + /* 216MHz */ + case 216000000: + crm_usb_clock_div_set(CRM_USB_DIV_4_5); + break; + + /* 240MHz */ + case 240000000: + crm_usb_clock_div_set(CRM_USB_DIV_5); + break; + + /* 264MHz */ + case 264000000: + crm_usb_clock_div_set(CRM_USB_DIV_5_5); + break; + + /* 288MHz */ + case 288000000: + crm_usb_clock_div_set(CRM_USB_DIV_6); + break; + + default: + break; + + } + } +} + +/** + * @brief this function config gpio. + * @param none + * @retval none + */ +void usb_gpio_config(void) +{ + gpio_init_type gpio_init_struct; + + crm_periph_clock_enable(OTG_PIN_GPIO_CLOCK, TRUE); + gpio_default_para_init(&gpio_init_struct); + + gpio_init_struct.gpio_drive_strength = GPIO_DRIVE_STRENGTH_STRONGER; + gpio_init_struct.gpio_out_type = GPIO_OUTPUT_PUSH_PULL; + gpio_init_struct.gpio_mode = GPIO_MODE_MUX; + gpio_init_struct.gpio_pull = GPIO_PULL_NONE; + + /* dp and dm */ + gpio_init_struct.gpio_pins = OTG_PIN_DP | OTG_PIN_DM; + gpio_init(OTG_PIN_GPIO, &gpio_init_struct); + + gpio_pin_mux_config(OTG_PIN_GPIO, OTG_PIN_DP_SOURCE, OTG_PIN_MUX); + gpio_pin_mux_config(OTG_PIN_GPIO, OTG_PIN_DM_SOURCE, OTG_PIN_MUX); + +#ifdef USB_SOF_OUTPUT_ENABLE + crm_periph_clock_enable(OTG_PIN_SOF_GPIO_CLOCK, TRUE); + gpio_init_struct.gpio_pins = OTG_PIN_SOF; + gpio_init(OTG_PIN_SOF_GPIO, &gpio_init_struct); + gpio_pin_mux_config(OTG_PIN_GPIO, OTG_PIN_SOF_SOURCE, OTG_PIN_MUX); +#endif + + /* otgfs use vbus pin */ +#ifndef USB_VBUS_IGNORE + gpio_init_struct.gpio_pins = OTG_PIN_VBUS; + gpio_init_struct.gpio_pull = GPIO_PULL_DOWN; + gpio_pin_mux_config(OTG_PIN_GPIO, OTG_PIN_VBUS_SOURCE, OTG_PIN_MUX); + gpio_init(OTG_PIN_GPIO, &gpio_init_struct); +#endif + + +} +#ifdef USB_LOW_POWER_WAKUP +/** + * @brief usb low power wakeup interrupt config + * @param none + * @retval none + */ +void usb_low_power_wakeup_config(void) +{ + exint_init_type exint_init_struct; + + crm_periph_clock_enable(CRM_SCFG_PERIPH_CLOCK, TRUE); + exint_default_para_init(&exint_init_struct); + + exint_init_struct.line_enable = TRUE; + exint_init_struct.line_mode = EXINT_LINE_INTERRUPUT; + exint_init_struct.line_select = OTG_WKUP_EXINT_LINE; + exint_init_struct.line_polarity = EXINT_TRIGGER_RISING_EDGE; + exint_init(&exint_init_struct); + + nvic_irq_enable(OTG_WKUP_IRQ, NVIC_PRIO_USB_WUP,0); +} + +/** + * @brief this function handles otgfs wakup interrupt. + * @param none + * @retval none + */ +void OTG_WKUP_HANDLER(void) +{ + exint_flag_clear(OTG_WKUP_EXINT_LINE); +} + +#endif + + +/******************************************** + * copy from cdc part + */ + +uint32_t CDC_Send_FreeBytes(void) +{ + /* + return the bytes free in the circular buffer + + functionally equivalent to: + (APP_Rx_ptr_out > APP_Rx_ptr_in ? APP_Rx_ptr_out - APP_Rx_ptr_in : APP_RX_DATA_SIZE - APP_Rx_ptr_in + APP_Rx_ptr_in) + but without the impact of the condition check. + */ + uint32_t freeBytes; + ATOMIC_BLOCK(NVIC_PRIO_VCP) { + freeBytes = ((UserTxBufPtrOut - UserTxBufPtrIn) + (-((int)(UserTxBufPtrOut <= UserTxBufPtrIn)) & APP_TX_DATA_SIZE)) - 1; + } + + return freeBytes; +} + +/** + * @brief CDC_Send_DATA + * CDC received data to be send over USB IN endpoint are managed in + * this function. + * @param ptrBuffer: Buffer of data to be sent + * @param sendLength: Number of data to be sent (in bytes) + * @retval Bytes sent + */ +uint32_t CDC_Send_DATA(const uint8_t *ptrBuffer, uint32_t sendLength) +{ + for (uint32_t i = 0; i < sendLength; i++) { + while (CDC_Send_FreeBytes() == 0) { + // block until there is free space in the ring buffer + delay(1); + } + + ATOMIC_BLOCK(NVIC_PRIO_VCP) { + UserTxBuffer[UserTxBufPtrIn] = ptrBuffer[i]; + UserTxBufPtrIn = (UserTxBufPtrIn + 1) % APP_TX_DATA_SIZE; + } + } + return sendLength; +} + +void TxTimerConfig(void){ + /* Initialize TIMx peripheral as follow: + + Period = CDC_POLLING_INTERVAL*1000 - 1 every 5ms + + Prescaler = ((SystemCoreClock/2)/10000) - 1 + + ClockDivision = 0 + + Counter direction = Up + */ + crm_periph_clock_enable(CRM_TMR20_PERIPH_CLOCK, TRUE); + //timer, period, perscaler + tmr_base_init(usbTxTmr,(CDC_POLLING_INTERVAL - 1),((system_core_clock)/10000 - 1)); + //TMR_CLOCK_DIV1 = 0X00 NO DIV + tmr_clock_source_div_set(usbTxTmr,TMR_CLOCK_DIV1); + //COUNT UP + tmr_cnt_dir_set(usbTxTmr,TMR_COUNT_UP); + + tmr_period_buffer_enable(usbTxTmr,TRUE); + + tmr_interrupt_enable(usbTxTmr, TMR_OVF_INT, TRUE); + + nvic_irq_enable(TMR20_OVF_IRQn,NVIC_PRIO_USB,0); + + tmr_counter_enable(usbTxTmr,TRUE); + +} + +/** + * @brief TIM period elapsed callback + * @param htim: TIM handle + * @retval None + */ +void TMR20_OVF_IRQHandler(void) +{ + + uint32_t buffsize; + static uint32_t lastBuffsize = 0; + + cdc_struct_type *pcdc = (cdc_struct_type *)otg_core_struct.dev.class_handler->pdata; + + if (pcdc->g_tx_completed == 1) { + // endpoint has finished transmitting previous block + if (lastBuffsize) { + bool needZeroLengthPacket = lastBuffsize % 64 == 0; + + // move the ring buffer tail based on the previous succesful transmission + UserTxBufPtrOut += lastBuffsize; + if (UserTxBufPtrOut == APP_TX_DATA_SIZE) { + UserTxBufPtrOut = 0; + } + lastBuffsize = 0; + + if (needZeroLengthPacket) { + usb_vcp_send_data(&otg_core_struct.dev, (uint8_t*)&UserTxBuffer[UserTxBufPtrOut], 0); + return; + } + } + if (UserTxBufPtrOut != UserTxBufPtrIn) { + if (UserTxBufPtrOut > UserTxBufPtrIn) { /* Roll-back */ + buffsize = APP_TX_DATA_SIZE - UserTxBufPtrOut; + } else { + buffsize = UserTxBufPtrIn - UserTxBufPtrOut; + } + if (buffsize > APP_TX_BLOCK_SIZE) { + buffsize = APP_TX_BLOCK_SIZE; + } + + uint32_t txed=usb_vcp_send_data(&otg_core_struct.dev,(uint8_t*)&UserTxBuffer[UserTxBufPtrOut], buffsize); + if (txed==SUCCESS) { + lastBuffsize = buffsize; + } + } + } + tmr_flag_clear(usbTxTmr,TMR_OVF_FLAG); +} + +/************************************************************/ + +uint8_t usbIsConnected(void){ + return (USB_CONN_STATE_DEFAULT !=otg_core_struct.dev.conn_state); +} + +uint8_t usbIsConfigured(void){ + return (USB_CONN_STATE_CONFIGURED ==otg_core_struct.dev.conn_state); +} + +bool usbVcpIsConnected(const serialPort_t *instance) +{ + (void)instance; + return usbIsConnected() && usbIsConfigured(); +} + +/** + * @brief this function handles otgfs interrupt. + * @param none + * @retval none + */ +void OTG_IRQ_HANDLER(void) +{ + usbd_irq_handler(&otg_core_struct); +} + + +static void usbVcpSetBaudRate(serialPort_t *instance, uint32_t baudRate) +{ + UNUSED(instance); + UNUSED(baudRate); +} + +static void usbVcpSetMode(serialPort_t *instance, portMode_t mode) +{ + UNUSED(instance); + UNUSED(mode); +} + +static bool isUsbVcpTransmitBufferEmpty(const serialPort_t *instance) +{ + UNUSED(instance); + return true; +} + +static uint32_t usbVcpAvailable(const serialPort_t *instance) +{ + UNUSED(instance); + uint32_t available=0; + + available=APP_Rx_ptr_in-APP_Rx_ptr_out; + if(available ==0){ + // check anything that hasn't been copied into the cache + cdc_struct_type *pcdc = (cdc_struct_type *)otg_core_struct.dev.class_handler->pdata; + if(pcdc->g_rx_completed == 1){ + available=pcdc->g_rxlen; + } + } + return available; +} + +static uint8_t usbVcpRead(serialPort_t *instance) +{ + UNUSED(instance); + + // Check the cache is empty. If empty, add a read + if ((APP_Rx_ptr_in==0)||(APP_Rx_ptr_out == APP_Rx_ptr_in)){ + APP_Rx_ptr_out=0; + APP_Rx_ptr_in=usb_vcp_get_rxdata(&otg_core_struct.dev,APP_Rx_Buffer);// usb Maximum 64 bytes each time + if(APP_Rx_ptr_in==0) + { + // No data is read, return 0 + return 0; + } + } + return APP_Rx_Buffer[APP_Rx_ptr_out++]; +} + +// Write buffer data to vpc +static void usbVcpWriteBuf(serialPort_t *instance, const void *data, int count) +{ + UNUSED(instance); + + if (!usbVcpIsConnected(instance)) { + return; + } + + uint32_t start = millis(); + const uint8_t *p = data; + while (count > 0) { + uint32_t txed = CDC_Send_DATA(p, count); + count -= txed; + p += txed; + + if (millis() - start > USB_TIMEOUT) { + break; + } + } +} + +static bool usbVcpFlush(vcpPort_t *port) +{ + uint32_t count = port->txAt; + port->txAt = 0; + + if (count == 0) { + return true; + } + + if (!usbIsConnected() || !usbIsConfigured()) { + return false; + } + + uint32_t start = millis(); + uint8_t *p = port->txBuf; + while (count > 0) { + uint32_t txed = CDC_Send_DATA(p, count); + count -= txed; + p += txed; + + if (millis() - start > USB_TIMEOUT) { + break; + } + } + return count == 0; +} + +static void usbVcpWrite(serialPort_t *instance, uint8_t c) +{ + vcpPort_t *port = container_of(instance, vcpPort_t, port); + + port->txBuf[port->txAt++] = c; + if (!port->buffering || port->txAt >= ARRAYLEN(port->txBuf)) { + usbVcpFlush(port); + } +} + +static void usbVcpBeginWrite(serialPort_t *instance) +{ + vcpPort_t *port = container_of(instance, vcpPort_t, port); + port->buffering = true; +} + +static uint32_t usbTxBytesFree(const serialPort_t *instance) +{ + UNUSED(instance); + return CDC_Send_FreeBytes(); +} + +static void usbVcpEndWrite(serialPort_t *instance) +{ + vcpPort_t *port = container_of(instance, vcpPort_t, port); + port->buffering = false; + usbVcpFlush(port); +} + +static const struct serialPortVTable usbVTable[] = { + { + .serialWrite = usbVcpWrite, + .serialTotalRxWaiting = usbVcpAvailable, + .serialTotalTxFree = usbTxBytesFree, + .serialRead = usbVcpRead, + .serialSetBaudRate = usbVcpSetBaudRate, + .isSerialTransmitBufferEmpty = isUsbVcpTransmitBufferEmpty, + .setMode = usbVcpSetMode, + .isConnected = usbVcpIsConnected, + .writeBuf = usbVcpWriteBuf, + .beginWrite = usbVcpBeginWrite, + .endWrite = usbVcpEndWrite, + .isIdle = NULL, + } +}; + +void usbVcpInitHardware(void) +{ + IOInit(IOGetByTag(IO_TAG(PA11)), OWNER_USB, RESOURCE_INPUT, 0); + IOInit(IOGetByTag(IO_TAG(PA12)), OWNER_USB, RESOURCE_OUTPUT, 0); + + /* usb gpio config */ + usb_gpio_config(); + + #ifdef USB_LOW_POWER_WAKUP + usb_low_power_wakeup_config(); + #endif + + /* enable otgfs clock */ + crm_periph_clock_enable(OTG_CLOCK, TRUE); + + /* select usb 48m clcok source */ + usb_clock48m_select(USB_CLK_HEXT); + + /* enable otgfs irq,cannot set too high priority */ + nvic_irq_enable(OTG_IRQ,NVIC_PRIO_USB,0); + + usbGenerateDisconnectPulse(); + + /* init usb */ + usbd_init(&otg_core_struct, + USB_FULL_SPEED_CORE_ID, + USB_ID, + &cdc_class_handler, + &cdc_desc_handler); + + //config TX timer + TxTimerConfig(); +} + +serialPort_t *usbVcpOpen(void) +{ + vcpPort_t *s; + s = &vcpPort; + s->port.vTable = usbVTable; + + return (serialPort_t *)s; +} + +uint32_t usbVcpGetBaudRate(serialPort_t *instance) +{ + UNUSED(instance); + cdc_struct_type *pcdc = (cdc_struct_type *)otg_core_struct.dev.class_handler->pdata; + return pcdc->linecoding.bitrate; + // return CDC_BaudRate(); +} + +#endif diff --git a/src/main/drivers/serial_usb_vcp_at32f43x.h b/src/main/drivers/serial_usb_vcp_at32f43x.h new file mode 100644 index 0000000000..13ce455fa1 --- /dev/null +++ b/src/main/drivers/serial_usb_vcp_at32f43x.h @@ -0,0 +1,55 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + +typedef struct { + serialPort_t port; + + // Buffer used during bulk writes. + uint8_t txBuf[20]; + uint8_t txAt; + // Set if the port is in bulk write mode and can buffer. + bool buffering; +} vcpPort_t; + +#define APP_TX_DATA_SIZE 2048 +#define APP_TX_BLOCK_SIZE 512 + +volatile uint8_t UserTxBuffer[APP_TX_DATA_SIZE];/* Received Data over UART (CDC interface) are stored in this buffer */ +uint32_t BuffLength; +volatile uint32_t UserTxBufPtrIn = 0;/* Increment this pointer or roll it back to + start address when data are received over USART */ +volatile uint32_t UserTxBufPtrOut = 0; /* Increment this pointer or roll it back to + start address when data are sent over USB */ +tmr_type * usbTxTmr= TMR20; +#define CDC_POLLING_INTERVAL 50 + +/* + APP RX is the circular buffer for data that is transmitted from the APP (host) + to the USB device (flight controller). +*/ +#define APP_RX_DATA_SIZE 2048 +static uint8_t APP_Rx_Buffer[APP_RX_DATA_SIZE]; //rx buffer,convert usb read to the usbvcpRead +static uint32_t APP_Rx_ptr_out = 0; //serail read out, back pointer +static uint32_t APP_Rx_ptr_in = 0; //usb Read in, front pointer + +void usbVcpInitHardware(void); +serialPort_t *usbVcpOpen(void); +struct serialPort_s; +uint32_t usbVcpGetBaudRate(struct serialPort_s *instance); + diff --git a/src/main/drivers/system.c b/src/main/drivers/system.c index 5079e48395..18a569857e 100644 --- a/src/main/drivers/system.c +++ b/src/main/drivers/system.c @@ -29,7 +29,7 @@ #include "drivers/system.h" #include "drivers/time.h" -#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) +#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7)||defined(AT32F43x) // See "RM CoreSight Architecture Specification" // B2.3.10 "LSR and LAR, Software Lock Status Register and Software Lock Access Register" // "E1.2.11 LAR, Lock Access Register" @@ -43,24 +43,33 @@ void cycleCounterInit(void) { extern uint32_t usTicks; // From drivers/time.h -#if defined(USE_HAL_DRIVER) - // We assume that SystemCoreClock is already set to a correct value by init code - usTicks = SystemCoreClock / 1000000; -#else - RCC_ClocksTypeDef clocks; - RCC_GetClocksFreq(&clocks); - usTicks = clocks.SYSCLK_Frequency / 1000000; -#endif - + #if defined(AT32F43x) + //crm_clocks_freq_type clocks; + //crm_clocks_freq_get(&clocks); + //usTicks = clocks.sclk_freq / 1000000; + usTicks = SystemCoreClock / 1000000; + #else + #if defined(USE_HAL_DRIVER) + // We assume that SystemCoreClock is already set to a correct value by init code + usTicks = SystemCoreClock / 1000000; + #else + RCC_ClocksTypeDef clocks; + RCC_GetClocksFreq(&clocks); + usTicks = clocks.SYSCLK_Frequency / 1000000; + #endif + #endif + // Enable DWT for precision time measurement CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk; -#if defined(STM32F7) || defined(STM32H7) - DWT->LAR = DWT_LAR_UNLOCK_VALUE; -#elif defined(STM32F4) - volatile uint32_t *DWTLAR = (uint32_t *)(DWT_BASE + 0x0FB0); - *(DWTLAR) = DWT_LAR_UNLOCK_VALUE; -#endif + #if defined(STM32F7) || defined(STM32H7) + DWT->LAR = DWT_LAR_UNLOCK_VALUE; + #elif defined(AT32F43x) + ITM->LAR = DWT_LAR_UNLOCK_VALUE; + #elif defined(STM32F4) + volatile uint32_t *DWTLAR = (uint32_t *)(DWT_BASE + 0x0FB0); + *(DWTLAR) = DWT_LAR_UNLOCK_VALUE; + #endif DWT->CYCCNT = 0; DWT->CTRL |= DWT_CTRL_CYCCNTENA_Msk; @@ -115,6 +124,8 @@ void checkForBootLoaderRequest(void) volatile isrVector_t *bootloaderVector = (isrVector_t *)systemBootloaderAddress(); __set_MSP(bootloaderVector->stackEnd); bootloaderVector->resetHandler(); + + while (1); } @@ -168,7 +179,7 @@ void failureMode(failureMode_e mode) #endif #endif //UNIT_TEST } - +// Tightly-Coupled Memory for instruction AT32 not enabled, can optimize preloading void initialiseMemorySections(void) { #ifdef USE_ITCM_RAM diff --git a/src/main/drivers/system_at32f43x.c b/src/main/drivers/system_at32f43x.c new file mode 100644 index 0000000000..fadcfe239a --- /dev/null +++ b/src/main/drivers/system_at32f43x.c @@ -0,0 +1,148 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include +#include +#include + +#include "platform.h" + +#include "drivers/accgyro/accgyro_mpu.h" +#include "drivers/exti.h" +#include "drivers/nvic.h" +#include "drivers/system.h" +#include "target/system.h" +#include "at32f435_437_clock.h" + +void SetSysClock(void); + +void enableGPIOPowerUsageAndNoiseReductions(void) +{ + crm_periph_clock_enable( + CRM_GPIOA_PERIPH_CLOCK | + CRM_GPIOB_PERIPH_CLOCK | + CRM_GPIOC_PERIPH_CLOCK | + CRM_GPIOD_PERIPH_CLOCK | + CRM_GPIOE_PERIPH_CLOCK | + CRM_DMA1_PERIPH_CLOCK | + CRM_DMA2_PERIPH_CLOCK | + 0,TRUE); + + crm_periph_clock_enable( + CRM_TMR2_PERIPH_CLOCK | + CRM_TMR3_PERIPH_CLOCK | + CRM_TMR4_PERIPH_CLOCK | + CRM_TMR5_PERIPH_CLOCK | + CRM_TMR6_PERIPH_CLOCK | + CRM_TMR7_PERIPH_CLOCK | + CRM_TMR12_PERIPH_CLOCK | + CRM_TMR13_PERIPH_CLOCK | + CRM_TMR14_PERIPH_CLOCK | + CRM_SPI2_PERIPH_CLOCK | + CRM_SPI3_PERIPH_CLOCK | + CRM_USART2_PERIPH_CLOCK | + CRM_USART3_PERIPH_CLOCK | + CRM_UART4_PERIPH_CLOCK | + CRM_UART5_PERIPH_CLOCK | + CRM_I2C1_PERIPH_CLOCK | + CRM_I2C2_PERIPH_CLOCK | + CRM_I2C3_PERIPH_CLOCK | + CRM_UART8_PERIPH_CLOCK | + CRM_UART7_PERIPH_CLOCK | + CRM_PWC_PERIPH_CLOCK | + 0,TRUE); + + crm_periph_clock_enable( + CRM_TMR1_PERIPH_CLOCK | + CRM_TMR8_PERIPH_CLOCK | + CRM_USART1_PERIPH_CLOCK | + CRM_USART6_PERIPH_CLOCK | + CRM_ADC1_PERIPH_CLOCK | + CRM_ADC2_PERIPH_CLOCK | + CRM_ADC3_PERIPH_CLOCK | + CRM_SPI1_PERIPH_CLOCK | + CRM_SPI4_PERIPH_CLOCK | + CRM_TMR9_PERIPH_CLOCK | + CRM_TMR10_PERIPH_CLOCK | + CRM_TMR11_PERIPH_CLOCK | + CRM_TMR20_PERIPH_CLOCK | + CRM_ACC_PERIPH_CLOCK | + 0,TRUE); + + gpio_init_type gpio_init_struct; + + gpio_default_para_init(&gpio_init_struct); + gpio_init_struct.gpio_pull = GPIO_PULL_NONE; + gpio_init_struct.gpio_pins = GPIO_PINS_ALL; + gpio_init_struct.gpio_pins &= ~(GPIO_PINS_12|GPIO_PINS_11|GPIO_PINS_9); // leave USB D+/D- alone + gpio_init_struct.gpio_pins &= ~(GPIO_PINS_14|GPIO_PINS_15|GPIO_PINS_13); // leave JTAG pins alone + gpio_init(GPIOA, &gpio_init_struct); + + gpio_init_struct.gpio_pins = GPIO_PINS_ALL; + gpio_init(GPIOB, &gpio_init_struct); + gpio_init(GPIOC, &gpio_init_struct); + gpio_init(GPIOD, &gpio_init_struct); + gpio_init(GPIOE, &gpio_init_struct); + gpio_init(GPIOF, &gpio_init_struct); +} + +bool isMPUSoftReset(void) +{ + if (cachedRccCsrValue & CRM_SW_RESET_FLAG) + return true; + else + return false; +} +//AT32 DIAGRAM2-1 AT32F435/437 DFU BOOTLOADER ADDR +uint32_t systemBootloaderAddress(void) +{ + return 0x1FFF0000; + //return system_isr_vector_table_base; +} + +void systemClockSetup(uint8_t cpuUnderclock) +{ + (void)cpuUnderclock; + // This is a stub +} + +void systemInit(void) +{ + //config system clock to 288mhz usb 48mhz + system_clock_config(); + // Configure NVIC preempt/priority groups + nvic_priority_group_config(NVIC_PRIORITY_GROUPING); + + // cache RCC->CSR value to use it in isMPUSoftReset() and others + cachedRccCsrValue = CRM->ctrlsts; + + // Although VTOR is already loaded with a possible vector table in RAM, + // removing the call to NVIC_SetVectorTable causes USB not to become active, + extern uint8_t isr_vector_table_base; + nvic_vector_table_set((uint32_t)&isr_vector_table_base, 0x0); + +// disable usb otg fs1/2 + crm_periph_clock_enable(CRM_OTGFS2_PERIPH_CLOCK|CRM_OTGFS1_PERIPH_CLOCK,FALSE); + +// clear all reset flags + CRM->ctrlsts_bit.rstfc = TRUE; + enableGPIOPowerUsageAndNoiseReductions(); + // Init cycle counter + cycleCounterInit(); + // SysTick + SysTick_Config(system_core_clock / 1000); +} diff --git a/src/main/drivers/timer.c b/src/main/drivers/timer.c index 094b54f714..ecdf1ba48d 100755 --- a/src/main/drivers/timer.c +++ b/src/main/drivers/timer.c @@ -38,6 +38,21 @@ timHardwareContext_t * timerCtx[HARDWARE_TIMER_DEFINITION_COUNT]; +#if defined(AT32F43x) +uint8_t lookupTimerIndex(const tmr_type *tim) +{ + int i; + + // let gcc do the work, switch should be quite optimized + for (i = 0; i < HARDWARE_TIMER_DEFINITION_COUNT; i++) { + if (tim == timerDefinitions[i].tim) { + return i; + } + } + // make sure final index is out of range + return ~1; +} +#else // return index of timer in timer table. Lowest timer has index 0 uint8_t lookupTimerIndex(const TIM_TypeDef *tim) { @@ -53,6 +68,7 @@ uint8_t lookupTimerIndex(const TIM_TypeDef *tim) // make sure final index is out of range return ~1; } +#endif void timerConfigBase(TCH_t * tch, uint16_t period, uint32_t hz) { @@ -156,9 +172,13 @@ void timerChConfigIC(TCH_t * tch, bool polarityRising, unsigned inputFilterSampl uint16_t timerGetPeriod(TCH_t * tch) { +#if defined(AT32F43x) + return tch->timHw->tim->pr; //tmr pr registe +#else return tch->timHw->tim->ARR; +#endif } - +//timerHardware target.c void timerInit(void) { memset(timerCtx, 0, sizeof (timerCtx)); diff --git a/src/main/drivers/timer.h b/src/main/drivers/timer.h index d1cc3cc16e..cdbb8dc2d7 100644 --- a/src/main/drivers/timer.h +++ b/src/main/drivers/timer.h @@ -29,7 +29,7 @@ typedef uint16_t captureCompare_t; // 16 bit on both 103 and 303, just register access must be 32bit sometimes (use timCCR_t) -#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) +#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7)|| defined(AT32F43x) typedef uint32_t timCCR_t; typedef uint32_t timCCER_t; typedef uint32_t timSR_t; @@ -49,10 +49,32 @@ typedef uint32_t timCNT_t; #define HARDWARE_TIMER_DEFINITION_COUNT 14 #elif defined(STM32H7) #define HARDWARE_TIMER_DEFINITION_COUNT 14 +#elif defined(AT32F43x) +#define HARDWARE_TIMER_DEFINITION_COUNT 15 #else #error "Unknown CPU defined" #endif - +// tmr_type instead in AT32 +#if defined(AT32F43x) +typedef struct timerDef_s { + tmr_type * tim; + rccPeriphTag_t rcc; + uint8_t irq; + uint8_t secondIrq; +} timerDef_t; +// TCH hardware definition (listed in target.c) +typedef struct timerHardware_s { + tmr_type *tim; + ioTag_t tag; + uint8_t channelIndex; + uint8_t output; + ioConfig_t ioMode; + uint8_t alternateFunction; + uint32_t usageFlags; + dmaTag_t dmaTag; + uint32_t dmaMuxid; //DMAMUX ID +} timerHardware_t; +#else typedef struct timerDef_s { TIM_TypeDef * tim; rccPeriphTag_t rcc; @@ -60,6 +82,19 @@ typedef struct timerDef_s { uint8_t secondIrq; } timerDef_t; +// TCH hardware definition (listed in target.c) +typedef struct timerHardware_s { + TIM_TypeDef *tim; + ioTag_t tag; + uint8_t channelIndex; + uint8_t output; + ioConfig_t ioMode; + uint8_t alternateFunction; + uint32_t usageFlags; + dmaTag_t dmaTag; +} timerHardware_t; + +#endif typedef enum { TIM_USE_ANY = 0, TIM_USE_PPM = (1 << 0), @@ -73,17 +108,6 @@ typedef enum { TIM_USE_BEEPER = (1 << 25), } timerUsageFlag_e; -// TCH hardware definition (listed in target.c) -typedef struct timerHardware_s { - TIM_TypeDef *tim; - ioTag_t tag; - uint8_t channelIndex; - uint8_t output; - ioConfig_t ioMode; - uint8_t alternateFunction; - uint32_t usageFlags; - dmaTag_t dmaTag; -} timerHardware_t; enum { TIMER_OUTPUT_NONE = 0x00, @@ -155,7 +179,14 @@ typedef enum { TYPE_TIMER } channelType_t; -uint32_t timerClock(TIM_TypeDef *tim); +#if defined(AT32F43x) + uint32_t timerClock(tmr_type *tim); + uint16_t timerGetPrescalerByDesiredMhz(tmr_type *tim, uint16_t mhz); +#else + uint32_t timerClock(TIM_TypeDef *tim); + uint16_t timerGetPrescalerByDesiredMhz(TIM_TypeDef *tim, uint16_t mhz); +#endif + uint32_t timerGetBaseClockHW(const timerHardware_t * timHw); const timerHardware_t * timerGetByUsageFlag(timerUsageFlag_e flag); @@ -191,5 +222,3 @@ void timerPWMStopDMA(TCH_t * tch); bool timerPWMDMAInProgress(TCH_t * tch); volatile timCCR_t *timerCCR(TCH_t * tch); - -uint16_t timerGetPrescalerByDesiredMhz(TIM_TypeDef *tim, uint16_t mhz); diff --git a/src/main/drivers/timer_at32f43x.c b/src/main/drivers/timer_at32f43x.c new file mode 100644 index 0000000000..a49eba86f9 --- /dev/null +++ b/src/main/drivers/timer_at32f43x.c @@ -0,0 +1,117 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + +#include +#include + +#include "platform.h" + +#include "build/atomic.h" + +#include "common/utils.h" + +#include "drivers/io.h" +#include "drivers/rcc.h" +#include "drivers/time.h" +#include "drivers/nvic.h" +#include "drivers/timer.h" +#include "drivers/timer_impl.h" +#include "at32f435_437.h" + + const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = { + #if defined(TMR1) + [0] = { .tim = TMR1, .rcc = RCC_APB2(TMR1), .irq = TMR1_CH_IRQn, .secondIrq = TMR1_OVF_TMR10_IRQn }, + #endif + + #if defined(TMR2) + [1] = { .tim = TMR2, .rcc = RCC_APB1(TMR2), .irq = TMR2_GLOBAL_IRQn}, + #endif + + #if defined(TMR3) + [2] = { .tim = TMR3, .rcc = RCC_APB1(TMR3), .irq = TMR3_GLOBAL_IRQn}, + #endif + + #if defined(TMR4) + [3] = { .tim = TMR4, .rcc = RCC_APB1(TMR4), .irq = TMR4_GLOBAL_IRQn}, + #endif + + #if defined(TMR5) + [4] = { .tim = TMR5, .rcc = RCC_APB1(TMR5), .irq = TMR5_GLOBAL_IRQn}, + #endif + + #if defined(TMR6) + [5] = { .tim = TMR6, .rcc = RCC_APB1(TMR6), .irq = 0}, + #endif + + #if defined(TMR7) + [6] = { .tim = TMR7, .rcc = RCC_APB1(TMR7), .irq = 0}, + #endif + + #if defined(TMR8) + [7] = { .tim = TMR8, .rcc = RCC_APB2(TMR8), .irq = TMR8_CH_IRQn, .secondIrq = TMR8_OVF_TMR13_IRQn }, + #endif + + #if defined(TMR9) + [8] = { .tim = TMR9, .rcc = RCC_APB2(TMR9), .irq = TMR1_BRK_TMR9_IRQn}, + #endif + + #if defined(TMR10) + [9] = { .tim = TMR10, .rcc = RCC_APB2(TMR10), .irq = TMR1_OVF_TMR10_IRQn}, + #endif + + #if defined(TMR11) + [10] = { .tim = TMR11, .rcc = RCC_APB2(TMR11), .irq = TMR1_TRG_HALL_TMR11_IRQn}, + #endif + + #if defined(TMR12) + [11] = { .tim = TMR12, .rcc = RCC_APB1(TMR12), .irq = TMR8_BRK_TMR12_IRQn}, + #endif + + #if defined(TMR13) + [12] = { .tim = TMR13, .rcc = RCC_APB1(TMR13), .irq = TMR8_OVF_TMR13_IRQn}, + #endif + + #if defined(TMR14) + [13] = { .tim = TMR14, .rcc = RCC_APB1(TMR14), .irq = TMR8_TRG_HALL_TMR14_IRQn}, + #endif + + #if defined(TMR20) + [14] = { .tim = TMR20, .rcc = RCC_APB2(TMR20), .irq = TMR20_CH_IRQn}, + #endif + }; + +uint32_t timerClock(tmr_type *tim) +{ + UNUSED(tim); + return SystemCoreClock; +} + +// Timer IRQ handlers +_TIM_IRQ_HANDLER(TMR1_CH_IRQHandler, 1); +_TIM_IRQ_HANDLER2(TMR1_BRK_TMR9_IRQHandler, 1, 9); +_TIM_IRQ_HANDLER2(TMR1_OVF_TMR10_IRQHandler, 1, 10); +_TIM_IRQ_HANDLER2(TMR1_TRG_HALL_TMR11_IRQHandler, 1, 11); +_TIM_IRQ_HANDLER(TMR2_GLOBAL_IRQHandler, 2); +_TIM_IRQ_HANDLER(TMR3_GLOBAL_IRQHandler, 3); +_TIM_IRQ_HANDLER(TMR4_GLOBAL_IRQHandler, 4); +_TIM_IRQ_HANDLER(TMR5_GLOBAL_IRQHandler, 5); +_TIM_IRQ_HANDLER(TMR8_CH_IRQHandler, 8); +//_TIM_IRQ_HANDLER(TIM8_UP_IRQHandler, 8); +_TIM_IRQ_HANDLER2(TMR8_BRK_TMR12_IRQHandler, 8, 12); +_TIM_IRQ_HANDLER2(TMR8_OVF_TMR13_IRQHandler, 8, 13); +_TIM_IRQ_HANDLER2(TMR8_TRG_HALL_TMR14_IRQHandler, 8, 14); +_TIM_IRQ_HANDLER(TMR20_CH_IRQHandler, 20); diff --git a/src/main/drivers/timer_def.h b/src/main/drivers/timer_def.h index e8c8afad27..af1c4e85fb 100644 --- a/src/main/drivers/timer_def.h +++ b/src/main/drivers/timer_def.h @@ -20,6 +20,9 @@ #include "drivers/dma.h" // Macros expand to keep DMA descriptor table compatible with Betaflight +//0 TMR3_CH1 +// DEF_TIM_DMAMAP_VARIANT__0, DEF_TIM_DMA__BTCH_TMR3_CH1 +// DEF_TIM_DMAMAP__D(1, 4, 5) #define DEF_TIM_DMAMAP(variant, timch) CONCAT(DEF_TIM_DMAMAP__, PP_CALL(CONCAT(DEF_TIM_DMAMAP_VARIANT__, variant), CONCAT(DEF_TIM_DMA__, DEF_TIM_TCH2BTCH(timch)), DMA_VARIANT_MISSING, DMA_VARIANT_MISSING)) #define DEF_TIM_DMAMAP_VARIANT__0(_0, ...) _0 #define DEF_TIM_DMAMAP_VARIANT__1(_0, _1, ...) _1 @@ -49,7 +52,26 @@ #define DEF_TIM_CHNL_CH4N 3 // map to base channel (strip N from channel); works only when channel N exists +//BTCH_TMR1_CH1N #define DEF_TIM_TCH2BTCH(timch) CONCAT(BTCH_, timch) + +#if defined(AT32F43x) +#define BTCH_TMR1_CH1N BTCH_TMR1_CH1 +#define BTCH_TMR1_CH2N BTCH_TMR1_CH2 +#define BTCH_TMR1_CH3N BTCH_TMR1_CH3 + +#define BTCH_TMR8_CH1N BTCH_TMR8_CH1 +#define BTCH_TMR8_CH2N BTCH_TMR8_CH2 +#define BTCH_TMR8_CH3N BTCH_TMR8_CH3 + +#define BTCH_TMR20_CH1N BTCH_TMR20_CH1 +#define BTCH_TMR20_CH2N BTCH_TMR20_CH2 +#define BTCH_TMR20_CH3N BTCH_TMR20_CH3 + +#define BTCH_TMR15_CH1N BTCH_TMR15_CH1 +#define BTCH_TMR16_CH1N BTCH_TMR16_CH1 +#else + #define BTCH_TIM1_CH1N BTCH_TIM1_CH1 #define BTCH_TIM1_CH2N BTCH_TIM1_CH2 #define BTCH_TIM1_CH3N BTCH_TIM1_CH3 @@ -64,6 +86,7 @@ #define BTCH_TIM15_CH1N BTCH_TIM15_CH1 #define BTCH_TIM16_CH1N BTCH_TIM16_CH1 +#endif // Default output flags #define DEF_TIM_OUTPUT(ch) DEF_TIM_OUTPUT__ ## ch @@ -82,6 +105,8 @@ #include "timer_def_stm32f7xx.h" #elif defined(STM32H7) #include "timer_def_stm32h7xx.h" +#elif defined(AT32F43x) + #include "timer_def_at32f43x.h" #else #error "Unknown CPU defined" #endif diff --git a/src/main/drivers/timer_def_at32f43x.h b/src/main/drivers/timer_def_at32f43x.h new file mode 100644 index 0000000000..1390cfa54a --- /dev/null +++ b/src/main/drivers/timer_def_at32f43x.h @@ -0,0 +1,307 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + +#pragma once + +#define timerDMASafeType_t uint32_t + +#define DEF_TIM_DMAMAP__D(dma, stream, channel) DMA_TAG(dma, stream, channel) +#define DEF_TIM_DMAMAP__NONE DMA_NONE + +// Define TIM device/DMA/MUX +#define DEF_TIM(tim, ch, pin, usage, flags, dmavar) { \ + tim, \ + IO_TAG(pin), \ + DEF_TIM_CHNL_ ## ch, \ + DEF_TIM_OUTPUT(ch) | flags, \ + IOCFG_AF_PP, \ + DEF_TIM_AF(TCH_## tim ## _ ## ch, pin), \ + usage, \ + DEF_TIM_DMAMAP(dmavar, tim ## _ ## ch), \ + DEF_TIM_DMA_REQUEST(tim ## _ ## ch) \ + } + +// AF mappings +#define DEF_TIM_AF(timch, pin) CONCAT(DEF_TIM_AF__, DEF_TIM_AF__ ## pin ## __ ## timch) +// MUX mappings +#define DEF_TIM_AF__D(af_n, tim_n) GPIO_MUX_ ## af_n + +#define DEF_TIM_DMA_REQUEST(timch) \ + CONCAT(DEF_TIM_DMA_REQ__, DEF_TIM_TCH2BTCH(timch)) + + +/* add the DMA mappings here */ +// D(DMAx, Stream, Channel) +// at32f43x has DMAMUX that allow arbitrary assignment of peripherals to streams. +#define DEF_TIM_DMA_FULL \ + D(1, 1, 0), D(1, 2, 0), D(1, 3, 0), D(1, 4, 0), D(1, 5, 0), D(1, 6, 0), D(1, 7, 0), \ + D(2, 1, 0), D(2, 2, 0), D(2, 3, 0), D(2, 4, 0), D(2, 5, 0), D(2, 6, 0), D(2, 7, 0) + +#define DEF_TIM_DMA__BTCH_TMR1_CH1 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR1_CH2 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR1_CH3 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR1_CH4 DEF_TIM_DMA_FULL + +#define DEF_TIM_DMA__BTCH_TMR2_CH1 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR2_CH2 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR2_CH3 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR2_CH4 DEF_TIM_DMA_FULL + +#define DEF_TIM_DMA__BTCH_TMR3_CH1 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR3_CH2 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR3_CH3 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR3_CH4 DEF_TIM_DMA_FULL + +#define DEF_TIM_DMA__BTCH_TMR4_CH1 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR4_CH2 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR4_CH3 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR4_CH4 DEF_TIM_DMA_FULL + +#define DEF_TIM_DMA__BTCH_TMR5_CH1 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR5_CH2 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR5_CH3 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR5_CH4 DEF_TIM_DMA_FULL + +#define DEF_TIM_DMA__BTCH_TMR8_CH1 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR8_CH2 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR8_CH3 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR8_CH4 DEF_TIM_DMA_FULL + +#define DEF_TIM_DMA__BTCH_TMR15_CH1 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR15_CH2 NONE + +#define DEF_TIM_DMA__BTCH_TMR16_CH1 DEF_TIM_DMA_FULL + +#define DEF_TIM_DMA__BTCH_TMR17_CH1 DEF_TIM_DMA_FULL + +#define DEF_TIM_DMA__BTCH_TMR20_CH1 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR20_CH2 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR20_CH3 DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR20_CH4 DEF_TIM_DMA_FULL + +#define DEF_TIM_DMA__BTCH_TMR9_CH1 NONE +#define DEF_TIM_DMA__BTCH_TMR9_CH2 NONE + +#define DEF_TIM_DMA__BTCH_TMR10_CH1 NONE +#define DEF_TIM_DMA__BTCH_TMR11_CH1 NONE + +#define DEF_TIM_DMA__BTCH_TMR12_CH1 NONE +#define DEF_TIM_DMA__BTCH_TMR12_CH2 NONE +#define DEF_TIM_DMA__BTCH_TMR13_CH1 NONE +#define DEF_TIM_DMA__BTCH_TMR14_CH1 NONE + +// TIM_UP table +#define DEF_TIM_DMA__BTCH_TMR1_UP DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR2_UP DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR3_UP DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR4_UP DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR5_UP DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR6_UP DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR7_UP DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR8_UP DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR9_UP DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR10_UP DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR11_UP DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR12_UP DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR13_UP DEF_TIM_DMA_FULL +#define DEF_TIM_DMA__BTCH_TMR14_UP DEF_TIM_DMA_FULL + +#define DMA_REQUEST_NONE 255 + +#define DEF_TIM_DMA_REQ__BTCH_TMR1_CH1 DMAMUX_DMAREQ_ID_TMR1_CH1 +#define DEF_TIM_DMA_REQ__BTCH_TMR1_CH2 DMAMUX_DMAREQ_ID_TMR1_CH2 +#define DEF_TIM_DMA_REQ__BTCH_TMR1_CH3 DMAMUX_DMAREQ_ID_TMR1_CH3 +#define DEF_TIM_DMA_REQ__BTCH_TMR1_CH4 DMAMUX_DMAREQ_ID_TMR1_CH4 + +#define DEF_TIM_DMA_REQ__BTCH_TMR2_CH1 DMAMUX_DMAREQ_ID_TMR2_CH1 +#define DEF_TIM_DMA_REQ__BTCH_TMR2_CH2 DMAMUX_DMAREQ_ID_TMR2_CH2 +#define DEF_TIM_DMA_REQ__BTCH_TMR2_CH3 DMAMUX_DMAREQ_ID_TMR2_CH3 +#define DEF_TIM_DMA_REQ__BTCH_TMR2_CH4 DMAMUX_DMAREQ_ID_TMR2_CH4 + +#define DEF_TIM_DMA_REQ__BTCH_TMR3_CH1 DMAMUX_DMAREQ_ID_TMR3_CH1 +#define DEF_TIM_DMA_REQ__BTCH_TMR3_CH2 DMAMUX_DMAREQ_ID_TMR3_CH2 +#define DEF_TIM_DMA_REQ__BTCH_TMR3_CH3 DMAMUX_DMAREQ_ID_TMR3_CH3 +#define DEF_TIM_DMA_REQ__BTCH_TMR3_CH4 DMAMUX_DMAREQ_ID_TMR3_CH4 + +#define DEF_TIM_DMA_REQ__BTCH_TMR4_CH1 DMAMUX_DMAREQ_ID_TMR4_CH1 +#define DEF_TIM_DMA_REQ__BTCH_TMR4_CH2 DMAMUX_DMAREQ_ID_TMR4_CH2 +#define DEF_TIM_DMA_REQ__BTCH_TMR4_CH3 DMAMUX_DMAREQ_ID_TMR4_CH3 +#define DEF_TIM_DMA_REQ__BTCH_TMR4_CH4 DMAMUX_DMAREQ_ID_TMR4_CH4 + +#define DEF_TIM_DMA_REQ__BTCH_TMR5_CH1 DMAMUX_DMAREQ_ID_TMR5_CH1 +#define DEF_TIM_DMA_REQ__BTCH_TMR5_CH2 DMAMUX_DMAREQ_ID_TMR5_CH2 +#define DEF_TIM_DMA_REQ__BTCH_TMR5_CH3 DMAMUX_DMAREQ_ID_TMR5_CH3 +#define DEF_TIM_DMA_REQ__BTCH_TMR5_CH4 DMAMUX_DMAREQ_ID_TMR5_CH4 + +#define DEF_TIM_DMA_REQ__BTCH_TMR8_CH1 DMAMUX_DMAREQ_ID_TMR8_CH1 +#define DEF_TIM_DMA_REQ__BTCH_TMR8_CH2 DMAMUX_DMAREQ_ID_TMR8_CH2 +#define DEF_TIM_DMA_REQ__BTCH_TMR8_CH3 DMAMUX_DMAREQ_ID_TMR8_CH3 +#define DEF_TIM_DMA_REQ__BTCH_TMR8_CH4 DMAMUX_DMAREQ_ID_TMR8_CH4 + +#define DEF_TIM_DMA_REQ__BTCH_TMR20_CH1 DMAMUX_DMAREQ_ID_TMR20_CH1 +#define DEF_TIM_DMA_REQ__BTCH_TMR20_CH2 DMAMUX_DMAREQ_ID_TMR20_CH2 +#define DEF_TIM_DMA_REQ__BTCH_TMR20_CH3 DMAMUX_DMAREQ_ID_TMR20_CH3 +#define DEF_TIM_DMA_REQ__BTCH_TMR20_CH4 DMAMUX_DMAREQ_ID_TMR20_CH4 + +// TIM_UP request table +#define DEF_TIM_DMA_REQ__BTCH_TMR1_UP DMAMUX_DMAREQ_ID_TMR1_OVERFLOW +#define DEF_TIM_DMA_REQ__BTCH_TMR2_UP DMAMUX_DMAREQ_ID_TMR2_OVERFLOW +#define DEF_TIM_DMA_REQ__BTCH_TMR3_UP DMAMUX_DMAREQ_ID_TMR3_OVERFLOW +#define DEF_TIM_DMA_REQ__BTCH_TMR4_UP DMAMUX_DMAREQ_ID_TMR4_OVERFLOW +#define DEF_TIM_DMA_REQ__BTCH_TMR5_UP DMAMUX_DMAREQ_ID_TMR5_OVERFLOW +#define DEF_TIM_DMA_REQ__BTCH_TMR8_UP DMAMUX_DMAREQ_ID_TMR8_OVERFLOW +#define DEF_TIM_DMA_REQ__BTCH_TMR20_UP DMAMUX_DMAREQ_ID_TMR20_OVERFLOW + + +// AF table +//GPIOA +#define DEF_TIM_AF__PA0__TCH_TMR2_CH1 D(1, 2) //A MUX1 1 +#define DEF_TIM_AF__PA1__TCH_TMR2_CH2 D(1, 2) //A MUX1 2 +#define DEF_TIM_AF__PA2__TCH_TMR2_CH3 D(1, 2) +#define DEF_TIM_AF__PA3__TCH_TMR2_CH4 D(1, 2) +#define DEF_TIM_AF__PA5__TCH_TMR2_CH1 D(1, 2) +#define DEF_TIM_AF__PA7__TCH_TMR1_CH1N D(1, 1) +#define DEF_TIM_AF__PA8__TCH_TMR1_CH1 D(1, 1) +#define DEF_TIM_AF__PA9__TCH_TMR1_CH2 D(1, 1) +#define DEF_TIM_AF__PA10__TCH_TMR1_CH3 D(1, 1) +#define DEF_TIM_AF__PA11__TCH_TMR1_CH4 D(1, 1) +#define DEF_TIM_AF__PA15__TCH_TMR2_CH1 D(1, 2) + +#define DEF_TIM_AF__PA0__TCH_TMR5_CH1 D(2, 5) +#define DEF_TIM_AF__PA1__TCH_TMR5_CH2 D(2, 5) +#define DEF_TIM_AF__PA2__TCH_TMR5_CH3 D(2, 5) +#define DEF_TIM_AF__PA3__TCH_TMR5_CH4 D(2, 5) +#define DEF_TIM_AF__PA6__TCH_TMR3_CH1 D(2, 3) +#define DEF_TIM_AF__PA7__TCH_TMR3_CH2 D(2, 3) + +#define DEF_TIM_AF__PA2__TCH_TMR9_CH1 D(3, 9) +#define DEF_TIM_AF__PA3__TCH_TMR9_CH2 D(3, 9) +#define DEF_TIM_AF__PA5__TCH_TMR8_CH1N D(3, 8) +#define DEF_TIM_AF__PA7__TCH_TMR8_CH1N D(3, 8) + +#define DEF_TIM_AF__PA6__TCH_TMR13_CH1 D(9, 13) +#define DEF_TIM_AF__PA7__TCH_TMR14_CH1 D(9, 14) + +//GPIOB +#define DEF_TIM_AF__PB0__TCH_TMR1_CH2N D(1, 1) +#define DEF_TIM_AF__PB1__TCH_TMR1_CH3N D(1, 1) +#define DEF_TIM_AF__PB2__TCH_TMR2_CH4 D(1, 2) +#define DEF_TIM_AF__PB3__TCH_TMR2_CH2 D(1, 2) +#define DEF_TIM_AF__PB8__TCH_TMR2_CH1 D(1, 2) +#define DEF_TIM_AF__PB9__TCH_TMR2_CH2 D(1, 2) +#define DEF_TIM_AF__PB10__TCH_TMR2_CH3 D(1, 2) +#define DEF_TIM_AF__PB11__TCH_TMR2_CH4 D(1, 2) +#define DEF_TIM_AF__PB13__TCH_TMR1_CH1N D(1, 1) +#define DEF_TIM_AF__PB14__TCH_TMR1_CH2N D(1, 1) +#define DEF_TIM_AF__PB15__TCH_TMR1_CH3N D(1, 1) + +#define DEF_TIM_AF__PB0__TCH_TMR3_CH3 D(2, 3) +#define DEF_TIM_AF__PB1__TCH_TMR3_CH4 D(2, 3) +#define DEF_TIM_AF__PB2__TCH_TMR20_CH1 D(2, 20) +#define DEF_TIM_AF__PB4__TCH_TMR3_CH1 D(2, 3) +#define DEF_TIM_AF__PB5__TCH_TMR3_CH2 D(2, 3) +#define DEF_TIM_AF__PB6__TCH_TMR4_CH1 D(2, 4) +#define DEF_TIM_AF__PB7__TCH_TMR4_CH2 D(2, 4) +#define DEF_TIM_AF__PB8__TCH_TMR4_CH3 D(2, 4) +#define DEF_TIM_AF__PB9__TCH_TMR4_CH4 D(2, 4) +#define DEF_TIM_AF__PB11__TCH_TMR5_CH4 D(2, 5) +#define DEF_TIM_AF__PB12__TCH_TMR5_CH1 D(2, 5) + +#define DEF_TIM_AF__PB0__TCH_TMR8_CH2N D(3, 8) +#define DEF_TIM_AF__PB1__TCH_TMR8_CH3N D(3, 8) +#define DEF_TIM_AF__PB8__TCH_TMR10_CH1 D(3, 10) +#define DEF_TIM_AF__PB9__TCH_TMR11_CH1 D(3, 11) +#define DEF_TIM_AF__PB14__TCH_TMR8_CH2N D(3, 8) +#define DEF_TIM_AF__PB15__TCH_TMR8_CH3N D(3, 8) + +#define DEF_TIM_AF__PB14__TCH_TMR12_CH1 D(9, 12) +#define DEF_TIM_AF__PB15__TCH_TMR12_CH2 D(9, 12) + +//GPIOC +#define DEF_TIM_AF__PC2__TCH_TMR20_CH2 D(2, 20) +#define DEF_TIM_AF__PC6__TCH_TMR3_CH1 D(2, 3) +#define DEF_TIM_AF__PC7__TCH_TMR3_CH2 D(2, 3) +#define DEF_TIM_AF__PC8__TCH_TMR3_CH3 D(2, 3) +#define DEF_TIM_AF__PC9__TCH_TMR3_CH4 D(2, 3) +#define DEF_TIM_AF__PC10__TCH_TMR5_CH2 D(2, 5) +#define DEF_TIM_AF__PC11__TCH_TMR5_CH3 D(2, 5) + +#define DEF_TIM_AF__PC4__TCH_TMR9_CH1 D(3, 9) +#define DEF_TIM_AF__PC5__TCH_TMR9_CH2 D(3, 9) +#define DEF_TIM_AF__PC6__TCH_TMR8_CH1 D(3, 8) +#define DEF_TIM_AF__PC7__TCH_TMR8_CH2 D(3, 8) +#define DEF_TIM_AF__PC8__TCH_TMR8_CH3 D(3, 8) +#define DEF_TIM_AF__PC9__TCH_TMR8_CH4 D(3, 8) +#define DEF_TIM_AF__PC12__TCH_TMR11_CH1 D(3, 11) + +//GPIOD +#define DEF_TIM_AF__PD12__TCH_TMR4_CH1 D(2, 4) +#define DEF_TIM_AF__PD13__TCH_TMR4_CH2 D(2, 4) +#define DEF_TIM_AF__PD14__TCH_TMR4_CH3 D(2, 4) +#define DEF_TIM_AF__PD15__TCH_TMR4_CH4 D(2, 4) + +//GPIOE +#define DEF_TIM_AF__PE8__TCH_TMR1_CH1N D(1, 1) +#define DEF_TIM_AF__PE9__TCH_TMR1_CH1 D(1, 1) +#define DEF_TIM_AF__PE10__TCH_TMR1_CH2N D(1, 1) +#define DEF_TIM_AF__PE11__TCH_TMR1_CH2 D(1, 1) +#define DEF_TIM_AF__PE12__TCH_TMR1_CH3N D(1, 1) +#define DEF_TIM_AF__PE13__TCH_TMR1_CH3 D(1, 1) +#define DEF_TIM_AF__PE14__TCH_TMR1_CH4 D(1, 1) + +#define DEF_TIM_AF__PE3__TCH_TMR3_CH1 D(3, 3) +#define DEF_TIM_AF__PE4__TCH_TMR3_CH2 D(3, 3) +#define DEF_TIM_AF__PE5__TCH_TMR3_CH3 D(3, 3) +#define DEF_TIM_AF__PE6__TCH_TMR3_CH4 D(3, 3) + +#define DEF_TIM_AF__PE5__TCH_TMR9_CH1 D(3, 9) +#define DEF_TIM_AF__PE6__TCH_TMR9_CH2 D(3, 9) + +#define DEF_TIM_AF__PE1__TCH_TMR20_CH4 D(6, 20) +#define DEF_TIM_AF__PE2__TCH_TMR20_CH1 D(6, 20) +#define DEF_TIM_AF__PE3__TCH_TMR20_CH2 D(6, 20) +#define DEF_TIM_AF__PE4__TCH_TMR20_CH1N D(6, 20) +#define DEF_TIM_AF__PE5__TCH_TMR20_CH2N D(6, 20) +#define DEF_TIM_AF__PE6__TCH_TMR20_CH3N D(6, 20) + +//GPIOF +#define DEF_TIM_AF__PF2__TCH_TMR20_CH3 D(2, 20) +#define DEF_TIM_AF__PF3__TCH_TMR20_CH4 D(2, 20) +#define DEF_TIM_AF__PF4__TCH_TMR20_CH1N D(2, 20) +#define DEF_TIM_AF__PF5__TCH_TMR20_CH2N D(2, 20) +#define DEF_TIM_AF__PF6__TCH_TMR20_CH4 D(2, 20) +#define DEF_TIM_AF__PF10__TCH_TMR5_CH4 D(2, 5) +#define DEF_TIM_AF__PF12__TCH_TMR20_CH1 D(2, 20) +#define DEF_TIM_AF__PF13__TCH_TMR20_CH2 D(2, 20) +#define DEF_TIM_AF__PF14__TCH_TMR20_CH3 D(2, 20) +#define DEF_TIM_AF__PF15__TCH_TMR20_CH4 D(2, 20) + +#define DEF_TIM_AF__PF6__TCH_TMR10_CH1 D(3, 10) +#define DEF_TIM_AF__PF7__TCH_TMR11_CH1 D(3, 11) + +#define DEF_TIM_AF__PF8__TCH_TMR13_CH1 D(9, 13) +#define DEF_TIM_AF__PF9__TCH_TMR14_CH1 D(9, 14) + +// GPIOG +#define DEF_TIM_AF__PG0__TCH_TMR20_CH1N D(2, 20) +#define DEF_TIM_AF__PG1__TCH_TMR20_CH2N D(2, 20) +#define DEF_TIM_AF__PG2__TCH_TMR20_CH3N D(2, 20) + +//GPIOH +#define DEF_TIM_AF__PH2__TCH_TMR5_CH1 D(2, 5) +#define DEF_TIM_AF__PH3__TCH_TMR5_CH2 D(2, 5) + diff --git a/src/main/drivers/timer_impl.h b/src/main/drivers/timer_impl.h index bb9d55af98..82c0983721 100644 --- a/src/main/drivers/timer_impl.h +++ b/src/main/drivers/timer_impl.h @@ -17,12 +17,35 @@ #pragma once +#if defined(AT32F43x) +#define IMPL_TIM_IT_UPDATE_INTERRUPT TMR_OVF_INT +#define TIM_IT_CCx(chIdx) (TMR_C1_INT << (chIdx)) +// 0x2 0x4 0x8 0x10 0\1\2\3 + +#define _TIM_IRQ_HANDLER2(name, i, j) \ + void name(void) \ + { \ + impl_timerCaptureCompareHandler(TMR ## i, timerCtx[i - 1]); \ + impl_timerCaptureCompareHandler(TMR ## j, timerCtx[j - 1]); \ + } struct dummy + +#define _TIM_IRQ_HANDLER(name, i) \ + void name(void) \ + { \ + impl_timerCaptureCompareHandler(TMR ## i, timerCtx[i - 1]); \ + } struct dummy + +uint8_t lookupTimerIndex(const tmr_type *tim); +void impl_timerCaptureCompareHandler(tmr_type *tim, timHardwareContext_t * timerCtx); + +#else // end at32 + #if defined(USE_HAL_DRIVER) -# define IMPL_TIM_IT_UPDATE_INTERRUPT TIM_IT_UPDATE -# define TIM_IT_CCx(chIdx) (TIM_IT_CC1 << (chIdx)) +# define IMPL_TIM_IT_UPDATE_INTERRUPT TIM_IT_UPDATE +# define TIM_IT_CCx(chIdx) (TIM_IT_CC1 << (chIdx)) #else -# define IMPL_TIM_IT_UPDATE_INTERRUPT TIM_IT_Update -# define TIM_IT_CCx(chIdx) (TIM_IT_CC1 << (chIdx)) +#define IMPL_TIM_IT_UPDATE_INTERRUPT TIM_IT_Update +#define TIM_IT_CCx(chIdx) (TIM_IT_CC1 << (chIdx)) #endif #define _TIM_IRQ_HANDLER2(name, i, j) \ @@ -39,11 +62,13 @@ } struct dummy uint8_t lookupTimerIndex(const TIM_TypeDef *tim); +void impl_timerCaptureCompareHandler(TIM_TypeDef *tim, timHardwareContext_t * timerCtx); + +#endif //end of else (stm32) + void impl_timerInitContext(timHardwareContext_t * timCtx); volatile timCCR_t * impl_timerCCR(TCH_t * tch); -void impl_timerCaptureCompareHandler(TIM_TypeDef *tim, timHardwareContext_t * timerCtx); - void impl_timerNVICConfigure(TCH_t * tch, int irqPriority); void impl_timerConfigBase(TCH_t * tch, uint16_t period, uint32_t hz); void impl_enableTimer(TCH_t * tch); diff --git a/src/main/drivers/timer_impl_stdperiph_at32.c b/src/main/drivers/timer_impl_stdperiph_at32.c new file mode 100644 index 0000000000..4579db2bb7 --- /dev/null +++ b/src/main/drivers/timer_impl_stdperiph_at32.c @@ -0,0 +1,409 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + +#include +#include +#include + +#include "platform.h" + +#include "build/atomic.h" +#include "build/debug.h" + +#include "common/utils.h" + +#include "drivers/io.h" +#include "drivers/rcc.h" +#include "drivers/time.h" +#include "drivers/nvic.h" +#include "drivers/dma.h" +#include "drivers/timer.h" +#include "drivers/timer_impl.h" + +const uint16_t lookupDMASourceTable[4] = { TMR_C1_DMA_REQUEST, TMR_C2_DMA_REQUEST, TMR_C3_DMA_REQUEST, TMR_C4_DMA_REQUEST }; + +const uint8_t lookupTIMChannelTable[4] = { TMR_C1_FLAG, TMR_C2_FLAG, TMR_C3_FLAG, TMR_C4_FLAG }; + +void impl_timerInitContext(timHardwareContext_t * timCtx) +{ + (void)timCtx; // NoOp +} +// Configure the interrupt priority +void impl_timerNVICConfigure(TCH_t * tch, int irqPriority) +{ + if (tch->timCtx->timDef->irq) { + nvic_irq_enable(tch->timCtx->timDef->irq, irqPriority, 0); + } + + if (tch->timCtx->timDef->secondIrq) { + nvic_irq_enable(tch->timCtx->timDef->secondIrq, irqPriority, 0); + } +} + +void impl_timerConfigBase(TCH_t * tch, uint16_t period, uint32_t hz) +{ + tmr_type * tim = tch->timCtx->timDef->tim; + tmr_base_init(tim, (period - 1) & 0xffff, lrintf((float)timerGetBaseClock(tch) / hz + 0.01f) - 1); + tmr_clock_source_div_set(tim, TMR_CLOCK_DIV1); + tmr_cnt_dir_set(tim, TMR_COUNT_UP); //Count up (default) +} + +void impl_enableTimer(TCH_t * tch) +{ + tmr_counter_enable(tch->timHw->tim, TRUE); +} + +void impl_timerPWMStart(TCH_t * tch) +{ + tmr_output_enable(tch->timHw->tim,TRUE); +} + +void impl_timerEnableIT(TCH_t * tch, uint32_t interrupt) +{ + tmr_interrupt_enable(tch->timHw->tim, interrupt, TRUE); +} + +void impl_timerDisableIT(TCH_t * tch, uint32_t interrupt) +{ + tmr_interrupt_enable(tch->timHw->tim, interrupt, FALSE); +} + +void impl_timerClearFlag(TCH_t * tch, uint32_t flag) +{ + tmr_flag_clear(tch->timHw->tim, flag); +} + +// calculate input filter constant +static unsigned getFilter(unsigned ticks) +{ + static const unsigned ftab[16] = { + 1*1, // fDTS ! + 1*2, 1*4, 1*8, // fCK_INT + 2*6, 2*8, // fDTS/2 + 4*6, 4*8, + 8*6, 8*8, + 16*5, 16*6, 16*8, + 32*5, 32*6, 32*8 + }; + + for (unsigned i = 1; i < ARRAYLEN(ftab); i++) { + if (ftab[i] > ticks) { + return i - 1; + } + } + + return 0x0f; +} + +void impl_timerChConfigIC(TCH_t * tch, bool polarityRising, unsigned inputFilterTicks) +{ + tmr_input_config_type tmr_input_config_struct; + + tmr_input_default_para_init(&tmr_input_config_struct); + tmr_input_config_struct.input_channel_select = lookupTIMChannelTable[tch->timHw->channelIndex]; + tmr_input_config_struct.input_mapped_select = TMR_CC_CHANNEL_MAPPED_DIRECT; + tmr_input_config_struct.input_polarity_select = polarityRising ? TMR_INPUT_RISING_EDGE:TMR_INPUT_FALLING_EDGE; + tmr_input_config_struct.input_filter_value = getFilter(inputFilterTicks); + tmr_input_channel_init(tch->timHw->tim,&tmr_input_config_struct,TMR_CHANNEL_INPUT_DIV_1); +} + +void impl_timerCaptureCompareHandler(tmr_type *tim, timHardwareContext_t *timerCtx) +{ + unsigned tim_status = tim->ists & tim->iden; + + while (tim_status) { + // flags will be cleared by reading CCR in dual capture, make sure we call handler correctly + // currrent order is highest bit first. Code should not rely on specific order (it will introduce race conditions anyway) + unsigned bit = __builtin_clz(tim_status); + unsigned mask = ~(0x80000000 >> bit); + tim->ists = mask; + tim_status &= mask; + + if (timerCtx) { + switch (bit) { + case __builtin_clz(TMR_OVF_INT): { + const uint16_t capture = tim->pr; + if (timerCtx->ch[0].cb && timerCtx->ch[0].cb->callbackOvr) { + timerCtx->ch[0].cb->callbackOvr(&timerCtx->ch[0], capture); + } + if (timerCtx->ch[1].cb && timerCtx->ch[1].cb->callbackOvr) { + timerCtx->ch[1].cb->callbackOvr(&timerCtx->ch[1], capture); + } + if (timerCtx->ch[2].cb && timerCtx->ch[2].cb->callbackOvr) { + timerCtx->ch[2].cb->callbackOvr(&timerCtx->ch[2], capture); + } + if (timerCtx->ch[3].cb && timerCtx->ch[3].cb->callbackOvr) { + timerCtx->ch[3].cb->callbackOvr(&timerCtx->ch[3], capture); + } + break; + } + case __builtin_clz(TMR_C1_INT): + timerCtx->ch[0].cb->callbackEdge(&timerCtx->ch[0], tim->c1dt); + break; + case __builtin_clz(TMR_C2_INT): + timerCtx->ch[1].cb->callbackEdge(&timerCtx->ch[1], tim->c2dt); + break; + case __builtin_clz(TMR_C3_INT): + timerCtx->ch[2].cb->callbackEdge(&timerCtx->ch[2], tim->c3dt); + break; + case __builtin_clz(TMR_C4_INT): + timerCtx->ch[3].cb->callbackEdge(&timerCtx->ch[3], tim->c4dt); + break; + } + } + else { + // timerConfig == NULL + volatile uint32_t tmp; + + switch (bit) { + case __builtin_clz(TMR_OVF_INT): + tmp = tim->pr; + break; + case __builtin_clz(TMR_C1_INT): + tmp = tim->c1dt; + break; + case __builtin_clz(TMR_C2_INT): + tmp = tim->c2dt; + break; + case __builtin_clz(TMR_C3_INT): + tmp = tim->c3dt; + break; + case __builtin_clz(TMR_C4_INT): + tmp = tim->c4dt; + break; + } + + (void)tmp; + } + } +} + +void impl_timerPWMConfigChannel(TCH_t * tch, uint16_t value) +{ + const bool inverted = tch->timHw->output & TIMER_OUTPUT_INVERTED; + tmr_output_config_type tmr_output_struct; + tmr_output_default_para_init(&tmr_output_struct); + tmr_output_struct.oc_mode = TMR_OUTPUT_CONTROL_PWM_MODE_A; + + if (tch->timHw->output & TIMER_OUTPUT_N_CHANNEL) { + tmr_output_struct.oc_output_state = FALSE; + tmr_output_struct.occ_output_state = TRUE; + tmr_output_struct.occ_polarity = inverted ? TMR_OUTPUT_ACTIVE_LOW : TMR_OUTPUT_ACTIVE_HIGH; + tmr_output_struct.occ_idle_state = FALSE; + + } else { + tmr_output_struct.oc_output_state = TRUE; + tmr_output_struct.occ_output_state = FALSE; + tmr_output_struct.oc_polarity = inverted ? TMR_OUTPUT_ACTIVE_LOW : TMR_OUTPUT_ACTIVE_HIGH; + tmr_output_struct.oc_idle_state = TRUE; + } + switch (tch->timHw->channelIndex) { + case 0: + tmr_output_channel_config(tch->timHw->tim,TMR_SELECT_CHANNEL_1, &tmr_output_struct); + tmr_channel_value_set(tch->timHw->tim, TMR_SELECT_CHANNEL_1, value); + tmr_output_channel_buffer_enable(tch->timHw->tim,TMR_SELECT_CHANNEL_1,TRUE); + break; + case 1: + tmr_output_channel_config(tch->timHw->tim,TMR_SELECT_CHANNEL_2, &tmr_output_struct); + tmr_channel_value_set(tch->timHw->tim, TMR_SELECT_CHANNEL_2, value); + tmr_output_channel_buffer_enable(tch->timHw->tim,TMR_SELECT_CHANNEL_2,TRUE); + + break; + case 2: + tmr_output_channel_config(tch->timHw->tim,TMR_SELECT_CHANNEL_3, &tmr_output_struct); + tmr_channel_value_set(tch->timHw->tim, TMR_SELECT_CHANNEL_3, value); + tmr_output_channel_buffer_enable(tch->timHw->tim,TMR_SELECT_CHANNEL_3,TRUE); + + break; + case 3: + tmr_output_channel_config(tch->timHw->tim,TMR_SELECT_CHANNEL_4, &tmr_output_struct); + tmr_channel_value_set(tch->timHw->tim, TMR_SELECT_CHANNEL_4, value); + tmr_output_channel_buffer_enable(tch->timHw->tim,TMR_SELECT_CHANNEL_4,TRUE); + + break; + } + +} + +volatile timCCR_t * impl_timerCCR(TCH_t * tch) +{ + switch (tch->timHw->channelIndex) { + case 0: + return &tch->timHw->tim->c1dt; + break; + case 1: + return &tch->timHw->tim->c2dt; + break; + case 2: + return &tch->timHw->tim->c3dt; + break; + case 3: + return &tch->timHw->tim->c4dt; + break; + } + return NULL; +} + +// Set the channel control register +void impl_timerChCaptureCompareEnable(TCH_t * tch, bool enable) +{ + tmr_channel_enable(tch->timHw->tim, lookupTIMChannelTable[tch->timHw->channelIndex],(enable ? TRUE : FALSE)); +} + +// lookupDMASourceTable +static void impl_timerDMA_IRQHandler(DMA_t descriptor) +{ + if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF)) { + TCH_t * tch = (TCH_t *)descriptor->userParam; + tch->dmaState = TCH_DMA_IDLE; + dma_channel_enable(tch->dma->ref,FALSE); + tmr_dma_request_enable(tch->timHw->tim, lookupDMASourceTable[tch->timHw->channelIndex], FALSE); + DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF); + } +} + +bool impl_timerPWMConfigChannelDMA(TCH_t * tch, void * dmaBuffer, uint8_t dmaBufferElementSize, uint32_t dmaBufferElementCount) +{ + dma_init_type dma_init_struct = {0}; + tmr_type * timer = tch->timHw->tim; + + tch->dma = dmaGetByTag(tch->timHw->dmaTag); + if (tch->dma == NULL) { + return false; + } + + // If DMA is already in use - abort + if (tch->dma->owner != OWNER_FREE) { + return false; + } + + // We assume that timer channels are already initialized by calls to + tmr_output_enable(timer, TRUE); + + // enable The TMR periodic buffer register + tmr_period_buffer_enable(timer,TRUE); + + tmr_channel_enable(timer, lookupTIMChannelTable[tch->timHw->channelIndex],TRUE); + + tmr_counter_enable(timer, TRUE); + dmaInit(tch->dma, OWNER_TIMER, 0); + + dmaSetHandler(tch->dma, impl_timerDMA_IRQHandler, NVIC_PRIO_TIMER_DMA, (uint32_t)tch); + dma_reset(tch->dma->ref); + dma_channel_enable(tch->dma->ref,FALSE); + + dma_reset(tch->dma->ref); + dma_default_para_init(&dma_init_struct); + + dma_init_struct.peripheral_base_addr = (uint32_t)impl_timerCCR(tch); + dma_init_struct.buffer_size = dmaBufferElementCount; + dma_init_struct.peripheral_inc_enable = FALSE; + dma_init_struct.memory_inc_enable = TRUE; + dma_init_struct.loop_mode_enable = FALSE; + + switch (dmaBufferElementSize) { + case 1: + dma_init_struct.memory_data_width = DMA_MEMORY_DATA_WIDTH_BYTE; + dma_init_struct.peripheral_data_width = DMA_PERIPHERAL_DATA_WIDTH_BYTE; + break; + case 2: + dma_init_struct.memory_data_width = DMA_MEMORY_DATA_WIDTH_HALFWORD; + dma_init_struct.peripheral_data_width = DMA_PERIPHERAL_DATA_WIDTH_HALFWORD; + break; + case 4: + dma_init_struct.memory_data_width = DMA_MEMORY_DATA_WIDTH_WORD; + dma_init_struct.peripheral_data_width = DMA_PERIPHERAL_DATA_WIDTH_WORD; + break; + default: + // Programmer error + while(1) { + } + } + + dma_init_struct.direction = DMA_DIR_MEMORY_TO_PERIPHERAL; + dma_init_struct.memory_base_addr = (uint32_t)dmaBuffer; + dma_init_struct.priority = DMA_PRIORITY_HIGH; + dma_init(tch->dma->ref, &dma_init_struct); + + //Set DMA request Mux mapping + dmaMuxEnable(tch->dma, tch->timHw->dmaMuxid); + dma_interrupt_enable(tch->dma->ref, DMA_IT_TCIF, TRUE); + + return true; +} + +void impl_timerPWMPrepareDMA(TCH_t * tch, uint32_t dmaBufferElementCount) +{ + tch->dma = dmaGetByTag(tch->timHw->dmaTag); + if (tch->dma == NULL) { + return ; + } + + // Make sure we terminate any DMA transaction currently in progress + // Clear the flag as well, so even if DMA transfer finishes while within ATOMIC_BLOCK + // the resulting IRQ won't mess up the DMA state + ATOMIC_BLOCK(NVIC_PRIO_MAX) { + dma_channel_enable(tch->dma->ref,FALSE); + tmr_dma_request_enable(tch->timHw->tim, lookupDMASourceTable[tch->timHw->channelIndex], FALSE); + // clear dma flag + DMA_CLEAR_FLAG(tch->dma, DMA_IT_TCIF); + + } + dma_data_number_set(tch->dma->ref, dmaBufferElementCount); + + dma_channel_enable(tch->dma->ref,TRUE); + tch->dmaState = TCH_DMA_READY; +} + +void impl_timerPWMStartDMA(TCH_t * tch) +{ + uint16_t dmaSources = 0; + timHardwareContext_t * timCtx = tch->timCtx; + + if (timCtx->ch[0].dmaState == TCH_DMA_READY) { + timCtx->ch[0].dmaState = TCH_DMA_ACTIVE; + dmaSources |= TMR_C1_DMA_REQUEST; + } + + if (timCtx->ch[1].dmaState == TCH_DMA_READY) { + timCtx->ch[1].dmaState = TCH_DMA_ACTIVE; + dmaSources |= TMR_C2_DMA_REQUEST; + } + + if (timCtx->ch[2].dmaState == TCH_DMA_READY) { + timCtx->ch[2].dmaState = TCH_DMA_ACTIVE; + dmaSources |= TMR_C3_DMA_REQUEST; + } + + if (timCtx->ch[3].dmaState == TCH_DMA_READY) { + timCtx->ch[3].dmaState = TCH_DMA_ACTIVE; + dmaSources |= TMR_C4_DMA_REQUEST; + } + + if (dmaSources) { + tmr_counter_value_set(tch->timHw->tim, 0); + tmr_dma_request_enable(tch->timHw->tim, dmaSources, TRUE); + } +} + +void impl_timerPWMStopDMA(TCH_t * tch) +{ + dma_channel_enable(tch->dma->ref,FALSE); + tmr_dma_request_enable(tch->timHw->tim, lookupDMASourceTable[tch->timHw->channelIndex], FALSE); + tmr_counter_enable(tch->timHw->tim, TRUE); + +} diff --git a/src/main/drivers/uart_inverter.c b/src/main/drivers/uart_inverter.c index 0cb015671b..b815883df7 100644 --- a/src/main/drivers/uart_inverter.c +++ b/src/main/drivers/uart_inverter.c @@ -98,8 +98,11 @@ void uartInverterInit(void) #endif } - + #if defined(AT32F43x) +void uartInverterSet(usart_type *USARTx, uartInverterLine_e line, bool enable) +#else void uartInverterSet(USART_TypeDef *USARTx, uartInverterLine_e line, bool enable) +#endif { IO_t rx_pin = IO_NONE; IO_t tx_pin = IO_NONE; diff --git a/src/main/drivers/uart_inverter.h b/src/main/drivers/uart_inverter.h index 0acf1dddf5..dd3b87498a 100644 --- a/src/main/drivers/uart_inverter.h +++ b/src/main/drivers/uart_inverter.h @@ -25,4 +25,8 @@ typedef enum { void uartInverterInit(void); + #if defined(AT32F43x) +void uartInverterSet(usart_type *USARTx, uartInverterLine_e line, bool enable); +#else void uartInverterSet(USART_TypeDef *USARTx, uartInverterLine_e line, bool enable); +#endif diff --git a/src/main/drivers/usb_msc_at32f43x.c b/src/main/drivers/usb_msc_at32f43x.c new file mode 100644 index 0000000000..fbeef809b8 --- /dev/null +++ b/src/main/drivers/usb_msc_at32f43x.c @@ -0,0 +1,299 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +/* + * Author: Chris Hockuba (https://github.com/conkerkh) + * + */ + +#include +#include +#include + +#include "platform.h" + +#if defined(USE_USB_MSC) + +#include "build/build_config.h" + +#include "common/utils.h" + +#include "blackbox/blackbox.h" +#include "blackbox/blackbox_io.h" + +#include "drivers/io.h" +#include "drivers/light_led.h" +#include "drivers/nvic.h" +#include "drivers/persistent.h" +#include "drivers/sdcard/sdmmc_sdio.h" +#include "drivers/time.h" +#include "drivers/usb_msc.h" + +#include "usb_conf.h" +#include "usb_core.h" +#include "usbd_int.h" +#include "msc_class.h" +#include "msc_desc.h" +#include "usb_io.h" + +#define DEBOUNCE_TIME_MS 20 + +extern otg_core_type otg_core_struct; + + +#if defined(MSC_USE_BUTTON) +static IO_t mscButton; +#endif + +void mscInit(void) +{ +#if defined(MSC_USE_BUTTON) + if (usbDevConfig()->mscButtonPin) { + mscButton = IOGetByTag(usbDevConfig()->mscButtonPin); + IOInit(mscButton, OWNER_USB_MSC_PIN, 0); + if (usbDevConfig()->mscButtonUsePullup) { + IOConfigGPIO(mscButton, IOCFG_IPU); + } else { + IOConfigGPIO(mscButton, IOCFG_IPD); + } + } +#endif +} + + +/** + * @brief this function config gpio. + * @param none + * @retval none + */ +void msc_usb_gpio_config(void) +{ + gpio_init_type gpio_init_struct; + + crm_periph_clock_enable(OTG_PIN_GPIO_CLOCK, TRUE); + gpio_default_para_init(&gpio_init_struct); + + gpio_init_struct.gpio_drive_strength = GPIO_DRIVE_STRENGTH_STRONGER; + gpio_init_struct.gpio_out_type = GPIO_OUTPUT_PUSH_PULL; + gpio_init_struct.gpio_mode = GPIO_MODE_MUX; + gpio_init_struct.gpio_pull = GPIO_PULL_NONE; + + /* dp and dm */ + gpio_init_struct.gpio_pins = OTG_PIN_DP | OTG_PIN_DM; + gpio_init(OTG_PIN_GPIO, &gpio_init_struct); + + gpio_pin_mux_config(OTG_PIN_GPIO, OTG_PIN_DP_SOURCE, OTG_PIN_MUX); + gpio_pin_mux_config(OTG_PIN_GPIO, OTG_PIN_DM_SOURCE, OTG_PIN_MUX); + +#ifdef USB_SOF_OUTPUT_ENABLE + crm_periph_clock_enable(OTG_PIN_SOF_GPIO_CLOCK, TRUE); + gpio_init_struct.gpio_pins = OTG_PIN_SOF; + gpio_init(OTG_PIN_SOF_GPIO, &gpio_init_struct); + gpio_pin_mux_config(OTG_PIN_GPIO, OTG_PIN_SOF_SOURCE, OTG_PIN_MUX); +#endif + + /* otgfs use vbus pin */ +#ifndef USB_VBUS_IGNORE + gpio_init_struct.gpio_pins = OTG_PIN_VBUS; + gpio_init_struct.gpio_pull = GPIO_PULL_DOWN; + gpio_pin_mux_config(OTG_PIN_GPIO, OTG_PIN_VBUS_SOURCE, OTG_PIN_MUX); + gpio_init(OTG_PIN_GPIO, &gpio_init_struct); +#endif + + +} + +/** + * @brief usb 48M clock select + * @param clk_s:USB_CLK_HICK, USB_CLK_HEXT + * @retval none + */ +void msc_usb_clock48m_select(usb_clk48_s clk_s) +{ + if(clk_s == USB_CLK_HICK) + { + crm_usb_clock_source_select(CRM_USB_CLOCK_SOURCE_HICK); + + /* enable the acc calibration ready interrupt */ + crm_periph_clock_enable(CRM_ACC_PERIPH_CLOCK, TRUE); + + /* update the c1\c2\c3 value */ + acc_write_c1(7980); + acc_write_c2(8000); + acc_write_c3(8020); +#if (USB_ID == 0) + acc_sof_select(ACC_SOF_OTG1); +#else + acc_sof_select(ACC_SOF_OTG2); +#endif + /* open acc calibration */ + acc_calibration_mode_enable(ACC_CAL_HICKTRIM, TRUE); + } + else + { + switch(system_core_clock) + { + /* 48MHz */ + case 48000000: + crm_usb_clock_div_set(CRM_USB_DIV_1); + break; + + /* 72MHz */ + case 72000000: + crm_usb_clock_div_set(CRM_USB_DIV_1_5); + break; + + /* 96MHz */ + case 96000000: + crm_usb_clock_div_set(CRM_USB_DIV_2); + break; + + /* 120MHz */ + case 120000000: + crm_usb_clock_div_set(CRM_USB_DIV_2_5); + break; + + /* 144MHz */ + case 144000000: + crm_usb_clock_div_set(CRM_USB_DIV_3); + break; + + /* 168MHz */ + case 168000000: + crm_usb_clock_div_set(CRM_USB_DIV_3_5); + break; + + /* 192MHz */ + case 192000000: + crm_usb_clock_div_set(CRM_USB_DIV_4); + break; + + /* 216MHz */ + case 216000000: + crm_usb_clock_div_set(CRM_USB_DIV_4_5); + break; + + /* 240MHz */ + case 240000000: + crm_usb_clock_div_set(CRM_USB_DIV_5); + break; + + /* 264MHz */ + case 264000000: + crm_usb_clock_div_set(CRM_USB_DIV_5_5); + break; + + /* 288MHz */ + case 288000000: + crm_usb_clock_div_set(CRM_USB_DIV_6); + break; + + default: + break; + + } + } +} + + +uint8_t mscStart(void) +{ + ledInit(false); + + // Start USB + usbGenerateDisconnectPulse(); + + IOInit(IOGetByTag(IO_TAG(PA11)), OWNER_USB, 0, 0); + IOInit(IOGetByTag(IO_TAG(PA12)), OWNER_USB, 0, 0); + + // The SD card is not supported + /* switch (blackboxConfig()->device) { + #ifdef USE_SDCARD + case BLACKBOX_DEVICE_SDCARD: + USBD_STORAGE_fops = &USBD_MSC_MICRO_SDIO_fops; + break; + #endif + + #ifdef USE_FLASHFS + case BLACKBOX_DEVICE_FLASH: + USBD_STORAGE_fops = &USBD_MSC_EMFAT_fops; + break; + #endif + default: + return 1; + } + */ + + /* init usb */ + /* usb gpio config */ + msc_usb_gpio_config(); + + /* enable otgfs clock */ + crm_periph_clock_enable(OTG_CLOCK, TRUE); + + /* select usb 48m clcok source */ + msc_usb_clock48m_select(USB_CLK_HEXT); + + /* enable otgfs irq,Priority NVIC_PRIO_USB must be used */ + nvic_irq_enable(OTG_IRQ, NVIC_PRIO_USB, 0); + + usbd_init(&otg_core_struct, + USB_FULL_SPEED_CORE_ID, + USB_ID, + &msc_class_handler, + &msc_desc_handler); + + // NVIC configuration for SYSTick + nvic_irq_disable(SysTick_IRQn); + + nvic_irq_enable(SysTick_IRQn, 0, 0); + return 0; +} + +bool mscCheckButton(void) +{ + bool result = false; +#if defined(MSC_USE_BUTTON) + if (mscButton) { + uint8_t state = IORead(mscButton); + if (usbDevConfig()->mscButtonUsePullup) { + result = state == 0; + } else { + result = state == 1; + } + } +#endif + return result; +} + +void mscWaitForButton(void) +{ + // In order to exit MSC mode simply disconnect the board, or push the button again. + while (mscCheckButton()); + delay(DEBOUNCE_TIME_MS); + while (true) { + asm("NOP"); + if (mscCheckButton()) { + delay(1); + NVIC_SystemReset(); + } + } +} +#endif diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index e1633983b0..d4c2b3873e 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -3306,7 +3306,17 @@ static void cliStatus(char *cmdline) } } cliPrintLinefeed(); +#if defined(AT32F43x) + cliPrintLine("AT32 system clocks:"); + crm_clocks_freq_type clocks; + crm_clocks_freq_get(&clocks); + + cliPrintLinef(" SYSCLK = %d MHz", clocks.sclk_freq / 1000000); + cliPrintLinef(" ABH = %d MHz", clocks.ahb_freq / 1000000); + cliPrintLinef(" ABP1 = %d MHz", clocks.apb1_freq / 1000000); + cliPrintLinef(" ABP2 = %d MHz", clocks.apb2_freq / 1000000); +#else cliPrintLine("STM32 system clocks:"); #if defined(USE_HAL_DRIVER) cliPrintLinef(" SYSCLK = %d MHz", HAL_RCC_GetSysClockFreq() / 1000000); @@ -3321,6 +3331,7 @@ static void cliStatus(char *cmdline) cliPrintLinef(" PCLK1 = %d MHz", clocks.PCLK1_Frequency / 1000000); cliPrintLinef(" PCLK2 = %d MHz", clocks.PCLK2_Frequency / 1000000); #endif +#endif //for if at32 cliPrintLinef("Sensor status: GYRO=%s, ACC=%s, MAG=%s, BARO=%s, RANGEFINDER=%s, OPFLOW=%s, GPS=%s", hardwareSensorStatusNames[getHwGyroStatus()], diff --git a/src/main/io/serial_4way.c b/src/main/io/serial_4way.c index 0119e61e75..dd825050e1 100644 --- a/src/main/io/serial_4way.c +++ b/src/main/io/serial_4way.c @@ -47,6 +47,8 @@ #if defined(USE_HAL_DRIVER) #define Bit_RESET GPIO_PIN_RESET +#elif defined(AT32F43x) +#define Bit_RESET 0U #endif #define USE_TXRX_LED diff --git a/src/main/msc/at32_msc_diskio.c b/src/main/msc/at32_msc_diskio.c new file mode 100644 index 0000000000..8d30d6b9a5 --- /dev/null +++ b/src/main/msc/at32_msc_diskio.c @@ -0,0 +1,107 @@ +/* + * At32 MSC scsi interface + * FLASH emfat reads and writes are implemented + * Other storage read and write services, such as sd, are not supported + * + * + * + */ + + +#include + +#include "at32_msc_diskio.h" +#include "platform.h" + +#include "common/utils.h" +#include "msc_bot_scsi.h" +#include "drivers/usb_msc.h" + + + +#define STORAGE_LUN_NBR 1 +#define SCSI_BLOCK_SIZE 512 + +static const uint8_t scsi_inquiry[MSC_SUPPORT_MAX_LUN][SCSI_INQUIRY_DATA_LENGTH] = +{ + /* lun = 0 */ + { + 0x00, /* peripheral device type (direct-access device) */ + 0x80, /* removable media bit */ + 0x00, /* ansi version, ecma version, iso version */ + 0x01, /* respond data format */ + SCSI_INQUIRY_DATA_LENGTH - 5, /* additional length */ + 0x00, 0x00, 0x00, /* reserved */ + 'I', 'N', 'A', 'V', ' ', 'F', 'C', ' ', // Manufacturer : 8 bytes + 'O', 'n', 'b', 'o', 'a', 'r', 'd', ' ', // Product : 16 Bytes + 'F', 'l', 'a', 's', 'h', ' ', ' ', ' ', // + ' ', ' ', ' ' ,' ', // Version : 4 Bytes + } +}; + +usb_sts_type msc_disk_capacity(uint8_t lun, uint32_t *block_num, uint32_t *block_size) +{ + UNUSED(lun); + *block_size = SCSI_BLOCK_SIZE; + *block_num = emfat.disk_sectors; + return USB_OK; +} + +/* + + if( ((USBD_StorageTypeDef *)pdev->pUserData)->Read(lun , + hmsc->bot_data, + hmsc->scsi_blk_addr / hmsc->scsi_blk_size, + len / hmsc->scsi_blk_size) < 0) + +static int8_t STORAGE_Read( + uint8_t lun, // logical unit number + uint8_t *buf, // Pointer to the buffer to save data + uint32_t blk_addr, // address of 1st block to be read + uint16_t blk_len) // nmber of blocks to be read +{ + UNUSED(lun); + mscSetActive(); + emfat_read(&emfat, buf, blk_addr, blk_len); + return 0; +} + +*/ +usb_sts_type msc_disk_read( + uint8_t lun, // logical unit number + uint32_t blk_addr, // address of 1st block to be read + uint8_t *buf, // Pointer to the buffer to save data + uint32_t blk_len) // nmber of blocks to be read +{ + UNUSED(lun); + //mscSetActive(); + emfat_read(&emfat, buf, blk_addr/SCSI_BLOCK_SIZE , blk_len/SCSI_BLOCK_SIZE); + return USB_OK; +} + +usb_sts_type msc_disk_write(uint8_t lun, + uint32_t blk_addr, + uint8_t *buf, + uint32_t blk_len) +{ + UNUSED(lun); + UNUSED(buf); + UNUSED(blk_addr); + UNUSED(blk_len); + + return USB_FAIL; +} + + +/** + * @brief get disk inquiry + * @param lun: logical units number + * @retval inquiry string + */ +uint8_t * get_inquiry(uint8_t lun) +{ + if(lun < MSC_SUPPORT_MAX_LUN) + return (uint8_t *)scsi_inquiry[lun]; + else + return NULL; +} diff --git a/src/main/msc/at32_msc_diskio.h b/src/main/msc/at32_msc_diskio.h new file mode 100644 index 0000000000..9ece8cf59c --- /dev/null +++ b/src/main/msc/at32_msc_diskio.h @@ -0,0 +1,43 @@ +/* + * This file is part of ATBetaflight and INav. + * + * ATBetaflight and INav are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * ATBetaflight and INav are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + * + * Author: jflyper (https://github.com/jflyper) + */ + +#pragma once + +#include "emfat.h" + +extern emfat_t emfat; + + +#ifdef __cplusplus +extern "C" { +#endif + + +#include "usb_conf.h" +#include "usb_std.h" + + + +uint8_t *get_inquiry(uint8_t lun); +usb_sts_type msc_disk_read(uint8_t lun, uint32_t addr, uint8_t *read_buf, uint32_t len); +usb_sts_type msc_disk_write(uint8_t lun, uint32_t addr, uint8_t *buf, uint32_t len); +usb_sts_type msc_disk_capacity(uint8_t lun, uint32_t *blk_nbr, uint32_t *blk_size); diff --git a/src/main/navigation/navigation_fw_launch.c b/src/main/navigation/navigation_fw_launch.c index 92a7967afb..d83b61426e 100644 --- a/src/main/navigation/navigation_fw_launch.c +++ b/src/main/navigation/navigation_fw_launch.c @@ -52,7 +52,7 @@ #define SWING_LAUNCH_MIN_ROTATION_RATE DEGREES_TO_RADIANS(100) // expect minimum 100dps rotation rate #define LAUNCH_MOTOR_IDLE_SPINUP_TIME 1500 // ms -#ifndef UNUSED +#if !defined(UNUSED) #define UNUSED(x) ((void)(x)) #endif #define FW_LAUNCH_MESSAGE_TEXT_WAIT_THROTTLE "RAISE THE THROTTLE" diff --git a/src/main/target/SAGEATF4/CMakeLists.txt b/src/main/target/SAGEATF4/CMakeLists.txt new file mode 100644 index 0000000000..60b7ac0879 --- /dev/null +++ b/src/main/target/SAGEATF4/CMakeLists.txt @@ -0,0 +1 @@ +target_at32f43x_xMT7(SAGEATF4) \ No newline at end of file diff --git a/src/main/target/SAGEATF4/target.c b/src/main/target/SAGEATF4/target.c new file mode 100644 index 0000000000..3d8ed6feb5 --- /dev/null +++ b/src/main/target/SAGEATF4/target.c @@ -0,0 +1,46 @@ +/* +* This file is part of Cleanflight. +* +* Cleanflight is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* Cleanflight is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with Cleanflight. If not, see . +*/ + +#include + +#include "platform.h" + +#include "drivers/bus.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" + +timerHardware_t timerHardware[] = { + + DEF_TIM(TMR5, CH4, PA3, TIM_USE_PPM, 0, 4), // PPM UART2_RX_PIN DMA1 CH5 + DEF_TIM(TMR2, CH3, PB10, TIM_USE_ANY |TIM_USE_LED, 0,5), // PWM1 - LED MCO1 DMA1 CH6 + DEF_TIM(TMR2, CH4, PB11, TIM_USE_ANY |TIM_USE_BEEPER, 0,6), // PWM2 - BB DMA1 CH7 + + DEF_TIM(TMR4, CH1, PB6, TIM_USE_MC_MOTOR|TIM_USE_FW_MOTOR, 0,0), // motor1 DMA1 CH1 + DEF_TIM(TMR4, CH2, PB7, TIM_USE_MC_MOTOR|TIM_USE_FW_MOTOR, 0,1), // motor2 DMA1 CH2 + DEF_TIM(TMR2, CH1, PB8, TIM_USE_MC_MOTOR|TIM_USE_FW_SERVO, 0,2), // motor3 DMA1 CH3 + DEF_TIM(TMR2, CH2, PB9, TIM_USE_MC_MOTOR|TIM_USE_FW_SERVO, 0,3), // motor4 DMA1 CH4 + + DEF_TIM(TMR3, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0,8), // PWM1 - OUT5 DMA2 CH2 DMA2_CHANNEL1->ADC + DEF_TIM(TMR3, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0,9), // PWM2 - OUT6 DMA2 CH3 + DEF_TIM(TMR3, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0,10), // PWM3 - OUT7 DMA2 CH4 + DEF_TIM(TMR3, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0,11), // PWM4 - OUT8 DMA2 CH5 + +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); + \ No newline at end of file diff --git a/src/main/target/SAGEATF4/target.h b/src/main/target/SAGEATF4/target.h new file mode 100644 index 0000000000..8dd3b18f76 --- /dev/null +++ b/src/main/target/SAGEATF4/target.h @@ -0,0 +1,208 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "ATF4" + +#define USBD_PRODUCT_STRING "SAGEATF4" + +/**********swd debuger reserved ***************** + * + * pa13 swdio + * pa14 swclk + * PA15 JTDI + * PB4 JREST + * pb3 swo /DTO + + * other pin + * + * PB2 ->BOOT0 button + * PA8 MCO1 + * PA11 OTG1 D+ DP + * PA10 OTG1 D- DN + * PH0 HEXT IN + * PH1 HEXT OUT + */ + +#define LED0 PD15 +#define LED1 PD14 + +#define BEEPER PB11 +#define BEEPER_INVERTED +#define BEEPER_PWM_FREQUENCY 2500 //0 Active BB | 2500Hz Passive BB + +// *************** Gyro & ACC ********************** +#define USE_SPI +#define USE_SPI_DEVICE_1 + +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 +#define SPI1_NSS_PIN PA4 + +#define USE_EXTI +#define GYRO_INT_EXTI PA15 +#define USE_MPU_DATA_READY_SIGNAL + +// MPU6000 +#define USE_IMU_MPU6000 +#define IMU_MPU6000_ALIGN CW0_DEG +#define MPU6000_SPI_BUS BUS_SPI1 +#define MPU6000_CS_PIN SPI1_NSS_PIN +#define MPU6000_EXTI_PIN GYRO_INT_EXTI +// MPU6500 +#define USE_IMU_MPU6500 +#define IMU_MPU6500_ALIGN CW0_DEG +#define MPU6500_SPI_BUS BUS_SPI1 +#define MPU6500_CS_PIN SPI1_NSS_PIN + +// ICM42605/ICM42688P +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW0_DEG +#define ICM42605_SPI_BUS BUS_SPI1 +#define ICM42605_CS_PIN SPI1_NSS_PIN +#define ICM42605_EXTI_PIN GYRO_INT_EXTI + +// MPU9250 +#define USE_IMU_MPU9250 +#define IMU_MPU9250_ALIGN CW0_DEG +#define MPU9250_SPI_BUS BUS_SPI1 +#define MPU9250_CS_PIN SPI1_NSS_PIN + +// BMI270 +#define USE_IMU_BMI270 +#define IMU_BMI270_ALIGN CW0_DEG +#define BMI270_SPI_BUS BUS_SPI1 +#define BMI270_CS_PIN SPI1_NSS_PIN + +// *************** I2C/Baro/Mag/EXT********************* +#define USE_I2C +#define USE_I2C_DEVICE_3 +#define I2C3_SCL PC0 // SCL pad +#define I2C3_SDA PC1 // SDA pad +#define USE_I2C_PULLUP + +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C3 +#define USE_BARO_BMP280 + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C3 +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 + +// temperature sensors +//#define TEMPERATURE_I2C_BUS BUS_I2C1 +// air speed sensors +//#define PITOT_I2C_BUS BUS_I2C1 +// ranger sensors +//#define USE_RANGEFINDER +//#define RANGEFINDER_I2C_BUS BUS_I2C1 + +// *************** OSD ***************************** +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PD1//PB13 on LQFP64 +#define SPI2_MISO_PIN PD3//PB14 on LQFP64 +#define SPI2_MOSI_PIN PD4//PB15 on LQFP64 +#define SPI2_NSS_PIN PD5 //confirm on lqfp64 + +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN SPI2_NSS_PIN + + +// *************** SD/BLACKBOX ************************** +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PC10 +#define SPI3_MISO_PIN PC11 +#define SPI3_MOSI_PIN PC12 +#define SPI3_NSS_PIN PD6 //confirm on lqfp64 + +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define M25P16_SPI_BUS BUS_SPI3 +#define M25P16_CS_PIN SPI3_NSS_PIN + +#define USE_FLASH_W25N01G +#define W25N01G_SPI_BUS BUS_SPI3 +#define W25N01G_CS_PIN SPI3_NSS_PIN + +// *************** UART ***************************** +#define USE_VCP +#define USB_DETECT_PIN PC14 +#define USE_USB_DETECT + +#define USE_UART1 +#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 + +#define USE_UART2 +#define UART2_RX_PIN PA3 +#define UART2_TX_PIN PA2 + +#define USE_UART3 +#define UART3_RX_PIN PC5 +#define UART3_TX_PIN PC4 + +#define USE_UART4 +#define UART4_RX_PIN PA1 +#define UART4_TX_PIN PA0 + +#define USE_UART8 +#define UART8_RX_PIN PC3 +#define UART8_TX_PIN PC2 + +#define SERIAL_PORT_COUNT 6 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_CRSF +#define SERIALRX_UART SERIAL_PORT_USART1 + +// *************** ADC ***************************** +#define USE_ADC +#define ADC_INSTANCE ADC1 + +#define ADC1_DMA_STREAM DMA2_CHANNEL5 +#define ADC_CHANNEL_1_PIN PB0 +#define ADC_CHANNEL_2_PIN PB1 +//#define ADC_CHANNEL_3_PIN PB0 +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +//#define RSSI_ADC_CHANNEL ADC_CHN_3 + +#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_TELEMETRY| FEATURE_VBAT | FEATURE_OSD ) + +#define USE_LED_STRIP +#define WS2811_PIN PB10 //TIM2_CH3 + +// telemetry +#define USE_SPEKTRUM_BIND +#define BIND_PIN PA3 //UART2_RX_PIN + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff +#define TARGET_IO_PORTE BIT(2) + +#define MAX_PWM_OUTPUT_PORTS 8 +#define USE_DSHOT +#define USE_ESC_SENSOR \ No newline at end of file diff --git a/src/main/target/system_at32f435_437.c b/src/main/target/system_at32f435_437.c index 259d511fb1..c0135bbed5 100644 --- a/src/main/target/system_at32f435_437.c +++ b/src/main/target/system_at32f435_437.c @@ -99,7 +99,7 @@ void SystemInit (void) /* disable all interrupts enable and clear pending bits */ CRM->clkint = 0x009F0000U; -// todo set RAM +// set vector table relocation #ifdef VECT_TAB_SRAM SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* vector table relocation in internal sram. */ #else From 1df3f07244617cd3385bc7d834b42cdc0dd478ed Mon Sep 17 00:00:00 2001 From: EMSR Date: Sun, 29 Jan 2023 23:31:16 +0800 Subject: [PATCH 045/130] add support for lsm6dxx imu Co-Authored-By: EMSR <10240646+shanggl@users.noreply.github.com> Co-Authored-By: carl <101383042+tcdddd@users.noreply.github.com> Co-Authored-By: Hugo Chiang --- src/main/CMakeLists.txt | 2 + src/main/drivers/accgyro/accgyro_lsm6dxx.c | 249 +++++++++++++++++++++ src/main/drivers/accgyro/accgyro_lsm6dxx.h | 114 ++++++++++ src/main/drivers/bus.h | 2 +- src/main/fc/cli.c | 2 +- src/main/fc/settings.yaml | 2 +- src/main/sensors/acceleration.c | 14 +- src/main/sensors/acceleration.h | 1 + src/main/sensors/gyro.c | 10 + src/main/sensors/gyro.h | 2 + src/main/target/common_hardware.c | 5 + 11 files changed, 399 insertions(+), 4 deletions(-) create mode 100644 src/main/drivers/accgyro/accgyro_lsm6dxx.c create mode 100644 src/main/drivers/accgyro/accgyro_lsm6dxx.h diff --git a/src/main/CMakeLists.txt b/src/main/CMakeLists.txt index 317da760b6..243a0ca5b4 100644 --- a/src/main/CMakeLists.txt +++ b/src/main/CMakeLists.txt @@ -92,6 +92,8 @@ main_sources(COMMON_SRC drivers/accgyro/accgyro_mpu6500.h drivers/accgyro/accgyro_mpu9250.c drivers/accgyro/accgyro_mpu9250.h + drivers/accgyro/accgyro_lsm6dxx.c + drivers/accgyro/accgyro_lsm6dxx.h drivers/adc.c drivers/adc.h diff --git a/src/main/drivers/accgyro/accgyro_lsm6dxx.c b/src/main/drivers/accgyro/accgyro_lsm6dxx.c new file mode 100644 index 0000000000..e665558891 --- /dev/null +++ b/src/main/drivers/accgyro/accgyro_lsm6dxx.c @@ -0,0 +1,249 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + * from atbetaflight https://github.com/flightng/atbetaflight + */ + +#include +#include +#include + +#include "platform.h" + +#include "build/debug.h" + +#include "common/axis.h" +#include "common/maths.h" +#include "common/utils.h" + +#include "drivers/system.h" +#include "drivers/time.h" + +#include "drivers/sensor.h" +#include "drivers/accgyro/accgyro.h" +#include "drivers/accgyro/accgyro_mpu.h" +#include "drivers/accgyro/accgyro_lsm6dxx.h" + +#if defined(USE_IMU_LSM6DXX) + +typedef struct __attribute__ ((__packed__)) lsm6DContextData_s { + uint16_t chipMagicNumber; + uint8_t lastReadStatus; + uint8_t __padding_dummy; + uint8_t accRaw[6]; + uint8_t gyroRaw[6]; +} lsm6DContextData_t; + +#define LSM6DSO_CHIP_ID 0x6C +#define LSM6DSL_CHIP_ID 0x6A +#define LSM6DS3_CHIP_ID 0x69 + +static uint8_t lsm6dID = 0x6C; + +static void lsm6dxxWriteRegister(const busDevice_t *dev, lsm6dxxRegister_e registerID, uint8_t value, unsigned delayMs) +{ + busWrite(dev, registerID, value); + if (delayMs) { + delay(delayMs); + } +} + +static void lsm6dxxWriteRegisterBits(const busDevice_t *dev, lsm6dxxRegister_e registerID, lsm6dxxConfigMasks_e mask, uint8_t value, unsigned delayMs) +{ + uint8_t newValue; + if (busRead(dev, registerID, &newValue)) { + delayMicroseconds(2); + newValue = (newValue & ~mask) | value; + lsm6dxxWriteRegister(dev, registerID, newValue, delayMs); + } +} + +static uint8_t getLsmDlpfBandwidth(gyroDev_t *gyro) +{ + switch(gyro->lpf) { + case GYRO_HARDWARE_LPF_NORMAL: + return LSM6DXX_VAL_CTRL6_C_FTYPE_201HZ; + case GYRO_HARDWARE_LPF_OPTION_1: + return LSM6DXX_VAL_CTRL6_C_FTYPE_300HZ; + case GYRO_HARDWARE_LPF_OPTION_2: + return LSM6DXX_VAL_CTRL6_C_FTYPE_603HZ; + case GYRO_HARDWARE_LPF_EXPERIMENTAL: + return LSM6DXX_VAL_CTRL6_C_FTYPE_603HZ; + } + return 0; +} + +static void lsm6dxxConfig(gyroDev_t *gyro) +{ + busDevice_t * dev = gyro->busDev; + const gyroFilterAndRateConfig_t * config = mpuChooseGyroConfig(gyro->lpf, 1000000 / gyro->requestedSampleIntervalUs); + gyro->sampleRateIntervalUs = 1000000 / config->gyroRateHz; + + busSetSpeed(dev, BUS_SPEED_INITIALIZATION); + // Reset the device (wait 100ms before continuing config) + lsm6dxxWriteRegisterBits(dev, LSM6DXX_REG_CTRL3_C, LSM6DXX_MASK_CTRL3_C_RESET, BIT(0), 100); + + // Configure data ready pulsed mode + lsm6dxxWriteRegisterBits(dev, LSM6DXX_REG_COUNTER_BDR1, LSM6DXX_MASK_COUNTER_BDR1, LSM6DXX_VAL_COUNTER_BDR1_DDRY_PM, 0); + + // Configure interrupt pin 1 for gyro data ready only + lsm6dxxWriteRegister(dev, LSM6DXX_REG_INT1_CTRL, LSM6DXX_VAL_INT1_CTRL, 1); + + // Disable interrupt pin 2 + lsm6dxxWriteRegister(dev, LSM6DXX_REG_INT2_CTRL, LSM6DXX_VAL_INT2_CTRL, 1); + + // Configure the accelerometer + // 833hz ODR, 16G scale, use LPF2 output (default with ODR/4 cutoff) + lsm6dxxWriteRegister(dev, LSM6DXX_REG_CTRL1_XL, (LSM6DXX_VAL_CTRL1_XL_ODR833 << 4) | (LSM6DXX_VAL_CTRL1_XL_16G << 2) | (LSM6DXX_VAL_CTRL1_XL_LPF2 << 1), 1); + + // Configure the gyro + // 6664hz ODR, 2000dps scale + lsm6dxxWriteRegister(dev, LSM6DXX_REG_CTRL2_G, (LSM6DXX_VAL_CTRL2_G_ODR6664 << 4) | (LSM6DXX_VAL_CTRL2_G_2000DPS << 2), 1); + + // Configure control register 3 + // latch LSB/MSB during reads; set interrupt pins active high; set interrupt pins push/pull; set 4-wire SPI; enable auto-increment burst reads + lsm6dxxWriteRegisterBits(dev, LSM6DXX_REG_CTRL3_C, LSM6DXX_MASK_CTRL3_C, (LSM6DXX_VAL_CTRL3_C_H_LACTIVE | LSM6DXX_VAL_CTRL3_C_PP_OD | LSM6DXX_VAL_CTRL3_C_SIM | LSM6DXX_VAL_CTRL3_C_IF_INC), 1); + + // Configure control register 4 + // enable accelerometer high performane mode; enable gyro LPF1 + lsm6dxxWriteRegisterBits(dev, LSM6DXX_REG_CTRL4_C, LSM6DXX_MASK_CTRL4_C, (LSM6DXX_VAL_CTRL4_C_DRDY_MASK | LSM6DXX_VAL_CTRL4_C_I2C_DISABLE | LSM6DXX_VAL_CTRL4_C_LPF1_SEL_G), 1); + + + + // Configure control register 6 + // disable I2C interface; set gyro LPF1 cutoff according to gyro_hardware_lpf setting + lsm6dxxWriteRegisterBits(dev, LSM6DXX_REG_CTRL6_C, (lsm6dID == LSM6DSO_CHIP_ID? LSM6DXX_MASK_CTRL6_C:LSM6DSL_MASK_CTRL6_C), (LSM6DXX_VAL_CTRL6_C_XL_HM_MODE | getLsmDlpfBandwidth(gyro)), 1); + + // Configure control register 7 + lsm6dxxWriteRegisterBits(dev, LSM6DXX_REG_CTRL7_G, LSM6DXX_MASK_CTRL7_G, (LSM6DXX_VAL_CTRL7_G_HP_EN_G | LSM6DXX_VAL_CTRL7_G_HPM_G_16), 1); + + // Configure control register 9 + // disable I3C interface + if(lsm6dID == LSM6DSO_CHIP_ID) + { + lsm6dxxWriteRegisterBits(dev, LSM6DXX_REG_CTRL9_XL, LSM6DXX_MASK_CTRL9_XL, LSM6DXX_VAL_CTRL9_XL_I3C_DISABLE, 1); + } + + busSetSpeed(dev, BUS_SPEED_FAST); +} + + + +static bool lsm6dxxDetect(busDevice_t * dev) +{ + uint8_t tmp; + uint8_t attemptsRemaining = 5; + busSetSpeed(dev, BUS_SPEED_INITIALIZATION); + do { + delay(150); + + busRead(dev, LSM6DXX_REG_WHO_AM_I, &tmp); + + switch (tmp) { + case LSM6DSO_CHIP_ID: + case LSM6DSL_CHIP_ID: + lsm6dID = tmp; + // Compatible chip detected + return true; + default: + // Retry detection + break; + } + } while (attemptsRemaining--); + + return false; +} + +static void lsm6dxxSpiGyroInit(gyroDev_t *gyro) +{ + lsm6dxxConfig(gyro); +} + +static void lsm6dxxSpiAccInit(accDev_t *acc) +{ + // sensor is configured during gyro init + acc->acc_1G = 512 * 4; // 16G sensor scale +} + +static bool lsm6dxxAccRead(accDev_t *acc) +{ + uint8_t data[6]; + const bool ack = busReadBuf(acc->busDev, LSM6DXX_REG_OUTX_L_A, data, 6); + if (!ack) { + return false; + } + acc->ADCRaw[X] = (int16_t)((data[1] << 8) | data[0]); + acc->ADCRaw[Y] = (int16_t)((data[3] << 8) | data[2]); + acc->ADCRaw[Z] = (int16_t)((data[5] << 8) | data[4]); + return true; +} + +static bool lsm6dxxGyroRead(gyroDev_t *gyro) +{ + uint8_t data[6]; + const bool ack = busReadBuf(gyro->busDev, LSM6DXX_REG_OUTX_L_G, data, 6); + if (!ack) { + return false; + } + gyro->gyroADCRaw[X] = (int16_t)((data[1] << 8) | data[0]); + gyro->gyroADCRaw[Y] = (int16_t)((data[3] << 8) | data[2]); + gyro->gyroADCRaw[Z] = (int16_t)((data[5] << 8) | data[4]); + return true; +} + +// Init Gyro first,then Acc +bool lsm6dGyroDetect(gyroDev_t *gyro) +{ + gyro->busDev = busDeviceInit(BUSTYPE_SPI, DEVHW_LSM6D, gyro->imuSensorToUse, OWNER_MPU); + if (gyro->busDev == NULL) { + return false; + } + + if (!lsm6dxxDetect(gyro->busDev)) { + busDeviceDeInit(gyro->busDev); + return false; + } + + lsm6DContextData_t * ctx = busDeviceGetScratchpadMemory(gyro->busDev); + ctx->chipMagicNumber = 0xD6; + + gyro->initFn = lsm6dxxSpiGyroInit; + gyro->readFn = lsm6dxxGyroRead; + gyro->intStatusFn = gyroCheckDataReady; + gyro->scale = 1.0f / 16.4f; // 2000 dps + return true; + +} +bool lsm6dAccDetect(accDev_t *acc) +{ + acc->busDev = busDeviceOpen(BUSTYPE_SPI, DEVHW_LSM6D, acc->imuSensorToUse); + if (acc->busDev == NULL) { + return false; + } + + lsm6DContextData_t * ctx = busDeviceGetScratchpadMemory(acc->busDev); + if (ctx->chipMagicNumber != 0xD6) { + return false; + } + acc->initFn = lsm6dxxSpiAccInit; + acc->readFn = lsm6dxxAccRead; + acc->accAlign = acc->busDev->param; + + return true; +} + + + +#endif diff --git a/src/main/drivers/accgyro/accgyro_lsm6dxx.h b/src/main/drivers/accgyro/accgyro_lsm6dxx.h new file mode 100644 index 0000000000..6da333b065 --- /dev/null +++ b/src/main/drivers/accgyro/accgyro_lsm6dxx.h @@ -0,0 +1,114 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See tLSM6DXXhe + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + * moved from atbetaflight https://github.com/flightng/atbetaflight by tcdddd + */ + +#pragma once + +#include "drivers/bus.h" + +// LSM6DXX registers (not the complete list) +typedef enum { + LSM6DXX_REG_COUNTER_BDR1 = 0x0B,// Counter batch data rate register LSM6DSL_REG_DRDY_PULSED_CFG_G + LSM6DXX_REG_INT1_CTRL = 0x0D, // int pin 1 control + LSM6DXX_REG_INT2_CTRL = 0x0E, // int pin 2 control + LSM6DXX_REG_WHO_AM_I = 0x0F, // chip ID + LSM6DXX_REG_CTRL1_XL = 0x10, // accelerometer control + LSM6DXX_REG_CTRL2_G = 0x11, // gyro control + LSM6DXX_REG_CTRL3_C = 0x12, // control register 3 + LSM6DXX_REG_CTRL4_C = 0x13, // control register 4 + LSM6DXX_REG_CTRL5_C = 0x14, // control register 5 + LSM6DXX_REG_CTRL6_C = 0x15, // control register 6 + LSM6DXX_REG_CTRL7_G = 0x16, // control register 7 + LSM6DXX_REG_CTRL8_XL = 0x17, // control register 8 + LSM6DXX_REG_CTRL9_XL = 0x18, // control register 9 + LSM6DXX_REG_CTRL10_C = 0x19, // control register 10 + LSM6DXX_REG_STATUS = 0x1E, // status register + LSM6DXX_REG_OUT_TEMP_L = 0x20, // temperature LSB + LSM6DXX_REG_OUT_TEMP_H = 0x21, // temperature MSB + LSM6DXX_REG_OUTX_L_G = 0x22, // gyro X axis LSB + LSM6DXX_REG_OUTX_H_G = 0x23, // gyro X axis MSB + LSM6DXX_REG_OUTY_L_G = 0x24, // gyro Y axis LSB + LSM6DXX_REG_OUTY_H_G = 0x25, // gyro Y axis MSB + LSM6DXX_REG_OUTZ_L_G = 0x26, // gyro Z axis LSB + LSM6DXX_REG_OUTZ_H_G = 0x27, // gyro Z axis MSB + LSM6DXX_REG_OUTX_L_A = 0x28, // acc X axis LSB + LSM6DXX_REG_OUTX_H_A = 0x29, // acc X axis MSB + LSM6DXX_REG_OUTY_L_A = 0x2A, // acc Y axis LSB + LSM6DXX_REG_OUTY_H_A = 0x2B, // acc Y axis MSB + LSM6DXX_REG_OUTZ_L_A = 0x2C, // acc Z axis LSB + LSM6DXX_REG_OUTZ_H_A = 0x2D, // acc Z axis MSB +} lsm6dxxRegister_e; + +// LSM6DXX register configuration values +typedef enum { + LSM6DXX_VAL_COUNTER_BDR1_DDRY_PM = BIT(7),// (bit 7) enable data ready pulsed mode + LSM6DXX_VAL_INT1_CTRL = 0x02, // enable gyro data ready interrupt pin 1 + LSM6DXX_VAL_INT2_CTRL = 0x00, // disable gyro data ready interrupt pin 2 + LSM6DXX_VAL_CTRL1_XL_ODR833 = 0x07, // accelerometer 833hz output data rate (gyro/8) + LSM6DXX_VAL_CTRL1_XL_ODR1667 = 0x08, // accelerometer 1666hz output data rate (gyro/4) + LSM6DXX_VAL_CTRL1_XL_ODR3332 = 0x09, // accelerometer 3332hz output data rate (gyro/2) + LSM6DXX_VAL_CTRL1_XL_ODR3333 = 0x0A, // accelerometer 6664hz output data rate (gyro/1) + LSM6DXX_VAL_CTRL1_XL_8G = 0x03, // accelerometer 8G scale + LSM6DXX_VAL_CTRL1_XL_16G = 0x01, // accelerometer 16G scale + LSM6DXX_VAL_CTRL1_XL_LPF1 = 0x00, // accelerometer output from LPF1 + LSM6DXX_VAL_CTRL1_XL_LPF2 = 0x01, // accelerometer output from LPF2 + LSM6DXX_VAL_CTRL2_G_ODR6664 = 0x0A, // gyro 6664hz output data rate + LSM6DXX_VAL_CTRL2_G_2000DPS = 0x03, // gyro 2000dps scale + // LSM6DXX_VAL_CTRL3_C_BDU = BIT(6), // (bit 6) output registers are not updated until MSB and LSB have been read (prevents MSB from being updated while burst reading LSB/MSB) + LSM6DXX_VAL_CTRL3_C_H_LACTIVE = 0, // (bit 5) interrupt pins active high + LSM6DXX_VAL_CTRL3_C_PP_OD = 0, // (bit 4) interrupt pins push/pull + LSM6DXX_VAL_CTRL3_C_SIM = 0, // (bit 3) SPI 4-wire interface mode + LSM6DXX_VAL_CTRL3_C_IF_INC = BIT(2), // (bit 2) auto-increment address for burst reads + LSM6DXX_VAL_CTRL4_C_DRDY_MASK = BIT(3), // (bit 3) data ready interrupt mask + LSM6DXX_VAL_CTRL4_C_I2C_DISABLE = BIT(2), // (bit 2) disable I2C interface + LSM6DXX_VAL_CTRL4_C_LPF1_SEL_G = BIT(1), // (bit 1) enable gyro LPF1 + LSM6DXX_VAL_CTRL6_C_XL_HM_MODE = 0, // (bit 4) enable accelerometer high performance mode + LSM6DXX_VAL_CTRL6_C_FTYPE_300HZ = 0x00, // (bits 2:0) gyro LPF1 cutoff 335.5Hz + LSM6DXX_VAL_CTRL6_C_FTYPE_201HZ = 0x01, // (bits 2:0) gyro LPF1 cutoff 232.0Hz + LSM6DXX_VAL_CTRL6_C_FTYPE_102HZ = 0x02, // (bits 2:0) gyro LPF1 cutoff 171.1Hz + LSM6DXX_VAL_CTRL6_C_FTYPE_603HZ = 0x03, // (bits 2:0) gyro LPF1 cutoff 609.0Hz + LSM6DXX_VAL_CTRL7_G_HP_EN_G = BIT(6), // (bit 6) enable gyro high-pass filter + LSM6DXX_VAL_CTRL7_G_HPM_G_16 = 0x00, // (bits 5:4) gyro HPF cutoff 16mHz + LSM6DXX_VAL_CTRL7_G_HPM_G_65 = 0x01, // (bits 5:4) gyro HPF cutoff 65mHz + LSM6DXX_VAL_CTRL7_G_HPM_G_260 = 0x02, // (bits 5:4) gyro HPF cutoff 260mHz + LSM6DXX_VAL_CTRL7_G_HPM_G_1040 = 0x03, // (bits 5:4) gyro HPF cutoff 1.04Hz + LSM6DXX_VAL_CTRL9_XL_I3C_DISABLE = BIT(1),// (bit 1) disable I3C interface +} lsm6dxxConfigValues_e; + +// LSM6DXX register configuration bit masks +typedef enum { + LSM6DXX_MASK_COUNTER_BDR1 = 0x80, // 0b10000000 + LSM6DXX_MASK_CTRL3_C = 0x3C, // 0b00111100 + LSM6DXX_MASK_CTRL3_C_RESET = BIT(0), // 0b00000001 + LSM6DXX_MASK_CTRL4_C = 0x0E, // 0b00001110 + LSM6DXX_MASK_CTRL6_C = 0x17, // 0b00010111 + LSM6DXX_MASK_CTRL7_G = 0x70, // 0b01110000 + LSM6DXX_MASK_CTRL9_XL = 0x02, // 0b00000010 + LSM6DSL_MASK_CTRL6_C = 0x13, // 0b00010011 + +} lsm6dxxConfigMasks_e; + +typedef enum { + GYRO_HARDWARE_LPF_NORMAL, + GYRO_HARDWARE_LPF_OPTION_1, + GYRO_HARDWARE_LPF_OPTION_2, + GYRO_HARDWARE_LPF_EXPERIMENTAL, + GYRO_HARDWARE_LPF_COUNT +} gyroHardwareLpf_e; + +bool lsm6dAccDetect(accDev_t *acc); +bool lsm6dGyroDetect(gyroDev_t *gyro); diff --git a/src/main/drivers/bus.h b/src/main/drivers/bus.h index b6a3d78e44..c27f21d600 100755 --- a/src/main/drivers/bus.h +++ b/src/main/drivers/bus.h @@ -84,7 +84,7 @@ typedef enum { DEVHW_ICM20689, DEVHW_ICM42605, DEVHW_BMI270, - + DEVHW_LSM6D, /* Combined ACC/GYRO/MAG chips */ DEVHW_MPU9250, diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index d4c2b3873e..2da4d769ae 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -177,7 +177,7 @@ static const char * const blackboxIncludeFlagNames[] = { /* Sensor names (used in lookup tables for *_hardware settings and in status command output) */ // sync with gyroSensor_e -static const char * const gyroNames[] = { "NONE", "AUTO", "MPU6000", "MPU6500", "MPU9250", "BMI160", "ICM20689", "BMI088", "ICM42605", "BMI270", "FAKE"}; +static const char * const gyroNames[] = { "NONE", "AUTO", "MPU6000", "MPU6500", "MPU9250", "BMI160", "ICM20689", "BMI088", "ICM42605", "BMI270","LSM6DXX", "FAKE"}; // sync this with sensors_e static const char * const sensorTypeNames[] = { diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index a089c01859..413345110c 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -4,7 +4,7 @@ tables: - name: gyro_lpf values: ["256HZ", "188HZ", "98HZ", "42HZ", "20HZ", "10HZ"] - name: acc_hardware - values: ["NONE", "AUTO", "MPU6000", "MPU6500", "MPU9250", "BMI160", "ICM20689", "BMI088", "ICM42605", "BMI270", "FAKE"] + values: ["NONE", "AUTO", "MPU6000", "MPU6500", "MPU9250", "BMI160", "ICM20689", "BMI088", "ICM42605", "BMI270","LSM6DXX", "FAKE"] enum: accelerationSensor_e - name: rangefinder_hardware values: ["NONE", "SRF10", "VL53L0X", "MSP", "BENEWAKE", "VL53L1X", "US42", "TOF10120_I2C"] diff --git a/src/main/sensors/acceleration.c b/src/main/sensors/acceleration.c index 45be068a39..9543ff5b96 100644 --- a/src/main/sensors/acceleration.c +++ b/src/main/sensors/acceleration.c @@ -47,6 +47,7 @@ FILE_COMPILE_FOR_SPEED #include "drivers/accgyro/accgyro_bmi270.h" #include "drivers/accgyro/accgyro_icm20689.h" #include "drivers/accgyro/accgyro_icm42605.h" +#include "drivers/accgyro/accgyro_lsm6dxx.h" #include "drivers/accgyro/accgyro_fake.h" #include "drivers/sensor.h" @@ -221,7 +222,18 @@ static bool accDetect(accDev_t *dev, accelerationSensor_e accHardwareToUse) } FALLTHROUGH; #endif - +#ifdef USE_IMU_LSM6DXX + case ACC_LSM6DXX: + if (lsm6dAccDetect(dev)) { + accHardware = ACC_LSM6DXX; + break; + } + /* If we are asked for a specific sensor - break out, otherwise - fall through and continue */ + if (accHardwareToUse != ACC_AUTODETECT) { + break; + } + FALLTHROUGH; +#endif #ifdef USE_IMU_FAKE case ACC_FAKE: if (fakeAccDetect(dev)) { diff --git a/src/main/sensors/acceleration.h b/src/main/sensors/acceleration.h index aa9ef73754..d81a83a908 100644 --- a/src/main/sensors/acceleration.h +++ b/src/main/sensors/acceleration.h @@ -43,6 +43,7 @@ typedef enum { ACC_BMI088, ACC_ICM42605, ACC_BMI270, + ACC_LSM6DXX, ACC_FAKE, ACC_MAX = ACC_FAKE } accelerationSensor_e; diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index d40676477b..5cde701161 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -49,6 +49,7 @@ FILE_COMPILE_FOR_SPEED #include "drivers/accgyro/accgyro_bmi270.h" #include "drivers/accgyro/accgyro_icm20689.h" #include "drivers/accgyro/accgyro_icm42605.h" +#include "drivers/accgyro/accgyro_lsm6dxx.h" #include "drivers/accgyro/accgyro_fake.h" #include "drivers/io.h" @@ -209,6 +210,15 @@ STATIC_UNIT_TESTED gyroSensor_e gyroDetect(gyroDev_t *dev, gyroSensor_e gyroHard FALLTHROUGH; #endif +#ifdef USE_IMU_LSM6DXX + case GYRO_LSM6DXX: + if (lsm6dGyroDetect(dev)) { + gyroHardware = GYRO_LSM6DXX; + break; + } + FALLTHROUGH; +#endif + #ifdef USE_IMU_FAKE case GYRO_FAKE: if (fakeGyroDetect(dev)) { diff --git a/src/main/sensors/gyro.h b/src/main/sensors/gyro.h index f6a3f71b8f..da892a3a18 100644 --- a/src/main/sensors/gyro.h +++ b/src/main/sensors/gyro.h @@ -37,7 +37,9 @@ typedef enum { GYRO_BMI088, GYRO_ICM42605, GYRO_BMI270, + GYRO_LSM6DXX, GYRO_FAKE + } gyroSensor_e; typedef enum { diff --git a/src/main/target/common_hardware.c b/src/main/target/common_hardware.c index a8bf517223..3f674d8df2 100755 --- a/src/main/target/common_hardware.c +++ b/src/main/target/common_hardware.c @@ -77,6 +77,11 @@ #if defined(USE_IMU_BMI270) BUSDEV_REGISTER_SPI(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_CS_PIN, NONE, DEVFLAGS_NONE, IMU_BMI270_ALIGN); #endif + + #if defined(USE_IMU_LSM6DXX) + BUSDEV_REGISTER_SPI(busdev_lsm6dxx, DEVHW_LSM6D, LSM6DXX_SPI_BUS, LSM6DXX_CS_PIN, NONE, DEVFLAGS_NONE, IMU_LSM6DXX_ALIGN); + #endif + #endif From b8d263b2e992798fd91dfb0e6ef6c75a9df05b59 Mon Sep 17 00:00:00 2001 From: EMSR Date: Sun, 29 Jan 2023 23:31:50 +0800 Subject: [PATCH 046/130] fix bug flashdrivers idx overflow Co-Authored-By: carl <101383042+tcdddd@users.noreply.github.com> Co-Authored-By: Hugo Chiang --- src/main/drivers/flash.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/drivers/flash.c b/src/main/drivers/flash.c index 18c26f6df7..30002f17fc 100644 --- a/src/main/drivers/flash.c +++ b/src/main/drivers/flash.c @@ -80,7 +80,7 @@ static bool flashDeviceInit(void) { bool detected = false; - for (uint32_t idx = 0; idx <= ARRAYLEN(flashDrivers); idx++) + for (uint32_t idx = 0; idx < ARRAYLEN(flashDrivers); idx++) //idx = ARRAYLEN may cause overflow { detected = flashDrivers[idx].init(0); if (detected) From 37c417e36e08ebea64702f70f70f992f8f708e5b Mon Sep 17 00:00:00 2001 From: EMSR Date: Sun, 29 Jan 2023 23:34:10 +0800 Subject: [PATCH 047/130] add three targets based on at32 chips NEUTRONRCF435AIO - based on AT32F435RGT7 NEUTRONRCF435MINI - based on AT32F435CGU7 NEUTRONRCF435WING - based on AT32F435CGU7 Co-Authored-By: EMSR <10240646+shanggl@users.noreply.github.com> Co-Authored-By: carl <101383042+tcdddd@users.noreply.github.com> Co-Authored-By: Hugo Chiang --- .../target/NEUTRONRCF435MINI/CMakeLists.txt | 1 + src/main/target/NEUTRONRCF435MINI/target.c | 39 ++++ src/main/target/NEUTRONRCF435MINI/target.h | 201 +++++++++++++++++ .../target/NEUTRONRCF435SE/CMakeLists.txt | 1 + src/main/target/NEUTRONRCF435SE/target.c | 46 ++++ src/main/target/NEUTRONRCF435SE/target.h | 204 ++++++++++++++++++ .../target/NEUTRONRCF435WING/CMakeLists.txt | 1 + src/main/target/NEUTRONRCF435WING/target.c | 44 ++++ src/main/target/NEUTRONRCF435WING/target.h | 203 +++++++++++++++++ 9 files changed, 740 insertions(+) create mode 100644 src/main/target/NEUTRONRCF435MINI/CMakeLists.txt create mode 100644 src/main/target/NEUTRONRCF435MINI/target.c create mode 100644 src/main/target/NEUTRONRCF435MINI/target.h create mode 100644 src/main/target/NEUTRONRCF435SE/CMakeLists.txt create mode 100644 src/main/target/NEUTRONRCF435SE/target.c create mode 100644 src/main/target/NEUTRONRCF435SE/target.h create mode 100644 src/main/target/NEUTRONRCF435WING/CMakeLists.txt create mode 100644 src/main/target/NEUTRONRCF435WING/target.c create mode 100644 src/main/target/NEUTRONRCF435WING/target.h diff --git a/src/main/target/NEUTRONRCF435MINI/CMakeLists.txt b/src/main/target/NEUTRONRCF435MINI/CMakeLists.txt new file mode 100644 index 0000000000..da125cbfac --- /dev/null +++ b/src/main/target/NEUTRONRCF435MINI/CMakeLists.txt @@ -0,0 +1 @@ +target_at32f43x_xGT7(NEUTRONRCF435MINI) \ No newline at end of file diff --git a/src/main/target/NEUTRONRCF435MINI/target.c b/src/main/target/NEUTRONRCF435MINI/target.c new file mode 100644 index 0000000000..e964c19156 --- /dev/null +++ b/src/main/target/NEUTRONRCF435MINI/target.c @@ -0,0 +1,39 @@ +/* +* This file is part of Cleanflight. +* +* Cleanflight is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* Cleanflight is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with Cleanflight. If not, see . +*/ + +#include + +#include "platform.h" + +#include "drivers/bus.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" + +timerHardware_t timerHardware[] = { + + DEF_TIM(TMR1, CH1, PA8, TIM_USE_ANY |TIM_USE_LED, 0,7), // PWM1 - LED MCO1 DMA1 CH2 + + DEF_TIM(TMR4, CH1, PB6, TIM_USE_MC_MOTOR|TIM_USE_FW_MOTOR, 0,0), // motor1 DMA2 CH7 + DEF_TIM(TMR1, CH3, PA10, TIM_USE_MC_MOTOR|TIM_USE_FW_MOTOR, 0,2), // motor2 DMA2 CH6 + DEF_TIM(TMR2, CH4, PA3, TIM_USE_MC_MOTOR|TIM_USE_FW_SERVO, 0,1), // motor3 DMA2 CH5 + DEF_TIM(TMR3, CH4, PB1, TIM_USE_MC_MOTOR|TIM_USE_FW_SERVO, 0,3), // motor4 DMA2 CH4 + +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); + \ No newline at end of file diff --git a/src/main/target/NEUTRONRCF435MINI/target.h b/src/main/target/NEUTRONRCF435MINI/target.h new file mode 100644 index 0000000000..92c9f351a1 --- /dev/null +++ b/src/main/target/NEUTRONRCF435MINI/target.h @@ -0,0 +1,201 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "NERC" + +#define USBD_PRODUCT_STRING "NeuronRC F435 MINI" + +/**********swd debuger reserved ***************** + * + * pa13 swdio + * pa14 swclk + * PA15 JTDI + * PB4 JREST + * pb3 swo /DTO + + * other pin + * + * PB2 ->BOOT0 button + * PA8 MCO1 + * PA11 OTG1 D+ DP + * PA10 OTG1 D- DN + * PH0 HEXT IN + * PH1 HEXT OUT + */ + +#define LED0 PC13 +#define LED1 PC14 +#define LED0_INVERTED +#define LED1_INVERTED + +#define BEEPER PC15 +#define BEEPER_INVERTED + +// *************** Gyro & ACC ********************** +#define USE_SPI +#define USE_SPI_DEVICE_1 + +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 +#define SPI1_NSS_PIN PA4 + +// #define USE_EXTI +// #define GYRO_INT_EXTI PA15 +// #define USE_MPU_DATA_READY_SIGNAL + +// MPU6500 +#define USE_IMU_MPU6500 +#define IMU_MPU6500_ALIGN CW0_DEG +#define MPU6500_SPI_BUS BUS_SPI1 +#define MPU6500_CS_PIN SPI1_NSS_PIN + +// ICM42605/ICM42688P +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW0_DEG +#define ICM42605_SPI_BUS BUS_SPI1 +#define ICM42605_CS_PIN SPI1_NSS_PIN +// #define ICM42605_EXTI_PIN GYRO_INT_EXTI + +// BMI270 +#define USE_IMU_BMI270 +#define IMU_BMI270_ALIGN CW0_DEG +#define BMI270_SPI_BUS BUS_SPI1 +#define BMI270_CS_PIN SPI1_NSS_PIN + +// LSM6DXX +#define USE_IMU_LSM6DXX +#define IMU_LSM6DXX_ALIGN CW0_DEG +#define LSM6DXX_CS_PIN SPI1_NSS_PIN +#define LSM6DXX_SPI_BUS BUS_SPI1 + + +// *************** I2C/Baro/Mag/EXT********************* +#define USE_I2C +#define USE_I2C_DEVICE_2 +#define I2C2_SCL PH2 // SCL pad +#define I2C2_SDA PH3 // SDA pad +#define USE_I2C_PULLUP + +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C2 +#define USE_BARO_BMP280 +#define USE_BARO_DPS310 + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C2 +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define DEFAULT_I2C_BUS BUS_I2C2 + +// temperature sensors +//#define TEMPERATURE_I2C_BUS BUS_I2C1 +// air speed sensors +//#define PITOT_I2C_BUS BUS_I2C1 +// ranger sensors +//#define USE_RANGEFINDER +//#define RANGEFINDER_I2C_BUS BUS_I2C1 + +// *************** OSD ***************************** +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 +#define SPI2_NSS_PIN PB12 + +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN SPI2_NSS_PIN + + +// *************** SD/BLACKBOX ************************** + +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define M25P16_SPI_BUS BUS_SPI2 +#define M25P16_CS_PIN PB5 + +#define USE_FLASH_W25N01G +#define W25N01G_SPI_BUS BUS_SPI2 +#define W25N01G_CS_PIN PB5 + +// *************** UART ***************************** +#define USE_VCP +//#define USB_DETECT_PIN PC14 +#define USE_USB_DETECT + +#define USE_UART1 +#define UART1_RX_PIN PB7 +#define UART1_TX_PIN PA9 + +#define USE_UART2 +#define UART2_RX_PIN PB0 +#define UART2_TX_PIN PA2 + +#define USE_UART3 +#define UART3_RX_PIN PB11 +#define UART3_TX_PIN PB10 + +#define USE_UART5 +#define UART5_RX_PIN PB8 +#define UART5_TX_PIN PB9 + +#define USE_UART7 +#define UART7_RX_PIN PB3 +#define UART7_TX_PIN PB4 + +#define SERIAL_PORT_COUNT 6 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_CRSF +#define SERIALRX_UART SERIAL_PORT_USART7 + +// *************** ADC ***************************** +#define USE_ADC +#define ADC_INSTANCE ADC1 + +#define ADC1_DMA_STREAM DMA2_CHANNEL5 +#define ADC_CHANNEL_1_PIN PA0 +#define ADC_CHANNEL_2_PIN PA1 +//#define ADC_CHANNEL_3_PIN PB0 +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +//#define RSSI_ADC_CHANNEL ADC_CHN_3 + +#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_TELEMETRY| FEATURE_VBAT | FEATURE_OSD ) + +// #define USE_LED_STRIP +// #define WS2811_PIN PB10 //TIM2_CH3 + +// #define USE_SPEKTRUM_BIND +// #define BIND_PIN PA3 //UART2_RX_PIN + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff +#define TARGET_IO_PORTE BIT(2) +#define TARGET_IO_PORTH BIT(1)|BIT(2)|BIT(3) + +#define MAX_PWM_OUTPUT_PORTS 8 +#define USE_DSHOT +#define USE_ESC_SENSOR diff --git a/src/main/target/NEUTRONRCF435SE/CMakeLists.txt b/src/main/target/NEUTRONRCF435SE/CMakeLists.txt new file mode 100644 index 0000000000..e21f83226c --- /dev/null +++ b/src/main/target/NEUTRONRCF435SE/CMakeLists.txt @@ -0,0 +1 @@ +target_at32f43x_xGT7(NEUTRONRCF435SE) \ No newline at end of file diff --git a/src/main/target/NEUTRONRCF435SE/target.c b/src/main/target/NEUTRONRCF435SE/target.c new file mode 100644 index 0000000000..7eb72ead92 --- /dev/null +++ b/src/main/target/NEUTRONRCF435SE/target.c @@ -0,0 +1,46 @@ +/* +* This file is part of Cleanflight. +* +* Cleanflight is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* Cleanflight is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with Cleanflight. If not, see . +*/ + +#include + +#include "platform.h" + +#include "drivers/bus.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" + +timerHardware_t timerHardware[] = { + + DEF_TIM(TMR5, CH1, PA0, TIM_USE_ANY, 0, 13), // TIM_USE_CAMERA_CONTROL + DEF_TIM(TMR5, CH2, PA1, TIM_USE_ANY |TIM_USE_LED, 0,7), // PWM1 - LED MCO1 DMA1 CH2 + DEF_TIM(TMR2, CH4, PA3, TIM_USE_ANY |TIM_USE_PPM, 0,6), // PWM2 - PPM DMA1 CH6 + + DEF_TIM(TMR8, CH4, PC9, TIM_USE_MC_MOTOR|TIM_USE_FW_MOTOR, 0,0), // motor1 DMA2 CH7 + DEF_TIM(TMR8, CH3, PC8, TIM_USE_MC_MOTOR|TIM_USE_FW_MOTOR, 0,2), // motor2 DMA2 CH6 + DEF_TIM(TMR3, CH2, PC7, TIM_USE_MC_MOTOR|TIM_USE_FW_SERVO, 0,1), // motor3 DMA2 CH5 + DEF_TIM(TMR3, CH1, PC6, TIM_USE_MC_MOTOR|TIM_USE_FW_SERVO, 0,3), // motor4 DMA2 CH4 + + DEF_TIM(TMR4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0,11), // PWM1 - OUT5 DMA1 CH7 + DEF_TIM(TMR4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0,10), // PWM2 - OUT6 DMA2 CH1 + DEF_TIM(TMR3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0,9), // PWM3 - OUT7 DMA2 CH2 + DEF_TIM(TMR3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0,8), // PWM4 - OUT8 DMA2 CH3 + +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); + \ No newline at end of file diff --git a/src/main/target/NEUTRONRCF435SE/target.h b/src/main/target/NEUTRONRCF435SE/target.h new file mode 100644 index 0000000000..4a151ca290 --- /dev/null +++ b/src/main/target/NEUTRONRCF435SE/target.h @@ -0,0 +1,204 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "NERC" + +#define USBD_PRODUCT_STRING "NeutronRC F435 SE" + +/**********swd debuger reserved ***************** + * + * pa13 swdio + * pa14 swclk + * PA15 JTDI + * PB4 JREST + * pb3 swo /DTO + + * other pin + * + * PB2 ->BOOT0 button + * PA8 MCO1 + * PA11 OTG1 D+ DP + * PA10 OTG1 D- DN + * PH0 HEXT IN + * PH1 HEXT OUT + */ + +#define LED0 PC4 +//#define LED1 PD14 + +#define BEEPER PC15 +#define BEEPER_INVERTED + +// *************** Gyro & ACC ********************** +#define USE_SPI +#define USE_SPI_DEVICE_1 + +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 +#define SPI1_NSS_PIN PA15 + +// #define USE_EXTI +// #define GYRO_INT_EXTI PA8 +// #define USE_MPU_DATA_READY_SIGNAL + +// MPU6500 +#define USE_IMU_MPU6500 +#define IMU_MPU6500_ALIGN CW180_DEG +#define MPU6500_SPI_BUS BUS_SPI1 +#define MPU6500_CS_PIN SPI1_NSS_PIN + +// ICM42605/ICM42688P +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW180_DEG +#define ICM42605_SPI_BUS BUS_SPI1 +#define ICM42605_CS_PIN SPI1_NSS_PIN +// #define ICM42605_EXTI_PIN GYRO_INT_EXTI + +// BMI270 +#define USE_IMU_BMI270 +#define IMU_BMI270_ALIGN CW180_DEG +#define BMI270_SPI_BUS BUS_SPI1 +#define BMI270_CS_PIN SPI1_NSS_PIN + +// LSM6DXX +#define USE_IMU_LSM6DXX +#define IMU_LSM6DXX_ALIGN CW180_DEG +#define LSM6DXX_CS_PIN SPI1_NSS_PIN +#define LSM6DXX_SPI_BUS BUS_SPI1 + + +// *************** I2C/Baro/Mag/EXT********************* +#define USE_I2C +#define USE_I2C_DEVICE_2 +#define I2C2_SCL PB10 // SCL pad +#define I2C2_SDA PB11 // SDA pad +#define USE_I2C_PULLUP + +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C2 +#define USE_BARO_BMP280 +#define USE_BARO_DPS310 + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C2 +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define DEFAULT_I2C_BUS BUS_I2C2 + +// temperature sensors +//#define TEMPERATURE_I2C_BUS BUS_I2C1 +// air speed sensors +//#define PITOT_I2C_BUS BUS_I2C1 +// ranger sensors +//#define USE_RANGEFINDER +//#define RANGEFINDER_I2C_BUS BUS_I2C1 + +// *************** OSD ***************************** +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13//PB13 on LQFP64 +#define SPI2_MISO_PIN PB14//PB14 on LQFP64 +#define SPI2_MOSI_PIN PB15//PB15 on LQFP64 +#define SPI2_NSS_PIN PB12 //confirm on lqfp64 + +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN SPI2_NSS_PIN + + +// *************** SD/BLACKBOX ************************** +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PB3 +#define SPI3_MISO_PIN PB4 +#define SPI3_MOSI_PIN PB5 +#define SPI3_NSS_PIN PB9 //confirm on lqfp64 + +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define M25P16_SPI_BUS BUS_SPI3 +#define M25P16_CS_PIN SPI3_NSS_PIN + +#define USE_FLASH_W25N01G +#define W25N01G_SPI_BUS BUS_SPI3 +#define W25N01G_CS_PIN SPI3_NSS_PIN + +// *************** UART ***************************** +#define USE_VCP +//#define USB_DETECT_PIN PC14 +#define USE_USB_DETECT + +#define USE_UART1 +#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 + +#define USE_UART2 +#define UART2_RX_PIN PA3 +#define UART2_TX_PIN PA2 + +#define USE_UART3 +#define UART3_RX_PIN PB11 +#define UART3_TX_PIN PB10 + +#define USE_UART4 +#define UART4_RX_PIN PC11 +#define UART4_TX_PIN PC10 + +#define USE_UART5 +#define UART5_RX_PIN PD2 +#define UART5_TX_PIN PC12 + +#define SERIAL_PORT_COUNT 6 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_CRSF +#define SERIALRX_UART SERIAL_PORT_USART2 + +// *************** ADC ***************************** +#define USE_ADC +#define ADC_INSTANCE ADC1 + +#define ADC1_DMA_STREAM DMA2_CHANNEL5 +#define ADC_CHANNEL_1_PIN PC2 +#define ADC_CHANNEL_2_PIN PC1 +//#define ADC_CHANNEL_3_PIN PB0 +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +//#define RSSI_ADC_CHANNEL ADC_CHN_3 + +#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_TELEMETRY| FEATURE_VBAT | FEATURE_OSD ) + +// #define USE_LED_STRIP +// #define WS2811_PIN PB10 //TIM2_CH3 + +// telemetry +// #define USE_SPEKTRUM_BIND +// #define BIND_PIN PA3 //UART2_RX_PIN + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff +#define TARGET_IO_PORTE BIT(2) + +#define MAX_PWM_OUTPUT_PORTS 8 +#define USE_DSHOT +#define USE_ESC_SENSOR \ No newline at end of file diff --git a/src/main/target/NEUTRONRCF435WING/CMakeLists.txt b/src/main/target/NEUTRONRCF435WING/CMakeLists.txt new file mode 100644 index 0000000000..11b7988899 --- /dev/null +++ b/src/main/target/NEUTRONRCF435WING/CMakeLists.txt @@ -0,0 +1 @@ +target_at32f43x_xGT7(NEUTRONRCF435WING) \ No newline at end of file diff --git a/src/main/target/NEUTRONRCF435WING/target.c b/src/main/target/NEUTRONRCF435WING/target.c new file mode 100644 index 0000000000..b64e1a5c8f --- /dev/null +++ b/src/main/target/NEUTRONRCF435WING/target.c @@ -0,0 +1,44 @@ +/* +* This file is part of Cleanflight. +* +* Cleanflight is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* Cleanflight is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with Cleanflight. If not, see . +*/ + +#include + +#include "platform.h" + +#include "drivers/bus.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" + +timerHardware_t timerHardware[] = { + + DEF_TIM(TMR1, CH1, PA8, TIM_USE_ANY |TIM_USE_LED, 0,7), // PWM1 - LED MCO1 DMA1 CH2 + + DEF_TIM(TMR4, CH1, PB6, TIM_USE_MC_MOTOR|TIM_USE_FW_MOTOR, 0,0), // motor1 DMA2 CH7 + DEF_TIM(TMR1, CH3, PA10, TIM_USE_MC_MOTOR|TIM_USE_FW_MOTOR, 0,2), // motor2 DMA2 CH6 + DEF_TIM(TMR2, CH4, PA3, TIM_USE_MC_MOTOR|TIM_USE_FW_SERVO, 0,1), // motor3 DMA2 CH5 + DEF_TIM(TMR3, CH4, PB1, TIM_USE_MC_MOTOR|TIM_USE_FW_SERVO, 0,3), // motor4 DMA2 CH4 + + DEF_TIM(TMR4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0,10), // PWM1 - OUT5 DMA2 CH1 + DEF_TIM(TMR1, CH2, PA9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0,9), // PWM2 - OUT6 DMA2 CH2 + DEF_TIM(TMR3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0,8), // PWM3 - OUT7 DMA2 CH3 + DEF_TIM(TMR2, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0,11), // PWM4 - OUT8 DMA1 CH7 + +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); + \ No newline at end of file diff --git a/src/main/target/NEUTRONRCF435WING/target.h b/src/main/target/NEUTRONRCF435WING/target.h new file mode 100644 index 0000000000..6b6a288b51 --- /dev/null +++ b/src/main/target/NEUTRONRCF435WING/target.h @@ -0,0 +1,203 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "NERC" + +#define USBD_PRODUCT_STRING "NeuronRC F435 WING" + +/**********swd debuger reserved ***************** + * + * pa13 swdio + * pa14 swclk + * PA15 JTDI + * PB4 JREST + * pb3 swo /DTO + + * other pin + * + * PB2 ->BOOT0 button + * PA8 MCO1 + * PA11 OTG1 D+ DP + * PA10 OTG1 D- DN + * PH0 HEXT IN + * PH1 HEXT OUT + */ + +#define LED0 PC13 +#define LED1 PC14 +#define LED0_INVERTED +#define LED1_INVERTED + +#define BEEPER PC15 +#define BEEPER_INVERTED + +// *************** Gyro & ACC ********************** +#define USE_SPI +#define USE_SPI_DEVICE_1 + +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 +#define SPI1_NSS_PIN PA4 + +// #define USE_EXTI +// #define GYRO_INT_EXTI PA15 +// #define USE_MPU_DATA_READY_SIGNAL + +// MPU6500 +#define USE_IMU_MPU6500 +#define IMU_MPU6500_ALIGN CW0_DEG +#define MPU6500_SPI_BUS BUS_SPI1 +#define MPU6500_CS_PIN SPI1_NSS_PIN + +// ICM42605/ICM42688P +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW0_DEG +#define ICM42605_SPI_BUS BUS_SPI1 +#define ICM42605_CS_PIN SPI1_NSS_PIN +// #define ICM42605_EXTI_PIN GYRO_INT_EXTI + +// BMI270 +#define USE_IMU_BMI270 +#define IMU_BMI270_ALIGN CW0_DEG +#define BMI270_SPI_BUS BUS_SPI1 +#define BMI270_CS_PIN SPI1_NSS_PIN + +// LSM6DXX +#define USE_IMU_LSM6DXX +#define IMU_LSM6DXX_ALIGN CW0_DEG +#define LSM6DXX_CS_PIN SPI1_NSS_PIN +#define LSM6DXX_SPI_BUS BUS_SPI1 + + +// *************** I2C/Baro/Mag/EXT********************* +#define USE_I2C +#define USE_I2C_DEVICE_2 +#define I2C2_SCL PH2 // SCL pad +#define I2C2_SDA PH3 // SDA pad +#define USE_I2C_PULLUP + +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C2 +#define USE_BARO_BMP280 +#define USE_BARO_DPS310 + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C2 +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define DEFAULT_I2C_BUS BUS_I2C2 + +// temperature sensors +//#define TEMPERATURE_I2C_BUS BUS_I2C1 +// air speed sensors +//#define PITOT_I2C_BUS BUS_I2C1 +// ranger sensors +//#define USE_RANGEFINDER +//#define RANGEFINDER_I2C_BUS BUS_I2C1 + +// *************** OSD ***************************** +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 +#define SPI2_NSS_PIN PB12 + +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN SPI2_NSS_PIN + + +// *************** SD/BLACKBOX ************************** + +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define M25P16_SPI_BUS BUS_SPI2 +#define M25P16_CS_PIN PB5 + +#define USE_FLASH_W25N01G +#define W25N01G_SPI_BUS BUS_SPI2 +#define W25N01G_CS_PIN PB5 + +// *************** UART ***************************** +#define USE_VCP +//#define USB_DETECT_PIN PC14 +#define USE_USB_DETECT + +// REDEFINE for servo pwm output +// #define USE_UART1 +// #define UART1_RX_PIN PB7 +// #define UART1_TX_PIN PA9 + +// #define USE_UART2 +// #define UART2_RX_PIN PB0 +// #define UART2_TX_PIN PA2 + +#define USE_UART3 +#define UART3_RX_PIN PB11 +#define UART3_TX_PIN PB10 + +#define USE_UART5 +#define UART5_RX_PIN PB8 +#define UART5_TX_PIN PB9 + +#define USE_UART7 +#define UART7_RX_PIN PB3 +#define UART7_TX_PIN PB4 + +#define SERIAL_PORT_COUNT 4 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_CRSF +#define SERIALRX_UART SERIAL_PORT_USART7 + +// *************** ADC ***************************** +#define USE_ADC +#define ADC_INSTANCE ADC1 + +#define ADC1_DMA_STREAM DMA2_CHANNEL5 +#define ADC_CHANNEL_1_PIN PA0 +#define ADC_CHANNEL_2_PIN PA1 +//#define ADC_CHANNEL_3_PIN PB0 +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +//#define RSSI_ADC_CHANNEL ADC_CHN_3 + +#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_TELEMETRY| FEATURE_VBAT | FEATURE_OSD ) + +// #define USE_LED_STRIP +// #define WS2811_PIN PB10 //TIM2_CH3 + +// telemetry +// #define USE_SPEKTRUM_BIND +// #define BIND_PIN PA3 //UART2_RX_PIN + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff +#define TARGET_IO_PORTE BIT(2) +#define TARGET_IO_PORTH BIT(1)|BIT(2)|BIT(3) + +#define MAX_PWM_OUTPUT_PORTS 8 +#define USE_DSHOT +#define USE_ESC_SENSOR From 507f61dd384c51b1d2f69cf113c3015ff4fb1243 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Mon, 13 Feb 2023 09:56:22 +0000 Subject: [PATCH 048/130] Update Programming Framework.md Added more detail to the programming framework documentation. --- docs/Programming Framework.md | 76 ++++++++++++++++++----------------- 1 file changed, 39 insertions(+), 37 deletions(-) diff --git a/docs/Programming Framework.md b/docs/Programming Framework.md index 2713835414..527d74f4aa 100644 --- a/docs/Programming Framework.md +++ b/docs/Programming Framework.md @@ -11,7 +11,7 @@ INAV Programming Framework coinsists of: * Global Variables - variables that can store values from and for LogiC Conditions and servo mixer * Programming PID - general purpose, user configurable PID controllers -IPF can be edited using INAV Configurator user interface, of via CLI +IPF can be edited using INAV Configurator user interface, or via CLI ## Logic Conditions @@ -46,16 +46,16 @@ IPF can be edited using INAV Configurator user interface, of via CLI | 10 | NAND | `false` if `Operand A` and `Operand B` are both `true`| | 11 | NOR | `true` if `Operand A` and `Operand B` are both `false` | | 12 | NOT | The boolean opposite to `Operand A` | -| 13 | STICKY | `Operand A` is activation operator, `Operand B` is deactivation operator. After activation, operator will return `true` until Operand B is evaluated as `true`| +| 13 | STICKY | `Operand A` is the activation operator, `Operand B` is the deactivation operator. After the activation is `true`, the operator will return `true` until Operand B is evaluated as `true`| | 14 | ADD | Add `Operand A` to `Operand B` and returns the result | | 15 | SUB | Substract `Operand B` from `Operand A` and returns the result | | 16 | MUL | Multiply `Operand A` by `Operand B` and returns the result | | 17 | DIV | Divide `Operand A` by `Operand B` and returns the result | | 18 | GVAR SET | Store value from `Operand B` into the Global Variable addressed by `Operand B`. Bear in mind, that operand `Global Variable` means: Value stored in Global Variable of an index! To store in GVAR 1 use `Value 1` not `Global Variable 1` | -| 19 | GVAR INC | Increase the GVAR indexed by `Operand A` with value from `Operand B` | -| 20 | GVAR DEC | Decrease the GVAR indexed by `Operand A` with value from `Operand B` | +| 19 | GVAR INC | Increase the GVAR indexed by `Operand A` (use `Value 1` for Global Variable 1) with value from `Operand B` | +| 20 | GVAR DEC | Decrease the GVAR indexed by `Operand A` (use `Value 1` for Global Variable 1) with value from `Operand B` | | 21 | IO PORT SET | Set I2C IO Expander pin `Operand A` to value of `Operand B`. `Operand A` accepts values `0-7` and `Operand B` accepts `0` and `1` | -| 22 | OVERRIDE_ARMING_SAFETY | Allows to arm on any angle even without GPS fix | +| 22 | OVERRIDE_ARMING_SAFETY | Allows the craft to arm on any angle even without GPS fix. WARNING: This bypasses all safety checks, even that the throttle is low, so use with caution. If you only want to check for certain conditions, such as arm without GPS fix. You will need to add logic conditions to check the throttle is low. | | 23 | OVERRIDE_THROTTLE_SCALE | Override throttle scale to the value defined by operand. Operand type `0` and value `50` means throttle will be scaled by 50%. | | 24 | SWAP_ROLL_YAW | basically, when activated, yaw stick will control roll and roll stick will control yaw. Required for tail-sitters VTOL during vertical-horizonral transition when body frame changes | | 25 | SET_VTX_POWER_LEVEL | Sets VTX power level. Accepted values are `0-3` for SmartAudio and `0-4` for Tramp protocol | @@ -73,17 +73,17 @@ IPF can be edited using INAV Configurator user interface, of via CLI | 37 | MAP_OUTPUT | Scales `Operand A` from [`0` : `1000`] to [`0` : `Operand B`]. Note: input will be constrained and then scaled | | 38 | RC_CHANNEL_OVERRIDE | Overrides channel set by `Operand A` to value of `Operand B` | | 39 | SET_HEADING_TARGET | Sets heading-hold target to `Operand A`, in degrees. Value wraps-around. | -| 40 | MOD | Divide `Operand A` by `Operand B` and returns the remainder | +| 40 | MOD | Modulo. Divide `Operand A` by `Operand B` and returns the remainder | | 41 | LOITER_RADIUS_OVERRIDE | Sets the loiter radius to `Operand A` [`0` : `100000`] in cm. If the value is lower than the loiter radius set in the **Advanced Tuning**, that will be used. | | 42 | SET_PROFILE | Sets the active config profile (PIDFF/Rates/Filters/etc) to `Operand A`. `Operand A` must be a valid profile number, currently from 1 to 3. If not, the profile will not change | | 43 | MIN | Finds the lowest value of `Operand A` and `Operand B` | | 44 | MAX | Finds the highest value of `Operand A` and `Operand B` | | 45 | FLIGHT_AXIS_ANGLE_OVERRIDE | Sets the target attitude angle for axis. In other words, when active, it enforces Angle mode (Heading Hold for Yaw) on this axis (Angle mode does not have to be active). `Operand A` defines the axis: `0` - Roll, `1` - Pitch, `2` - Yaw. `Operand B` defines the angle in degrees | | 46 | FLIGHT_AXIS_RATE_OVERRIDE | Sets the target rate (rotation speed) for axis. `Operand A` defines the axis: `0` - Roll, `1` - Pitch, `2` - Yaw. `Operand B` defines the rate in degrees per second | -| 47 | EDGE | `Operand A` is activation operator [`boolean`], `Operand B` _(Optional)_ is the time for the edge to stay active [ms]. After activation, operator will return `true` until the time in Operand B is reached. If a pure momentary edge is wanted. Just leave `Operand B` as the default `Value: 0` setting. | -| 48 | DELAY | This will return `true` when `Operand A` is true, and the delay time in `Operand B` [ms] has been exceeded. | -| 49 | TIMER | `true` for the duration of `Operand A` [ms]. Then `false` for the duration of `Operand B` [ms]. | -| 50 | DELTA | This returns `true` when the value of `Operand A` has changed by the value of `Operand B` or greater. | +| 47 | EDGE | Momentarily true when triggered by `Operand A`. `Operand A` is the activation operator [`boolean`], `Operand B` _(Optional)_ is the time for the edge to stay active [ms]. After activation, operator will return `true` until the time in Operand B is reached. If a pure momentary edge is wanted. Just leave `Operand B` as the default `Value: 0` setting. | +| 48 | DELAY | Delays activation after being triggered. This will return `true` when `Operand A` _is_ true, and the delay time in `Operand B` [ms] has been exceeded. | +| 49 | TIMER | A simple on - off timer. `true` for the duration of `Operand A` [ms]. Then `false` for the duration of `Operand B` [ms]. | +| 50 | DELTA | This returns `true` when the value of `Operand A` has changed by the value of `Operand B` or greater within 100ms. | | 51 | APPROX_EQUAL | `true` if `Operand B` is within 1% of `Operand A`. | ### Operands @@ -143,43 +143,45 @@ IPF can be edited using INAV Configurator user interface, of via CLI #### FLIGHT_MODE +The flight mode operands return `true` when the mode is active. These are modes that you will see in the **Modes** tab. Note: the `USER*` modes are used by camera switchers, PINIO etc. They are not the Waypoint User Actions. See the [Waypoints](#waypoints) section to access those. + | Operand Value | Name | Notes | |---------------|-------------------|-------| -| 0 | FAILSAFE | | -| 1 | MANUAL | | -| 2 | RTH | | -| 3 | POSHOLD | | -| 4 | CRUISE | | -| 5 | ALTHOLD | | -| 6 | ANGLE | | -| 7 | HORIZON | | -| 8 | AIR | | -| 9 | USER1 | | -| 10 | USER2 | | -| 11 | COURSE_HOLD | | -| 12 | USER3 | | -| 13 | USER4 | | -| 14 | ACRO | | -| 15 | WAYPOINT_MISSION | | +| 0 | FAILSAFE | `true` when a **Failsafe** state has been triggered. | +| 1 | MANUAL | `true` when you are in the **Manual** flight mode. | +| 2 | RTH | `true` when you are in the **Return to Home** flight mode. | +| 3 | POSHOLD | `true` when you are in the **Position Hold** or **Loiter** flight modes. | +| 4 | CRUISE | `true` when you are in the **Cruise** flight mode. | +| 5 | ALTHOLD | `true` when you the **Altitude Hold** flight mode modifier is active. | +| 6 | ANGLE | `true` when you are in the **Angle** flight mode. | +| 7 | HORIZON | `true` when you are in the **Horizon** flight mode. | +| 8 | AIR | `true` when you the **Airmode** flight mode modifier is active. | +| 9 | USER1 | `true` when the **USER 1** mode is active. | +| 10 | USER2 | `true` when the **USER 21** mode is active. | +| 11 | COURSE_HOLD | `true` when you are in the **Course Hold** flight mode. | +| 12 | USER3 | `true` when the **USER 3** mode is active. | +| 13 | USER4 | `true` when the **USER 4** mode is active. | +| 14 | ACRO | `true` when you are in the **Acro** flight mode. | +| 15 | WAYPOINT_MISSION | `true` when you are in the **WP Mission** flight mode. | #### WAYPOINTS | Operand Value | Name | Notes | |---------------|-------------------------------|-------| -| 0 | Is WP | boolean `0`/`1` | +| 0 | Is WP | Boolean `0`/`1` | | 1 | Current Waypoint Index | Current waypoint leg. Indexed from `1`. To verify WP is in progress, use `Is WP` | -| 2 | Current Waypoint Action | Action active in current leg. See ACTIVE_WAYPOINT_ACTION table | -| 3 | Next Waypoint Action | Action active in next leg. See ACTIVE_WAYPOINT_ACTION table | +| 2 | Current Waypoint Action | `true` when Action active in current leg. See ACTIVE_WAYPOINT_ACTION table | +| 3 | Next Waypoint Action | `true` when Action active in next leg. See ACTIVE_WAYPOINT_ACTION table | | 4 | Distance to next Waypoint | Distance to next WP in metres | | 5 | Distance from Waypoint | Distance from the last WP in metres | -| 6 | User Action 1 | User Action 1 is active on this waypoint leg [boolean `0`/`1`] | -| 7 | User Action 2 | User Action 2 is active on this waypoint leg [boolean `0`/`1`] | -| 8 | User Action 3 | User Action 3 is active on this waypoint leg [boolean `0`/`1`] | -| 9 | User Action 4 | User Action 4 is active on this waypoint leg [boolean `0`/`1`] | -| 10 | Next Waypoint User Action 1 | User Action 1 is active on the next waypoint leg [boolean `0`/`1`] | -| 11 | Next Waypoint User Action 2 | User Action 2 is active on the next waypoint leg [boolean `0`/`1`] | -| 12 | Next Waypoint User Action 3 | User Action 3 is active on the next waypoint leg [boolean `0`/`1`] | -| 13 | Next Waypoint User Action 4 | User Action 4 is active on the next waypoint leg [boolean `0`/`1`] | +| 6 | User Action 1 | `true` when User Action 1 is active on this waypoint leg [boolean `0`/`1`] | +| 7 | User Action 2 | `true` when User Action 2 is active on this waypoint leg [boolean `0`/`1`] | +| 8 | User Action 3 | `true` when User Action 3 is active on this waypoint leg [boolean `0`/`1`] | +| 9 | User Action 4 | `true` when User Action 4 is active on this waypoint leg [boolean `0`/`1`] | +| 10 | Next Waypoint User Action 1 | `true` when User Action 1 is active on the next waypoint leg [boolean `0`/`1`] | +| 11 | Next Waypoint User Action 2 | `true` when User Action 2 is active on the next waypoint leg [boolean `0`/`1`] | +| 12 | Next Waypoint User Action 3 | `true` when User Action 3 is active on the next waypoint leg [boolean `0`/`1`] | +| 13 | Next Waypoint User Action 4 | `true` when User Action 4 is active on the next waypoint leg [boolean `0`/`1`] | #### ACTIVE_WAYPOINT_ACTION From aadf5eced5104d18b123a888befe1c20ea300846 Mon Sep 17 00:00:00 2001 From: WizzXfpv <40316777+WizzX-FPV@users.noreply.github.com> Date: Wed, 15 Feb 2023 12:23:20 +0100 Subject: [PATCH 049/130] Update Temperature sensors - add picture to docs picture for text update Update Temperature sensors.md #8796 --- ...36-b30f364f-aaeb-426e-b211-ea7ef1f3c20e.png | Bin 0 -> 138749 bytes 1 file changed, 0 insertions(+), 0 deletions(-) create mode 100644 docs/assets/images/218416736-b30f364f-aaeb-426e-b211-ea7ef1f3c20e.png diff --git a/docs/assets/images/218416736-b30f364f-aaeb-426e-b211-ea7ef1f3c20e.png b/docs/assets/images/218416736-b30f364f-aaeb-426e-b211-ea7ef1f3c20e.png new file mode 100644 index 0000000000000000000000000000000000000000..fbeb449387d6da631dc716b56484c27036c0f910 GIT binary patch literal 138749 zcmV)cK&ZcoP)60eOUFZ4vxqC!BM_!egb$3_wp}y1-QX>HpvS9`o5Hn(Jk%n*Y}wCWC|I*EIhish3wjEB*VL zR(b_7lFyOfQ$U@$#n5D`?B7$e3kUyl;;G#J2QFwue<(0pc%ph`r+ zbZtF8I#$oELVy0K5kV3|5y6NMRf!=W>1zEwsm6R?>GKN5CWdP6*YtmkbbX>|RIGxA zbPi+8@;b((&kDq-1R^o_Et1+EV_g2-w-2@6OZphpOgt zf+e8J^7a0yr6(Dq5@G~fV8rzI8Z{C_#8^WJA@wm3CG~*<8uLA|WP_@T21R0e9-w$1 zP>p~fLT*p&$K&dEk3HKw9#tXcHW*`Y&h`BlLg>e4>fbybx(7zO7meu;W70g*7>QAd zF`c(4%D&Ge_i+q$x_*qybBJKA!AN@6!FvoX&RDD%G(v16&NwiZ04zeF^#Qa%j3Oo= zCW7QXpg@Dcdx&0X>jl1U(6%MCExu`qUWjT?3>b^WVWQwogL;oshqI31R>k_GYYcY= zoV$3Q-R-kj%(3yj`n(=eAWa>+IGSRD5?iGS5!9e6X>dlsrNLpX1)ymfV$6WBV%{{9 z2}T5CEXG;H2=n;@Tev0Ygn+dL^n?UrD=p#l2Clxw$noOdIO%t+d+XP-uGjtEK5X$ zrfF!J1`(mEDgeA+juUHb|Lj-igS9p!o7M1l{rzD>{4dy1l_NW?+m#qY^ThbgazBkSD(OK;|=}aLy)R zMe&*johmr%Fkc?Y(=-?nTv22IAd^Gs0lEX4 zt_|H!*MA~ljO~F#HRit)xCfs;M|VCk`E=S}YxN#Q1W{<}HUWC!uqFX~>X+2NZQIf| z4Hm)VMW+M8t`E|)NZ{f_V#)$5?0lt9J9eJ?ezmW=XJU-OT1#1$M2+}%Irh5G$Bq@B z=(CRc_5>rhK}6D`(Gk|X03;A^5E`s=IA@XEj_x|CZFN6hy0Ku*kPs3eM_p~Z&*Lpw z6?OEGZA?+cplQKV#SoK4AVP2?b}J6VVa4E^1m0p@0(0ZQI&2WEA%VJ4TGJ9{ff9#} z0(p*i&#JRpy5pe)(m;c=1{)lcTQg?wHH2EwXb3@j6U(|t)6{tqt(eQ%RO#8EE(cs^ zf{O?t16a@mKS2{KNs}Y7H*1sm6=G&H8ZntkCDX|#K!SdfXbdPmftn`JS3*A+)58qJ z*b+kre32-MNMdVI6^jLgCf3B@)4&rU#>Bkp*r2KuWq~o47z3?FqRFOyNNiLD^aRK& z5TeguL(gnG(=VC&OY43WNTUkYg0)G&h|y6Pi-crJ1QB8kxi6H2XK4U?=ZFC!5L=6? z$r40o>MBa4EQ$n(8H5t+0aXj6g`p!CQ3cfIdxIDSk+T0z%(l3&0x*z3GA7xid)A5Sd^Z~2uU_GC=wOXfFWQ_GTVI+oE1C~XFSe2 zgtYiuq&M%&SP`?CYDAz=+F8Tl;f%&dqGaBy%f2~zJd{9cNzc8VwM_0VaP1JOAx6*; z2qA$bjbJsIH!-GR8$uw2WNJa0yme<@v6LQt@EGI3NHS@nCx~XS40$DWXcLo6iNQ#c z1?nbEm|mA$VRGp(naQL z_!Y+1X_Xw661WRj z(1e!Q#$KD&*b$NLKP>fkBbXQw4@LAiV?hi)Mw%w#1*~%vw!mVL2!T0n9D>aYS)>htLcti9?lB5hg&;!V6!ifsia1As#j9oRJ>FVcD>Nu>g%q3w(}xmB z0i3bKRxzQVodqOxt7{-=NNg`z2>n1vt7HPH7$liN-lMkYT}^4l1Sn`iB({m&MnGM+ zS_?4)Met$8Do(%n7>;RZN#E0BCK9R`QDSWS$(H79Vi7&SkSC@|pH&UL?rIGXNxGC3 zLLn<=6H9Z@bdD*7;4wa#kkIGS%<@5>N#R!mKpLOw=ONv zQSeboKBxfRfl6YwzCe+z-2y&h3Z;=LVih$88vt+cE>Jg~h@eIYG2o2r7q63J`=JC< zgF%c#)zF53n351YkwBm&Xdq}}oIw9@69@=CkFS^~s)RNTGFAqn(0g1pCetGj`oXuV z9l}ztQYATl@<8piqs-iTAkr)qsA7%Hljg+dGQ@nh*gS^bxlb9VoBN2kq&#xK7Eh(t

@GUfzGHJ;S6h-ko7$XyS=C*;*L$l+AMBk~mflIu z-S1r#Mn4WnbEac~ot`NtpJDzt>hVSMukZNWWJ|=Iy(U3L93~W)6aGZ&1$I^&>h)9f@&8656tS-<(^Q)`p z2+{YeRj+~e?}cTUOExci@aTYf#cWK>qcgX%{v`>t`!FKaq>EaM4UtM~EiuPu5cVC)h5$Gmn z0tBZ^4U+u2F>(xGQ3%A6kcioHi9s`&@|e*t1BgNqFGAg)3IVdD60M zyZ*{>6nn5du3O5ACcoN_<9cak=qv29Ux-!@rDx;aVXRHhX~pbreVf~pda7IVJNDY$ zuQ9e~kKH1vs>dB&F-O6~7}uJFY&y%_CPf8H|)j&2)N1+bk#x%dj$xMq4Svl$?CZB5e+VbomsgD!^xv#chCWCCs7;+kHl{D*ylqN`bpXKXK9yuEg4+mBAkdV zJ>4OoQ6G5i)XxRqKZovLV_m-9^4ziYd4XImuF2Yt{Ucg+P{fsms0U>sI}`O-dyAP8mkxu?uvfi{P9RFOmXs2h_-EUYK(~`!YK%|SuT{2fP3-4~& zh{*$L*-z42LC~oHQ4}PDe;$Cr2TC<*tcrrQY?Nc}$c#pnfFcEygN7@Q?QrF>EnIoT zy~CGj@9k4BCd3eup6UuhY*8_+Z=PXm>jF3k@vxWbXvl>ihEjFs+qD1kKl@o^O1>0F#LD7)S(GL7v zdQSy34`&}c?Ne3;hh)|pNSGqT4h%(!CbIz(GHXsD6&+JsWe+M!6rc4SfUMnWr%5hN zY9|g814CQlJow3iA|_4CW`~mIiJTaA))G6DEqmd+pzzLt;IgAegZ7hF$fk2h6C+4+ zIIPCsO1c3cu|?=WDNmRtbPs9?N;bI&b)_Gc5eiFYWwZm=bb^y%LvWl0uO26vQ|iZ4 zc&Z-%R}q?yZLgTHB9a|uv1e?~NcQH(W1&JK5ORct0W>t(F_*M-fU+$63wP05BA~`3 zZ*{tfmHwa~M+vTS_*Z6-Xk0ETBKVLOa>?FqNnvh^roifCW@W}FDH0=FQ<$aZ*{@kS zG_Q-?NY~HqF_XqH0zRbgi5OH8t5YA3u~9XG2E~Yl5HVUqSzrbgF&Mm6TH_fEBOm+3 z8Me0z4iEpF{rz{T%78Hq17}jqwg+PhTCXgc32i&2uJ;)Z*4a68g&+9rRo>V<;?}!? z$^Du(I-ELG9BNz&CoutI3aYZi77jgSn5-TTC6IzmAw;2}K=DmLy@$-s0)m4X6Nfyfn!KQd6#!C`fYL^ijw+Fu!qq{Olh0rgwOFwPg&-X>&sv)6 zVmHC&P%HJG(~h`eQYwPi(1R1uYrU{yQfBAW$s_x)mod0uMJCB0*>TG*45!m?)yHFJ z>i(;}qa`g?O};Np8b<#OF_L8!NG!AHP4|usw#|wcjIi39|qrJ%sY7PX2QK%*@h4TCsf9z2D!H1h?eGe{wLlOi>I4ws5* zu$r}Kn_wh(PusLqRe>oDa~1>_v2lP!2)<1|3!5m6YXe3sS~wO)88n8OdWu4^G*m8m z?t?0g)C|uAp8e<+n`dq@UF@@H4j5Jjf(7rGE@ogY5kuR0+IEf)4K$Yd(UiNlZ`1li zMr$=szwiW93+h)J;=aeo7?0AJ1n|xjNG;f4Xq!keEcu}0AqCPjkb@8S;IkRhC3&)9 zlE?nDF|Y6`)-5r=sNH9pJZZAI8xzG>&GDX+%y92ZV)S_5f*72uvRAjpm4P$c1>3tL z2BQUo;gG5<`wWmS`w3DSpAUigqG2|xnN4e^vpMs5WIl^57McQ!O@a4{ah?SY_ZFVg zDr>Hy^@SP|cD;4m$27gRJLvX@bd5CB5nGqe2FvNCE(74S^I4 zEt=$zj@ftMl>S{hC%O=@4}6v@dgan7k}#zUe}aziKFB&(kCbSTbwHNa?#|g6=zUlZ zWDq|^w#b%qXVUlKY`HQ0`XeAQXP0#h>_oJ{X##HNggh;Mv;%mYoZ z@k(sk1m0_ox{Mq#Vf*S?YU_z=Fjz_*!@T8S?-09)tck9 z(=b{yJpRNEo9ltY$sL;M5tc|<3iaX;DWMcYP>(YW^Tj=iV#siq(ndAHpcr!Jy}M`> zKKHq2`Sj-=!MCro_iBT$Cm2dpi~I~N#;#gEr&~GQ@z4UPki3bB`A83zF-q0|Lk@9D zppjzsmLS>%A*ax$Hg%*5+I?RVge29nO_7_yWp)riJ<5XJ-3=~YKF_&}BZ3|fnGkeN zUGFoU&pDh1thIfLVV61=Bb3#MGdm?0E>)yQs_s0%hI(+*3?-%$^b6s&Z<;5yyry`oY=SENy zkVsyXyz$jJ2clhT& z_wzjZ{9`aQn4&~HR8sNIcdzlKU;AyYz4SWm-6>n;5N!ey4H^wmQY@~kN{n?-J#sBPIu&6Kdm4mmrcXNh%h-zqk(n-Y#)}c+l(EMX8p{W04&(t7S3PTVrO^A zaHurxZ4M_B7WF-RoKn}*%%nnYtI5ILfp(EiMTFVhpc-(6r6@~`sThrRc;w0k=gw`i zf4|}Oohkc=HBB9v2B@cjN!_w;9A}CVYp%f8k=6%de%hVh6SJpTGGHWGEvCeRtVzZ$ z06TYV=cwqk;?&Z#$fWpf&CZsXSlkNP>{uHt8E@ykK8=&6$O4lbfBCy&ZPtd9nH##I z9o@6<*xUOJj*fA!=(@+FCAx)TIhMLHbaIeozsoV*5;|tw{oV1^-2Nr*aq@&Gu{!DG ztKnZOzw|n3?6a<-fEq=O;-zKh$}V60Z+?~wPh95Sy(9kB+y5i8w-0cVGJb-IlsjXd z{GsOwJ0&mt#An#MyT_k@`9&J3`LTcg1zz}xAI1zUWmOQP$5@l(2BSRvi5IBOjQGlL z{XQ-RLi9ZQBcI^;AN>@Me)35|rHECi1ixr$HFECxi~N^Q{a5_k#hYn>`Afq=!LKGF~6Def~V>uRhIi?IQD8gNYv1 zIk)fav3cee`?v0Lcy}LbQv9kb3f{f`Ixqd%AMvCA_-ELAcf!%+7K{6H3UxS1g;y5! zoVINkN=mHwAZzEL1X9Sk&3#&6?9C*NT?(kj$CPiKfYhff49EbP9UdK1=|F|fqn^Q3 z1CfYGq#8}R{KyuUA01=M3G?||+`j)Fv)MjnVQ@|`77C}J9&)CNb3)t9(*()E`qny( zDo8-ACx$uR12RK&NLg<1=wmxvd}N#3do4HLJLKRXFrRsv)-y+v=eAg*Dhdb&(YP!M zmH(@KNJ~P?pec8MsTMB7yn2e2P2Z%2B!Nz{rmUpOTapt66yYS*>T~*|(gl=q1dO8?D^ zVG}(U9=*!i`7=zUX0Scx%CnF0@{2F>`Tz6_Jo%ZAGZ}gYg~17w<&cQ7KfRCIhz>13 z_Fw!IDlLEV+ke2;&MsGf@L3-J^fN4^rZ9#zR}p>^6^FeUb~0Kgas{C#lvh zFdl4D7)w(haX7ujo zxG|Z721HWyO^6X|UGnDp0Ok9e_YWzMc4?XkAdcx^kn^dNE5YZ270Gj*<2}ia5deXp z9wcS?U<{4-SZ9dZ5~X2nW5~Jln_Rx=vE`gu^A7uW-@!9g-9(9CT`o`7dW@fOYlBV(1^iM z7zZ&Bq>I8`9x0AA>9JmO2%0RjMLO*0Oxaa{Q8YzNtWem~HP-iM4}G?i$Zh0AwwA$vrgk9$?Up-eZC*=8G)u7k-7nJW#!c#6ugXs5WU1nY=x8vE8c4kkw&OeYLCH)(>$Sj+IjI#<5`BMdKW zF!v3Uy?ws?JO7?r*KQH5;dB4^N4R|T63wPE)fqqib6@0@S6|`#KK&`a|HnVeetXFJ zaLBzkuk($szRcoCnJs2)Kf2AQe*A}6lnbUBc>H5e@Y+{iX1?Fz#38Eq7_n}MTBt=S z*Gp_!v$a*Qck>#B^$e>q>ziYCFFwMRXI|jU#pkgb7YTMiBL!XyWU$5hc$dNWJW#N< zHsDYG;7c^~8O6LHsG&KkdF|WZ=J`+mIF}wj%iU|&ka=?UI(6AfP0u|gOT539|4;&{ zB=Ig+H%cKOT|mBKayH5e381WiVmr%qm0(}m0#LTE8X!}i&dC!adUXdG!~ z?@&(v58%kMM3LZwDpJ;j1`oY7=7~CN0Xur6s$`* z&-?p(Xfzb|K3hAxJoC&MHn-r~TXXjJ41VU=ZyRP)Pdgm5WvV18v_64&vT<|0)=V%v z4Nq4ltK?dwq)Ban=p)uyn&>fwfr3&Vj+wu%V>R{?mQKm;z0Ub_>XEY;mwM~!iuJ&i=;VOa(<#RT?w8D4mWyD1&t{fh zmM%MQ0;Mfeo`uO{P7O%Qcx_DS3WE0x+<>YY@Z2Xp&ieKyzNuNa6@Tz=e}}LC`X5q; z0csq-_N`y$pZq7E=i^`eAv`VhY{9|@=HfZ>b4F`x9NxUgum5kq%HB8L#?}>TB4HG` z{pNK(|8qah`sRqS8{%7!1VzN=3Tq%HB@eW*jH0l_dYkT&6rMwn!FECf3HUZLFpZC?jge9PMG(v;2v9U?DHlis! zZQT;R$C?yU6-AN4u)e-V;Vg9ss8c43Dc5e?V6kWzRcrkDH(%jvzxVGMHx)WJ)NR9H zW5B=r<=^DRm%c{1Hss#zyWD!~I>R6NY*No#k2cEw%>#;NK+!scNL0gXfABKWSavU5 z;9Fn$26iEo;y?od+gp)sTcZR91HIWz0Ivc7eRy&DHS_sP%ko!8#r=B?LKDMkZ#?%k$Q;gPFX7_GlZeSd~%AVFhl zix5Bp@OLh=DaB+C234*;6MIlp?W(#*z%H5TO6W@eldGP$YOu~ARXgmV8a@Q-W|kZg2;O&qogxKt#B(wujYTE3wQZZEwRYZQRfslMFN%b` z5LhuZO^Y_3<*ahFjd1JwZH|T$&YnHbN1hxr7&_j0r)GcOFsWNYJEtbHIcN^J@#=eQY_4(f!e!oi>Gc$&8bQs2pea3a zobv2+MO!?D;hhGMf6e5xmvs7ZAYJZydZSNH$jmY=vgx(casiHmVFu)0SI#|=@4JgN z?Hzpm@7f8e8834HTb35OPB5fh9h`H7sLb02EiG$nYgB`RnTbRj({r`Tyq*J*vaE*3o*8 zE0nD>C68WR=iEh06K-<<;Jb*OL#PS4k`1IfrBQ8)aqO5xHz7$81zk1yWIC5LP0C5` z3Oz&&*4b3OJ^D0XRC+IaQ8?O=YKS_i7?u^Gskw9eZ8pwqaOKK5th2oR_JaF&VLET| zv8Av!Z3&^8b_>X*-=JeQY1nia=<`JGLev9FtC6Oy8EvewnAb#!j5pUffB6D$fBQ{h zQ0lf>nzA4I=%D2kPdV?GwX|aL_Fq|99o~=qc1YEKPF8+f4Xrx)@6yy(>DroKJtYOk z8rvuP_E8UAdM?=l$f%mM=ahLA^Y3UE2i?PN)_JF&K?#?k^AuX48hUbW~DOXpTS# zLhTz|F2>RXPYjXSqG7BhMQMpXQrZDch*%XyrlQ0UW(^LLs`lF|kp?`T2J1Aj!w{KG zXG~^u+%V1Qq8w5VHmMm9f_-4o6^#TMtQ24?)C^Duiduz9|J*Kuq}ZA zCNLUXu0FQGrOSr92jAgvb`9qiV8FVH*0(rUA*M_dAt=tKRJ^jXSPP@!03(L^Y)(-Y z3281TLMw zgcEqvw;Zv?bbi3TpA*!vRgBTrQ%X#`FZDv(s%=jK3zyRwJG0&jftGK-@-mZl!sOnB zdvcd+@^;EWmwEGlYEZuGq#>j_d;NyFw^k z9fXtydHj}*q_C}S+mO^F+PA$A;p(oFP4S+_9%~z^tU`WobxRS+iz?6qYmC|RPIfTG zmAV09`bX5q;A*ZC9|e&D(SV4@N<>48Hfi6ZHCtlE5dyeiFg{QY9ea0fGo4OwJ7avC zGVzY4)3im(XvF0H5&K66Y!1gT4^+l zRkxlXhDD5&rogw6fh!5V#W)8|N(J@O;$2HDLdsBV1Fk5Dg@Mt4&CLsp25S%_zHOl> z@eVMl^kic2f-yrhI=Ya&Sv_aGF-}rh1cD_rf=Ed)foNKSdL&j9THu1>noFrdqohP16m zR3)^LW*XVQf1AVoyUeEhwCx0I3l>FW(F!3tkOD$W6h|sR3egD8I+}WhA53`Uk!=Le zo3GFD3U%wzX2N*GQ4}Oke#jLHBr#!Ox&1^k_Ln|OL9oUV)pGmB9fFOl73=s(;KrM` zFtG%2h$&NPxd$H5DXaSjfa~$Ez7I3#5VH#nN+mXyp-8LW?R81{u$MjcSk17KtdpMB zx+TEp&*+j{_Qh&e*l@R|om4=Qb}!l7Ke5<#j?8>1V+yu5&k%AE?!{t`DGOXVOqIcW zL+d@ID;Nxic$+GcRl|z&XU{Sy3PRJexw*x7ya9J3Rt-^8*pyf(wZKO528$BOXzuR)Z5uWgIa^TuSnXT&k2t$Cz#15o7Bd>7 z&Jd_6hN)I;DlHgDyFdg~4bcx0(btx+IAZ-w#T)l-5!xvt9%F^^+JLeUrn5P-X`Ob3 zh>DMGPOYV{Bl|&?)k6xTDX_PyDn^4LvvAPI-*xe&QS*+N5zx-*(`luG5t}M4Nu(Mo zS03Nw^3{_4>8sp5c#Wzsl;wc=B5j=JW58A;qW3tHFwK<(ic+nuv$4C)<*QdYf9Wb> zciGw5VKg4~=6z8Vy-r)#HH+DV#pE8op0Jqgar^q~+`jn^hll(4`-hay5)m375nJNb z(1zq7b0Xk9!>VAu*vH3)$3OBo^TmQi6WPDtV#IK7b|0w*SSgpL%nI0azbp%pD=PDOH=Ckt)n4GZxdD z(v>ViiyauudWjA!b!Zuk95R4nG=RKMl|;cW7Tnvr#s0lJZ0+o_ckdpv*__Q-;bPhW zAy{Z7?S2p>rMfR9P;11;$ap-)#UYz(WAx6HHdqP_zL{Z5OHmmni#dZ~l^mz75R-m{ zQNaX*iv_-!6R_MqIO5Wyy9}z5u$Z!#OcBo)Yyu(^)aK;aO3WMW=AzK^hVsPPDkzr#^E?Aoi&6evh))r$LLOmtS z?sN9y(>!|TI`3V3o%e3M!=1Z#n9im+jkJMOkU~-%UI=OD#%5ll($Wq*ckaB!)6ZVP zha-IS9NnKGv7k^W$^t8b>nro z1`?+*x6|~{(~kH)pF5VF)SLImvyHmNGJhlI?LXMO(~eW?o1UnY{()>%mNiAY*So)0 z;deDgv|{J@f#s#9Tl*#hX>dfIBz$XpR=RszgoTXMX;l@ugq-5^sI$Rc4bZ z+ZT8Fr$75Mv_wiA23o+{&IUUdcH!C#nt=BW!3wRkOp67>wJ~BX zlj)q+Dp-SWJ@s_Pbg^Jy4dhHgGcp{-DXb0n#E*T3x4!cRciy}=eI*1lyh*uV#$ih%%;3asFY zGYrQU8LVGn`}}<_UHLeNci!RkS6||d?|z%Rx8Gyo>l9%?+Mc6;RAt;7f<`(flW`Yf6lZ~_tnE~bt4O6Mr7BZ^`L zd?#qGh?Nfz-md@kI1pv{J0@QW(C-1YLL{XFlVf!~GoA{^!IUL9b$WPr?vvExw5hZD zTIa<-?YqYtxN?ujKDJ`kckNwSctoU+!%c;&@-KgyU-`v-Y=j^G!cS7{u3@W!ih@7;Y2Bmr$6~D zufOmdUw`MzY;UYVv^1vW$}^AieV_j{=PzC2=-v^({BQmbY?;gbsZvLe*%&Z6m@w3W zMLoxi3_DjY^SPh-3I5?v{3CwpfB9vuy?dQuXeq=XlB-um$<8cCJrC54<<{O2ZEGlv zWp?i_x8Hu9qk{vE_7Blwm&cy^G{xF3seWHTb;07`27mU=uW;wa8@y{h@4Wshw{G5K zI+-vWuQ3>mc>1Z2GQE4mt#|HF&jK-+B(I5LiWK?K?c(}D$3qIF>3_i|@1bJ)$=p>z zT2^1r121pU8hws?G%e#bxcKOp@#c&>_pWp2?t3XPKZ4}#U4u_ri@{JzU@%(a$!9;# zm8YKP!qsOPZd||?8+a;WbQoJ8woQA&=cBMi+NQ(`Vmo$Y2ug2m2HPip3g7TPryy2j8S(D7S9jWc#e;+2_ymr~lywwzAZ% za8Nf4M-?%8N?Z?L{T@+$LE_v`d9GWR_hPhZ0y)*b9A3~!w~3vIS!P5@sxj~&N-cR= zSL7oB=L+*$b+M=g+F=KQUC>Z>*P@Urak|cK6j4Am$>;yY7nn~MTzv8>jrR=8Aus*mpYmJ(`d8U#D#AfcY&bvM8W#t&V0h5Cn&6yE5 zZcKP&XBVvlv)O|A^bj%dt*`z&?jA=c6C}D7zQ0@W;RRGB@7bqn<`YZK`tR6jKywT$p9n+xs04DUi|^ zWrnn^K}_z$elPmam(c52X{rQetfBT3);0}KJhj8+t0ir?&b4dbW>8cROROo;kXCdWlid5;ikTHoShl~}D9VrX>>?J-@2{LaK@=?dv#UYFJ0owbQL2|3vz2TH9ZJ@lUU??I64SzAx( zmTXLWwzdMKvf>)+ojZw1FZ1!!Ipx?sQ|~`nK3t~M>8Sw^zLHAnXEauFBokw;-EOp&ds^d?-^hbQ< zH~#?cc?Q1Z;GO%l_iAiWayU8S$xlARQ_ubnET%PfI6y1G4jp@kM~q{|x4!ZU)9XjP zy#FGPT)N29KkzJb8rH9D@zek97b!w287WSgkCi3{w#|V1@4km^0^$R08!_UNJYmyr zp+j*@7cjdY7!;2ATE*tzEPID<;_u$$yb*SHb{Gu<_YU6W%U}9MVoWjFRZ(!^(j^Y| zZZSVPVlkc3EaueBoWZza_uMWoeE+Ap{@S~|{M9$uzr6r&an2$R%3+1I8A$(v5_$mk z7k=Rve&IumkiUIL8@T!Ad%XGbJ7{ePKJ5YTgW{u-{EXeEY1!GNfv5rN0$aP5r=Htp z>ulilH@<;L#2G+SzIj;|*?bI$QMPt=c;-_-%xC}M7dUhNNo=)E&;gPw$y9~l94HOO zq#`FD{G(V>C`|ujlDAxp!xSUR(HYjyY%^LPB;bmkdOoLVTUv!+1mgsow>B{d#wpHO zKJt;Lxp)7N*}P5LLr0}73oL?-(lf3l#7NHJPX9VdkqJfw>1vSXaPUOFa$b5T2FS9u zFY1?%yZ8$8V>P` zKuN(^OWu9)yZqiS|0eTm2Mqmy*c$5jf;ZoIi^o6mB4Oh{x#v&96fB99UgLScbhX?TWE}2IDdh)GiO-aTBoW~Sm2pzov-}H@AKt< z^INRd14>_}t&>T_AyvIe^B|&3>IOGR@u)#t=1f!Ua!5t5MLpIj>*JE~z)=}6!E@{8 z9@E1kCWl9~Z7SMsoG@Bn+t76%3D1?$qz8pHK5>u0z4$j2UM zyg9-+)9-h7S}gO!38b1fx4ZTBEna{59sEpb>IFUoeAJ|Ss7EDNGuMtaMSN_jM#7~> z*Lduyb@uLmhx>Q;5ESogoCDEF;anc-}Tg!?|OE9IE8hWq2$!tSbmyGurQm6bp0IsM0 zDaT$|t#ZHG?%s6FAlf_CG70bR({%S|dO)^05I@=oMM^y`jl;B>3e|XU#_{5dU+2-w zk8pAKBE}0hUU`fE=YRbr;_U^)rbHV7S7HMk+&|#mTQ?buD=uHUz^EE9EC-Zg8K|YK zm3P1M2EXx3|1bAnzr|=_akX;i)-CSr-Qm)Oi)gFdzIGdtNM(|~SxLcf{K~KK$G`gj z;qFJO+Tj<_rc7)C3RZ|QrL(FC^BAc^izy_Lob8fkQ8PO{A~X##2I{)TYh-dXV>YRo zO%^PsQ<{377A)&1s*3G%+x*l|{WOE(JYWCHb>8~(347OP#JWle2&LdEiyc%{YeSy> z**wes^-Z3cA2Dr@SiE-|zlcCVF&tuC#D^voiI5p@efJwY z``l-F_2oCYK5uAd%G4|4%HeF8_XS_62&GGgs!N2U3o+_`r+1jpGp3GUt)}C4ca%Un zUF4WT*k$^xkjPcjH*H9mE@gWr*Y%XHIIoTa^XhBD1K79H|EsrhT)*t!f1kafRGA5QC?XRP&*-1&iQ`v&gUi z@4v?S=I_%sEt6aOxVc~!772zJl(zAd*5HEU-Iw0tclVFD@y$0uplLn6@r1@R*+1l9 z?;iKB-(@Wh(1php1%syG-LJpJ|NPDWiLG}Ru_1=Lhx^>M4bBe1Em#{|U^c(S{ezlCbBN->IE+;I zM(|CfZWgpL1^W*M1J0hk$PazyhiU5(FTeN>dp8U>-kA^=hSC^}OB%EhgVrrgGY9$q z$$PUWOOouo?|0limb>Osdv#Us)zdwL?g3`QV2lI^h!_w8jD!f&g9wSD%xE&19`x7f zg^(F3nPf7EA|O!^VC0aXVFtipu*}l4cX#zt)m>{=u6K{M@45!ceVJ|HilTJY-r2nr(J>u?|#hT{wGQNMnh37uPwfSwTZ4X%y1No5t#G@UI8T=h>L>~;@3IqnPM^`WOm16u6ES_~Q(<#D zu9xUZx1Sk^R5u@@K0`2qFBJ!F%Cw%dkq_7?3aYw7OU5iz92`!`=L_n+ioVb2*9KpE zf|W!*7sLw{HF!tSXlAb+@RzUuDcYo_b%_}fd?2&J$d_?K#$ZDLtLZsIPe5)qY)H<| zS8lUw?suJH2hQM{GCmh3lHUmqCsCi)1W*!9ledn6QCKx#vR`pOKwwCIcEDg`gsmU2 zw1-rSCC)DCm%?&k2?)#JF?r52&pyjXKl%z+E??t~@89L!cOG!_ojE&qYg}b0B(@hJ zQ&I7$2?!0E1}6<#7bx_p2zWalOG7G3fosXwQ9&tsrGDi(0c|x%K+!ZF=b)Fv_L(7r zq2@2Y{+);oc_Anhn|6hO7Kawine&%;{-syAc;#ul%77Ix{iBv~d(>!gHmx+3- z2fX<5Pjh%MWj=qCuuv?g6QX#1K>0vvpv(()_xJeh=YE=3zxn@?_cYEyZ7t~3n#IRt z$Z?v_2h8V@KM&n}BVI{5wmfpJ+NN+ZOmDO53ZFWO8p&|hp|oD9{1cm{#m9dA*livB zddcM@CVVU_-X7z4i2l&|g-8DCm_yqdSm{<}<-H>kmAKmQKDAm=t&nv~OH(UuuM)xM zo@G`u@iXpKdo zY-|+_M_}Cqut_7a6_W&fLoTqjvB{Iqy~tB9d>mD7(gdAq;UC=&_{TMj&TuYZdK>iY z6X0r|eC}o5efK_&C4S~;fTfRw<7EIRH4papc+Pmvoa-~0z~sPDTZ=QH<14P4lpxY& z=hyqsuio(J9lPDYd{;Yu0A}jcsvEf1;mK3vV13oId?rTEp3Sv})~GVeKyyyC5>o5>G+ae&78(5S&ZJ z0I`W*qdW(8%I@-z!)8H0E2D^b16WOHG(l&G&Z(OPM~el0-9zg>rZbB1^OeMqnstXj zR(p;Ltp^=TLr

d+&E*>V(t+ycJW4ISLVpkztGf2GB{Y1&Pp2r`%>8d9K;cdKect zJgT`fpK`FbVC#I3;bzWY+-KO&kjhYIu{`-`-?P6{(Nqn~nXr3*!TmcECI^;W4=^gn z*AVh>?81eX?$>T&67RkDqd+~jhBWRfx?2d>bp~z4i@{@Qd<+8+McGqaeqw`*mxkQk zc`J%7gb;C(K-`ssqbPDVH_q_fi$94Oo?})kRHn&JR=UWeGt@t-A*3XV3ix2idgrOC zIZs}DnRnj4&KuwT9vPn6T54O7>mJq#^|Il?-UHsd^(H^{sh4=?oj;{=js=#+J4%(I zRH724_9u{%ERQgK-f=Fd001BWNkl2~alIg0atI_mPM2*zQzDaA|N+n7(rdk_{qUbjB_ZyF;A&otTI!W@*dsvA+B)Su+ z!5tCLEP9H;2)56bym?~}!BOTp1dkTF=2@fRh^x8@(!Gx|exr>ZbD47( z4q_%*7i7+W6%09Et$8~FttdvICC9fsPI<@x#s?~_Y^-psXVXKRtF_Uc`>_={4qqI{ z+LBl7<6kPJ)59zsKUR(%BXoFg+t%7!$b8ON8}cl}c*v9nBZ$s$&Xar1rY_kS7*r3m z6^sLMYeFbOEU)w-)vb3s4lS)~{Tb@cCanJH+I8xHsAu&Is zZ7vyN-&+xI9$#CuKwm4eypQpQgJ#ZTx!`b8vnw^F&d>pj(l`|2HMuFko7m38NA^S4 zoz1(X(6&0CmaC#o6q;@~{`Y&f|7v5d*U z2w_gOn2=|&H;)TZmox-Nmgj7oxxkap{{$2p)J`K9Vs`z9H=^r_k&_NA`S^5>NSS_}+SG^_db*$=a)vHP<_%>pCk%u|QDgH4B^BASp}&No zGYlo83?>S{Lq{g@5 zw;qUW8zeTqq}>$Sq+hyzN+~j9aL%8g*PT8dOGDb4p;rEC{ics0Wh`Mt2V5f5dum1- zIsKvH!Gk-@=M(TQlC`r8QJ}TZ>kqha^?5El^%5cEQ7TRpnL4hv|9*VQALR(?jJvZF zKxc>s?3kAsPI{WFE7Wc-?YSQdf7g!VTMR$= z1ZlLGV+y51>;0{5M*$>wRB(uG@V25T4bQ*)91}g`o!PtSZA~!}3W36EbOlm*LgTxu z8LR$?C8mc& z{bOlJ+lwz+rI(Ij3#%PH_<(isouWM^_l!0&hQos0-TSfqYDoT`(d4@|j)Bb14Crs5rf!zdv$2BQ@F5AO5y z)hFonGJ*=!&Zb)V)y;G4Hu?b>3G02*n_~% z+k3qA-5V5AqLsqrZMD+MIJcPSy1{=G?xmFK@O9mKlBbOJ0c_{{C_A!#E^Pwr*w4}{ zbaG_fj63hNHSDd_qW2Ex;!B)^szE8i22VNabK&Y`To#~ETzTdyg!#^L^p#-uy~BShxLHA7W--o#IBXjPIk3V|pXU z-VoLi($#XsNMQwwbiQZ^5iVgRrMI4-jJND+4#z#<(5;s7AYNgWq7j%^4R2h3i`its z(f))t-*|^{W$>a1nV>~S!{mIV35G})Q@%xLLRu^7JW$djv?{;~ID|-Ijoeu!>l?)S z&UkzgyG9JM`aDlqZCLGX9Ab133ok+!wFDB58XO)=@O8TP6U-$Fg~lXkf*`3&LDbxc zs$WfH3J^PvdWkf!=m`tfT9(Ttb<=#PXZW!+q_BR&3eG|Z5$kjz?pQ8Sn!Jm>?6uC& zhS*=mdz3OL0p~2*D}r}W6coKN{n2@RFp1CS(uH0JtXJblX-FS|%Eg;VRzZFUG09Mi zq3918Zf&77Wa7z{!L=cK@D!P5I^AbuGovUxNMtg274SNMgLO5g*l9J9-NPyy-@PH( zNC~Za)XG~^(jMbOoa|bd-(`0tdeq8!3N(HZp_fc+GL;it)EGs;Tc14L1oN!5QE917 ztQ$3sdzY(uuRN7?-O-aMwyb|`A%S!rtw(+`{BIr4fbSA(DnSV_ z?V*#wlS~LE;FV=oFM0htZ&21bm&yyw?#~F4Q;hor70}LM8W7uN(tu&*Uu-Yj*!|>dk9|PgwAkBKUQI#qFFZh zrb48_hYC&k$lLX?G^FiK?VL*$BQX^4-eW@(m6V9RZhQbyQAd>EnM{tD98GAd8dYQv zKv@sU6GYP=ZBrB@f)|2v37}UXI+2!tbmPMqVIhFH?txPwd3+*RW$0ynh8x=;f#55& z&(kLD(4r6p)-N!*MO01MGgLJ52;NpOdFQ)!9>=g(5@o5iV3Jx?2;JYdpW7yh+7P>C zMRo=~{i@qUQgUjQn0S~nb3DXfC0|;_dzC!*;M$2qgDtJ+7FJ2Tb(q3w%~Azw9lde9 zhlQuGhRo}@gY`3Z!<5-_j$SxMp=3KBBbcs3ZQC+BYB{K=Jl5JIB+>sO%f(An03$^1 zi>K9Jh_ARLA<+#Z&MP4j-kgtNd^CRXzS0Q6R(Pcn^q>eqfzlm~yNf2Mu}U%b6$`O6 z3T)#kGVm(S#)-oQPiCTSFsVWg6t1zDEJsi@&Y}Bx?BA8-He&}fgRcYPJxW;+`{)~% z$JCIvH=FmKrfH6aYU{)M)ozvN875PhEYR2nZA`37hq#ODC|WQa4$1SJI(eb-fg$eR zAIjDGQIGbaTZt4Cq6ckshA}0>!I;r-1G@;!W`SkX(6|Oi%=|_iC_c!U$yf%5vlc?W z3d=cuGlzsftgv61!2Rfetuz0nYx!K^vp!E7Hh4-Ccyk|}(XHbNhb=kX$g)rKeO9w2x$ zpp%w;L{|Np@ORA6$F6v>o37F^38WHKp#(I^`wpp)Du5G1%Y9J^dQ-CM$rO|jRMZlf z*AZHx$D%_M@s}kEr>i#x)A>GmMmI6~)+54wLE5?~h9O(G!mL zBLF5n2l>gn@z{7g4QW`Fw#6_shTyID6jC@vhmd)U(I_1-2E1=j;t4+KE}59^&hm_2 zua`b$WrW*6@3e|0{|JiBk8i~Jcn?Z)f>S6}U`&qIk*MC*x+@bOoaM5@xmZdYb*;lH zJZr)F_UK{dBzEU}A|zfPtsQMWu+}^MFvGhO2|S5S4O7eygIq|9U)9c=*AM=OyUW$S;c-Zy!4bAOVvZGGn@OINP+ktSPah6rq*p59ye) zdXQs?7h32le(Gs9qzg}5;<-N_uD{PXbz_p1fy2i+=#;=()ATr&9bYAHQetOqGia-( z9`<0@Hii>lTbfTtvrBl~Y7JWK__%lcew(V27WZtsw?=BxG2A`Pv-4(k+z6F(^ptR} zH$rEM*=$az9L_`y+NN%BG!%_tdobo)Z-b%|v=tP&z^ml7J2+ zo$(>G?~VV(U_XFL%Kbrg(V!P1cA7HuF=-X>N`NR6DR@+fK~`MXWQ0{9=s@06jJ8ME zY{KA7PLO@d>;RK%tZ$f3GMdJL3-ro9o98w;bFRmkvzo&_Vdw6G*^$Eg9(AM0b=$iu z-v7=!(yYj`EJb*{FURSzG^9Rwv}$+w_|$vvIzTx7qbJL_U4O$H?Ss;L4+YLArH3&5$bSG*2NJu{Qja700y| z&RAyyh!SF{Omyj_t9w7OekYBpoPK@UvkvWsN{h3$RY$R6r`=#hq~nRwvKLqtH?;R< zJogAC(AJ}`C*P9C+Db#}pzw8U4|l#drWy26PGfxRqa_}ODkI;xh|w8^RcPnqCMtl5 zy}d-m);Z!O33p4RKlxZMuT_Q*Hc{B(T$K>L+K_VmAs{+ck%fR3P2&_sXIN|F8Hbf; zAGxBE?xEPaMvKNb4iOEKRF||Th{g1U!DUCIju3OiaBQfWeS`&d6O+fm7NEd~8H>uW zSlnhX*rXh7a&b6jwAtg%P0Qi#5<*(%wjv?K;t%H4hGPI{P9t9Nm#+T2n8s$dI)2;NtcpW2@g~4&D|R1@JQqELyaHED4%cz(?6pI zs;6mcoQu7sdi{dRH4&$?E*acNOIj?eC;B!%~FvIAhvfUQF2)28;Yr@mgf z)g2;4RijqK-lc@mX{XxFt26MSJEmHX4%RM6+j>SMZW67>_+bQQT95j)(Hj1CqtL3Y zCvUx0h4nE}p|y?=YQj@ngLM4((JNXp6;_+nda|jFqzD1g(UZ$uK-ZeWsVKAS0p-Xt zh1NtBGY1MEp^7|a)hEk2Sy|B36{3VPD_G3tm?C!54c?>C=pY0P!8PbiBSvGJ2pxFa z(1K|}V)dDrh}Gv=K~>dY;>L~(;2c^R6oPGR;y$;MiD_HPGAidGH+WrBl!js)xWD)g zrt}zNnN6YB7jQ1FftapZP8*9L)OF254)A`-aIoa!)vJuhBktdUci)-f?GWoSyww;L zA+LD70P%)$>&e8{ha)?Bw zA#1DHbH1*ApoGa^%{UoT2ecNf^&pO_o>SF}w4qoC0qf$!twa*;8~JuBaqZTn<64}o z#W){5jfZcx7Ak17-K}g|`(Bm4k0q|GGUn1kF~^5b6epzx(x%oLuWp{LVNJ%q3oF|W zq^$w&rg41Ur(WMv&dvJ{_gKBHJ8minNF|)dE8V0sz^V;%)8cjr?i$rWWcAPXGeW{B zfmBXu(7~e{g?JCXEe96zT+!G$xlyP*&akPM1Px9g8yV_qfmVVzVX-*E^bAWsCokgs zvXsom7!ce&yubP<5avsN&IvF)_Lcb`0BTT4gBFSm&whn!X-9be&I*$I_5?1^`k>AIm^t zg^5M}T1)m8mdl!Y>2NksmOUni0q}^5I;Fu|oO3J}%VQ$H|Nk3t-bz8BL6jqe8eD9P3YG`DLKIgbg5a$l1X9N*xn%2Fkde4 z!LxCGgLB(M%5fi+#R@S~AEXQI@@~AzD<3iSPH`Gnr1Ps*0@mYdy8K(PC%oA!^K`T3h2(jdfKdoNfL)4;dU{5d)lq5 zlM0ki$53nSq1WfpDn@lufFyotmmN#^ocfU4!fA{I-)6VgN>NiXt;J}e1Al0d!8q@g zSK8_kv>yMllG^pPB!#>pU1wAwkP%ho1F4Is)-<7^4h;c|I^W~xf9)4};+3Z#wny4>{6v{_B7G8+`WjpXCq#!e^E1lI7llbI)Gl ztN-T9-247}^d!eF9GS_Xa%imxIzXmbx+O>T1T_rkVZ-I;hAfo@Z7DK?Q31Rs%MDvw z+l)t>3l#GBx(1~c@4R!JufO^ge&rwjV-6pDk#GLVJ4|Ow zBq+Q$I2Y-WO67Pb5wCrp`{eO7q)t#lQ@IAG0#=|=v1URAi?1s(CAhEvF;otM6=uu8 z(NV?b_$+tTJA_b2t{I9f%TOv%RfkNc?{RMXEKMkZ41#<>BZ8CTVH0s02KQkh1Qh~a zTqHj$l~m~(G)uH!u$&wbnph6#n+nl6^SZ`l28HF^nX`QR+uvtCw=Aogu`0-Xpg_@h z7ln;O>@FGzxE9Eyy|q@P`%}+Uj@Op^#3gLoh(tjXi5`P!LQ-rpS>yq>%1>INzGe_l zP$6bkB~|C3qgUcpluDCCy!W9iNfZ^!BYlWE3K36jjr%HMY2^ZAPAg{9Tf^O6mlj_= zUNhewZ

=8+Yh9q#d5z8ACcHs22b2x`h&3Hxs$m({up5-W5hCFAlyQ&`jm z!^eN=ll;Ul{WNAH!%OUAKb_9-AyD~>@?61h{P+JQfA~B9mOuaZU*?&ge3r`}yTY40 zxA@rK`ZR}=Isfi|{oTmDbPA^f?u_R7&%A&YN2xX#T|UG3>?UCV6L*BGB3@~%u&@;l zXxtoIIDYDvKf~6gExz!-{~q_hbBod!*qKKYUk;BGsFbHRj!Re1ke3t2BOx~ylV{)> z#{E9S(SS3TF0*m&Y5K#<42Rp~S%wOh#dN{#Td(u>o8MyZ!F}e_Ifd@iR5d|6-n(_3 z$?OiF{`^n#_N@mjuTM$!)A9bYE~=!cfTKaZkGXs-4XFkiAL4Epp+CF=@eSibldB%q zd#cQ{KeJST(m9KT=l;$i&ptIKGdb4Q@p#EQwYFxt*k^zDZO%UNELs;h7fTeCL>2xI z9`7F_{GdZTg_0wCJZtrhFl6}JwX#+ zD(VKA%wSNMV4x9bh_oAM8Eyzr*LA#>0Kubzj+7sXMs}qzy{;h?Jz8PSLrz|!)+@y? zmH4euwMli%1|NK<;MD$%?wp}zLBz|JK0#JEYX^{~KZ|_Q)qU0`+(LUFBvp5(ExsRk z;WN+kbN}!c@VQV|6|>!a-n@MuEt;pVJ;M^qQsB&$Gd%N&7x?Nozd`>@pJH6#wP)5W zdEu3h^2W!$$L&9Vn}Hc{SkEZV4WNi@wxzXLC8#XJ|MZtx$=ecn8 zDwm)880F@(47Q%dWCOsH>%ekWapvliTzU2>ZocsyzWa?=xqs(AI@bho?C#y=JFkC( zpZr_@gy%nbje}dS5*BGQR6eRniQs8c3hZx~A$2~=#N~P9O8R;Zp`o8CE{sN$Rz(40 zpP`!thmFNHHH+zz;D(GxTWoA?F`YPq%ULXHeB)ToD<%iK?A*Pg~) zq{8~QE4o!HSR9j_YwzfAUFi&J%N{sQV7mLuv`($TT@{=}V;j}<HxBucBjLJSA|Cvv6@uN@k!lzzgcRJyv&wPTPdi!18e&c%_ z?j16^yv?GrY@OfY*Z-^koPTlaH#xj{B-lP4EozA%pRlUcXOOH4J(KmeY!V z_dCDOop0S_KB>q@eJ)?S%CG(xe;->pDz)H~pZ)}QUVVq_U-};PWR5Z+ih^x`vyN1VU%G*_N|h2i$Il;fw!2AgWw~8#!5S zm``Usd2~RvoKn@Xv#0{zz4;EG(w>jL{374}_ur$cV%|iM*vmePnxvxN(m0a71Onc zlBI9ZBB_Q0!~g&w07*naRA>y&HU#Gw_A~0{i2Z{*ESot+o-ynxw$EcAX!cw1g``MTa=sd^hX>|KYf{<-Mid)^9F@vWXdo(++(>oU*nmjY)TA_l+H8tXdP(`ukLTkhe2m5ml4wu}z z^MGD|5KAZ<8!<8`V8Jdd%fmh1yZ$PdF1>*6Wz=?nn6}{bhtC54a3`yx*XWaEn5%Ki zLk5Load?+^-hP9ESm@Q@Wh3yvOjlruk|Dzo;>E06sr{`8xNq8iyYQ!cGoMYf`qP=6p7c%i_jkou_$)$ z?NR7H)xr}R$aKl(2Ad4bkYE?|DudOY<=pX=Fa8NHe(qz8`WwueB~?;x@*zTF z%EzrM$8dggi_PSzr!iW{3pjJ>GTT?4r74C~K10! z=N47HzWqQP&<$}b7DWiHx3m@}#~CLh6947H zs&eW0tBq$@Ic!PkX`hlUN=fQ*9}RVIu>#F`hZB$2U~|O`%fdSZ%}{z=$TqkrL#~wD zJW+15X@-=#z)MV$+4O3>qYjQLSZ2Oq;%fHof}MKGo$8RCW=3s5m4-k-2gpdtptgS% zE2Gxc!6&>|N$M0pd+B9mIM?~O-7#9BljxQzQK?7P@fRGgit4CblKkZLo>s|lOWL}E z2#dPnaC$^z8;sTz!;IbLfNHF$FZ8I+7Brg~y$hQZXGaugMpUKZ$!pKk>knAW7u1U- zxPWyHwQBhMum3XVp1FV&8l!c@rV(;&DDs@DiDEdlbsQZ|!6|f5U<09Xy!hfrID7sa z)_az=A!tM6K*T_5Q{o$s5yRGK#JFFuF(}AYpqE82vKWrozW5Zy@B)jFVGRV`U`%Rj z5(FbciBK2=I!E`;pa)Oz{L4Rs>5mYTA;A!=P}g&mhF-70q#}ag<8=>&4)=b)@pyWq zq)cdt+1%(&wb{Uc1!@ls3g^LzLaUtMYL1R->RL0IS}t6;!kwFMAX+EGDA-1r9?qE^ z?s4dc&CM~vRRk|wdE#0A@QZ)JVhQtE#jqSxqA7xowa!YfH7#4qey5Cc zXBv`6)p|~kI*s<%U42yRNd;Ei&tw!Nh09)G5iFC&GPO&zS8SO+=dvLql}A9_L6PMg zD#Jt?4y6Xy9P^N)&{s$vl%jE#WnD2h8=`buh}1VP$5o*pQWNVC zgf)-zm~$D9|GULG+ha)T9dsJTo;IL1@3amH9RIxd!}k9{34`&7jqNSww!!-)GdJbQ zk3Y#T{Nm^7ZH^gjk8ng1{MKlL+5U`w^;^HqOj&FQ7?a^@$Ah~MxbXBP0)eNlUFB1M z`_oM4M>yvxvK)h;eV|$_D9aKX0$E|`4M!|#sGTEZAX=DCr%Y#4!cc?Jn4*ZXbwNcj z^#C}qwjnG7XYwJgsVPl{UCb#4J+g9xqJJLr81HhF(I`CPL3tgSA0eQpki_q*e@N|p1I1--FIo~B@h!z&Uu=-W%u4LdH-Er`}SA(sh{2^ zD>PM=k>^EM)ncvvvG=%-wayI&kE{0By?dRfFO|G|>jpPozs~e%#&9@B>k^YyXam#b zlC9ANhJ*9`(U-o6=RDP7!gis^okClcdaSR+vE%u#`?B^BHEdAkQ<_U;YN4$#OQ%ZBXe2pZ(d-GOcDDOb*!|Z&Bt2dRf!xGr-Yo)y!GJK$&|XkRlNDtw{k9RZ@@aDl&Lci1 zT3zaS_NejL8d8FyS~f`vFR9AJu3d-&?G!?tNZE=)45ef&tz++g#h{n-V7Fp0KEwXK zyPz#%92$ddG8Qw(;m$6`yvBEn0U!PNFOZF&=_oHo8|+CLxF5%v28+Vtnitx+`w^^(mMvSKDmt=V!uTKyPa=!k@U*-Jx zJXfB63ZHv6FK&|cbG&$#iy8eg=h73GCx12e*#p38L1;V0QaCEo>c1|fJSuo&L5?S}j632)N*Fb2n%Uv>6ad7`F>gf@- zTH>^#H!R4@9+Uf1=0`KUhuV93DkBQQ`4o)2|EBqv8d6eK69^hSk)-VcVgt&8@`8j0 zLsXUbB9uB~x}5Xgjr;WaXXur}+3hW+`Vg%p?-+*6m>s}8w2*`-t&uUvhOgE#L|P(*RwsEddXky<4o zRyIW)h6sm@vK~+9z}>}!rMFCcO*KEjD9z*Lvk|7gj?bsV)5o<7B$ z_eq|P5Lp6oz4Xb0vC`jN8E5AlRa2As0s-l65_v|IaD7+SYZm4`9*HM_o1VgXLSvX5x zCiNKMcU0h0b(cEy<1;xS^9rfp4;AyIW*WnfBz z6tOKzC1fF%dRk?v77IiIXD^ueC{YG4B^2a!AxF(I!b?M|DRc(cS`Y6*(oU$*>4IR}kC>wh?-4JyHlL4PF|8#8N_! zk8NL7Ky)Cu7CViZ5{+QIA(tMz_ht;Yb97m-)f;07c)MUwYO1D=yvC+sGFedQL$(6k zy8b78x!UE^pZg_>jjLp8K+qYDwOAj}DkCOR){_dd0unn~OY~4Yv1PQVEcRAvY?S#5 z4T5DcJz($N>nx6LqDy#hvgDmN-{SUr5135@)@Kx>0uf8q%o&dReC(xj&x+)Hm;xq0ITOFzf%&v8EEo$GI5gU4jC{kE5=XBo|R6rJ!*fFxEDtb-sZ zXBaBY`C?26o$4Tk#F~ys0Ew70iqO@sI^p^$o-5G!I+h5@4{_!s|==BgFQ#s;c&>JGo z<0_BNG*w+Q+8VQO?z1T8cpBW$^W0Bfqr#$eL1B7aIe!J3kXn4iwNN28D=bvbyoOBo zxqt7Ft!D>JCwrhW>iL|V_ugPKImDYScJ95$)u&!$^UN6n7V8$wclWsc?rWUiDmc1- zll$-8;Lff0n9e2?y#Y_0JI_k-s8=0zs+J+BQgRnh>H!LI|+-wnaQSyN6TAm zv*=nIL}KMhynxXwG%BOihQ)HpgWC%>w+0ksY>dv~ssl3P7>x%U98GB|N4;?D+9Qn4 z>6^ga8{g!MvjaZ&vwxrAxod=GfYK40Lu&$V&9I!zIHdG9@u3SEjLET0YzI+j4SoTt zW^(s+-hS)b^i0i@=eIfB+vWQ8o7}&1#IjNZ(dazG1&7Ww3P-Oj8TT*oKmFG4BiSYH zy?e+|kGPQc*}$Nji%K_ZfL#nd+wameNydc4^CZ@zx3s1c3%@$eHc4~J?k=h9baky( zVX6dBETS$2@steIkXtzCaFf0e`-rAv_)#O__<<=&D?;rgG zUV7yfzWT*KW3qS1-~Hvk!^M}bFubtAa#@ih9NxLlu;^j390y!^<{3s?Th#me6j{mb z*WTgo>+kXtPrMQ$FYxjwex8d@zC@mtSZ{H`kx9nN zvs?E_yZ^;hPl(D@S_#SrXqN2VeT&z=`zP%0yvB3SoM)6}?B71*=FK}?f9)o>@9eW! zI&Hu~!{3uWP(gU_IgjnP@U?=$8XFOu=SZFw{AIUJ;Z*TSqB|-28v!y;-nr*L9xv z&2Fu=yVKqlw?PlEhe?wH)q!d#S&BMR5^bxEtWxBZ9amXZN~Q9Yhg9V$d5g=bxNIk} zBr7U4R$@_2BvGOyQtU~HASn_ccmZ7Cw&$L+&u&&T=Nx&MbM3wF#l2)wc}W4Q3OK+y z`|PvVTx*Rv#y|e?{{!3*P{NI7j@OZ|9bKgkE$7WPy0EA=Sy))5lW?}ml6Y(gd*^*< zg#&NmpTY(gcYSPTqCI8`8#)H8+g+RA6M=xwZl6iCg#fx!9KC#t5C8s$_CNpMKiC7uE2Kz5slLY)JZ(% znZNifyZhUmfBU18-hcil@UAB4NJpTyKv0Ys^1AnPbK&BB+_yWR zdgufPM+=Ux{Vk1eQ=$|c?R?6uc1Byz84Mj=Q{%no-QV&a-u}e9_{%@~E1v)IO{NDO z#45p@CXjt%#AB4jDTnrs>n|N6roiYC zaRTF^!#8tcNI}E<4(k-N#T=t5tTwpP6XPwOedfbF|J>hj@!=~|qp_y}V;}s6BzQ89w^2c0x@ozb~TT=R)aOMmzeeDWg{Nh)+ zert{oFqjN`4IQeo;=zj#a_ZCtKKO^9;LDeeIj;Ay+A?s8{c=nh9NAJdW$1D9LEZ?A z8`ZsJx3tyV{B6>B-1a;DYT zlb9IOX3Dgk(V2iahnA#IY49lNi1Q^QWjR|+xH#CMDAM{nWiV|(2iPr2e7T(@6GO|q zt9jw@8gUpnJ=|h|hDDd{gR@gY41Iut1nz)e)W(^Yj9X%7r6A0;dhZcew0( zG$Ry6)Ff%#uxjFzTC+76aNI1p{z}cTDk!u?A`FTFAueg#CaXRLl(y7uXUYK+afsJ+8TW%eIQD7iMoGVs1@)QM?d!hoX6s%! zxi5M9fZPX{JCEFC5mEFmcD+oULj#)qVhi5|8q=|8mMm3+F%~>1t?<4}HoVRf>W;z~ z3T=r9or**)9QzKs4)GlqcTQm&jkF#nG$y$Yu>HE_O+{4RbCZ^7%zsDeq&^l^ z%pr~lxudF=dy>^*#%xM=ZROIv$_4|w14m1jT8$Nuyq+9j*eByWilKUTfn8ToGzIs5YYrgb{pFm9t z8VR(E8r=wks^o>sFJsD*svPr~k9?ZLOV==SLHX2f^u$&3&T2~pf={Jwo?r zx1MWgyFXBXWH4}`Bb^AdMp(9*h{MOgXf$DKYlrc8!q(O{!3XMQ z0SF; z%Xg2_Hy zltCMl4GaZWDjMBlw<_Ycg+ikO#JWR#Aap)q#+{;+65|!E>!_tknYJfU;-X2S#|o5H zXaff`OB zX=>{^sBh8gj>%rhiE}l(J0(WdDCWetz^F7$*pCIreBVkY$y~hn0B?N5TNw{ea_PAv zUc9vAmCFq`u6HQC#n4w66VXM|-*9C?amMkJ|NQTB=7G~_4Mkycg7E4x|23JB!n&O7 zPrCQ^(I%znDd`I9J6aSvm)RzFmo=JkF`%nG#|KkhB+zyPPM;Yw8CC4;YG(86__&}b zDr%V{7@7u}rei*{42LDUFcc`X6~LqLwDYSR9be^@#gd{Z8I4BF=QE1Ja{j_O>TKPx zH?b_IH)&D$uH(upH`v+U=4f`z&4UBxiw5h)Xq%{AqiVo-Ys_@ITXdc;UpbVnlPzs1^dJvLdr!DtBf9Wh?Lr}ZMQgX7tF6Vgb3YIv%R~;crsyFb+{t1 zT+T32upv^G1(ueF9(sgF9(kO$RlI!p7GM6-WiDS@a_vfBdI(jyn{ef*z~o9yE0i+0 zqNFIRyz_ni`~Ni>NCoR0gTVl!lPOoPG!A{oGk^+!phSbDF0X_{#h{0%v}I>dqG~uk zn$w0FbOom?#zVzm5b<5PQ_JA0lF zedzQ2?X$NC_AD=7tx=ufR5|3V9Wn?Oyvh?yT^g5*j^t^sHkb1M#gTDPdg+Y*yRUlH ztA2BxwdK*#RS?OWnk0oQ=LKUOg)?l~3QaO7b47&_L(yusR6%H#2x%z7YBK}&E&u=^ z07*naR4^V+7ejO@IODj{%$TkS#CU~qmag#xpF}IR^#EHMS{=FBCeah$ z9@9(%=O_CNl|}okxUW?jOa2DuyJkY%@!gF{rxmVzTM*^824A*$B<3vD0*Z)Nf=38s z(V5QBE&|Ru3Zucu$^=mxjg1bK?V|;S?vkQbh+!oqr&RiDI$r>)Kvln{pcFbN6v;_6 z_<(Umx_^3G<1Ro{w5>q)O$y>Ev?ch!s+lG|;=5VuWGvZxBnacGq8bc1TpV-j#v#qJ zVKIl%wqZCa*xD(ms$F)rCJd^I;h-Y4HEpYS`swQ&9km?Y47~i}F$Xt1U2So8jQE%Z zXJmEnfkI{O^RiwN;|ObCm(3B9L1U=S)!)bac$&GwMStJq$<(|6TymNtSo1$F(Sg%2Jnni4G=-Ydg!b zIRkrvJi#X`5)CSG zmKSx+d@)Cxllb5hCVr3OH5y0(rD)nV2OdY=2zBd;l_o?(A}*K7iP1m}3qjJ>@R%x3fC#@6ghMOHw4W4Y zk>vH$8o>Ytg^wYLPZ&ifkq}{047o5qK`}jGig3_1)N+fNh6lG#Q??4*g%pH3kF|zV zvW=@Mf)}ngM|c&v(H-J+^i8!GWu4LY z4Zr?(a<-&ZZx$#Z>AkE@?xdm>0Z?MlAvL9xRv;ZZ-SYT;v&!oKQPx;11Y+mYzyhFR zBz8VM3px?hgLqQj3#Lf2gIbdPM=#~5B#l*S<5Dp8o!owE=Avh1OKsV9EC468jUEe9Kfz z)D~wfpmCBg_&~bfG#ahawBy($aT8vj87ZWVIc8(E6ckd~(N9n)5Y2jIGtbnny2?4# z7ll&}qmswH*aEE#3*T{cv*r14%=Vr_mpdr8jVniNZCRqPnI7F>I4m(%v#6IT;AqW! zF=x40qP1qRn6s?w>{9BHC@hyXWnrlbi?xQuvc@@sF{#`LKJo2N?C-O)b%HaeAL8J+ z;Wz%nUvT+)O<GhC2v>8_Po))p2EUh(>W{xPy)4^^Q+f03Xuo z=D=pseGrpq&F1w>YtQ=c=gF(|t^RY#<}HvKajVzJN^a5Uq@=dqJS2}$uP2=H2V6tv zDrqs8P7_pQs~8cLaAkHA<0@hVA2hWntSGdt(h4a}$`Ep&Q+3FDl_=(R!F$|Feb*$2t5SwG-WB=7PXrz|6-utspP;HVW2uFaS& zg=h-4wkygq;X&ikgfo+Ex@L-Rmn`QCoVEBa5KX#~%27$zdG>dAn9XNc>nMwY*=&xr zin2(}v5_8NjKlkwiYsk7d*3PmONN!Jp6xBvgf8?CO@ z=1*dNUr~A$-<5#s@oyiftY%bA&}h2DYqS!mC35NT1|o`!J0}=wi(Uqt(JVrX=@ci2 zBeY7+t%sqeCGzs(2(01EXqTe4gw7|C?HpJ{sf0618g;nyJno!;+7$O*2jJ`lwc0%7 zuGe7mJvSAm?scr2T=~DX+DIh&Fn{;a-+R5^t3S;8-dLSaU-gJ&HLE;!n_s_bsYSJ> z=H^01ivleat{|8Z({{mJ5`!Z2RBTbWUgmWpIByE;Y)+ruehy>^us}#+F;=}!Gg7TI z*4oTXT!Z-Qi+Qgb5Z13qdwv(dNZOPNl|&+(F0oa~R4Qimj2FH($JmzL{SlLiXE=e|NYb_%EEJS{g?tTq7ML*U;Alw$5Q>L1^uW7^zk<@5O z;>^AMMh-$Tb@G)6S{wH5faPeP`RqDVTH?TRxjv#h=y+`J3}t1IMT@bZT2E1HPP-9q z%kkCeb*{I^%$4WT>^e)|@^Ez)t2C+!>2qsHrEpx~z#5f>rt=wy>OcBz=bpam)taVn zq;*?EBI~;1&SO0xb?@sPGd5^U&t8$uFSmV`|3}BYc(NPGOj2e`bfvYXfUM491yu?? zNW7w1E2Xdk7@O3*L>Lc-EEY#dcG6W@Fs83E)88~Xv)7v+>Yf{okb>!aK4&{@f5VOB zH5*8y#1%%mDVn>^Nbj{%=RI@d^@7einX)Qtl~N3GC^Nx{W8Ti`I^p1zn#I&HniL#X zk-;Fcw_P$S9i@v5CPVfo70czEwyi-4F>0#8m})div<+iGgkd$n+5tfxHYPA#gk<|>*@!@^lJT~6i$br|o`Rvi z?b+zd(ao%7bM5Z7p0E1O#zVczV()RMYOPaM!RCXuo)RJl`-o0eVE=Z#eqR2aWXZ0w zrHM%+q#}%3*d2@*)yEun9SwnKg{$o`?iM^a*=KKDVVVZ#3^oWRM0Ty?!f+o^aHBn< zR*_ehM_6w;Gu~rZXmm`aYD|@4DsAt2qIY)jQ`FEZ4=D7?`KuClU0vKWBV8@&`seFz z|HkWbX|3};x3Y|p)gQZ8Y`p7n_p{@+XAr>q)SOEYNFI>sHxF28$*%MVHcrAQg%1IR zMJduml~!4>J@g4_f-8ETEBgC+y|J$c!|(XKlGffBjqkb@_OH#o%lp@CAWe9WCdNLS zNd$33@WBIS{r%jXjvEiSQYzyn3Z*StWvOHFMDd^ms}w^K3gy@;w>a|9`i}abV|Hss zG@fc~xG^?tO&nFJFs1{2jJ1ZcEGPO2sXOM=BMy&VCPYIBmPIXe zon_f*mP?`aCK0AZu~%-hXU0rSMG*|T6O7VnQbR}dt0*R{&r@RZr_w41t@WW;KLoea zaW=B09F(=vx7|?+g|!xmvUc1gWxXMbUYl&=Vy($pN~RIzpZ9-HBuT85!vS@@1i%_g z=R1rxtJn565iz7V+MBAy++DFbGeJUnkc`1uoht-M6F~&#G4j&!LAsH4PctqJ+A357 zHfrqBb9OwU+%njiaAkQ&N8oZeq>G-5lYK@5M_jh3nBascz308koW0>^Zy{DN2iV3LIFcuvSp2 zMkIhb!djg%L!oN}5=$2IlITH#B6bRbLPf(sN=DjJS<9BGsC2fz{2@_>#3~j9UTNoq!>c^JeS+=Lh!{I; z6B!j2Uw7(~PSa4;bIaO^j9+apyP#Q~)MR`NMyL-ZIQ%(6H?>DSS zk`zqAYz?7ouHVKbxo4TZT4Qyuj4VGZMz0tJ>-S&#Lfz}Q^Bz$-D8_Ul=!ZOdyuJTk zdfs{;s=Vns10ke5Gi!$|RR`9v#54Cxnvk;FUMm-6k*HCUJ(tAfG9Ee~Fj;Tcrfh2k zN%dzKV%=xQOf3U445eQBH-1ro8=pp@W!pc<4kHMFfD!6gMFOtM2U z1qFuEI0|hklx3i*G^G+%a%+@?5hwm-_8wP}G=OmXAsOKBC%(d6tcO<~MIvkQjoUV$ zuOCEjdmnnNRaQYD1@z5QbsZ$qHHxbe--l$m8ztTBTAP)v^SYr(G9FYhb!T(aK_EL9 zsPrCMb6qXDzML`-b)p3M9lh_hRUIy}c+l8~5nF*828q4Xfa` z`uVGe17iMpFC3k!gH5~@)(nHY9IK#||GhGROdG(u!Li=G_vU!Z!^@S&VV18y}&nTrw{dg>epN4514c<4{>rybt(2$2@tut*f@4 z?eL9`*Hs{mS&vk0+z@?w->3RL4x;GwHeymo*Fc^WQIf|@B{w;8nWhzx0dPa|fZB2+ zycRkMv@y^TXyX9ib@!4HPzHrY?z7;?P|lkiI0_2!NZoW{*{Vy{5$7g2tLfpmM;_DN|gP zv1EvA-H?cR%@u1-rL6zRs;q5em&O_kgDMQsY65{SB#{}3fzAhRsfJl>SkeJW8^9Wq z_`sqFD3&5znjg^#JUrQFG^o;pTc|YAgJxF`aHXY=OJ+38eaF@Im=@u5xt&}BqTF`x z^>}kH;4FFg;WkWPB=KhRq>;#7*6=RNe)kr@I%uwf)!kmVQtRKqNAsGmKl7`z;M@Q9 zTJXDvC6G05H9;7#8QAZ%<`I(C113?}qJmBWFCQIIOHD(K8481;;q++2pfZ%h0#jO) zP9*;rHSIDoo3lfpldt4_X#@s20-!aCXn_W;2v|? zC{#CJh3U!BS@Btj80&Lv(nwH9?1O@^wwDk*OSITz#ud_TrNYV$qCv9Y$%V--uQW53&74^XbnOg0xN4V?v6;9ocb@QV*W|X%UDoHN`|`do z$)&%8@3!c#4sy3!gKu8v+h41dUJ20jfqR9GZ~UIz1D@zJy!ACvDFf7?VlTLouH$Mm z)xCD@dTAv8J~nxW)m_8Fchm~JGYltVw)QNeQD9Iu6t>0|N8kdYBLh>SRY_@fAnr3g z5U#)6a(EE&4M;Reuu|m))y6qPp88U0%E`wh%zm%qH5*8^)=4EjXEJTu5}iSt^k4{S z3c|-okUVp)A)}$I8#=~_@(!cYEKPqilN(h^CBkv)eilR&UI}7)`(A*El8B88Bbv%6 zLQvWERbz|-Ngg(W0?DqYA&(Jw1zI7=00;$2T$zl~~0% zv6!HU(G!)&YmX-)m{js8K`ReIC693F@zJc>zp`yfC8~)@b}%(=be_{sYht1zsEwu( z(1Wt6gv)^A>(EHy`A$@O~1 zJhth<(26E_>gW-zm;^&ycwF{F($*pY94UkEblxo5hNBR9uI^}$B9HH#Wp7a8mVpLg zsXT&aXFjH^#>D0tm)iqs<9Q`^L?1cpCP`BvXe8*>1nrt(rW1ib=6p`lSfoY~x-MmH zN+Ti3LR#liQwort=a}IDrPFXgSroKwOX&)HOcIh^SfVXBV~L$$Fc@u6q#689T7m?u zHW=m5DqVvR`=N1bt$h~x}3y*_pMWEB_?!N$}j7m+m5#wM1OFjf^4 zr&9?;$tG~gvNPvu2~igm(IgyJ%Vrjk-Yp_@d5WhGmp$Vry=H?Nqf#e4*--~1=wt+^ zHOakE5YZS+veNC#O|@>!^g%f)azO3ZE>8^sQOk-Ssp;V-$v@q^IC-)Aj93Ir?{S`K zFea^?gq(aojkZgBF^1G&NIjDqv2CIk~f>j)~H8<-S$6bS{6xa*p7#0H>0=4gu z5LTsQ5P=vmJ^r|Hhgjn1+{&eooYy&*I2CxO-CWg{b0YE&{^R|JtZO> zcMDtqRZSS%3e)B0UWh3JmZUAJ^SK~tjr;6bNacOX?$U;jq^}9jH0#C9uSt5l8mApd zy5`y%j4O#Mxiw%@b0$QPkk-C*Wy%(FV@?^Bs}-SiE>CYoyzelsz>80_fo-7Bh8P9s z66aT2OKclTW0T`Sj7h(Dm3sEiRFY<}Dw!&V7zipL*0EH98_OxRZKx)OGiNkP-J&dO zMkCFzQXnmD*Pwu|O)`^2hjE6ktvTpwj42pRU@)ApzrV#RmjgGh-6X1tDByiZ>5>g& zjDo~~wPvM#@b!+@Y#@yybZwiXN-AA-k(v}fb4zocg(CZ@=jO&rhbVXSvcDKn#dI@@ z!dL|{u0&t~j3k8{Q8{y6VTipTgQR#WS#&~lehB)EF)LAJTLWc0{oG#~1I(BcLQq1N zHvo%HUP3v;OOBoE>7;~d=7&P(am)M<^mFTijv*luJ@-zpgVnkLkk+Yha;zJ_a@#0m zRDkZ+_4Y&7@qHDLjkaqF8tHS!%$881Q2AUsEvx4*f1uTybrR9efHlli$3a~)%jNgb z7HruHhsIb#E0LMh9H}L(gmt!MRB9yV57vMF7$P`BFq)b7Ty5v5>2)62JBO-~ z_cnYwzrbpP=!ow^;zTL~Dj=ajo1}auibSE(HVK}KN#`5$)@L=*k~h?}(fTf+MX)N( z*((dQ5re~M3qDfXD#0)Ybg8g9dD<6cYW_%A!xz#Eh9XHSQ73joR0>r(Y6I7gryRCZ z#wQ9+-#1{lxyfx@}eFx8-<5WUB!lm|5R0;MARCkx*3u19(PtH=EH zN1o&GhM=NF1&xTIZ6Z}Ehy;qlqD_K2zTRxpYcr5adf2SB7`rB+kH=%GvSO(_l+%R9 zuO3p}V^bLi>UoEP!sKb>WSy&0FeQm7Km-+6B{$?uMx{a>@)XOe>z{63rIKxJ3J);{ zub3lC$|xM`Kofs={o8CG-?IDD@Xwog_7jLzUs)60^+NH`a3%wN?|3*j7a{R=uA~&-CPm` zG3nfO)>2g=J>)?tn&=bUVl~s)vWOk7aO?~xY}=BdSGWK=D#R#utCAubj+zC>Avq>s zOwv5aXSXUSRGJNMkYu8$J0xFcnzFmbN>l zi;=1*DY6WnL2$Y^rcU>c(&^z>8;%40u{q3Obb{K#8I!K@>3Tze@@!q2bk*GQ_ zg6Px?5+8_?V1v>aR2QhNu!tQEZStvd5JE>~9omEO3a2#fvVquQ3x^erv}r>`MRZ{( z2bSYz&Rlo6QAtob`IXhlk)Rh{Npt=&QI}%AfvqA|nmTl}O4!;NGTsghs$))`)UfQq7Mf;RV^oPzin^Y2<=S)D%JS}S|2~fEDWCf5YqZBp3=Ba)x614433CsT9#bXM`wS@@2{mC@q2mbdvVLcuC?LM= zuh!Si4+TW6R-a{cY{bz%C>U>2mTnRuJ`m6@NgpbmC|pKs8tqX^u#((Ak%a46XA{0@ z6;14@rACZr;3~F<1>>k08$%HlAx69etX7;*4r?7Mbj-!$W6IT4Kf_A8?jfd4P8m(m zk=i8XecCDIvE`wiQ&c01sXYVH=r-b)fzxh?8)#H5v|V5!p6D0Y_9iE`b{Gy_Qmhw+ z#7IzzkadQ21RD~c)954*7(-aCyXvot)&!OB-F~wcAy(j{M_VY$g7Jg>+E~92G*I&Fw zXn;22iW032ONA3n; z4VPbjjvEKh@(+LJds!?$#8*CdNHNF_HyRyu>JF|=GR>B<2} znk_ckQa3e03DvM7#gZHqAl1jVErvNIea#uD2W>xEJoLKLEC+5lBm z;zPi<9h%fZjXL0}G)dAl9nLtq)}u2}kTR&$Fu1d`-g8y^UIRdMK4E(fY-#XHX#El) zk*c*yWc<#7Z#zm14vloV(WQkZMBK3CXf|UWj%js6X#}^mix$OTIO5>i^)x&&C}@3$ z)B$HT5(3sFy;q|(;?u?#qa+bxt&(_lwqo%i;B%32>G*&qbUb?EEL+MF>Of@;ZR4?` zI9XPx(GGaU^>#`VJXhn4<3-2bXhMm`X_G65#KZ^+oY7d5y2ojgNu>7MCe1P}2&3~z zsQ>}x6k5-*L(OP=z>odhk8|PekD?|HXDz{dv`MA9w8F3b>wm|`{^Tz?G1#G1o~J(W z6ek`yLstlmv}h$1+M)uSfBOT(2!&Yw&A<3JeEiQpo>cOiIo^BR(9!9Z!Cu7={?vE# z&hPwY7RL+NFZkd8)xW2$Yb*|}44wB`axh>u#F#2Ak5K!TCU)F+b{B1Laq+?ym7B9f zW$&~Sqv8Gw53s#`igL7%D#qw?$Y5CE=f_;T`V}s}@GLj4UT47@YEb|HAOJ~3K~z4i z2|l?$)XSPLe&K1}^2C$8`#YZC>gA7e+$l__kr*j#!DuvKu}DJgsU3Uo2piK>cw(Bt3L5O%2 z>0G2PJl;mit%~7f50qkge2i~>k_&4*#waS|SjvKBY>*195yWdM3MPzb7d|(egmP;{ za4mJwapuBV7EQcK;s7%GtV!0@1g>a;4>Ze$E4OaZ)D82)W2VPT zwnmdAmnd*Jn-P^~IrhB!$#-+#eP@uSV|jSY$*moZ4-ScE9G6~tiKo8n-JCpgnnDZ* z$H#o(xo7#Sk9~sr`T;{XNW}P%Z8?;t!zT+CAvNlhL3F~tXX1HjafH7XdDG5W#*-4g zj107)Z98a%t-=z^EmVwL3p3a%=|u6u^g5MILl-(%M`Sk#rFzVB&A;qvNIjLQA1h50 zJP@K!qpU6xe8=-bz9m|~Dc<{m@8jizD}3U^ALF~; z`)!PLp2Lp!p&a2{L3`sCJ16ev{Kdz)^z7g8 z*-w3pu4xc46vlCI{RW@?>?e8qyMKgdKYxSI9DSAcs7)iy!7@Ld0f|pqmF3qBH?Q45 z+GAP0aP8fWuEp9&YdwA-jL+}#!$151_RgH-+V$&PyK;@#1%?;~qY+0(GoJp`(=4yF zsD;OxOU^%ZfgkzFf57!yQ-1G1 z{2rh9@JA@B0#BeA7QE-XpW>Uo^+^U>Lrh`V-QPuN&0@J^G#PVrH0Oi=#~<*aKln51 zqb1XJfj0$jd;6Ps;IW4=&hh1EzRYJo{xmi^+NMh-v_zCuh>AS^rib|_zx>ZQcm5)O z^oM`Kul}1~;o#s9-6c<-7!uT=%M?hvF413l0g`?=LTjCr$JGK8g$EyhfS>!Xet`>* zoTrU#Mvv2!Rt!QNB6Z!cIG)qYYbL`9S{XzXzxTmE;D7sfzrs)a)KBnJzxWfWs%SeF z(-~W%F@N*9r+NO;*HAAE`Q{&f54-z&h!1F2@a_J4`QGPWb#EWu8QUO37fY>AOJ z`0QSrp^goW5|zg^eKtJQI;FvqxtL0U4qX;^PM=4*fDnl)@V@W=Zr<^pZ({L^3hr<}WZh7diawnUwJ43EA2 z4g9nJ=9l=5U-?Zw{D1u=wk+@qpR^%J*k;llO>1FwWU;);qYqD*&aSexHDpw2%E5r~ z?g>tueTef9zLjEp7Ck(HxB*@nL@6d`_84rRV0vSV(Qu2ctr4I6=$|v6HIOmhYgb;O z8e87-#N&MNQ(q%41?53vpsqu1f@ZA$>m+5b*+43=G7`Jjp$ehX9ZOsD#wVZPy+82- zjL&WpjIbqpyxF`3BbsqJrVGMy-tfpf-^6eK>tE;AS6*RvFhrJ-X1M^R(Z)hy=$z+0 z|H*go=BM6)9}0_ZfmW9L?|YE*{vuIphT>RUe+!q6Uc!s#n}6gfhC5q`z>^Q`gN4uk z_D89YTAZ<{64CQxpzyf${!;pZ@uuq;dtn_3wWRDd6M-r};1c+y5H3yOodh&j|Zi=@BXv=r~k!2;>3d|XjIF0zyEs(Ch|Z1_x}b3dN?57q z2nlma(d_@ojJ7{>L8Rus%c=D)A4aO7MnKP=PBn`@4Gy$IM{va4_Qj zH(ub)?|1`0@c!?^OG8&LlD);qQd9GmZ+aUumb~@JC)hu;M;AIe*U_{ys$#^$k6q-w z-}4=O^22{kY&>m{)JwJokuGJ2J^MmHh0K3Y3R4s`A#%By(H+3!r_M1RS&Z?hWs(A< zQS3^EDio@{MHeDNJD_fxgvX&)(tq@$q%qULq{p-qE*~RV6j^};oD~XJA}BiP2r9C7 zdXMk>?(anfp(;zRK6jO0|5v}xSN`Tp6ryp1f)~E@HGcLV|2$j!`&>MEfp@*_UF@G9 zv1nUVFob!{uluIAyuKoFm$R)0}_XgS_wO zew+{e>VM?w=PxmIC7~4xXR*rADX>a$`qW9f&?I9vrx4#|-x|dt)AX?0$An z>@k=WbW&5614?aq&-Z@^gSOz4AO1M=n@8-QJHeCh{k!ZveuiaLQ@8?DjrVgJ)v|qh zhoAX{pXI6V_%>RplRbipC^~}oh(POWFa-*Oh~ADvyYEPlqL2``!Rwxi5(G=lYlW6 zk*stiin{B-fnOZKE1pO8Pjg~8fG8BLM)^cTa>g(iCW=o-q>F)~DpQsj1?7`RlFDok z5y50WV-DlQ5LbR$k!-VJ%Ot{K6`cv3Jbjv7J;YC2YHB|A2Y-dS(eci6Z^1S~z%zaN zC4Tk4``G3yRE|93C&J)CEF`$y_PoAmhC^}t=ipMuWRL6 zNfy^uHYrh*M34YU5FiK=BnTps1VMlRh{>_Lr^D;l@4b8PN&CmSuV+YFsQuUQo$BhD z>F(F}-goZr{K7Y!d-)8v-t`tX%@`{igb~Ep8sNrAkDRsRE4=jemw4N|@5ZAEGNZ8y zf+yyY+kW<4tmPxlojA@7x8BIzA9yE~uP9|sXadS8jL_`q&vM}EE4k^W!;I|&jKnn! zF?e#JzyU$fmtC~dNF$Pu&Ya@iKXxxcHk>?j8b1km8IdMqb3EbleV1`~*A6Hf41g@FcMVw49A`Rvm0>OqPBS)+8IK}iz*_O(!AW5#6P|>`$ z%$Gj?X>Pvv4(R0gC@@8it!rfPXz!RvXatmnA=d(%2`CJ8OjGYBM7*ytXmVwU4g{J> z?GP$bZ8c;fC%S-+3e!l!pkg%K;@G3#W?uGLH`WBuO3@Z_*dEE z8xK6rRfn!3?wNyrhuQ8N^{ESVVh7g*q>9upFEcp1ftoMr_H+6(efI6z#f>-IfR_TV z1X?H_edrO6zWN&EhVz4U-uJ-|uybb#xn$QhS8>lz{wSaLw|~Mu(IEy&um%7xBT+Z# zY(x|_y~Q0&h8FJwMaR=ym}73=L4ujX#|$GJMuL(CA-V**WQ>WSCTN3MSYW)h$f4VR zgfBn+EjE@;lS!D2hJ^7Lxl2*blw_inc?=GtGH?*RLga?mtL@*IffTl}k3J*}D56!( zSBjt{J_KYTdEbZL&%(joOx&2#WcVP6W5=s6y~KE9#Msun>4$D-cK1A+ZVPENgL=f3 zH(krG{Kl{HAOH35BP#G?kF^e|CCb4!zVbBlmoJcC+2yipFGm*!p%k|Elsf0DpL>iK zpZo@4WV!yD>!_O=qYNff1RrtI;iKa{AAB#F64aq)tio3WkGqLQ`Y&z(85v_TG1J*FASKu{C5l zgn-tqZ@LI{O_6}{#4E@D>q0S{jPX(9Ltq2nYfxGkox= zjid!ycw9B%!nyOc~mSkEZWKNcM5IRG}q{z1I9^!hWP1+{A^v?17}gcGEo36`?oMH!6?9xXJTti#~!21md38by_nS0dr| zh5|VVtgWACbYc~=a0S(Hi{mf8%GTNdtpr|4f&_e9I<`VCN~&}ZrJyhwS|`D4?;@dP z*O*R@7~5p@CL~fxvQ`x-whA3Ww3xhUZ?UBQQXkpi4hDPYQJTqS+klY(dnf@lmC zk~5Pb?t@bPh$cR#g$#@K|!RSciZ5s5pOvKpcPco);CxoM} zHt2Q~t{GET6O>Y95<0yOoqiWvTSlWXQ7Rk)q(W=ml12jIzs5icq*7kW_GXA}uyPVJ zNd2gBRWqt8I>Ds0z6tm`AR0kObYK|JLL+Rl^myn`9$@9Q^X$7~KgW+8^q zwIjGB9-B79n9A5DGF;t6Mn$jJ$H{~PJil}fSJ!l8LG*CswIl4k<4|k#mi)n!Jex;p zjnpcs@hDAQrQqO#Bg;z`7IrY(pCNdUR!RLolI&EPx*?YaTh}x$@c0*>M2;ohpt$dM zKf-5Ba@b{p^f*&id!YAP&7 z8k94{q2ybSJV!nh?CA6{AxRB};K)lu)6|$;Q8x`SBr=B35KW{}0-eqBo?rS&KK&p5 znyr`5)3b`K4(v5En4aX!aGhlrw%KL0V#C|wEp5e zqnDRB+CJx{)zc+Mg6;X#+iyikLQFm7)Cp)usWB3TNgpwtmnJ41S{soa$@v#w=E%9z z>^*dV+9zDH_n!HE3%vIy-%r`iA;RvP53umc0oFHG$meGfMaI@(i_@E{xX}ph(xA|8 zdM;bo$G(I62_^}l*kCzz_9WwaL^@7d*&AkoEwsrirh$s>&rC56|(smOp9m` zB&K3$1F8z3R3zFVTZ41#zj8Onp8p1$8>>he5lYaX?NN3+4A%!NonOZKNQep}4I(P) zszC^a_^;JP^dio#)dck(r82bAG_l5ePrtu|qUhp%f}JFcqhLI#(9R{H2S7B5#wV-5 zQ=fXA#x`_{4*gIjH79A1CQ(E^fYL;jWVvp=>1O5@cQR=j@-k0T=#GI*;p*hgQ`HSZ zN$RR0*Bv%D20Zo5Q@r(#Te;%O1BpxSEds$-Q!$u~C_5b>Wkj)d5RxfaB(aYA3q3*s zYipZG5g;h)NhAbCAxh%Nm0uR8b0(BAEY;1a%$x)n`;}auWqC_ML@6Dr`zu)IwvG0F7J5p zspom(^N-U}CBE_q4_TQ}tA>E!?eDvbcl`8^;ibn)NAQ6%^r)9AKK-YkX7Jh?v$01l zEt$zuW|nE{V3C=`Mn{%sEu}XSaj6d%0%%Qt?+owwsrT^oeP3qv`IBfXF+nhI`ovjH zy}riCTSmbWjlu=r>ba8`Su$nV9)Su8ARm213b4XsGsTh{Guo)pTH{T=tv)~XcE3~y zQwUH>pyb6Uy^Ta^$tK&ve%>R zcj@*z2&K?c@!03T#Icu-U{IVoewt^VeVQnKf`ivw2{BM~3N}WYEN>0itj09HLPU)u zBMFoSHqY0rjKgsuv2-pzVwPz1yUUKBvDMo`Kb?uPoj?fBF0}t1D~loY~WQ^=O3AU=&d%mChJFAtcs_L{f-?LKTThmiqm; z2*iM4IwSyM#1m0@PE@iLIEi@YXo97Q9_64kJr);sG9Hh~%8~%&I_LRkpXdCMliYjH zJ>Wd&PoH6J^#V7(>1Os_bD+)QlBT5d0j&&~(V$2JARpOqTP$rZp&Nw=1}P0$F7aAX z1xu`Is!%f=R$RCEW~>Nwi;UnLc~P)B8gO!bnb2r5m6Iz)Rd0|r3kWSSD%o8NB?&rm z<&B5<<$wGus7&FNG~%yWF_*jciepk&cm ztg5)_`dj$G-}?}%XD~h_Bt_O^<<(`Ly#H&Q{^qOnqG949Go2X>1yLD-aF{Ghn~)du z^FEWU3Fpq9rYJSt*^;cIQx_wbT>qx)8Jt<=t4Gcx)|!oUq5&y!T^QI2%ab8vpKO0a zyyy`XTG5->T8cnOS~g08Ryd$0F`-0^G?N-7)6g@vj4!42c9u$n=o6QGI?10-?UUKx zB?8$hDJZF!)T)#cIO)jpoLla=o?rcE|CC1_eS}BudkDAL5JR92p1Q8FZDwn&MMg!p z+hgCJedJk5?JRXw(L_rv9Yz_nDHu#P2}UxmE3z^t2*J3ilTJa5xTYaD9b9E`BTpS2 zD%Y4YXLe?uqA0Q6B1L4lzL|!!UQv@A00@HUTM?WnS(sbk#H&l(e%o#ao99@Uo0Po) zQ5|P>b)AtlTzli2x%}FjL8LYmZUkg()YTwrm>T*8N` z1W$3nB{l3A@NFa8i_og2w|~M#5sx^fqNX`v`ajrKCVKhXFLL1YVRl}Q+gv5@WccW@!6!AIra=gSF(zej?eNLDWarQX z*m9mR0jDC822{iCZ@q?ds)=FD&Q3~t_k2ho>6)hLpdxw}#h1;Igr4|TPHO4g+ZW7R)EWLGM+Q=6qv1N&r zE)iOgNyH??)H8`mzEZU+MoG0PWhgQv_4o|I-d(#9x)qD{fv)N#{YDJFajY+`vb8xt z^mC+v*||Q#2mAzbkS?rQ2ov@c8lJ`34p>8Z%YMP0osv8^< z>r-1#2v1|{R$*PWrK3Oz$ciHIiCgs`?`*4f-jJD+#(Qjtm{yj}dPj&FA0rZtw}GQa zj&bbBF)q7e9{`v@XTK4THYLJlL?_W%xgGeewMmmQCdSRi#s(kxqmQz5ZW(QIe2hdD zdF!2T<{$t1KV;A4JE>ib(K+=X@{y1JHD7u3E9eUo?pVBvuF_2WnAx&qFm8D93(s=p zfvZ^T&$F?y#;eC(;{H#5mM0&34kHR=CVBRmZ}ZvDe3AG6)O*vzt|CpebQZhBu0oC@ zqV`EtMkGIbsSV@2OGBWkJr2^n;-cY4>ZL`3B=wX@$O{n_A}U(%N}_k$VmgrEVa}#N zI1Qp{Gr#yfQnbGFAwdK}+X65$PfQ@;aWVn(X|bG-S7ZpHeW=;u9}iA5Q~!s2e;`j&e+bz+rgpLmJkQiZTd)Y%71W|GFQ(y}FPybeEjx={Bw~ zL3%_K+qUJ=dDd1|=yev53YsVqAY2+UnNbIi@R6*gmkL5s+R=&}!;J2*)AT7^n#fke zif*Uh_SYi4ejnY*vC+}EhCDN5CTHSZdN74fSVRdPhsqT~iS7G=kgTt-bN19JuDSjy zy!B*-K?=#-%q)e;llN0dC8JUbtxd`{qlG9^U)5wBdF3_!_kaC=@H0RAGtA6)sNIOo z&6*1<>v$g+4To$FhYSY;T;ph(nwkC#=gyqr^s!|!m4SdJG~DyUck}E2{8#AC8JbX& zcMAraLq7HKNBP7jK1XaUvo)MJeUbz73zWG*_=X;mm6wk5XTSYn?tIsseB-5W@c5Ho zqpAW09kebP)e{hkS6(~LyDT_wDZ2)#C1YQ4bom5V#YGl-J>uA5Cp8_B;ay}#Wi&+> zCt#x)LrW2ziZ06pSZ+c4BzTgirLsn%OR7;(#9aSKs#Kt7|EPR9*$TG*+^wNk_; zAklp3^N;b|)6Y}P7wo!xCkL+BkF}PCJ&Q?WKC$O%ypVuKHsh^5dS zY9ClyA930Kom?1fGT$jMI#Lh|J6*O$ z1MXN((%aCyo~bEsm2G^tT8U4p=D zxdzoUNLAr#h42|3MXe&T0H+cYMoNv41;w7ll#%!bRA6H?gb*pDKnqD#Tk4Gwi(0Zv z_vyHt5CV;Gtgf$7XlP=DJZHRBQH>^GEuCCpou%;(D+RI05JsSV63?)qK^kz%GP|SC z%assNaDuGp2~}otN#!%=MXUBzTF7$%RuYjmb1ZCO1eQEi?Ttr7BrE zy29`LZyyE?K}W20EmJ3M_xUcZ4y0@|u2`m?w5)miJ-6~t|NCE}J69s4M2iBP;-Lrb z=f1!E8_XnN8`wf|R0P(B11_7NV^^m{RAX{ALCB1kp8qC;)eZK~UBU9w2E%$nur*4i zLDA~+5>3_6>85JLHWn8HOU)MJQNwkeeeBLkvI?SdHdsMYesu@UB&`Pass~lkZgY{vzOBi*4dU!lT91V-7J*%xTi3 zItr9cOtBCpjgy=>b%EdhH~*f$_xFE}8}GU)fzVBcuPsI@GBPHEiu><-fKPtx6ZB-x zb6T!S(KEhFAqwAR>(=Rf}5AMu^9e}`z{=qsnWaB9F+SMOkb zV}s50Rids4K1l@Hra>Zj{>c~EHM@t?7rx6gPdtlO;9Nrt8Pf)u!hq039|$tCJ{X~N z#=^oPMxA3vcaF8u5?iO%C`(1R=n|czo;ZSYjH?CI3te~qEt`qPX(3M<$_*(9K*S#Eh^(aTb^IguLKg(P1 zy_4&1zmX7YmX59P`M-IXtcjFF_RjV>xO*q#=&?P4!;P{)cxhY#^D{?-4&-o3jyb^Ij1|GU4B&J|GwoON`vgfn!Lnr1R?(F+1&6kdC_ z2J6_yB8{SJN|eYz80sbvq6S*FlaF|p0>pMZFHSXLTU>7tI3IDYA(M*3H(tyC@IU`1 zvkM(2bwh9hDGVo$9_4}iK0`BU2rkKHhZt$1XKg$tLT%Zeu^A4p9S<$75g5~iRqB@7|?_|$hA2DuP zn+#7TC38iGS_CFrH9ktbNLDAJwJM1hSKIcGC|y6T-Ap^CpJJZ3zaF+t8@+Qa`efQ4 zy=Y&ZAXn+9yidbBt&(^9bYNv0%gjv4vDc3AJOA$g;cYLxoz85Brm6|v(#gAQt_^tQ zrSEd~=u9#mjQBVI>;FaBDcQ4oH*bC0TbP@hN&Q#bP*oF%krPMH@P&uING3A8 z4J@Bp;h+DvzsU_Z-@ssFgR`g3k;?)tGlF+0p$U!WkN@94=IO6KgR_BSFCSyJKhLll zUov568zpVeSIX2en6`NT^L*rAva724E%sS`}gp3zw-0!J$wa~^c=kF1}>aB z$A|y@?{Uk!Z)5SmUZPg)yXiV=E%@q#UxX&m-!n@SJt0Q2EKibgfGRR%%o)+}!|#4C zJ9qCU;ou{-YEVI;J71B{M>q8}7dIZ9Mwm zBY5wSM$u4n`&(}1zxkDaz~Y`AG_L0AYYy?Dzw<$k9DNNJ8p>`-Z7oIKL1vPDSM25V z(X;4M<3df|HQf1*w_)-ukq?ByHj$-st5g$9aDY!%CcYh_#8%BHl3Famx7g9?;*1IR zm?_28hpwXAD;Z6OXq}^_;guI(JtyJ#gMWn=`Z%U`(1aEl@jYJ3Y{k#jCKeZv}diUkdqA> z;kl~pBaA>)4&?(KG`or(QNp>=I-7Pv6cVRIJ8WtPog!tEQ^0-;LFES~z=9-r?UOm9 z5Yr(kNewAXOZ%9n+AY3xn$?FW@ZJHs9o9sY7ObtVp^ap?xy5Jx>N5zHJd}h;wjdIj z1k7C$OCC)oXrl>Ro~o)iv38PUFCK*{p0%AnNGX_%E#16_tsOcVViV|PeO~$2s~BzQ zsvfTP$udT&^gc^Lp$$i0Iz~OI$yLtQg)MTOD9qn~UqpL;J|=yJ)e9SBqQlPJJ$gNZ zR*r7BgLflhuy{KmM2E^UF59<&cY(KFdp&!0?FV1*;;+t{lfQfcz4{gb`va&)onb1)s(WLCii@?1<{!WhUd6}1< ze+e-=!;jweZVny3ir&6?F2pUevcserkT@RlEc2gO34l{2Tg z;f@<|-8}WpqQtp~)|#LNBUe-Fz`jG5Bb1<;OfWJ}%0@2Yn?P_9g~Z1|(1L4jxDJ&| zJf2)<7y;GRn9cbN1;6l%Kh5sNIaV*M6GcE3lK21kds*DO6GU=)9BmER zwR0zreBt5kOeiSWsz>ZOu$N!^&0pn#`##Oq<`%Pav+TQaH}C(+_hPaPBQ@2yp_k8a z>i8LK?eUH@PzV45p;~VqpMq-I*{5Xkc8CIG#^9Qo(Qq>vr4 zL=X-m4VlWQw;Eph`gd?62SHND!1?h8TjL>}h0B=Bx@aT72bA;ljE20AL|{gn41LXr zfQ?gQx^#&`weY!k$@=^OdB+xX-v;5(KD@FGUXiH*q1X=6NhJHCE@=qK*;B|wI`Gb+ zjY3L=ZERw<1(^OoRLQZ_T90);DT)F0R&t1_TuqTD`w*=)xORi^$p^k?`izGaMj4z< zgRgo#LS=^FlF)eY+rJK>5)C`JWWkfmoM55U1x;lWN#gtNNkSH;DZWyPT(Pudsp=7P z^M)M@8U21ve`cOeDJcp?W+a_{Nic$Lw?|V2UU_-I>iH!G7hw5p&DMqhUy>WpsvQW* zG(VVDJ0YYBE$MZ<{_%zkq#<0K%uk0Z7wMtXMJ%x61~;-4GG{Q^B+qlaXt?^0>$vXL z!yGztGv)3D7JGBVXc48sHDm0kVpexqzi^)8FP|j58$<>|ra^$0kz4M*0}*e>3Cmap zj4}wX=oUSOD;F5oL$o$r7;UmNSm8>upV+{7JZX1Bk>D&M!Ii8D*etNHeFrEO@Ve`Ttqg3JO=g@GvrZoW^0|skBL617YRYz zI}O{*Zb}FL{tQQm#AZw0Q0?GK$>cEGW~P^#-lZQ(f4448%BMI~L9!Btl;uv7iO`C# zXq|lQQ_ng{0v1_D;~Jz?iO(J--J*-N79|DFyGzbC38~c9qJ*TbE6Sonh>=ovao*vb zOF?Nm*d^kuLn)ay)=1mu71XxIXhW0eESKJuZ5+6il4??uWd)7ZTv%-wY)-has+gV6 z*fC!)H`k%lk$B%=GKi|cxpktK4A&Y~&Q2H)B++Gvs4z;lq9%#8rj#azn4}uZf*8}f zC8iDS^`hw;GLXtvO3Yf@KD<-ev1D(dRO;bn6TyQY`6M6wCqK*VRf{yi;$s3UXG(JD z`u$9#$3>rv=z^mZY1+PibeTW--9KcwIpkYUeTSRwybUFrqz8#(YH}>22kTQG(M6tl z=4p;S`z?wnn79d!hF$x2(gcT#0WwWP)w;`jY64M8D&;u4zRZc0Q|!}M;M$((=K3b{ zdWM(2_5wFvb3J$5^Jc8Hc;N`fQu_%~NrX0d>k}R`B%9}E;`!{S9^#?Td;uTe4?g^# zs3r~Xc-Nf(7$ea#BC%;Y;v$&@Usn`G0YP)>)EORl;M1Hvdkz^*OQB3tY%N=;kBBXz zA*u3Q95ki!-pAxEFN~&g9_yi#b?_F(BS%$vy1GLX9TJ&J*p{^xeI)vbmZn8z2wwQc zi~P-Be1c#4M?X(*zK0c#Kzdj#9xalZQ4EqCL2f#HDI+{8hBmYwt4X~32oy-3yDj8*{T{NBxzb6 zlNXl{HW3f}_Q`zDA=>O%YDw*Dq(~Z`AX@e6E^6;O3mON&>>E1Unsfbl@z>T`fSa3m$#=Veb3rrwCOlyDDGvhrjp7gu3C~@Ba}>lT&$*x1J&^us#K{ z=p@DzoH}ui-}$${!wb*8NLQ8AlP0N%t2C7HjoZ$eL|X++=YC0SBetI7>0hpLTsXag zsuiX-_=#gR_RY-VhYi?( zaFIf57P68k1OtVoTF8RVGuW?DsK(z9D zQl`v3xV9`7h9Dh5Bsf*FeO758OGpqOk+Rb$MN2P946XDgPEYRQNh;C$c(t3<)H_#9 zXGJ0sMN3p@&t1f%PasIyy12y5PsSe{=!k8VEU`Ui4U9(-s3AJE z@F*2fDkk5vC=fL5Yshv5ru(XtLMyecYapfAzSOkVe&E!;=TN`(Tfg;Num3IoWgb3Q zCYuwEzHpM|69b&BD2-sQED2SUM0T5qDGHWWmI*O(^R2fbqo$knkQU}TGmO`V7@5&m zC5#-a$Ch~F!LRV0$De1`7qDdsm1T8lh0V29Zn^Om%AzDQIi0LTI!SH~XJ0zWNB`X) zV%8nAwj_FJv|x2I54IK;}p(&!Ih?3k(j13eRG8b{1TWp+J;^3|;c>HsZ z@xaIKM^?~L1*!$AhtOI?D+O}uN}3)t8Io>i6q0Yh@FL@_G1nfvnmj7v&=NKp-0FmS zdC2I@Dks1B3LpQIzhdqDkl-ZAC_80NK}e!dEv!B%d(}1xwm_uU?V_c^JHK6e=US6# zgSCz(IHHo@3)pWfBU&(i${^Fj{DXfY$>o6UV0tl2<>Cj^c$)&>bWjDYD0C7t1X@2N zk^!Dg-jnzKMSOC>F$ISOykr$E0X?=PNjQDz_Y0}x*%;Zk`ySFQb-|DLST$W zYty!*z~ma;)f~F%N*4DoAhbvdXqS*EE^B)nFs&uOT6&dF~;K! zc62od=I3y$BbvrDw%~Q7mNlK7UFI&|MSs^KMW;j4RP?(A7naYVixL&#?8!5%o?9hs z1-ea!9w%MSkO{U#&Fn&#L$@EMTv z)P}S$bwO`#md0ByoIi(jkj0!(fp;D+e3HBqN!m@t#De<%0fJI;`$3N};U--mIYa75 z2sQIN<`|7@0ty#lV>G0)6V6p*Cc!07d6mSLz4IucPyuulNnpZgJT;x3W^qT4EBEeU zR+X4W;ztd3Qd3tGMDUD}oZ8rA-8#lGi3(e1Q-&oHBh84=T9;TdADEXJ*Y4WSPSb^n zC)yO`rB=9HalYE*?0CQc%T};SYhhbhJXRl2e30wKzzJls-+uTh?A0s-%rTNf3!E-Vnein^I|qU{RkM{5Q8Dc#Dt15B6WJft7NSr9iI&p-Sm zVbjuc8O~Yg8X7-g>}#Ty2n&m9mg?Am5Dd}DMB^kqpwbIEB4;Z$tgo!|r3W8pPk)}h z+Q3r%cS%Pr1CEX=KAV!3z)jUvXx-0@tfV7b;LJX2}An1xNwRJQxFx%O| z=48mQas(lWI4qGcr4+T#TViXapjLJ|RKp?bjiXuK9AH%Z%!u+7L4^!fFT9Mh1geYL63NlZ{PDO%@KnKHD{W|e6eo(4yL zIt-Ko+CFB&qo%Wym%NV`i~QK)VcV>F`~Ta|QEZ#_Z70!fP@IZkr`NwU!)x!&_H~68 z-O*;eq|8+yx7#o2`y7ZAge59vrZJ{|uP_OIg=%3GayuSOj}TgkO&PY|7bR1Kdrq(DuWK78%ZfLTqQ7GCuWALQ@_Po zWNbhQYy=@Qf)&&XGzG>B#HcL?5y{&prruTKDwGK5OrSy_lc_ftOGzhaq!+jliAtgx z$VJ46hT1yjJ9Es$K6&j?K_+~v2uZoVrM}wAB1E8>Saey?H}e#A&d!AyR-0vxojb~0 z+2_icE2%eYbjTn|d=MydqPG|s@RJDW?W|J9qzJEwsnnf-3OQaRp0x3ST1CXltaHw7QU{L= zq3yGJk`|&Tikd2m*q9Twps|5kD_%H%j)U{N*l9}gMv%vX;Y6T-t_bWYyM(G{scF)H zOr)Tq62J*X0HbN5!%0DnV{7FcH!SXB!6-6Xl`rp@4Fv@=%ybOLstcTD3oF|7AT*Ao zZX~8bOH4B}P*Eh9k|2pS!*)RX-cZ&aZB!Cdm3S@*Tx}~L1WP@&dYSfRw{a}7-H1dh z5}kPNaf*daS;_Wqp7vy&bg9od9jyuoEgH0a;pBPL_E&|NVuvrLHN=RD0)^U6a8l6n z&{AL#uDvz|QQ%#MkW=l^{}sL?_aV?c@m zAv}>Lt@5A7sn-_T0Iec^f)blN}`L& z3OeO;?Q6Az2QJOZ(jZ35lvRWnQ@I}7u5)~*} z6a^9h2@w=PkOTpOL?VDe8UO=K?CIP$z2SuYaNgT9G=pltLZ_;0db)b%cE9($&-Da?ZO8v&=|)?G2o1as6ES+PBCSH6cNH0G(ku2 z>Qh)DSutZW?{G34C-E18=_ckhNYBV*oLW6cGCRjiEkUl0aVjRa78PrzL=z(|qL3^V zLrNd6ne!em1xkfq);k}%!O8HZDuxq9m=G81pMKW5sQdq^>!){BQdPz&)`9fZKrnQQ zVF$MnCIy+1v*g{qz+Ed7=Bh7*4289y-H1g&+mo41UobDf@kG~18c0oMIz9IWU#+;$jt$RAmo61DR8bb zT9FE4N-{HMtTk(Et3;*54-GQ$ET3OO>WZSGKt&4SDl=QJs7&^-6%W!?*q*5BZ0K1W zrI0u*%0Vu|jVM&ekU`!~~f%T0*qH%aH5TX(p;4u=;t}P?1$F=9!(w)X{j8WbrUBGpvt|Mw1 zF3Ak>=RT^#0ZB~p{NF&g+Sksg3OgjFVJXQ5n3hZCovOM1jpv9|F;*s>P{#04??lS zhhnJ!9SNicB7w|3lpg6Ex)ueDHFG#6@XCP-+{TF~YIuKL6-^QB{URBW>X^P8F*HL~ z3d;+xynrg86*rJxa^mDkVq(08TvU8psltQ7SFuJSFk-{T4R?_AVe%XDlq5z-tPtUA z)`Y}>%3D)M5+Oq`YA2nnP(cN=dAf5TEY4b@DCDx6(pJMNMItl}rI5y<3y0U5ND4YC z!6kt{BO=F$0z-8ScQ7%Daa2jN5}a@(I%b1{*Vh-(amsXB;g-20vXV&Xz=upaU@a@< zkeuLnq@=>;t|~eq3(RScQ?Ovy$jgrF!gL;^AvY}wXBF0C*u3Y_Op#O5%rq|?&qU*|3B{)*z}{2o4i&o8t_cu0r6uy+Y<_p^OK{y z*!;eqT$2Hq*!;M-SWi|s?YPY%>z$~in->OLfy^HfhJX$&OXA4Us717!DXm6AT#^1! zo+5LMMuu!`Da$chC4?tfxL1^nzz2EkOx&|Cpzxbp#<@Ts zb`xyMgOD06AQF&hP>Fz=C6_r?IZ~<6zM4oY&)63T0Y++^cGxIP(UlFIODQT{yYp2P zv!gvR)1XfyGK(5r#qGh6)|26&D^F(z(#R zNsSc(BV@q)09=Ln;ZaJWv_eD{hY4154usRV%vI2d!)b$;hCDB6Hrq&{gVM-HV4#~e znXk3!>6p6H6k3C|#3f9{F``~aNQ=!gz@TJ=D=nqTsMi%qoFa8ZTu;c$jNxjZL0&Q( z7ZhhtaM?_cR;^AgPH{s+Im}75V!qyl)Pgl^_>4?VR9IElD+6KODMQ>;TyfRa?C8z$ z#t&a68?UmnIYqYGCuydLnHo3V@D|p_LmqkPyTtt=#b8KQhBio6;*B4xEaJi^qUu8b z{*F)l{n&piHc#T=Ve2bAvl;@4i;v|0&Chi)E($+Zs3(6; zI`L3UCrkl3!FXT-qxl%6A&H^Wj_GzHX1WPlt z)Ci|hS`$SH&J-7hdDU<%JRk@;XtFvc{G9csETl?FeBsFQtV$8RkfAOFL~(?*1wOHq zv1jYyJsf!J5kxB{ZKl-g3Eo-KC?<&$N)3@w-2H_wbME<*xIu}wl2~ZUGRX6cEm7KE zL=&kd(}K;vPgW?XCG|8y8B3$r;P4Gc>F5^2SC?3M{xo(7DsE8X`S?HnB-h?}HTm)e z-}=(uQWhhewZux}jKE4+6)A@nf<_Wi$QpVo=J54baLHwd=uS-|l*S1|J*m-7Iz%$2 z-m0^(y1>`Jb|3fO`*)$YHUf+d+g^%IE~K-88l$Bkj7F*fiKqzNG7OTOGw4L&bV=M% z-1yF$_|zvp#nt4pDq#M;J2L;xQ zD90Arm_{a1(2om=HWncr?WTfmgKMt2iW`3MW@_~o8yiEs&FIa}qf|s%uY;15*7EqH zKje#_|01KsA)~_Z^3rMc^tRIxb!v$Ytc=oOM+LpOM%?OgKHuQ9ACis6IIqI*=?qaS zi5oE=|IA0Y{a1d8Mx((W{l`D%8(;Vv8oh{_=^A~Lam(!=8^8t@lN+Bn*(y(IyDwsrU4uLlJ)8xs`g_E+Z#3z$~9=@jnY&MV17Y0-T z3UeR=FL#2;hSRmcm@xfU6JJz9Vb_%`)f%%o3%Kw|2*pz=wP_aQy$i*0avv}Wr3??> z@O7B*YP}a|t+2KTL3S8ot!T9(dcBBF+o9DuI?736j}U=yKgx29%h9Sqq?$B4ZKkH% zwA*!-mn`cm1zK1j#57xDF3_4L*Rq0Bj5Wd5@8_&HWg(r!Fcd{jt(Fo+F-0LOuAD?j zi&TQLY3S~o`8GJ2; z&;gjm;oSs7tw_li%iRc^wnz(dY3Y|69C`Z@e)YHhG1J@TQKjbWk52G~|ML%MsFRb`upo1^pwV))eOewDYq=X#_Ts6SK3u>PN5g+S;oD@5RxcZt=?>`XF;#wsPdkBkbI> zlh6PD=P@fqknL&BQZ}L(c}%Crbd(@QhFAz9Eh!?&ou9drx7~I#eVb#9XP1a+rV&|| zqjikM2Llb@BOm(^ufKYNul@CXh$v#s6uh{2ioLz zx1VBtd4scO7O@@*1Wx#HO#U(I(PYXEo06a(qYJ?WtntF~6~SIsG30@67WQB$Y7SRH zAQvnCoVA<7rwLLUn(ztdbpkKAikKdprlhLy+lh*60%iTT$NeAs9mGW+uCfYr)oX;J zFDnBU=N(8x96PpdkxX?ZQmi5w(5QQ)$ceSYn4Gc*N2);k$|;I5&aI*vEvDx?w7N}} z&MOwrt>MZ#u9V;toR6>$oRdT%!kCggFE&{}KX1J$l}$l|>?npAYi9?XeCaHCG2T=* z$ueYTFV*^d;t=>U^?EGpWjFWnesU+b*$PNo`M;|KZ>K3p!i7cpQ;aoPGHWFFo-BiH|5u!ThD$ zdCN_2L8K0yC_1wO8ieBb~$vh42#P!7E1|p%9KGx?ufK4D@zQ`T^$y$8HuG_d>8Qzc(x$5$Ohqkb;uhVw zMK^9T9oLzP8%)IwX5uDu%?{goGgy~%>+SF5UAMj)XD!odi>JQ*7|(v|2|8t+9j!U) zB4TQ)#ex01*mrOb<09kGp-Xt-spn9ALtVtgal)X;7@GpCAXbt_t%h|0iaB`W5w7{* zO>DSva49MkViZjU)FCQ|V{r8Gs=1}EV|Zc?Mz zY$(FqKrk`q@RjsdX*HozBIO14i;{Bl>k~Js$;=_VmLrbi&0%i!6Cf&T6Pumzr1QK0 zA^1(0APjIX(wP#v=$v{}(d)%@JAFFMf>xuT)i5+_o{&Z#yj*ounKL^<97lxI34>M+ zDGTQ2XPD_tQ)?uwt*>Fm;kC35CoK@@C`P1?{fBolw__HSM4MgyPg6F%DLYaC=Pji% zjK|}E`)n#gF6gx1b=&)B&-ciUrIFSdo?fEAu*|SOLPv4H>xz>4Y|6}ztvDg5&9vEl zbRT>bTyBEJowYa-Y|;W(t~yHn7_KtG*F0VsWGm%ux86iL+r+w@np6Dnf$#CiSH4Fw zlDOQE)FYmK_Gun@?! z69hxP8x7WE8T}7tWob+!(O6)kQ@)MLwc*As$*ySQ%lv{>1ue zIO$KtCOuVA5}RGsg?}45Naw=vvU>W52pey!6GP}$m8u>pm2;O+1iFy5$cc%%t<+^o zY;r+eMdjM$O#R$3S=E_}N{IwjB5R<6rD;TWs!neSwGsWg!hWy9}-^Wmy%{@O1OlQPoLDYkme*PqEfgtd058-~D6OUOk5y8|lMy!tyZ+X}S9PYjMU9#|gdZY3AEqYJH0y zhtRfQY9)zPuz4$tL5YC>%8GLHeg3dg# z)a0clA6cG#ggr=Z!FWwYs4mEG#rD5b8F|g`)}^%(j%9$ZRa+eH%R3|G_?yt4Vh{NdBMvI zCyBT3BZ_N8LZF04BQaLdl!7iXV-@3*1Y>i&@2L1t$>$XoPj!@^-1OCV z1sF*NN|kh2X_3-b*kd5k5d~PlTaQM8aiI~Y*eFVRRHEq3%wTM2OtR64JkM#Sb)*Q= zWM76Oca$=*C3-^B^FJ|e;zD8d)z`&lBQoKyDxpXsNvEZlYD1@0lBOp3P8g4t zohFAqCbGd>X4(8DmIEC76Brrv=S{f+Bp;uxu8mM6^>+MiB;ge zMYynuO9fG@20*Md*|^}j7mhPpE9e$=tn)Y}si`^*4KKfNlJ$*}xD_F-p;k&F6Qqz* zE2J&3BA7+HSW@pcnVRl|BWeNTl`%D0!$mMI4Aw|W5e!>S96!nH&!6Dn!2=X|Mv;xF z2~ApB5*Jg-7^8!UvMdZ9Ln*@`N)ikr!p&>2!hv(dPEu15-PtZVV?-gD=}dE`lq6`9 zR)8(6a3~#<$Qpz75gti@IA-De5@lvFWkDQ8%-1_eEm<9}!W+dBGoh0&{jiDTk5fbvEAW9NC-8N_C0x~MF1lg-4*eDLhIcXeYeSvot zAtEA~QY$?3Mx%6sN;RiOBTAd#X@V~iB4fhlbDPw?Kq#MZJZ;4;5hmcGPD#ALHo_2!JsZ(0Ceyy7UOba`+kl@jMbD~T3{*>22iyU)HIHP(kYQaGCJI%zEFbehc0 z%@en#up*-L3Mn=7TX!=Ea6{i?e^3-#Waq#FNZurmv&h=L)-Vm6P zLdG$rHPlr^VI8G$)KM4z0za|dl!a9IiR+EnJo0$JSc|nGvLKR@*m+{-QPQDPNvTT; zS)l8ola)#^CPV86wk%0xigSXxOsF}Huny@$u(C0REEX6KS_*LBe87fel~-;F7->{G z(h?d@LGEazb$0LB#j#yI)?PY~NEM~<_!?wU&Vi%*n3 zz5;0lsfvk&Br6Mi?9pk2NJZrVkoO@=N=U2>n@$#jnv9VR&2_ij!0A(GSbq5|Nm1fUgN+=%8L|E9 z101^kO2$}PtuC`OJ=XO}WG+xf&?G|Z4!vfbQ(~R9@djBrVs%ikH15-j0*1FXSYxD1 zv@Y?&(e1SGgYf>(Y@OkTM0rS0 z&_XdK>qr5OfutN5O6^f;%v*1IJNTG!p5dGgR5}TG$2)I%C%Tqka*Ohcx>5{XiMOCp zOr;$%B^Vc;)p3DU1x|sTV5EWz10f%-`sA=2jPN{E;fWz~#!(7O($efYxP#yR*Z-Vt z2e&a84@hNx z8wN|lk`U3|I>VoR;fpMuTVl_i?c93Xt)x>8+VeejUUmtOpZg(otwL&o5Bn5AsGlr7 z22*+0Qu$<9N|$kH&vukL&z5a7EG@qdzM$ERX-_qo?oBf@yPZ~d2k2>ZI*pE-pkO>c zL$g1iJ++ni)nlAHb)3;~NLh?fXwIKI!_!Ya!P{>95XYWc=h(t42y-D`vO!JPtH=gVo{z|_WhgDBEvQGW z3K^84V9GFPva&knR#XyHpl*bAqAEfHz>_2?&;RIo<{sU}^&hyIL76jma5r!N<#+R= zho2-H=H#xVJ=35)+u`!-jsk(io`{&mHx@Yg;t5hBTu}zqMpfvnEpb_aEIo}{ox&At z+qZ-FeCQUUM3K}Q#AzL=CACIEcdAKex{V`vr{=~`ItNk*sK8sijBphZUqdCKb$H=$ zBG90yh|Gm^SmQ7w!}4qANq!+_-Hz$*o#T#w@oCIP&c^9QPQ7*lFCCX$dz2lQ?xpYr zW@JdbqJM4$J1)_pi6{k;1Fa)ul#pvjJ{mEymfRRt2LqxcCM!qG?cKtM|NBo;S9Qku zkY=liiZu0Rjo$WIR83>7qfx74P*|@k4Wh956A{D`zUP=ao0o_iQr@#F;8;i@- zv_dP7umW3ndb*8lDC%;9m3+v^n+g)DRz+17)e|kaI|bZ*B1VWLNa2FtYAR`NY4IEX z`k&I6PB_1Oo=&%mvXbG(8aj!Hn+Y4EAxGYNgn#reKga+6KmBhME9>0y!T0dtkAIln z_8!(7I<+>L&x1vvEwM<}%?3B!dLy&j=lK19_xtQQu#32%F~Z`|bZ4efQH;og!cPi; zS87va@Z-yaw|F72zUsImh!al~kLdMMwr!v0#phq55jpDhh_v0Hy=4dOEeEMJ_A=Ew zNK&7nbOPgZ>UKM3&}aSZYcv~8YO&&#m!E^IY9@*?uf6gj*WH+N_=-z-I8jXWcbo2XLo^{;;yyP6?0kCGZ+$=ZaoNDJj4 zV|{6r=`D4v_8h+E2v=Nt1feWCO0hP?J4glA=0uSO8){04XL;18sk_v)M4Diwu{lKb z7p~z%!8gIT908Y>LLiLch3`GX&ZGO8KfIevj%m%b(X*N@d$w@t+YjTsBlkH2)5m8J zXOd?g`60uT%hY9xD?xaHGgaT^EmI=K$5SlitBlHm@y0L=yS!y?#~fRCY$wrm@FiLX z)8{DCcm)PaS%!{iFdUO*C6P~p@v`s%NA!M^>SMj+^|eKe^lYzBQIi@u_5nM$idq@- zgReeBx7p;#yRT!p7=8Q1v{KjwnCi6SziDOBZ z4iDb-AbZ@U}LbsnbT)UU6@;}E-jE{8|*u@m#O(SYv(sAeAuIv z-ee(cdLjIb_2w+37257$vqiU+#n~n;$qVw8A*qW)yoe1Kc5HLJhd7BsT#2_(8k)@p zL;_cO60eYjBSKOV-0-6qC@d&hi8dtCNu-s5s4T;c>V&U&oQkt&miaIL{tx)vzxoX> zx#}>!rh^lX6S%^lM2aYbY_*|lES_8C2lqX~>rcK&S_Wg2!dZmWRbr||slX;!KD)@= zk=@8xW4$FSvtW+o9L7RfmPC<6;#lA4(`|Mck4sLUKhNT5gQ;enB(5P!i>iz|0GzyF zT(LQ5^#bV~(uW(|m!5i@ke^-W?mzqzAN$SEvg6QhOyMYfL8KGB^`vo%ENn1>jvBoD z)bo7#^IwFelDeo-S{tYkN`&s$Thc-@AGe9L;`Py49{cw9xb>HQk$R&>k!AE(R~Y*~ zNRJkhe4HUgnB}+dF{S6&@fZ2S|MW*Jo;Xk2 zBuwcIw$|EE6dTR}03ZNKL_t(2EQ||OZmD~iRVi_Eny$+*3X}{y%CaaoO|2oQl9bXo zB-T~KP6SE{GF{TyKF<}G9cHD!ifASrf9!dFc-KQT*Pt%DjE*ny)&KaXs88R?p|>1C z3dxSR%asQ&Wy@@je!q`OVottrf@dFijA-bQ7S6u9$d8JM%MTqQ^Oh*KL}O1)MiiqA zEd`^MHKJk3Wi#7JtOVk(Q)vlTNn zGt2DO{q(k7hS5EYs8JRAxyN&hLMS43Av43NYQ|InSV9+wy4=pdB zXZx#fmMo%V|HpGBD_P`^w zw)EI}o9&;lEKESA`%!5zMkY%KKo5C6yi%{$-!ZW^s7+AG%2E~5*);Vj&WlVE$1RJ1rybz3X1S`^pp4<~!VU^G(cenZp^! za5SVS9i}Y6TeK1+QOwffDi1&O2tR!CX^bs6(_bM?demYaH12?P;FYYj;2|A!LVOk> zc8S1z6htOuBCVcW+$aA!jm{AchFj0`p0#Cxq>q{g##3H85O1zL2 zW)=o(2#c_i*he%(%4~g#lgD4@cmCJk;Vo}F3f54rjbI!Mn&T*D)E|O()EWs^2EzM^ zS5EWF3$LJsgDA&3$0#3@HWKibIMFm4b<(&)tJR=hucPZV$~1>acKfkvC4Aqf_fJ+9-K>;VfpVWNWiS zT}srjMB89uqI8XBoMJ1!CPIW5ZgIgobHdehUf`?YQzR8q3-Z`fOS<@toHWr0D|zGP zSCP44OKS>71vAY#3Rm#`zj}Zt?|l?odWxZ;HU<5qb*4Klq|>atdXAoNl9ZO%D++4l zFD>$yzw@85N+Gr8)Vb4axpW8GD{@m%6Pl*b%qI=hFx-p5l`U*iRZYP!r2KlcFRD|V zMEHndf6TUB9oFnQY7I?2R>W~kQiCXM)0x?Yif1Tn9qS>E1X_mEQ#b=!JQC*xNxR3& z@;ZADU&UjOKgs!1CrE@xdl+XURH~@8Q&cR`+9O=Jo;nKg){{)9pS9kcg_K}0A*Bim zBdrj|f}B`s32=__pg;>9vaG3iaXx&{nNz2E<>eQNg(Obuq)EgmA0wUO^;0J?0#scx zaAWpfeUQCJ58&sgsKuJZc)ol0{q$d3#tw^+DW5pD9^OsTuCejjD$7d?h(uFb!|e1d zyv&1U%dM7u&_ZQeQwT0skKZjp0g88rtDUrfg?T83aMx-?x zqXGMOA7ETm9;RpJIs57v?){U$fssW=p|ceTln{ZBXf57pMBzxaVy-bo(x~&^_q>n2 zSL`Fwg2aN(p-du*(hzGMCclZsNk^L08Lj7h?XJJ&um9r9WVTOtW}463@iBJq*-gDs zqgii|rZGC!L~%r%rZ}b9IKRR}U%Z!%r(S19CzOMnL0z-^%FB57$KOwTYma-r@^?IX z|D(7fB(dh?{L_E+n_TnOYZ&!&{_GF`f``BP2=!Wx;V9>g^<^BEJySiT6Zo-3Rz3`izs7jI zPb8Y;gN%G(Kua`fX9T-ybRD>vxZYX_z&1X zYc$3{C5HZo*O9_z*BSgfC(~s%ccu59Mz>AWtc7&SG!#?m1aVU1ifgXq@RdiX#}TCw zs7i#9=#=C8U*Plq%kR-IGN$*FaJCC9o&a6B`0TJ=Z!~Rqvd04k<*)<;bWip z7<;Zbz-Tb$)qR)pjX(JsYsb$~(-K>hC@Jy6AylyD^Fpw9&ptl%f!i6X40Mq3DHkm6 zYK=Nc60y3nNIn|TZFgxVbuK-ymzSP>g_oXuf!un|+aW16rfM-d_fUk+LdoDT>Rh<4 zrFRHviPIP}wnzmgmE>*BHSfQkU;M}iD3s%-`5EqY3EzC`bda|iIDF(NSHAUH*2jI? zGaXv(Hh=ve{v4ZSC_`n0L2%-?o+ys7rJ<%H+&JgZ-d$XO_!^?QI%Aik5ojmyiKaA` zY&@p42B!rG#V{+Fp6YRE?;&hfGQGXaouB+Dx8Lz$2EzeK6ouBinu1#aD%O}hXJ${2 zkNmSw^57rc#j6iJg{XVxuegL?`rOB`4G_+=wb5ZN=`hSQMuQBMO7`yFOMAM_*6mF` z{cE4#g=5ci=9P0H(tB)h>l+BA+0|;Jw8xArTEl8EiWFja40Bd9l< z6osK)Zz83}7*8!p7>)wAjw?|pv=!7;g!GPbIKtWzt36f;N+l}hL9nuP(qE8F%Si|& zRRaJHg%Xtut_T@SQpFTSD6Y~#mKW4Sf)NrKN0ioJy(1CHrpgewD620hx0D1W95PZw zu|!82DFwZ`t+bn6N*CU1kHC~Au}A{HybSqVKVMAnW-X*XP@SB2nF%53mwx?YeCtbp$MerTPpWgW)UxJA_=bnnQA=Vz{@G8m|B^lACc|c)!CIfD ztfO;FlqBRL!%Isca?04U@9IlA@X{%Mu&{zz3p`8jE3A~@7@ije&cVW&1#0t6Y*}DU zpxOwj5T)VV(gNqtpJnmdI#J)WT7!5N9Yiq6||Eg)h^?n~lYjFu67MqK&cn|bdi-_KZ#iKCe3pMHiHAAgFP6{JofbjlOo`#!zP z=Gb@DA<6_Uz4mhE_HX0t!f|39;cU=`ORrEU#wHAr%ED5sMfA@sbNq+Tvh&J)WU6GX zzY$I%kw@#8-t24`VmOENf_Bp4_z$1syI=h#ThnQ-e#f=k_QBieZw&Cxb8caQtUq8p z9%Jwn&Jm@WD=yiKu^yXvuKK_YoLyR=8@0Llw)c^1&nO$=1{vpGc$F!UpuD5oY_e+C z_}X1}^U3*7kk^LH&v*H)-~J8$)9?PjEWN%0Dq^j$$kjElhW%61L^8%18I*F-1^V8m z`;(ujkb<-`xSIj48UU(*`%39qdgByNeg83b-}DxeB*7FVeKVleYZ1@4Fs`66pKzdi z7@u06`}Py$(y=ibFr}u*jiI+?j@MF6DFiyMVQh)C9y4juq(CQ{w4NfQz~DeD;#!J` zVpKyRjYqf(R(zA8*`zDQgLM%ofpiv>M%oy!HF2X!;Rlu3x2lpULgcuLWzfo_tLtO2 zvcw2W@S+X2)MYWI)rfKVfNazcg&B#ll6I?$ah~C5TzO;!m7a4xME;0>sD-p*<5=fV zS|EJzyY#|WQ&bO5^29?=uw&m|+B>JPiO2ea_2Gc|9XqIXS`b$$m2OO$q$D=s)n{Je zo2%)pG8-MJO31oM~d;)V~uiw!YGCL#pwxq?Qgj#F^e zl~;4)O*b*H8L>?G!S^2HyMOU5YQqrTWrb%r9`W$^9_0i3=RiwJ#=P~GxAW@L$JiL1 zrYy?f^6o>thwzF~zu>tazQBop^Y18|mLWrA1ik5L-gf;BTygbVSXy1?)mL9*w9#i* zZx;{U{QxgL`x4JR@gh@E1DhKRj-fZKnlVWnkt8u%Kxs@EYA69J7$&E4E%sk}fH#i6 z&ic6(R4buA-=v5P))>eH_x{5Tl%@Zi1Qq&wf_jyvzbX~C6O z9btA$k5k9bP>))areNp=CpI=Hg=go~96FN0e7K_ET)+~m5kS>(Ip;7om}N`vgK|lF zbR@}af%Fky|JwZ=&4*lf{k5cV3>rpeOy3Skr&7{JO0uoR)$hNa6AN#!er}Pt+aPHq ztSqkZ+$%3&>k(_&m_$cpt{_T1rWDjtg|#I{7+l^bcfplD8;u!cBgWcN6r<{B%w}^Z zl&tKm{N@14xG={6kC2X`gj1_))O#%=F~FF0@}iH)1wQXn4wp$Qx|36r_z{N{1}8nr z#Yh~=kFnV@ofP_u=NPZAV~U(Osgai%Mmo$mXMK4ClUoEKIo3HBJU1$w_2;3aZ^}aI z1)vpKQ34KYGNcD@T*VvoI3nV{8iL{r#;C~~ZA ztnui5Kj7u>Jj=$b3na~${a0K<9yuCO#M+rf?){UyIlp|KPk!#xba%{Qk^#L#^L+TT zxAWNdA7z*g>C8;A+FvJWwYc)Sw=pg)QM1A6*LIeU)t@gm>($^*E5#*9m-DTNenG}<*p>4*$CXV|do zw0CXgy`R3Ft8ToCrBe(1>F@s$%Zsb@=9u}0rtw4_z)3q*k!IDIhx{G<+yKmx` zKl3r_NsKdwM!n9<&%Vm3r(Wmj`@c`NI-nLSn$vA|?%IwMmcr(YhC_Vj@gqg5yIAj0 z&Jh)!uig7C4qkbbqgNd!jw9ML9fph%4Nq(pZs^e?Mcu`?VM$BXX?TsZ1x|UMc;qSG zbIUDk**ZsA7_1klNa6Alr4*%7HN4z9lOI&5r-Y6;ih_8z`||KH&o z8l+)rs=>%-ytr@@ITT<$xgX&ZLtVEiHJEE5MC#A3~I_E-0D>X|oamkCp{P2ZPvw{1r@npmOOSlXa}{2U@1^QGVYV{ZG*N7#PF zK1{f~vOFeDSu6HP$p*MSo18=#U zz1LpCl38bZ_bk&}XE=ZE9BYf`(B)CIPdI!0ByJ-o^-a<^VmumSMNt3vyaZ#2l|&dz zE3F}1aMlt+21-?!Pg7v4393b6@RSUVB{!CxZ`sGMed?dlJFuO|N5KtCMm+rBqdfSP zZ=x4V8bd+bYRb$Z#-9H2fST$cw8AOH*p{Sm62b&=!R$gfWF&|Z9asd`F*`lW;^HE; zdYxf^NQt38Sf^oB2wfaIYH^Bc%`h5|>81_pX^It|%#_%&tPDataill7tj;?&@*%Ma z=?rBQ$l#m&XXnBoW-}5baBQ`T&`MO$OAv3Un#L&0HP>Iw`f!6+o`0Fh2t?IP*r?># zQ_phkTd%=+iSGIsMg>!IYss^W(il>iR?z`JeZ6T5DL@=WfgoN<7B8mL z3LuGKNY15K9O6A6{{Z#54uxY&~zT*0c zKq*I@X#PL)-YZ(J>pt`R?QlZn8<9a?5QzW-z)X-5GeygiEQ!|0mMw>Fd+gS9&+_!k zteKZtlUC1~;MKi)+C6Q1B)2SCwj@hbA|+9oIf*0$f&hq|FK(`Q;@*26cGU$a(dv0^ zdUMsPi_5y_)Tuh>JOA+gzmHJUD+g?tnPKDR4J_w9vMi@6Vg_l38&2eC>3MoXLW$?Q z2GEfM_C0hL`#y3XYqoD7bp_5^v=Myg@yGezW8a2$!I-FGFqA?N1rbS+GB(-d;g5Zo zdw=WwtQ1|!EF~-*c`rc)5%su5ztttdg4|lR?7fy# z$Ij56?a;|nXgW$|v9aK`_ufHk!!)@wP~?PROyL~iP$B)YV4T8=oFJ5xCdX+*5tMAa zVTM~Dxtr;0H`3TNNs2*47254KKX~$ceB&!$BPuoPg9(C072D6zQOKa^6B`g|feACJ z%?j~EmEK$jV;w;ppyB{D-2K2lHqLBBN<|<-<}WO9=InX0G)E{wtyN{)%{zGc)I~ZM zSExr7WMJtFLu-1H2R`@^<7+4BC4DM!l}JU{(p#Tk9i{c>0|I;=ewHto0?*^KBcr#R)K_YE`a`Hg@2aduw2gJz|{=RWs& z3RmKkVvwY$YCtFLkcpH?)x0RU^r{Sn%Wy(d8iO>k+vV)3nFMXy1iUHvBHu4r%2j40iiGY<7s9=7hnBNYW&dJk}{;MG@N=J_8zMYUeV)fDw=gNg{~ z%*~SyR=9BD7!#YuKx=NlXCHJV-~H^@s27UP=@q{DmtW@YU%!W4cU?~^4M}M!3PU}v z)1F`E%!yM>Zka}pg^aJ8;+BW*VsgVe>QR+S9D`Dn+7L}tXs3Ow5@;3SQcG1v!~`hk zRz;P4dC8G0OIcUk`_T`w_ujpocXhtFj?WdrjaCS#*D9>V0`l$j1{0FlGGqngjE7HRMzt2k-phdlqEXW zq!g^Zb`$$P`XD>@-M~uOBgbMgOFvtpqBZY%?_Jz~-+LK!69NM2vciEEUggziUnCn0 zICJC}yY9M~L7uVmy6yb&pZu4!q9&CvMhB80R)m#+xEd42-tTAr(h|qsIKjE|=XvUT zPxHPHK1{FM<)(XYXKej6`AS08Nzqypja3OIDy*4VLvPS04k9j{zQpYLS(H#1Ybo>6 zdrFPGrnExJ0Efhx5oO31{-si@=djXV!cJO03}Kw`jke)@coao!*)ro5oSflfzx^od zH?C*@Yp;_G25i}R4SVjmg)=HxgRXJ^qWATJBjJYjmnB%8Kvq*a*!=crU7D%F^* zD5%w%EM02z`U^ip2}POah#+Jnqc-Z^D?(=Hm#H^f^wI)d(b%LwEG<*1RcW;*2xUnx zZ?pe}$4NV9xNvEn*|}MEZQnwfEYV#O9Dd^{v*+h2QbV4XG@CVU*mDcx&2>Ea-NVeD zTB7JX0_!s%r8O!L1Um4J1@E9idgXdo0_n*6#jl~M*U;Q+#JzJ^Tr1+Hhwodx@`n?n`{~PyPwx6E(6tW&2In zv-9Sg(1G@M?!wRe2bF-NObLZX7K#_X`!olidzCnIV0;9lk*J}zWMK=|ZM}+nAAN*G z4@hOf$S+C?iII}Mx8KBVcicuO0@7Ya+RLcb8vN+9-{F;SKEtI8m-zbMeUd6qj}L?KwdG>^+urYEMkYWGfbTqPjHC6F#2h*cfbetrp@@0xi+{tLuN^@LipRe64Yu#x&c;pau+Fe%+ghr! zg0c!7gjg+bks!%4sv_iPFYo8m|L!xKKXZXtRfYy@V(0pz zQFLcKUzN?G#IuRe&hegGf{6oa&jafU!eJpbH_eD{g(v1`|E zvR+0Icu}B-9=@N4AH1J9YT%qBj5I;0NQ#^|s&eVvB7gRO{Ci$|`n4hZ#Q5sy&@Kew zsYuQlR=OEMB_b;!bPdu>(rp*Gd!jb*Ya$)`wy+NO)^M@!3n7g!u6xu6V zl?6cGucZc}`IK#Q!ZBWrad}Rj8P?shm3<$2fI(1_k^`1NXtdBcCx|OCm1<1T2uNcn zVu=eRSuf?aXI|p$@zY#2a}AY7liXPvwUCYDYkB>dR|yJ*GLp2{_N&)1KP_AymjK;e|2Rd1mR z$D1#_#{7v3WbKqAhYquK>o!`g7QJpCN=w#DSXo+Tabb~OzmG#Od*Kpa{=(n$%=e$C z9C-EoZqnwBLkHNoV>>ffU5zLT$|T361zD1iXF2VaF5Tq;&;RH}zVz3Raqi?S3Q1Xb zx}A`UReKGA?{c`2(2cj;057V-P!L6|&O!S@1l+oN*-!3v--4eS%FJH&LIc zlT#3cdMI`RS}H0*g@tqT{Pkb_HS=c|spy!Wy}qBrhYz!N?_Q=Srzmo7*^y>_(rf_I zQV;4Jd*cM3{`Y^yh10W)*IV4QXAf(pCJD8oUa!)qH_%aqxLWb$1}V^CKwetv)h1~_ zMkA;(001BWNklRD=`) zt+dz5s0gmUb|Y8q*zAKK`421P3-`{pfB#u82lNJAW>22y;L~sNlgD16y)vM#9M?>Z zBl-#Hz)`zl4Uhc(N6>3xQkmk)g3xN56(p(GluYx4EKeAlnxbB9uy}fb13!9|gFkr{ zQ9^C9$)0;}=bjJT$71IUU;E5gnLRX1#nw6pFhaimkzSn zU*^1BV&34xM+zegw)N@}t}&ivUqp8VqDlxI6cJ%vgE=S>z$ z>#)Kiw8MraOi1qf=zZ+mw})IAgbgVAmMl*xOa{s!6-1SYJkQDVocXy04nOfa9P6R; z0xb-AWNBPAMOjr`>MSwaS;9t|rR7CTmePzOCadG@*mEOWuHDZ3$$3sZ{T5LVa@Aoa z?6H35)l6<&iyo^nxp^InofVS7fDO}Y*?QFsHZvT5=@2h{=UG(OLDvuv;EV?ia2V-T z_*JQiRg5(yx~6EWHtTP?inbasxoI6*$C%8r~Z^CNxI$265Fqs$j6iwhhUo2;uvi1$@^i9ty7wvbv= zZ`EQx9sB4PyQye7w7rbV~?Xl z&8C@+WJN+8M@&vlQe-)A9eRtGo_~SO@dh?9PRl4%k|S#YZJA+O0k=MUH`nglgRN;6 z=H@wf;sha{-n7_l6INn+7rHF$zkpfDn4W2|?_=+yr%Ec#Dk4@`Ef|{^r{C`r>4@p^ zX@2nC@AH$t{U+6(Am|FJwnCnkLw`LFE=EA1Bo*r^I3UsWki1f`q?dT;Z)C7_c}y%j>Va&Qsrenx(VLtcxbu5sx!AR;BL-%-p<_ z>+avj+HG5KQXrI|(x~F3MVo@c8M1!Kli&Cu-~969tSm3F=g#Z+$j3jx`gLp3LQ#~K zN>D*M{6GN?9Y%cVOONr@FMbnO1Qbb*a9)eR8iw5FVWbIO#{dPwH(r3t9r|IKKZ=T+ zm%8^gWZ|PxF{Bnb;T;~lYi`N(`a0ESNSc-8S?Nb_jUgMPB<+M)*D$$2#)@{oO{E&) zoIz@6O*YX{hzc}$S<+8Z=oxJ8kSg#ECM8JHF7-wQ>x|a~Fy5X-T2DXphL95D1g3NZ zGC&%ED=fLvn4x&JuL}EdLhIacV98K#giNo2si~Oh>3}FqFhv_%CUiS(-)xhTdZSKO z6qL>}J~6>nGh5iT`v&@5!>QvdoH^Fx(%F<=+u~e^q(K-+l<+_*gBYrC|D$(u+k-bz z8LJG<^xhdr-<35|@Io3v5RfJb&f1~SvwK_p)MSROJGZj$(FYjYGKEx*zyG^0^S}cS zv3ctj21SMp6^4>}P-X7uMHWsib7J-wRUMIMB|6ZgS;E@ZIKTS4A7bOwG+ID&VvO0P z1;T1XEviryIZg?xag|dq9_H_l{T0(wYxtf2`ct&7SwmnQMQTZ%!I_*&Gp4>~ify}g z6Gt_k{=w6H@h?7)bP9@+KnJ9`LC9f4##)3>!;4Ab0>_6w{xLS~*}=rxb+pDOnVK9Y zti_B^Pmr4o6=|0mdgP*+;az;_ipFf+jrw?Fd$`W z!#KNc*h;K5qLh>p@**cp1ODd!`Yb1w4s*@S7Pj7T9a$heWk(B2>+7|RMvXivNb-#P z9)6JZ)iJ*M=U<>gOxXoliOI7RHPiQV5dX3Q~KIDguFwB#(aLQ7&G*#5ce3b?&(L4))%*mm*8O^JG4ZON66zzLptQ z1K#)H2RMKJJg+^!9}2LA^b{*O6n{2=^_Is%NN`?;+l_>f#mL(oU+Z>qNa+(pOOlbu z=df;yPmNs(!b+-PgU-c1?Ms~@aotZrDd9-^10o%hB?VH16j@2AVy_RY{QUf2F2RTa zMo5hFk#9u^(tbi*)4sys98pju@0WzycfSKPd60XlNuf|Gq$o=A!VpF=NtP2RFTIF0 zC7mIzVcTRGK8q zyB?__a@d zm?zbDc)v&{FycXBUiwx0fYm{|QLuSUWz> z+Fe(1^RL`ZbHgNkn^O*QOytN-Nh7GB@bt3O7p#;y_{mXPv7RgKB_gn zZkI-_#?J#l<v^GYpG zXYHzB_~;qor_Rcv@SIj>De`O>rAqJFWi7^*C@F};h8Mrlg1j(jC5L(n0oHmDDN9dC za&pxCf+SA}!-yiy{C71BScHghrN9}VJec9AwlR(*&k#ZqMiE76&_O^^l-~bK%F!(B zko)dd)y2xvpoh)kY#^D<2K2f)-A;v8E1=a1sMjRbYK6KEFr_13(abGo^tx@*RM2a~ z^1LDGDnuEh@D8zH(8A$`hW$QO;LzHkhK)^Q3|jufaQUtUQm=~RKbw)xoN*3=CD0B^ z$K>{PY}m7fMbkk?F&9o>;*D1ia^sCRcu(uHB+?bKK}oY2GAIX(ZEo@5-~AAOdhiHY zH%C_$_k7?!Zh8M*ESij(Qe;Je(3-rk$Wn6nx!1UK>>_d88r}$t0 zr+>xWkKDr@dv2tzB1~>bdI?#U(=jPCH*9C^hAB!>a_57$GBw%c`=90Ch_P_iJCr%vYp$~t6P{kyjE@w`hV0mScy?5S5hGosh zY3{i1ZubB505UYxsulk5pMI3;REx|NzPDkNzd)?vts}=c|FaXM{e%nsMV1$rahFmm z3yyjbaPF0p{OdRVXA13D>~^WO#>w-7t2b|A`>w5wZ=B%TeK!)1$4Kqib=UO-QOFaY z`8qnchygeuumS{zz&ec6LuUeu)g?E-XAjl2O^78+i*0`V#1A=l;v9F~eFuS%gh9-+ z&pgMu!^imWuYZtQsHwNA+3hj0Tql^qju6%Ywun|%W zW$OGCRB1hN-cSq`&xWb86T`-o7f%)lisEvnCX}C8Tb<%r1!-SO7$)1`EJ7*o9y;V# zmd00lrI5ZzA-us};1sU(5{4rRhAT_7lVBX-@bAqk%gZ<2M%n@nJk<-I_G{%EbiGba zGU%|h6ri-FRtsq~D^#ixN=i)DBhL+G4tZk85{Dv2T8S3cHk|d?ltYZqn z@t+;#@y~sOdJ^CgZ}1hG5*G>Taf`WyIllIVZ}7_3pJLnidR%5HlEP2aXv4`{xAXqr z`ZZc>$4K&&-M8-L#B0ZS_0%(Hp$M#`9G(o)$2Y|FDx0=mjg1r$iZ>7Zj3*xZDy^|P zLKsq$QfX9JTAt@e-}@eG)=aW>_fE8wOiZ+>kJoV&-1mV8n7n!o-8>`94f!A^3^ZX7 z(WtaIdG-yS`pS3cEp?c8eNtzc)Z^?Py9Q|sRN;`RrJ^)-IfYsB4TSFgv%GrvEOI>H z{E3s?^3Ywhu33Yt#aw^qZ5(|55XWYJMn(APq>=7W=tJNnlj9S7>W}{!|J(oguUT4HB-DX#E@{ACk-IabJYC`01fyE12hP=6 zso)>H(65})_X?7~D5%V80QmEcrEgzi^)-Hb)|yqBB{5W;Vg$%yqz&XLT)tlF0bDAH z__;k?E=usWo5edE5ylp%VHv9^47TS-7`P(^Cw}f+&tD zlZ;Cz&oEhQG0`0NB;i5Mf#+W3;=!XVoSVfshtrxu7zQR~&DQnQH;>VlJxpYw%*fIK zNs=I(BoF~Am*`Yb&qCIeRT^DK)hWV4;07f!afAa&GmELNNNUT9@m`hjZiUTujAJhz zp|_c!kQ}QYhv9vEq=hQAbx|uWT>` zrC{Uq1|}K}YEkHYynr;%kXjMQ5R)2AYKU}1SW0v$5CxQ3iF1A^p|lQDIurp~1W2P% zg+LXKs)|qs+DmPcL5h|Efz-6>4XSZv=(FXIO-nTdy30|el%Al!N_E0__ZbRZ4?PLr z(NE}|A!taK`niW2Zgcd!+Vr~OA+Pw^zic!pVLh+aIV8jK(%T-q{lU-ueC2kBjWkvp zX77A?`_IF7*tF6}5g~Yt$?YL4J5XVa5lo4k(02G-2Dw^L@j%#eF&uTLk~j! zau9`gE0E$(3j_pOk8G51ri7twvcgdfDhMMevXV5-!3olS%JSS25h1;~E^oYifG`ex zm@B+lUcFvttkp#07^~M&LQtB5qR1%9935$d_EAGvjW7X}p(T|$s;0@^v*Qy=X%>A27Xc4cG3vmLSxmN#cP8L8vssLL5e`p5ddIq)c;`FU&z+B8Tsx z#B%QRc}^TUM%m4|aQrM6PG6u=A7|rL*I)@i#fX#`a+p1sJ6&%Vfbt$`>Ds&PQA z5feq;XwOMO*r;Mdfvjo>pr7|K+EFM&E(>yUmg&){@vsqze(hVa%K!`a>HjOC0HP&8!^ z7nsmcsGMA6h}dC+601r|nPYUpK;>Li3A0hgrAo#*(V-lV_?3@+gz@QVln6L?@+|-N zpZ;6sXXnvU<4QZ!T)iBDjr2H$xEy(|f~B~^iusE5^FSqqLsb1IqR>*GD9k{8l8^bpL3V>UH#|y&Jd`ScLwfux>#fXlM(5=GPMWaeDSul{+6xu zP?F7fw?&C#@ze#b-FG9o5KOL{X763M@zPVz@y#c`#clW8&ARFJ%2u=s!>r%Fk-`;h+B(DU{Ifsg#UDJ&51;-C6GskGBq=z@?f1TyT{rKgaE{n17S7M( zGC`+1;LCsW6{gosv;D@MloDK{f*jVTQdQ90JVoWI32HLnrp8sY^OTDxXK7z*Gu5aP zHLF~A=M97t4XhOCI7S7E)_9A|WY_@KZ`nwyOX4EHEu}p9g|E{+eUaEIO5AFV%43Vb z6ox=6&zE$Lx(=xaA-$x_hMDzz;*WltEXg@~1YA9_^5NNjDxQz`P*Kpuxuk*tG{RkbS&>Vbi zKZ8z>?K`&ek&pcvYu8Q^NX4L&5Ew}$6a<3ix(R}*20E;8{LSNh`rrNqr%#+iSV57O z1S%NzhrBqqb613Fa7E4Za-=#+n^$k2SAfj0*EHP3W&O|9^xxUl5cYB-%lQm_xbIO4 zFINA-sPA*dU*N@2;O!Bt9L27_?kY!9S$HmiyL?bXKoeJ#6oy8D?uz66x$D{?FvhG- zd#%<3R^OxtPk|T$z8w0t38XLtDp=j7HO8A$3gHi3jmF3QwzbmOD?YDZw%(OM>iNt9 zslD*9Lm*^;EfTC1C>3H&%F5{rr1Q(@xJ6PX+<4b5+;z`B3R#k3P&(%K{+mC-%98G& zgDp!!718cz*nUC14Ef1do}@9>V#hsuNo7eC#=b!yyamV9#wq^rzxx!`ASO#PrdpFc z|E;I^>gPX4PYn3T?|hW^JaQksP8)@H1PxV4qt;-l*JksM8FHIZA!KE4iLZVB%k+-S z(hwo3Es;w36GjYud@O`Ua^c_!rzyGP&HTovexLQz)5u1E z4npQnUE+WLZ~qq-yDQwZ=LSCd$NvRgm1C73P3>ptFuIgT30azWHK&!F$3OoSj=gYz zTA^`;7piu{3uScijwX15K$4{i-}=&5`9S@{%-nblN!}-(s8S2Yc<}10Nb(#RML0Q> zq$>-wmCT+v!^t;~lJ`=2-GtYE`UaJWF@FD3zlTr~9eUbOUgiX`Vq#{R_g?b=_y5+1 za8{y?;%`3vS-$$kFLTd>`*`24J;)&KA%&#O!5QzTRoIehvxd?EXHT8y|NRet#nHnj zaS6Cmp^!K;6l-2h=`X9syDI^LQA#`d=M`b&5RgW|cO@0-O2}m7s5|_#5x}kD<;Xq4 z*eibjbCK`rKJeaMc$%1Vc6CqyRxx>4BNeOaYoqVp6JCc3R>M2P>hX@g?~#!8+xE{D z$1nnDi79>5XoXw-IS|UzaTyLPxRIU#t9PD}vK9_o? zYV{i3g*HEU;(P2X?_&3@H-lR z3I>BdDo|8vRoo!w(9t7&%`B)#tl=>bJ>K`kyUo=#@4CqtP}bS2W9p z+7F1!fVmnJi+2Xm)x#ZvHUgX#I4h7cL=4r!q|`pLbl`@*VgiX23f!;@??!djQ3N{L zwp(qI8Eb|jF$!z#I}-6n>s<+?(m8}F$r3L(fRvP0fKbe}dlZ?WRvDwTA&2%K!&E{V z>nCZBk1;XUpc-qkA_rX(ikL7ADD#5lxh1~zAODt%N6u0$0`j~-g_;w`&$0CQk69Y@ zShIEwl{i8xNqc3PFbCPg5fe?(!OSDt^3t}eN5 z;YKRW3R#(gRH)KYwiBv4;^M_iWTxQ6(Gwhcbw9msPLer<4#;yyt=eG!i*K@UX^~I< z{wJ8(u#wJ%IiwS0X+eLGAu16o#R`|^=Q;l7aZaDQh%|zqJo_SDRdVC4dl;LXKm{6$ zW6|Kh8-QuD1Zf0qNV9->-{(WPTkWfCnQ z?RHqdaRar9FypS0W$Kka`4^6957cXg@Y0~h4%2pTE90!e37^7C~*g4@zQKQILL8X;eY=W?`%8y0sQ5l^@7} z)wJJ^jun34`SLz}DsP8yr<6b{kCQ>52!?{qQhG;GDJ5lYDbf;K3PR<-S1khq6`-U- zONr8wP%8rM|6a!u)r8w0xsCUJ;613STvdU&AfpI>K5egA_FfoZD>1F;Rl?IIVX>)9mRY#Wf2?9mC*T)nF zt0l&Q)&XVV2ttjt4qG@vp@^Izat3P?0tt?SLKtkGqn#xZf-sITCdTBFyZ|L5u$E>e zMq!6a>5@oDjIced6p|pZfRfr;qEeB+#Ags2iR0J|i zaAlv03J9w)y>3P&EojxoSy{=jr6fxVf>6NuAnU4~JM1YzPmjTBTGRiqQFoLgdI ztU;0nI3qA+F$5+*x-6x{I)hlHAdQ+YmveM^h0rx`i#~_NzSUUj9n$*MYr|auQlrT9 zo$H{h?IAbxc}J|)HUXp*mq}9soNx#O!ddK4bqgU8#(3s{5T2AjJPzdLNLDz99J

    )iu<$}SPEBn+U@)YR&NiK&pdst6+GxuHT5N=XoE%EHp`l(d&D?L|kP zcvg=Y68t?6Mq-7;3Wg8=UW2eQRMYz9@#eb}NF8Y51rW4G2|qt8Skno z1lSyD1v)CI*8_4BQxrA&y*|cDrY0wGEF-L8tQ9adUB{&Z>S0Wt6a^CUc8jvNXX|YF;rN zKeO$I_8Zn3R3Ipe604v&(W2MsQ466GMi|rQ)_phPT+ZUs9BbChke8AdUwW0iG!#~1 zYB963U8W}2Gc_GD=v^eBcwop;ev5#R{iR zE-*3KV$F1mB$-F6lFgfA_T90K<((2kIAYnpj-!tf>{>~NbFr!=MW zIoNs==UJ=i=Eu zOY;M)2$3rEB?l?7NIxO!ydH0eUOZejrpRn5ZEDi#92pK z8p5h(}6$Wm+x4)$7;sR1lkg)fR&XVDhQF%Vlrsfnv`yUh+ZPR;ucgy2D5{cFg^bl8j2x||r50vjml&UJ zGBz=w-MK{HoT3^OY}rwx3}T8R;?itNT!Hbih<<*G%^MpGI$g#a74p>3ny8YM8F@Zn z?V2XtcAx97zm;xJ@uMH_r^wqVBrs$n2(Z#WqM%mDFk_wTk5WYp-T;?i6KF zFu(i?N?InSTFfoH%GPbWShuNQ{l=?VyKXy=ef1|qm4cvFu+qK2t$Q|-E}x~}Il!5d zA!*S=MIoJ3ar($>#C6Gz?IByX?&ka7KghzO#uN!b7%(%_#F~`SoMO2PVKYZbfh$*d z?YW;(tJK(g>mELK%Y%ITJFoKXuRiaiIqQKOk1h_Wk&%9@bKol$U{X*tjW`Z!}5V zun_8ossCkI_lIVE#EJ%I{qT&G*m8Kh!lJdI-qc(@Ge)JFV#GOeYbnbv))}gCgpk^6 z1DK8vEQ}&^18`Nwrqd7K?#X1y#uk=Mg51@yONN< zYFjG=fz||pAMv`Zq~piiGTS3+7&dRIQE&BFTs}Z2IYQW4AsX)>8cWO#4)fNLACjd< zS-0Nsfe+qE7?;Eq1@xGjhHG~;=yng1WQPf(i!^Ergz6koaDgb8rB>@O*2;MBp}o|a zmZBUW7!c?I*Y94-+BFt9&)L}*G3p#k>0#RDII6NhH$BY6x|Bygu!r04*nxAIk3xp( zK*M-pIH~7PZ0kxNO>03MOSCGvW8W^~dYh?r1|2OC*4j8dhl&>HC2!Ga^;o~&@QF{{ z%k8&q<^Ln^&7Lf~uJg{{+QS*{&9R2eDilzds!$k65F)|B1Zh#GDYIpgk|kLoTXM8J z+TAbR{ZDj6zjX9Vhr1uTt&lA_6qGE<6lIDugOVuD;slB_P?!oeXXTuEhjY%J`eC1Y zGm8Kb>{sYiWF>GbZ{B;)*?XO}zV)r|!#BjX!*?T|eDZ$Ip0gygiDQF1dzX3f>NmN$ z{Uer6C#Ky^T)fRQ?|Y12|Md?M!Xd6bK&y@i?p@-UcU|D#bxUmzsq_Kj?yxdwIJF$9 z)E<@EXLRr)?|bGE78gBA8bWkOL9`cjjw%w8kYdhwLdcLn3WuCotGMr;l2fam6Du9s z?4Z;>lgUkt9&xyTh0`Y!Yo|5ud+$@!rRnKMP@2R8_n#o@UB>P6nTa7I9WsY{K~871v0!$S#F9&XVj^vt%0+0cNVF|qpBPnZ-jdPeC^7>Q_!*;w$H`#};R zPirYaqeS6qoE0rAWr&(|y4XCb+)>m?ks{-i{V&Sem!Z0npF>QeBoB^p8Z zhF;Nipfq(+U}MBZPh`r{i5hJ!RlP`26x723d$*@_&QsYTq3dXy{Gtb22P`a|AgGqT z?K?bn@jVy>)AK}C3i#<5e1{62#kwFSkDE9`>`2{&+77sJ?K!OZ5Jr1SYlx}nsVb6* z>U~f};=DoPeI$~(vkPU#^x%NnXu6R{mx}3R!ur}7iiL`%X*jtw;P&+^q!3sbtbpHV zAT>HF#05g@SXdZv`_>M_azIrUbg{!wFeoaz&eL@hhJzYwOM>qyK*1y4GcXlR165T) zQYT-Z4P$+{>p5Uh0l7=iR z*|r_E8s-M51e)m~mpTEP#8^UI}%V<1}RITYbcZu14vRNA5bab+Lqnz9g+yTFeqIz zo(7bIH0h91XeSL42N{1#s-N2Mh&B*%Mi5*8C1`DkE;lT+66)GgXjrLhs-nPmj)ShF zFq#+=qO!NTmV~IpV0lO&;X}e0OFM1y>qbp*f|iODvUX%q)C|i7#_gCw3r3MgA5$dw zz+hP7LqiA+Rz+gU!8=3`bJ60Cs#HYZQJ4ZH78eBX6G@Y;aZ@BP%Z_?(WzwjW=hUd+O4Xzo32s7g9YzV-w+w~~t0U33kSYp0VA=(|YVoNf zsR&Y{bi@<}kH;s6H3BMS5e}^wjT>An2`+PAy>s9rgUZm2N8lWl(Ue9*nu#1o^zlif ztjvte02`T=jWYi;FYEjDo{mM&dG7jpn5pE6zBnJJ>^t)5s6i!?OL(m{!FMRDXk!b7 zMHd=dlys8@TNU`$Ln60oQlA5Bg-anj8t6bsAxqKCnqndK(}mfhnUHy)GQ(XZCk96d zMnWs7E6w`)fYsHO;lL9@penLTlalOlHmD1;K{x`1tRBh0g8bN1j3zxXxjVa(+{q&E~%m4E?4Iq|8RVjL8}4v5_-Unp@kt zsl#f87LS&mKGS!;%feEZHs6sGXj?+c;59Mgx+z+%;C*%_+&>s0(m^sr527?7d9>1` z5U>&{B!5>}B?t04;sWuhsS=k8oDcYz(7Hg;(M%^0T1uU=C%I&tEJiT4 zL@A$fe2Mtj;DbXaLy8HN1Z#ytml%ntK4=`p)R@I{b-tX=d13_b5+sFI!suY1$>;#3 zO>c!LRm|YNL0D`)Vhd^Q^X`fDtd=Yn6!@4l!T_6j}g{oP1j8*jG&5yHmT1T zX95zD5Oa3vBu|&2b7?EOXHs-N(`V2KHtS=?*^Kn8p^?uS;t{getWsH$&4-pKf(rp3 zC-|61Sc;-zak$86?*P{Yl1`-P=-Lh+JwAD&f?zc*&^b@Hf5@Ugwntl()?!s;k{nKhE-a>Z$b?7~L0ipC)v51)&a=aO zWLRcCHhL^uJ7RP80d+>rk=Iu-dhO20zf(z1uIfqZ!ja3a3k}s`i5eK5`OwevYrpjy z=-OtCR4b-!%l*#r)Cb-rL`8l?3-^3bWJWdov&8siH!jFIaEbn~(M|ttZ zYg~3)jPH1q?#loL%4kIEzn_5=@}dkeFc=PVwxu+0dOM=I+JB4x6aA#|eapN=Bug~5|+4lD8=yM#5G_TyeLU6F#)NGBf zayYup;o%lanR)51m9Vt1z`1j$uwrOqes{5_n`aa{XPH_G2${>Pr65T}h<%2mNG1|u zIz~26eWn?EIX0caI(%+4#WW{JtC>B77ED>>?s8K2;24b$NhG>9pbJeD15%*0AxdHz zHI*5#AT?*Eiu-oP3=VdQDNvB8U8Ib{NC#|HGx_*uIQ`spK6toC*X?qusaTBroZEht z)6;zl_DMD}P9CQe)HUk#3G8VDSV90qqh?ul-}0H2?ngy->KU5HGDTG1c*@T^%0GXa zcIRu4l#WPDiFDM^lFU<8qAJ+%D7M?SXaWd66^c&M{m$!_ujTSi9#@%Hb(=y$DL7 zQ;Tn=oI3pgCst1J{15(?jT<+ajuVxw8BO>3;SavW+u!#=-uBK*T)n(QS1H=IMN8e^ zZ1c_U?`0s3Db9I!rk_GM8vp9Cp#;O>B0eaJdYPyf`18+wgBPv_Jb*xvAuPNCYZT7C z2=Wa|D>Q9MyrD=q5QkElGK5(XmuVD$1-^Uv6+ZC(chc!awhks3>q*iPqQMqLM*dWR z)f!_GK?NL%&LzsC!dQ*b6-ti0zjGF%dMU7MOA$iovx*!{vp7p4`AAd?eC_+U_}-6h zFm=5}(D7#QY^8ktGiVV6lZAV40N>9dEGk2LgqQ<=RvLh%`ZDkR2M==Qo=Z4yf$V~s z0;J?n%41Bx=!6l$lq!o$gwQu16kbVIbyuKm?xxSQHU;VL8@;)akPYL+Yrp(3;qKn!_#!Ysu6aQ2}iOVm*4HW~e=<_ok$m?(pc%Jys60HFp9e3I-wR zNKqDa-+GaYA@R1sBF)sHw-w>}?{YGFsw%@JqUMsFIIS3;T;{+IVA@cqK*Z0>qo1TX z%`Zmg9`$qOv+jKFJH~8gzJK1AL_MV9&Vj>7^oq3AZY{PIUW!Y}{!ue0k%B<~q- zZL@!SgJwKItmee}I%ghvn26^$|GR&McY)7*>NC9e{m<}^KK5afI1(K%J@*{n`oiCF z@zSF#ub)IJ!|8j@;$z20KK2nN8;5-HFTQ{d`PxK$uYv_6A;!qc%8=C+M^#3wjnu;d zM2Kz97Um>l(Zm#K`)sTicI@*;;qtAP z!@v4AzxkU}v}i~bA{wnBNlQ^h3M&lif}&7)GqxUyLeYco-baG(FseprA!4##XYv`w z5TSR~K_S$l7=}a{!CJ##e&MTp^9MKZy{LIiy}{b7t|XDeYc@BVWj*~F1qt-}6Cjq5 zW)>iht!d(~zx)c1J#m}&Kcf-j2n4$1Nj|}}WuOwng^HqDU}b5ENMiTkfc?D##CI57 zP>7(S$4FNC&v^7KutXAF&UIbDiZDblVmWCQldbFQr$Av8%PS{2_uxs^R#phD=eg&e zXM1~_=sFUbX*(vyhzSbDEh|NXeD&KrdTodGy^e}3m*^Eh!o)=CKs6n8zpheyKn1-Z zV?L61lzr1(r`Z{eEN|^0fBh_6yTQm2Bc$}A8}lYpVvh66v95l8 z;dFGFW|->iA=S^b$K$$B$DS+w4Ga1TK;gu5`urKjZh|s!=lT}^&;R~!ak~>@>xdG0 z=+O)O_W$xfuy}HXMB?nZbCjmwskgqB5FI`_KL1}o&)MZ|yXP$| zoW4l0e2&fvNXE2FEP^4K%sXBa^ZpJVO8b#7hR zrf4-b84MPbV6~vr8;8<2C69D=XZJp)xX7vK(r`jv(HX+7z-<_i(Gv4 z5uSSb9lYm#&+x#*4^h>I=sMbFO4qp_7BE0Tq?gZ&fiTO!l_I9heOo9CR;!wO*VkBG zUE%Xz{8GNtLZ9$t)u@~{9({(n0>xZCJObfpV*--0wL>E0%u*Di4*u#3U!!&YSO%r3 zicHz6ih`x3WgdUalU%s)2p2D2;_)Zm%JPX*3xVv1m2XO;|m##6uS^a^L+=@cY02XMFyP-{S4>{(0)9Rgz?jVo_PRR|TOG z#me58@<%Um?_tM)+03`hd7a0U-sWrJD0l3=kU2WH`7~w>Qvri6anH>IuK&>|DW_R$ zR?Rq=X(rVzbIerr0ddX^o!#f=P1C!-((!jB$G-RYCmfZg^WOjLM>!HhnFaEqDzK%+ z76z*|u?y^P9wJ?VYAdv>xN`X#pZT*-(@dr~@0c_b3TtFmDfAWX_i9uQS=XnO>WFD;+g|U#Np&n|Q=@=~rCD}CZ z+`SKT?)>AF!*#r>2;`=tNf8@CsQ@P66$Cq^UcQG%-tshO&!5j??UKp>axa zWU{mn`p=N3YjWd1BKZFM?2CC&If@xG5CcFH1itsfO_UzuJ4K}iR8r7%9a5GopIqbg z+536;ktg|`|L{lrum9WsfhvYP_0D%?92kfp&Slqr+R=tU=R_;m!x64^Xl)H7*}tO`TDnC3Z_;^&2MyKEgff7Oc>yFje)G)l zFRzExe?d}rKPLV4&P4KjPE~^Fp^k>{{`p_Ck}T23BPx8ac0VWAa}-2p0>eMcSB{;> zO7_{~{V{{OM9Ewkel`(x{P}_qI!E#z*EA3#ql3fDp=~`~7a-}LL#wF=c}lHXs?mjE zZG9bMEfY84L%;GNF23_&Hrjm-B(U91iG^i!IOdQ4;~(;S|JVOZ?G5puqf8~t-B0?x zs)VA*Bb-%T({?S^XjT>%(OR)`>LgS(N|&fqVq=Yo6*`t^3M^z;CJE>gGg#u}y$^D7 z{a*ZR`ijVSypJNY3TDGQkcFSyw&|-o6oTp&SZ3R4mdWNX+I z^8(HzYR3X9F!wOdt)bVxV48)eqacur`+oXF0wF>**qwfH}_2E(E=!>0000W07*naRK@%nBDq}m zF_21)3jw^#@@z*g3$xJ4Jd^G}?_Ju#cb(MN`OLG%M>2q;sz9VS8H*9sd5Xd!g=Oj^ z<#2_SQ}?p7-!O54sfMhdJ&h_Xe%dm#5_v-{N>SNrTM1gts4|MemN-A5^&O4xSUr7) zg{6~Rx^#hh`2>h1p);(UFkvGgM z&S#-}2D%DWSu(6Eg7+A!*t)YtWh+dyprC6ys1;4qF=-}LixovLJ^9VAe~X8oxJbEN zar)j>$LQ#T z#|-741yv2n;BiNfi6$kL%Z(lld*^%K&8-(Vvb8~o7+vH|B`_L|(AKcLvVt-NtE(s2 z*?yH61*J7bQDiZRexoR*Im%;lmXXQ&d4@aatZ)E9z4U}y>$Cn8F-XiA7OJj zvpQ;(^_y*u8%zFtl9i#;aEtuAJh%@4m!S zPd>@bD?jAg)#o93v@Q`eDXQGOL$kHE!2a|k2h#(V+JFjqEY${>mCrgaD1H*2oSn^C z&69v4%rf|Ve#K~Zwc>66`d8U163ls$a^%UB;CS4eU)S{iqiF1Z&s-21AkFNY`3Wh! z*sswze=W$|R+l18*HM%O$`}UqFk{^TR1^kwKp=4Y#!cF`VR3bckg!pB_KV-f>Vl8{ z)<;nbipMWq;)zF}Af)U};o6Qu-pSxp&7b^-KSt}4@wUU-LH3qUArEWJ@f1PC(lkDE zxg`+0?4E#uWCBSCh<&GDMKZNoA*sk>Dv~QO=Q>OqBwq8m?pL6vNL z7bOeqXr+5mmY;sSDFbOtF=M0ivgLTGbF|3vB97d9Zk-SR<9G3y&wT?IkM7m8Fd50z zp#HidsU#sNiI99&UYd7WkDeuD|7;cEtxv4+)Z-V}eEC);-iJKDn@Ef&hg`k-GHuuK zp7%aYRWER7>lWYq<~Ny6r&J3yB2bn^uk@2kd98E9i4cgY7ao)RxjOGT2pws+LoX#h z{EHvtNB`~*2p&XbGJnSXj_|W|?C)$v+NZH9WoAH}frcPDkV2wR2^Bj|FTn@i{T8e= zSer{Qbem;XAR*(*5~ zsr$frl))yH$}{e^tSAOGNra~B*grU+C<;`Y$4BTH73a>LWms3ZwnaywOqQi;h3|an zSsr-s0e=3&|B&&j1Z3urMJIy0J(1S8-a6ec2Jf(aA$wrNQ}D{<04wuyyNYU@N2*Hc7FJS=Xmw%Bx8YnGfeu=2F$U*d}tJ1R>esP zW5E0T0b`0N1w#uL&MolnpL>k;6^jZDMr)EN&^2|X8I%Rlcig`5D%Y;x!~m`9xcuWW zJ|v3Hk;oLT87Vx^ULV8x`pVNvR@qM`60O21Ayp;1Hkd+~jwfv1yv5e7K%6$T(-ud> zDuwi-(DOB*H7aU4UC=(V#^z&Z2{-l_9JH7eNikbps|10PC=pv$OeR8MPZAs?MwEre zyGieG+UseGkhEr68oF~QsNefIoL*vj6qp4lT;odf9VvC>b6IjAji&$IE_hF1s6rfW_>h|ak?yz;^W%jpj6I_cf zEra0#r%tWWO*}grdxTany6n3l%+33bRQ+H7cvA*a$O~x}NR^sVP4c1ol1hm}s{~<0 zGrGx>m)3auk9txKYo_3fkz)d%j1uqVR!EaTbmob1YtuoHMUUr@fN3sOL=0;Pjc5? z7x^xvYK+NwZPzsDo-#F_PH5VecsOEdd6lXvz&nhwSYvt^rWf&@yHe)S*BRy|S#p4= zaw(cbBii6YWHQb|)!K!u^;sB{Q5dZ-)}kaE6N)4%TcDz2XISv^#S`q@GvrJsSUF@;7noLD=FwiZFLxVVHV3Z|0=uM@8AxOwe1rMJi!s)ZrfH*fNL z|MvI!=l|w6xc8xR)WeF8{p!c~+s}O!8xpRELuONKg5X@DX%q+ho~6YBqACuij(R+1 zZ)=0CS6^V|)T8+6K2lcT6@@W4AF6-MI#S zL@634Is1}EaNe_ea)1syoLwC--r8e9Eh3YI@s1M%g|xSjW<>IPI65$fgkg1Yh@b3I zSBt2WsOv=nQ^E`;=!2h8I%koGV|KUqsp}!LhDcpk^D=GLvCkv02Bi`q`J;h@6iF(p zlgE$<{objxVyK}oiME>}$unHCBpR&tEDjeiCNVG_njscL*92^Ufk_-fNo(1Ds)RCkTIuF?+y^Vy3;QbUI6`l7Kw#XAMc7W0aK?zC=F0@qjpwGH(@7NfR zT{D)3mh*o(sBMN2vW|FpO?a?WbjGzqIQlX4OG$7d#!NnF^TE;}K+rai( z#dR0Zu|OL^*@Bn~3Mq*S?s@1Qp55?#arFwaQge821v$6IwXngobtI!0N`_8+0%r`Z zRa_WUVC)>i$e*ZRi~YS~-ej6XP_yjxjgMKI=&r|p%EmtmrWwGJp5&kJzxgIr+LB>W zV|sqHF$!fsm6?m3Od^(f(9DH^vIRT)2XxAF?$SA)eAiQ`Li6=6f0ON(wpm_SX4*^` z4l52ew(+BUQ}xbsaCnd#LBVHn5y>WXVP>Tq61Q*eaN^_|&VeyQCSl6P<|Zqvi#+%2 zS2(q{iD!k?_4~Nz{6ln6^+GTcwl{C0#c|`xj|uIVYgeyucsN39g9tqO$fF1)mw)sU z`2Y#pUapaL;C%A!V$ zVbV<~1{Uu}#LxhV6g83tXuW`I14>|V!J@s!b>N8v6$qj@y|zMX4ZFJ?VuwsaZa~F3 zHmT6cpiM!F*~F_f*o(R)N3*7luP-Q(IZ%;`@vRst}`xD`UwDwpJ1FiK&P zqU^0DX0Sw1(4{d}=ivk~28`qkHhGlFnTAq|PC44jVvJ&?)0ADLtqLdvlQJGoS(3sO zT^K@Yvxtou;yaBgvg@g~k>mm)X>1#qlJEjmQY<^eYAT3Y=p~C+fSP$8~d70~*BX%b( z=O4Vl($XrS^Z0{3ChdfGz4u-C?vTHG_E~OhY#>P}tBSK{&+^tM-^%6ZU*h>6zs%&Y zL5C7;Eup8eh2RL@*L6e}D5W5!o_k8BUMy7uaQo;$R*E6voMUBmNYivUUy{TUlV$799!j-T!xfAe z22y5na+Pgsi(-(;`Pw5kV9kIOG~R=scC-s!77hxLq9}+e6V^>kNa#r9kwi%boitX2 z5F>>cEQaViv>BkR!WhMHxWKe&awg3Ovenx^Z}HqeEZKu1Up zWhz7~l1hk*XeqE#;3Gtxh?+e8q#~i4&`cC|t;8o!Z7o$=z`FyINrc#;7!p*8Ya=EZ zv`ZAKpa_<-H7Kuf3d-7M;-@5{%7QN{CL95SVz4;K@vYaj^&yb81GCMwpxAM-S2Bh+ zI+BLYYHX~qts*!!t;dd( zW+2ckkm^32&A&LMUMkTme(=4^TzKqp%Egl5$^!rNw?E3{V1yQ7VPVM1@-oHA8s`E- zRWrJ|PvtFFpS!}r?LDg11yo#>>uDC(R*6nH+#KhQ=Q+5Oc>c?`*?Q@aq)K8EBzYA1 zy+qd%LUtp4qvOpPNE1CVJ?4_m7-FxibTo&e2_|F;g;EsNfNHSFXzG}>J_m{vFs3F5 z6lKY9ah36CO4GK4*kMcE%XQTxRj_lo3)1#N95FY9@RS3Esw~PtI~ilJNNO>vpeTl{ zpFL00Y_fl_%Xm5_c$G_ulxRYON(O6drc;;IqO?KBOz1aO<;H-@frsSgRuNs}D3c({ zGHzOQS>ym_6v+jUOqFUnhd9rv)9VZd3rr_F7^7)ZCcdX6Xj9@`B)SeQ22*NGS>j?= zR39uZaNqfdIXGyDL3$se3LhM{93ZB`_YJGAYZ)#qp|oMzwG@LzPM$i0wnGq$_pxs} z^npwS9fc?wA>vU)r4VgNp+Uq@mBUQ7PXoHC!eFU~tB4LgrL9C210K5fKAP5{v?ir& z$~LeyT^FgBPty7k+8BgDNDzXM0+@1@^Y`CR(`a_KN2I9eI*-vcZL85{8Ep=U(c!K1 z+|)!=f#K;>oWAdV*q^d{XNRWgh(VEJCdlXJT6}F5IcJ-|ERcerR61&a9D_Y(Fo2RH z1=F9{7PDV`>?PE(W{LtdL%Ya#zVs}WD*45a{S)dFH5V>jBuYTdyqkQaK^U5fkN?ic z`TkeF$51VB`R^|CsXzJ@zwl50G1c+{kGM;oY9%b@%OUX zG!K_bqjWBJ)r_;J1W^fP15v}I^(-#0qg2IY+~9&m>)fW1C6ma#uSDN-DOurYsE4 zMxaoW199s#0eSNi-0!7Aa?|K)3J+zO;r^mL&i z*RLM1vbx5F3-{56QD#r{^Yg|C%O_TW6+ZJ9Uu0{$!FMnJ{`b0B@K`ue;9#k|Kj zui$6HC3AceHII)oCctZd-)lQnYTnE{a*mL3qE;1O`Sh2W?oavUfB7rKA|eG;gR-Xv z!9uF}#K%9$*Z=Apa2Tj`MXfa7`O0^BpPxe5DHS~7>y4o>x$TT4o8Q4^M|DV2e2)sw4L#KlO81;H<{ynGR>#w-jICswBv1-+`e z!N(F(V0$w#KG;U|0+C&O6p{?Nb*tm-nV$nXQfhJDlafK}iq&6HPPZJCU25aS{- z?qXGeQA_OY2=&5Q7KW=iL(-bg1r&4QvdPwMMqw4GB?acoHdaV(46? ztS$R{4PCp0_Yv<0w9O*7Zym6=2gKMzC6N>(DRz()F({A@9~JGiBm~2B>e$=!G_A0= z*AN*Y1*D`&!Sy4c3FH=4b-@09%f*XNGCjCPN`lcQm-eDEVf818{&$tuR386Aum?T=Y8OH2$p0gpd%WnH;oSd10SU)jW9N4Cl_RGH!0NyMK*?!!2BJOq&Ul z#?v$ogC?fzIQ#I0hj{WWPjKIT58=i`uD(3w2YR2k@U?ONPFC8HYR7SB}tgmgJ!eFmLa#VO-UhARH4`Lj98}cu-x3ML6lta% z?jLFhz{agS@L>HFSWkDLH zEib=xi@`u3b|mjH+Mvu5K6Ho@oChtItSOagJ+9SASYUFX`2MpuP&$jpWQtY4EmC$P zf<6OO9f?SAnv_aJ49`D*6=MUWOnD1RK{7;_GectpA!5vw7=#zT_f?E&j6T+In!AAB z9r|W-_%pqTncL`WjnAlkGpzf_^ijQT_LNxxubq^-i`A0y#7|ijw9a9)rQPW;rDFTe z7Po(RJy&x8&Qh5nWh}Co2pU5|qX?tG=D`Nr>JFhFl8eEk5+olfq(DSbnL(C(v;}xW z!uN?!$R>v6ijml3ae7im6fGb7GXiMJ0^Id>y@ko zV%uMXlo!#A8k7WLEJzAOd=7jm&-$mNab3Roh|805ppcZ`M~Zo4Mwj}AB|ZQBNH8Qf zj$TWk?^nS*^L(SyGP5;~J#R**dY#{R{K%7-ch5iC$`A!?QRG14GYzR`zSs_DzP^ zlk^gKl2Dlbt}S_fx}See7>H{AZy>$$JIr*VGVjyOUNNr^DKgjPz?(tB%eg ze%rFPx&)mkiN+|)$iZRP(KweUu9Svk`vBVW|3c{Bv-BlfF4d&>OwW}157hH$9W>2%@<=E*q=6x_cyrq@(!oh7dd%)$ikw@ zLm)Z=Q-V|fAA4UOCPj6%|K3|w-8~Bf3^0HUo3h9biXft>5R{+$5+g>9Q3+9_pIgMZ z#xK#B=oe6vsAz~QPmF8aP+UNE7i5)P7)Ex6ZT9Kzs=B{FZk^k=x~pMuKw+r&dHR`| zo~pawbI*3qK}}T+cJHXc_APtB+z5o73oasH219Pll!q*H!MXgTT+h5c>^S?3lh>#T zDLJphQy$B~^7K|hUj1aAQd@Ft!lP*vO`mx|9b}e5z_TneFUr0m8oI?X#pg+*ilI17 z`qptRZ;cBt7((h!If$4FFH{?7VaxcT3>@4rkaTU7S0@n>1{_m5qdTrZWx_>8+(oS| z7laHX%{)%PQDZ~nk^#>}hEZ@5T0tV!CmD>`^)|4BRMS(dO>z;blo~=f;LJNv7?T{E z0N~}XvV|cDo&!KgPOrQsfl_xjk`7=9c^k|XNmSOls7N?)VZk(HOjhP;Rb|XkR}lzm z6N4NJ&l?qFs1XJLVMz&sNx~p!KuQ#H>Rjm#4WZVjdMzu8sQ>^V07*naR4-tDSt>5%Ucs21>Ywlq70NKc z7zC5)ZwwB&%<(u{SB{OK)G0D1x5H(i6A049dh@|#22e^jB|Q*i+*|SqmeN3g++@2j zxd|&;02e@Qxr6U2s>Xo!CNG5AhZUF|9qGV0NMXkeNGfRn#GL$`2>M<36GGN$T+H6dUq%w-WM~orI zNsg#IP#B|Y1r(-G{+B6zs~jH}3@(#Fu4P(aLuM;r%rnRU!nGwAAPhLnf*CbY<=80M zUMV-1!92IJD3XXma0cPjfOsWAPWg~t0ib+Da_YQv+GaA|(R%%1>SD1-N<6Dp9 zpJ1YnCZ}R!9LtjWU}!{=Cq~q=+n2w><~)tucK^t#EJ0l0{`0FFt-On4$6Lo^5tTn~ zT6D!BZ4YMJB{b=>c5X3|dG(hSRB(L!j`w_@CAN_gRNH!%x2DW<0Tx+Yy)XXa%l5JU zXp&g#yX-6^oFN{WvB9P355j9xnOZ2)t4S-OnpE>HrL$;X(Wb_X=*M^I2($Tqcn>os z$bGs$Fa=|6xOqS(pRJ$*udSBYMmy5l*!0|*(zx5^kWECum?2*E=w8xHG#=s8(Qm1A z1$XH9k|J$Y2RZ1+O*}Ppv1vl(skTt<8fDsC!|;bGVpP$7G+!*ywfvN){AKqe6ye?b z=PO%4#ho@|nzji(Zqasf8pfcm!jP|yzFS9rxT02k4J9lc{rA-NcK&Eog!L(j711H~Kp!x$L(C)^2wOzw{>}q^OtY7+fqKtIx@@-3;sTMhWWG zx#SaX)tXXpV-w+K(0D1F(AjfaEqv@?iW`-TPW#=bP<4czg2u0z@U$eNr)ddk8lT+{ zUcX6D#nFrYUSuQ9XP~I>CH|Uz*_=o2)p)zBNxi8iOZSSr?u-VZy^2Tu*2mVj=Qx7m z%%Sc>+bV2@$@7!snlpUn*m!8{bX$ti_OMflhJhT5Rn*{*n~PH0USyeGpZiA%op_a% z*!COv@J8s;kEK5|LTK>6C6^L}(3G4po&Q`=b=7!4>`_No&D1YabhRqC$D`}Nd)TdB zAi<#(h{?%-i*2ZgPpmwP>wd%X5qU;2i%hUeoW8eS5s5j&_861o;iC*Y-D`qLOiH6R5 zCKmn~!P*JR-%sNZE9)T5(r9~t;i0TzSV7k>WRaHgRg$}l(fOzAyA+(BKg8ekFdmhv z>0sUX(j~Mq~yHfrE)gc`$T6A-tGuz}u z=}`p`Z3xm@`(szWk$zK4lBK8kF)V zRnrpNFr}oAS&nL1Cv2g9|54ngcY_smh>J}q^CX49O6u-DX~(nyf^aUj#81M7Zihza z;u%^t@viz-$#IChmW4Gpw?pg7x%jsqiKMgQ%3frm0VMrz8=uFA+{fn;)&2gOsCz+d z*Es&``HC37#gC?!Z^TyWi-}&)zigMme3~*t?&@5#tS)#@iPNM|>4S{>U2}!6E)G*7 zoD3=?0*f>pHvIS{(o7!taZV{|om({4*vT8W=DlCx$Ic-XNY!Zh^_4O;hnmY9h^_yk zFZ8|3D`3T9TT`KT4_iSa=zpllx7awxU`}kB?mUpjf$BoR*OT8!Ow7mqQu-+35feQg@jD}AJdVrz~OX;Nf=a$gih-jct*;!aZY%et_!Z%3LI z2G}AM87?8NE~BsbE=E@ydFWUgqfvY<1g2jsGw)wlN=h%3aZ_@{050{ zh~L?l2B7bbk(C%?@z}aFY&r(C4$Oqz?Rmm#`F2^22u&92*%0ln>-$C-t*fP3Of?cT zL^A5ipFb?LuUXR6nHb`IWju8f@|ufu$0D1Y>7|PlnJ-zbHtKhSvGHBIP(tpK^5GMX zzEu=T!~7l2hu@Wm%f7&e^G$7VR?0E^VFy))pl0Rxt#{I#uCF&mYKLsCQBpp*gKio_UU~1m4sRQL5+{N zLzf-P+)?t*Ug(AM&Z`@KUbmU;aM4@Tk}^;+f1$pw4rqBVqZ2juapzp&n4j5Ay?yU@94$8@y<|Uwh z(%@yc|Mbj=m92nKKH9tyts)a4#qln6jK^^?Nx3ql(|X5TTB5xQOwQ zW?MK;xm;vh^UV{dA)kSq8(I06lGA1%AlOxpEa}PwkacmhJ5LiiKV;lOW>;gR^ zh0D`a@)F%~H{Mbmru47$T+{W7t0xcsk(}zTE>GUUNelL5B;p?=yB~t8oVu86eE9Dl zot!^TNd{iBj>1bcK7=dN!i^~llu0MdqRDw`oDvQ{)&AVO`4x8x#STRY3{MDt8y-E+ z&XQ8ap_e(r{6r%|$EM}X5S8I$gfereLE|x%^u4fEt@?%H&m)BEWn_%miKEE7Kci~O zUc6$vebw2r!>R>Q9&~z8&pTCUwaMc5*cs%{$+Ar^ zuC=s&lDkv*K80K9g>=Hr=|oxOkR0yXv(hq-;T2Rm`#(kU&Fs`el(EV<-fUL|8>xy# zKhQ>R#-gNA1pBLT6lCxZGAi8BESOL1Wha^N`aR}s;Pz)$NQ^0=LOr-fiavPXTB7VU zYnjCm{pD3ivlUSdZLy@SeXZCg$8TGnMAz$k{=4>?v=`{ETbUZ;&y^I^CQ zcJ;#;lwnCbr&svcN3$gDrLF$))nkq0`F?)|A1VG5do`whRG5I3o`A_mEki7W!Ig72 z*k`Lo(RTTd;6^AO&8h}wjRk^%ok@@#E!N<%|LeqrZ8FXxUinDk*OW)M9Ob!!chtyf z3(rR-Nl1r?nd4B#yz+%JnEcFonc*|cvfkJ@_Q=15h?$uQNLb_}FyvR8{t) z?0$P)REDhq5)&VvL>O|1UtIWkY)w(1V-d=y@|c*Xvp=5>UsN!xBvMsVtMWg8VdmSw z%l9#MeXKPw&@5K#%uMV}FB^VG+d$@ny;-mM_C1!B(c({^h%+B}5z<*nNS1CkB9H#> z@9(5NXj`*iFQ zLVo+Z=d908b_eZ}QV_h{+?B4%aT?qg6*3E>N8M|uYuQwB%h;2iVVjN6&!TO!{U5=1 z;0!b@WRyKQNK}@08BoyFjPt(O>(Qsbckf<{SQznAFct%`#{2sevHb0#R7Li<0}Y?J z)li754AnDUOxas5cfV#yRQ_*n*{ z?-m*>h-E)~VGkv~zT62^kdX=I)6nJX9ur&6h*4%^VM&a%8_o;!zB*kSKP&LMIYQXu z+S&d3rb0kKOFCovjv+UD3%t(>^SF+Ai%A$&TJ5w+M6vHY=aPBxxFVq><_b917XJN7YS7^QyJnUSe! z9J@w(0ZT9hgFGwHe4 zNv5?h=ewie==kxC-AIpEntI;XuXF}x{`cU@Zi=5Qge-_BcP*UPhVaw0H#auY7TLqi zExkr{+wO|L%|B$ykB>fG=iCE#JB4OM3)>i`ed$M;ANfg zqA7Qugu|n}7(6{a9dztu(uztV@tJUb-E{sMJe;qz{0)y+&r|Z?hoJYtPhpanu7^*a z;Ef9ThlXL}kc^Ft=w$e8lo)<-NY>&1i#P9oOwZk~)A{x+g{RwjzJ>m0`n`VYcn^$K zY?i$&O1q)%yjGR+JnH~N?lrYl>BmN~CFNJUIxW9yU(-K$v5*_VAj^{YQ2upyXlG!L z>)WXa_qeqzU&2YVK>wU*n?UJU)GtvJQkMkE;R`+KjI`*bfwPUC^%wj7f)je9MH;Su z(rojLK0j5$K)rRbATci7U}MyRGa}WgfZFChC=t=vDE8%(J^y^*^(D1bfcWDYyTsi1 z3_c4qYAa0Mv&*WB#rMVqR*YNmCjb)p0D)FAhxL>vvktU0`V~{}3EJ zOy&q}n`v;ba$nP=4iAR<@`ZE#I&PVXg9D4vZx>baVpncuWu<_$>E$3>k_xv;qtG)m z57}DFF5E)dp-mit`*+P+X0nwvvH#9AkOiLhn+=s2@V+a;>92O_rm|QBaE~#1`cvYMl`UhLi>4|@IOAO3%4FY19rkZtY1)k~J{D@J^ zH;=U#`=IT;o*VJ$#n$6_v3(oYp)*x1E`Kf3aK~xG7C+JL=3~|xziw)=7k?x9 zt-8(kS9(8GR6M$5vDC0JFfdq7HZW};H!yphm&fAyiHeePDZ_oBUFvF&==twzg`YRA z@MEZWyYm!c{N51y)Ajr}bk@CZSfdlJZg;cm$fqVJ+gqeuW~Z9^sEEX|mX?)uA&Rqk zsI4~S!YL;`6--Pr;Wm^*9es+s8;hP|6Ls&|1U7T1_x0s5`lj73PXGBR20doL!9 z-CqyxDlg0W=eUIv++^qC;u>p0xW7|ogDxe0JmX$kZpd9UCFQy#zt~ve4eKa5mzRS> z>C16t;AI(CS#9m3=hL+sbb%Lp-}vyyc^_woTSVFkadG#PI!@J)F!~=RZln^+!i~CR zMX%HP=;Px;e9^e&$VpRQjhg4bM}%z;lQy7rT_0axWeZ4dESs5{^7tHYf6SWfc{7K_ z3&SlrXbIlJv&35W< zIAEH5t*of%mLrk~^%k#)b?Y1kY(UU@x#dj3A!~#BFr2D`FF~0Np7me31W!E4U#fv7 z#|OjtBU{Ss=Z&L?nZ?8T?0_@-uSXM49Pa+Nv|u8=JyE-4zK8vhU_kWGkF*dfGe2z! zIY+jr2z-r3R}N@rq9^W;79Wxs9~GKGh80 z?FLwz4GxU1(?SembNXeE7Gnhm+Pvod*WNETf6<-~R6-*(k}chgLAgB~9C_>RJ7{)4 z(gc<6+Oc4!*yMir@O@1!oiKA36Tx|OHj;aOjHC6H;9FG>!~5Jolh%M{0YhwNWJS=^ z(+hHsgMr%s98sL%hKq}b_t{Cvp$Fz7+{?F`uQy;9ji{!`B8HIt2-~hd>E!nWnWOdP z7Qk_Z4#UlC@T@`=eJv*^SkB*jd)pJ3ZCK^?7BcD>67=KB@*ue+#uTBZrWK&(voa1&JKtsk~~47GIl{l zDd{(@cVV9MKQ@6@0~6Fv2)D--4jP&(7l9U}BZbZU(8wr?Bim2F#i_boNJIQ$x8ql> z<9k}+^!EXmXSr&rJkfk3)Uedm=pSde|9Hob4oTyG^xkpHIdDg)#l1fb3QxGw`5n)C zc^{1%w2La0J^DEG_2ohNW)&bU2f{dPMjg6up?Y44K7j12oMy$!pVSe~2b|wkRaJGF zH1P`N55MVDFXQ;!r^nL-S%v#9?afj&GqKSFtTgVUDP~YG5$Ki~R1*4CD8)0BikDgq zWQazaV~(rf`TqK3adNU8&+jxNvZ_gnF*F6QSg0;02EPd-(VMT%HuvBQ^R%)hTN?N^$jkyS?-@^aNnM|6eLWme z3szTz84G1UqK7eXrsuiP3%cr1Jt_N`n3&-bU5*;(d4^0ePgz%2{&XSxSGUws%;DHA zWXY6#t~g@+-!VziJ*&vS50sGFB>_z7+IrZeF)IK5zT;4pm6DBkZewX_Da@@B?9N8d zO+Q8IDY}M+20jh4uC6XgZHeZs6dQ}l3KPj?G8#EIcXyK4io-SbqitR)82K8N?v{<% z>PKY7)jmfKB60bh3QLC5HTLMELav9yN@e$nb1{R6q%MdnHn|M=O$wp1!E(bM5Cy!L zTW^wXz#{E4{lSk^1r_m1&PojJP`mpVBvfdzv6w24lcUE(nz#93HMJ^%>ts_2Sl-i=lwo6uH-P<)jBS(BxzwTq@sip|EhOoysKh=B@(_}z zD`bDCzT9!qNTibXmliG`Y4Gph<8z!6^85GOHaLUb#DO_k_P(VZHD;FYwy5X##OUyD z0k*s}SiCJ z3kwTV3D0_vNnT&LR0w_aqthhByWW{3KI3-spIJ^6WcU{bH zgX*PVLCm?>VFNRd_{|X$92%>Z_mStLbF8QlVRn^dIY*n5%g|DH?>eyLfxd9RJCq~i~GUfCHoUvnT#%X}zt5|ybY1_lx7 z>9pkJws9X8xUn4$u^*S*;Qi}0O*4X#tm=~MOh_kR|* zjztYYZ4H8+v5;n)C3Agsnf!h%mPXKJEz@fWhAnkaR!b_Wm#s)EJ8n7d0U>hajBGQL z`CH|KJeMgxrfFu1EnXha_bkUt#UUFjteyD%m_jd+HSaS-F~4Oe_PEoM?9tu^Kw!`n zK`2bI7!t%s?}2U_Fc>q3nVx+xD8)EzH`WtYe4MODi*S00;qQ!y#igN_yR>5`w3k)A zsWu-QFTRfrY~!sdc>Eu1T?=)kbKdXZ z=WQMy%mkJ;a)!G%Jrdtz)7`D`&-~gr-3tnbU_D)rt4sggx;9UfLWiMQr@sDvZ4lh@ z^70hj&qMG111!1l$LPj~<1W=oT*lEx}rtbS1Mu zvikw4Yri82`U0o}ce8vp;8l=(sHw(oQG+5+sl%gLi80ch9eVtaXCpwyGWlpPM$X{3 zD`V{b^WMDg-zd&cjyFN2fY0NA8l1XEM~_j{9U`LBO^rlfQkMv=7QDMf_Ll9hZfxu; zM3N&J$rDzB4rzUT3a93yM>h16AG8bm|7~(|$xf7^J}?!2ntO=22ixBx zT|7ZwwSpOP(#0E)>!E8het_kygP6Enz;yRfzBB4}#qfwY3-V?rUt{Z`{5M z%zoAyO=oHR-_~@pMIQ6A$88y}Ff^UI7!UuOB%E$$tnw@*9?M9&FdkneY}8 zwAv0bxD4!p0Ja=PWx7k!BseHe2I?CY@aOo$n_ z&QZ`e-ugG~+}Z^TIES*jV)FDL`#KhQQ_0VwrY|l7fNIC@;*s7!9D|q+x>QLJ-C>sL z^{^5n{V&PK51-UI9U*j=_v+*M$a)eh3vDID)Ro_8&s}zSZ02EVH+_4VTpac{rv~7yN#Y{0UQ#y ziT{4hc2dvX>m3|a5~4k7AVbyBkm;sD8&^sdnW}Y+0V4*?m2AQ{6MW-Jp{Wzh^k;yR zJ{Oklavy2`0$V7|FcejGGC1fkne*AcY?ATsA0J`)$N&m(X;o-qVR;8ss@14V!MWAr} zLm*fZvB9u`8oUc-hyh%hN5=5_C|Ez||F+Plm2T>^P8GXbynOl6u*QxADGcr{_bhw0 zo@Z*Q+r(PTeSHb%0qFH$T+Pv>(SsA9QS|lIajTJurd%r#Po0SL=CSRN6G(c&`YM?Tr`73J7^@V}ps=29yxuMm(GVEvua zog&hfCV7G7Q=7@p{d0^NL8 z-T26og9Jb?{{G5!(z!*7b0kTVJ|MQqt)3}1UKf6Q+t%K`BzmP#O&zEy@UU2@~GSpsTKp^ewK8ebEMi$1pZ=4T<`HNAEDmS5OSeYfu2 z+diYUo28ycU7LSBoYJ3&jT~^6+b)JR;Ag#dy+@lKE7Z& zx#|Cb3ansinw73b+X1!~ESgQ!13R>kTxh@|DChTB-YiiTAD65md}~627&(1ErGez+RSYrOwlU zwkWBqkH|f$;m{7#yv&&vk|i5ne{jhv#BX(RvbR1`s21+b>PofpMmEpZ!h#vxCken} z0?%&d4}Vz7Sa(BV=H=DOJbBCV*!cmI^XKQkKB0nVgLF+nH1J>Ix59_suR|w8tfZRJ z?%G3Ntn+l8F5Ypv<%t0nZiYJ&J8WDv4g7ZeU43KE+qgt${ot2X{386(w~3|ZM*}2d zaG*eEX=IefyF%}(Xw?&^Z+Q(WhRcj=kIe^enDs^7iJhj4G*v!_>$&nK&Bn973m}`z zz-@VJV@lQUd96ho0%Q8$`aKH-p=cMV!db=eo2ryBrvywEthl&yMp)EQ~j9jjf} zi<0BDGY10}GdLcLl(&HQ+8pURzCBsAdx6`D^L)N#*2`ft`#(KX>iI7|DAWFkq}Am1@B!RTxxVd@}YTP@=HbUok*clbEP*gi&z5lv0MRW zbZ1mlVks~Ez9SbVJ~b08T0hQL_5>qzqgr6nf)L0O9TO8~V??u=)OR0WuEt?p^+%S( z6KrO^4X4NMyv>Ji?8ZxzdCSlX35r|Kk2X1KpZ{iA+N*b%1|`X#G)i(_Ovz!o7Q8w# zfSZlLG9TJ(_@V~cjTA&t3qFmloCkpy2y=`)3p27UBYkkQxBmWG_v}aHk#n&0^_UcM zsNv_Quh%Clvp1;338{mq?>~PBX3Sir$Datncf?q~aJ7kuy%3E&;5pIS(d>*C6FshT zA^=Y4wLNngmoV1o`Rs6Wl2;A~l>9hQRgvrQ1k`Un(0M@a&4CgNhSqHu%qWYFaL%%# z?VD+Y%+|Y!0B`OPrfxrdk`kt?B|(wlj+Ep<_li~{Oxc@+sfhN{p|V*6K%R2bW?J{PfiBPxW8lES?r~sc<~^INpcb+tK08D#3r>)50Qv}n zNxJ~FsAprmtO|5*aN#_*XK3J(dvG{1g2*&QWJHH2u_`u^vkqoB<`Km3H#{m$)qvDfhgFMZ=ZhU2|(JKRl{8yfo(}K3dc{;y})(;5aj{?Gf55Q7L$+i9uS1X8$4xZj)pto(aJAcN-; zn8PdUpEUX{zcoa2xHcqlIl6vR;yfB3SuIZ&9qiV3eB8) z9}$Idj?u7Q<}hDAm%At+qPnbt6dBKr znaCDpPexTA&0_+Mo%n&Y;hmb7Bh$s_8wk1>$@`s|h|7tFZI5+}rAX;L z_R^krxJ4|!HzEUGA&8*!_OIVNd^tu$blK#wZZm3wVG@liIue4Nd5N{~d_v0m=>pDaZrBDtD6z6cs174S(on3!F3uH>%7Wvq;yw0dP zQq*LmJ$;Dbbf(qkuenov+#tzRcPo0jluXs1`w+wJY!DrXD=Ck~=4M$=RoS3BbGxG- z_Q!u%G&Svq?>P~>m*d;m*cjG6 zrwJuSsw`q2>p_4h$|85MtgNPLw_?7~$d{W;D!@}y!ksy9*-wMHI#FpBPjK_TImn-Y z1nH3^0!)19Y<*PqhONK#vuhEdsY_h|JnDYc*puCNnu+8wY0NRGG`-EmrSn^as9R(> zx61c;yLoQd8QNIs1BUqg#>PfdDq8hXy*)iSAwr?6rYBMYhtrDA%}10BFIPxF7!d{! z{>U{K@SVt?cUDNJYq9+EfY|NH4Tz@!c#Z-KgKu*+94S=AOI_6uo<6~*$yjYU-|j$` zIzHRWZ*m|541alMfYg#jkfD^Y;7e2!7DMnJkdXyHFx?ade!m{{%C@H!3a@vg@yVK?v~68`xqv8*|?1c(|uZ|;+X7}FkLZu;H(5hoX`)pS23BlFdyDhLN&GXU zaC&_MqlZDlrv_Xn`0b;sz^emBGinisK%W!Y?sp;^AM%l?V(FQ!zw{zuF=Rx*;9kb# zQn%TZLXFhb6jdlUX?m0_!#q85Zj$|C9T|CX1@9TRzuHfx?MRD_l*ISnUv2lptMeVK zxZwqIeY!G4-Tma>ZcIw0n!HG>%m7wC+~lcrTz9mK8Lr zk0P^mRUU|uOInV}7>y>24opw2jPgIoE)038p<2f$*=s0kbV(dq-N0ApauxnhV-vt!Qg_?S$-x( z^AOIq>gB;xpmpN^epx|i#bzv4o&}jB0`I&EVmj(s;=c_ztniWI_Wu6m<9sk7%jZ8ZpKQIaM?PV580S$sgU!j3S29Ym%4B^ z5-Z_UaB*?{S_(QzCjO@;2YT}rL>`ylJGW>j7NH=Ega`yw_`!>ShkG@*h&_OUbbXqA zy{Ax_H#XQfZ*yN(Rerjf8(90(qj3)tgViX={v0SUmja&UrQ%`6;JR}MCNYY%YoRQ* z$Icuw;>mTBeSzqcv5pQJieZD>Ex5gF?rDvXsNnT6e*eBK#b zwGqOA=e5ultg68h+6KcH1sRXRN67ln;$?0p3yd~h*g1~!?&BOljKCIDLi(UTF|!q5 z(LiE`W**U~ex~Bn??KP8MhE_b9*<-vXESJez?)AFN45OvsMqM4eU5Zm%2pm;!9?R+ z8Uwcu8Ga1jy2X;eCObK;-YG&Fl~Ykc2;?Ywh`6c}h9w~2DqwbCB;?6vXh!{%N2b%+ z2@dlR!1dT)g^*;C2H=X6Q_UnY+>xF<(!K6EhuBwq^a2#s7~Yn8nSfG{ll9=#__x%V zN~AD{BIU4yfeh!FwFaQ*&^d}T^neIb1z;L~?GzF&TBp`v)A6>P$lhwPip_=W6)-CO ziL=A^68Va+bvR2sLk1u}@er5`tOvtO#-M0pDVK#d|3AxO4|BwTxkV#AO=+%G$Pq&) zOjFfW2X0_s`m!*d7-D7?P@|%Az>m%F+waBdT+C+q-elUBO#B*;nOPzy0KPEdl00z*4a1O$RwbuB^bTm+I+4IG`EfR=&9}8`@pefs$gg_*Pf59kg3? zrmkTBlf?*#Hrot(m{5U?t^^$sRoPNUTRZslVC{S+r=ord7l=0RCms`w8`iS5pakVY z5*NZuB|e(*RML5$h|!Rj2qbPtSW0q2x)fN^y^aa3EcRWQ2$ZF~jQ!zDVMRiWs1Z zbs0_W;x4hCBDK&!jsQ-k%M@Cyav2o7c zh!T|ikihHn`HhEg_c^k>Et_MX7U1?`s#0i}Qsu_g>@lw>6Oq+8PE#V|J&+C|XmcLN zWK()-L|^|T;JH#Wt zMg^9LrGhd}W0I6(0E-KhMQ^|bei*SLPjs-XmkU5S28$m8->=)=iy$2qz(B~RWdSY- zmk3@|ADjUV@?^cm;icRhw$zN9XpfV1ERAKfo4|c)R+{1YU zvK@aOl#GE2Q@Ve%&p$%skeGBtjv8^=2b1CYskq!s>9Po@CEd{!cODuWL>TOzkj zCM-2FJ zQ|iv)%P_q<2PI;uAW0K#jSg~rGBB?Pz3+o^wTdI%ULMj{?fArXM+PP$Omv8jRPpjS zMs|n&2i)al=RY(KI5{&-W+2r9P{)kAT&sBov!xiNPJ6Z5s5<}}_zg~ujV(Z=HrRq1 zLS1s^qJUmyK;NFXwE>%7a z_iP6gS!MZ~jIzhYA+ZoFIjMMt#)*z~tF0e16C0{MNA&Jc(GJLF&IfJ-$mBNU7HLrY zFy2cq+1(eW%jAR5jm{TV`a_Pe_0+(Nv_k;=i6&=?#oi?VkM)k@)&g^1|DmY^Sx;;sJ4|4c#O>G+RO@Dc|7UN$U z^HWT?w63+j-tb7fHLM0;sz_W2&{B-rv?XG2Eyr}VPV23hF*KzvJ#M|y^@j~DNWcy~ z(*=r^73?rFZ1%Z_JPqfTQ%vNB1z?GLu=xXHAl}C49XXndN#>39sx$(WU5uPB>0rXz~;%| z;ff>Op?1dDpyA*%V<^TmY&9*Z%+occa2=j+_)i;u2jt*@hYu**diI6*;xv_mRn(gU6^E@xk^C z8M;PBEmkA52oOHwK>ikyZsdr8j$R2g8c2pbdTk~|t3R^=hW~3=qu>W7-!UkC@vs?U zmf}eC1_4mH5=xJI9ZfqeWqS0;Sg+5>b1Mb9+TD7WMvWB7tj@4a?P^&ep3u)e3GM&o zt&j_6wWCDIlEt!k-qHtV1X36HvIyCB?d-*_TE~n1)Yed9G-&m1ikTIgr5>$~1Mycy zJ|PKCo_{iy!4vO6cH!Iw4-yl*vwqk&V-EP^`_G@VyqV0&!VsV}_TBm-xukGC=~))b zFMhV3kCf|2q5uyWAf!rOLrVjDuam|$gT!zL@Bx9eqJ4CiWhu|>v@FJl`y)O5e6iAI zI${^=*JG6cHgjKGFolSuKr|5<8V1`27a27L)Rhanp&q>WD-DU=kBf)CdDAxQB|FrE!aj28bmwAV(Oa=EtrDO7x!O>Gz(614>)~wA&3#(yv0p|LjoPpM@~{+iBv>M`A#8 z6V=(1vvj>H)H_Wm!DyB;q!+{LqXv9SzuS6!-by1c06~V=fTxTg8c#Q8&XO@65)Jf; zI=sq2tzkD-p8OYVxP!0x*26O_K)E2kgr~@MnVZInONv4Q zuWd~u*L_B22mMWcp%BOKGsRS*P~!8i-Ly-)vdFq`1vg&(TZUz)b=c z$=`iA4svJXnzOl?kpcH7EBwc)#wt9%z56JIu&NVgfsV1MAJX>>`vX30D)DQg|GiyQ z=ziG$eRrt*|3#$yf8JvH|8)>TG3G*bcJRn9HE3vv)@o|rdT3nx24+d=N%#IjxuzTT zlHm*|!Z`HX!;l!%sjX7g8ZEyb8M$)L=nEnjhhv6KoyA|jnd+0o|lxDcf#(0 zC=hF6*N`#Qoceld6oLEK@dQh6)?nqr)&(s`>`|e`MjoGkf1~=rArEpd0#ORUn7$)Q zPJJJel|q%6d6sUE0x7gESZ#PrU4;VOuxt0fBf^FOtny~&SNygEbYIW6n;d2wr(tgx z1VOqXj*UKWDwFI$$Qc=e+ze|${Y^*%Rhq9G0|iK?IkIJh66aM{>mZ{kD7*f^XZ-oz zPniFzy$c(Zpx1%g6`db1DV9%!(h1J(nEQX*p923DoiB*Q!L9<1u^E>Eh$8THcXm;k zantpP-u84G5S)N-T53L?)3r+8G64q^Vr%d}kOly0*9M+45e-rR1L&jQJK>5m__1R7 zksAt-8)!Eh|3_Qz9nNL@#}8YHvMCwiV~0p&C1mdvT9gK&$V>^PWM(ESWtWvo+(rtK zoh>D@cLR}8cwX1{_dL%(&vPF~N8OFjxUTCw&-eSa-rMaqxWf)G3dh*r-xt#<&~JM` zJu8dqu=h_wgz(8*PY~)leGzTD*@^PPd}EdLP|hr+j@}(vE8Q*WRm(#&7fYN^KhF8j zS%4)}v@o`A$uD$nJ=E|ApLB@DUbORe!?}LFmdAUIb`ACQs-VB_ykwDUsOzoo@uNagqGhr7s9)!@ zm(NzNi&NE@!f?vpPw|`F&&m0+-$}!`Y`E+*eRWo#_raOqcW2O5;mco6+%*~}VmaZ#=O%wP< z2MP(gL4Bo50Tk})u}xXO4%_&qeRw+8A98z^>dq5^I|f{jg&*zCGqx6p2{~1#Np^{3 zrntPVSI3KJV;BVMv6Fsij1e${5cQI5-jhE0f_IMO7n$TacXGC@-=<-XppCeCFlotI z_p#{HDE0t3J3uu!)_bk*a~^8;rZGQ^$`Z`J49($XGu8VNEpV>Va33b&yJ1k=zI#;|T z5Bs^~4)$!}=q@-_vI8Z8IrY0ccPK#SGop3Y=j@{Qs53+9iDNSjzFd&pT1G|@dHJX- zroX%vL7AIG`lyv@CL|4PnoxWZj%R!Tvf2aqB&ab0u}5%15VDP|MELdIX3t@+pn%@| z;};;FfYK8_Ck>F_mS;Kl&I)YFQ)Ru$h$=Mrf`-&;?+or<+>`sB`_KBXW$!s)dmEfM z?1tILW#}~Eu&=oGLkxOm$v`F;0cc2B#t}{o%^!~_)FMC9 z%Mb9KxwYXHlaeCQa-2;|_ELwM?|jX6qy~JIh1_{$;dsbS@_VgrYxCDu7@pg5cHO>$xe6SByHB??+x1+=6(~>@U~tJu1Fs-yh&ogk{hqvlD;$Ip+RWOmS=kjg-y|ZSu5GiVxG~_ z(K-#rBZ3eujg!0J32Vhp^5N>Ozo&5nGU^jlG`S&77AN}7^tlRLAa}p2`S&~dj~uay z6eo*H%PFV)Vsl57@>62poOu=uxxWmf^EY=pYN~%Tgej}44v1)tABk} zn?iW-MNFO)6e<6HW3Qg)n5^LcuWaNbr_48={Qnv270=+KC0sCGW=zYJywxHcH>6*(Jhg-*($POsHZ=`OTxs%uTqW$!JxlF0d^x6|#p4VryVrCJUzu5xbIs_ujoluff+j`yu4*@-9;I9+QxT*x3Sc>n(1&TQsO zz#ed1OYfP$mB(($I}AN}f|BJ=^4AxeSWemlp9O2YtM?r>J?AivF7@;0GkP++l;7dG zj<0Z~m@%1xGaJw$r)OQ(&=JDYy)q}}@2)PE7(4iDg+Q<3I~h|%e|~wb!=isG&G;EX z6bTW|zPdWiTJ7EHwj=NFxyx`XxRQ|#ul%KV)-^P&vpjBd58AETv4uU{;qack^qR9G zbFj83n`1NO&{u@xAA(SIv9Wwg9!1%!-;@o`V=5%ld>G(a+P<)`K!kAsB%AOqPQuqB zoE$`iM3<8O*iJHWs{%Dqw!HtO?_X`k=N|pP+mQXKnf{3p`?v>c@4R_`G9W=KNK=M| zl~o$@Oya%TEG4l0>XetwR7B!w9Qkzm>Ie8aC5FZVZ-HB)zDhpZP55e@dPE(Usl^7f zU@Z@Ys9)@Fo+BsJ#e&b*H80+&;UgS@VA0R`H`rtnNiB-T*fH+nT-x)A^N>>@*k3}O z{-5lD^$q_d)pKwz#cR5OwImWWToH?*ds!ty2ew(f^!YyqmX-uY0f2!p05I7NXB^ou zsBIs;TRnJ-$kl17qyEQs*lRY9?vRkdB?WHn^XK_3ED5OsUHGRFS6jS#tgFk=JDZB) z=v$&C8fI*G-pc38=X#)M$W&lpD3WMsXgFO_UPs~PdXb}K^bD0p1h!zGJ+3PPMg3i` zi(|+e{{+^Kc(5E`82!0R>!`1%K=A3-!=tGrP0ftKX@ zZ`BPJutwM8{t8Nujd8Z~iFHP0h<4?@5Zys+?}HC>B;D=!jbpz(OC51N(MEa0w~mwY zS@%9ahg`oA*FAt-rKeIpWf#ur>gq<}VX$sLuKhlB{7R=p9furkJ< zOePNue(HGkGp{7V+6qFrQK`K9z>w{LNpyH3)HFf=C6;qpTGDfCd7b<7F}wxf z&>1PkH{P_qdoDP+oq{|rAwfV=vhb9%K;fq!*KlE1eN|f4(l_0C^~Fuqhz9UJa4i9# zP4&eG}&pk|9R+tec2;0LR`_ z#GqxCq3KT1Yd3jmrh57BM%P5s)NhVE#v%EK{yt5f3hTM}>d)RIwT$+&GA~4SHx4CQ z_b9NR>OGa)vf4zuFZD#)tRSmzkpeqy$`{Y7wU1ZFS2W4W%5+j5-gsqx_|LB)Mig41 zoJR~a8^3RFWGC-CvM`iS`Fk>KS(1IGKtc8A-6l)n%IAlSMvqRodIjy0K5(@sFQg04 zbtFy?j{cLDgO<*6Ke<|mUgh<1zt#AyIrM>_IwfDEFyUMJ4Z_n3W1B70u{9Y@!3z=L zYh-*BhAa#s%00qbX0D@kv^PS$zkg;H5)vX4qjd$PN%-6#qHR887##G}kvLzJ8}s$u zbi|_3$7rZ3JiEN@bx&Qx1CRA8*?$t;`-bSIx;&DGw%u2fkV((_Fyda$L`S_pR8*?{ z$2EaHbow!=y9<&YyjrMrZP@E=3;llVoBWox&z`QG$rIZT>6xTlXO(^~shjZ8qdIwL z%6N@Xot#sJn4QiUhMp}@&^A1>;K=ukkk|CZ$X^QG=7ZfiR=E}{6%F70K);9h1eIipy8Wali4f_%0kr!r5}{eldy zhGPxeC;~(&C(4`Ub?8q@?@|6mrgay9GYyt4v1ij~$V$Bs_Hp0wKsb8yAur#d(73;c zhDCT$F9#3^2ywJMv-hf5mZ>Nl8wuvshUz{mwh9=Xdq!SfhTB-ZCChs-UivFQSQJoe zuDO+4H#RoDWN*EZfyRX9o;vm1H5)3`mwOqu<38O+{cE6c_QnlGe8SdnwADB7sw`R$ z&t{c-OzDq3O!{qLXc*_b533cG8o@ef7;iJ`j*f{z5}ERvw~<;f&+(JY(!yiMY?SG4 z8U7o$Q16z-u8lC*CIy)43@;qDOk;J&CPzr3% zMw6ZUKF#P+DWZ8r5q>MqZWC!htlIbYoI8=9aSegIRf_PGu^6 z1NFS`%~)4zB4jMn^NjQZ<21YSxTh8KMz6QVkDpj}&lHGYwhPR-b~=D7taY<#a;Owu zqrbnZhUOpV<&}-c8k|4%V}|2hP6n57I1He3 z?aj$Q$0wAu72L;ZBw;nFRWj7otp=Na)?jG#tc?He&6J|VqcC4pZWMOD69m5VY~JwGbHLEn;$2gZ-Ad(x%ceA zZ=bh^x_T|`?oGA3wXCdF6!(n#{Y>SUOEa~!w5J%eS^-xF?mQEc2^@s4efzGc6|Fz{ zM6S1AvoXin`j*o+RC9;C(E)KzoWBv~`u-FO+OM=Jow@dQc1;o%OCw+Ma|-jU6H%LA zEYFG^@hc1sSna!$dM|pmBC?=B0-oxMW_p9b$gUdlhc5hNS;yqOzof4yr00tT6t_&= zdFn_*eK%;lM9of+ZOW%?+C=F&Z$>iT`GPqm7<<`&D~i22^VY|*Vs5@N?xLj-Z)5WG z>#~-favCw`j#;K}$!U3ujnV4<(XZr+^YShYR+O;m=m~nGbVSG>9>QSA5mV!Txtk@? z*-dIZ{KR*%zx?!*?io#AU*Ct@uOKInyjpGi61}!_1=YPlVlG zDGlrUYMEuJe7tWeDma&aw(6Zw&1C%f^+ytgaob}>GF8}DsY$$A`Q9Hl^V#o2TLp{L z-&4ny(WSI^ZZD}Vung|%?^fp%656Jc+O9T!eK6&Am%>g`G(P{9$;K$Rz;cX3`PA~_TK1c|)-*q@3iEfR z11{bXf+=Tr`pb2~9g5_yKHGcaY1>9!6$s5)la1TkLGc%rcL>KlOs%pZi4}#Jx3)HQ zjg5nF%>gUz|B9|OP|;&@7}66pKBnkT`eC!>2#B*gJ$-R1Ml<>82$7S5I�%yZjxK z(Hi1lzbRl9A_6G@WOQQxYf&L$D4@=|&EycP*iG%K^tcS5z~#8>$-yJ`4i00GP1b=c zbXdEhuKwQSC;O>Wr@~O~pF`t3)iWd(b_e1%rZX?tZ<|R0F^NLeXSG(?GNBIWhu(TG z^9voG8&o*=-oxb~(5o){3@K7afzuhPo1}~m*W8`x=bx^KgnfwFd(eyhw*H2^tM<}W zc;PMBc-*G)@@I{t%$QlvpNs|%dP0v5_HhkgEeSWHh1(7=uNw$go ziztgZ>mwI47vC)|I;QaWOp`QJ%=0&;tjkP4Y0Z3vc`il%L)_*M!rpJVpzTQSXx#c+ z^H&GAm_zsUUIkaR$(UYQBM1^s{u^Pu#RLf-8@@U#kps4hp63JDZ2DYQN9CEWDxf)F z=(KP*_Ing9dgt(lWrRQnWf)j{E~)zPr*A}fopn?tukX*?RDc&3FJ5eXrv=ak7oqdO zC)t(C=e~a8Vf@fB2pK<7-q*Jb7Ra0L-Y`miEg8W+zuW!Ja_9(h%9cA7Ekc0}GhdRbIkGpcT^@@>t(A`|-{$nq+Xi3s`X>h7lhvCHA%dWFAmEi0L|-*PWt+&7*g z8ULAoxp*aW&kR!JXgN4Iq^E+HoR*ZAga4^0%GW+H>G*7tEZcNo(~9>=!JXOh*n74E zNBkJcu=OBJAmv|V)}FkmvyL_NS1!_YdhLaxoe)I7MCdA^JH;KT1H^D2St2{(E!Bo2 z_2?~qYX{t=iO)cNXi|L_X*pqb`e5Upd#7v_-1rFUoA_T1VPxi(yT%%#8h{sG9nM?h zBx`fsNPbG%w~rR9NFA3;$l(Y`oZ5}^Sx>sWY{G_QRg`(RMP#;55gd3pfHB>}RL9S` zmS`w&*Au+Cfz(?I&Vx4wD>s%Tb2YDT<;@*GJvD#9dP{bJ9!k^m&>0 zS<~Jg0YN|eOY)I3lFO8_m=}Xh=+vLogWo(>H~hc&w>8~-dxo&iD+&jwsSO~V!0hDA z)ruM6h0>~xj|V;cPn}98LNQvew3iEwPJ(n6gUvw-nPN_jWsE6$_I?1qITZR`6(ovY zzy3hzw*kyv89tx80qx#y}L zRo<{_19&7Q!^k|P7NfCi*Dm0|()(`@V4lbt4iXTOsHN4fU6TXsNB9Pbh$`qZ!kgXe zUc~OYKi1sT^gl5xuPTG3B_T9fn(b|gejM_qglT)ptu22z4R!~pkr59!mgZe7*Q z2{;N`QG$&j{vu%)0eO>y<9hs`u8C9ji>x>oWzL|<+i$MK1aB+<>iX6iuL=zG-oXxJ|@)uYNM6df>{a|{GsZxsBv|6@241;7$Q$W9j|E4BrBVPjic zJx&l;h_ZX~k2At6sAX?248)jj_bruF`*}_N@vq5fn!)Fc0O>>%uWMq0-RB4tjRrF( z)qh&aT3uB5i>(}bVse6kqNJu%184yM{qVx|@jb`h)@7Sh@o9>#Un?7q`&sN z{X}=N?lI(1zu`n`Ww5|_q^Bn zxP5;~%$D;LDV5-XJmVjaVfvse7d%8?W%uBlklQkmq(kr<^SZ-x!TI;DpZz!&XPs2Q za6l~Kjo3nmf&X;(YXBA%e-||3``daC$lj7QDVDpTn)6oH<=+A6yS(abvbHMUS1T6- zB|T3(NDlb)Q;J>{9@pCX_Is$T;3QJUCQnGv-QZRhJtD%KIP`B)p6Ie6brg91Pwt8Z zyBw)xA)Ly4jDO)bHoONJ;;xfzg+L&PASU#F(bmIKF&By!#@-8O$@$0dsW;!E=p?3vXy#|Zm$ux)LSv^3p@^R=6lVqW*G``IEr6?G?U;#^a-kD~kG*RH?u{=fdrgLlI2Gge(|dH!%Y zIV$GMy~d!3vxjHdNJ4!NQ7YB^S~;$_RN*;uCtR|kF}gSS%{!dF1b<10;sJnR38Jr$ zPD~7eYxM$pc!GE#8AiS7s(TN87^42pHY!}mXF3YlWN723cMy}AN2354htxYz7;9UE z0vive8And*7#l{lqHTJaD#l)eGO5bA}rN@ zaP-UDX}{#Nh~k3-s`ZT4MCWJh7=Ik*@*|Qnjoq>!DF?6vfHvXFt%5RhEwh){7&T%U z^?$lfcaV@lMFn*>nblT=3xPR0-c9K`*`RwXCck;a`}H?dH+zj6!MB5^<5b>%N0XDBBp2is1i zMEit0A%iEfd9nYX&81(H+%~qDfW&LOPD#lYD!+=1=#Ns; z(#4h=$*U^)K|)`FWH_3^L;*2cG{cu-g+oTQgsmI8gPIXnO}l`D4(D0ahoK7BCOp^O zM)DkWzT!D~VeP701JUWh4!ZoJVRw*&XV#lmSMKzClmh0eNv#QpFM<4nx z;bBm~LqPf(X?a@KNCQ+x<+zch<@m(JNQC^i=%i=Y-R-~0lfd|pMRF_NAp%YaPeL<~ z=9pG+2ed3N;qA(Cqpj}qzlRovZ;4R7qDd=b|@o>EaB8kH>H8*keLULbvU*f(xe1j?p+mY z+qMwrSosf?E=5kI<3m>4NId!tvFz}b|Aah2ky+>|Hz&dth2>fT3g>& z<0I2D!@r4+jWrhvpr^hIruI4L7+HCJyU-@4mWYPokn z4umk8)(aiS-=QK6l9(scw6cmL3 zXsA#o1oq7xT8f(dgKlSc_cIfAECG<3e6#Unvt#h9iGYR?0mmWoYs#s=IJXSiGJ3!4 z&G@*u5b$Tji4snH&b{V{US-0o?jjVt*fXLloW#b6=xK<(b`!skfKnFX2V85+FbwWS zOzdt5HJL$~BZqP;+WBw3+GGAKb($N4!FhS^0iC^EfuYz;*j9X}$@eG4yiA!>M><4l| z?>jDy)&-rdS$L+pp~vFMZzwwjknPL`q6ox11_7J~_`)IO*Ff)rl17?K&Ei3g-^(QY zEl`q!uFj1_xy{N179PzAmyA_9#!`wtN92V9;3h!v#jPsF8OIC6?PqQtwEm!u z6X@tg{>=7{bdAi}om3Qf$`JJf$eBF1Fwg z7f*_%&hk;FXNWEq-u$LB%X-#Z*+b>{u9&=_e2ua_CO}&!;EaK@eLpus4=Mpxrn!OSA)-(Y? zSc&#>6lkQ#{H5o8C8!#DCKab*+S~^AH;%M4h!}oJF zmI4EN+YRevjUKSX<>e7{^IXD8Kr;?_Q3;7aaMpbZ^+ibiK`{-<;Ink8r6YsNmtFD; zQ_FYBaWk}V8GQU*$H>p+VET+^2B?fFGWgTnNt9~%vPhUdN8@b4whi*A_e5lz=kfLQ zVI`qcCx8aT<_lc3v#a@Wjmxv7_&SlZy7NELa)TBWbQ3{TVv4my?3}o`L0HRDr`OM(LE@O`+%@5(l+ zZ=JIX?K+*(b@9}JR8Fg4#ehkESQD)aE)^I^oqPM!$EcdL9?PEG3wBVx#_#S# zF{0;Eb49lw%EGAnBd&$AY&*`uH5_ydjD_r#&rA?HK+{OwxihEd*keWoW+9h-7>1!{ z7(#g&^ij_Rcem~tPhx_S^c>D|;ITy(;kbxRlzb!-IjZB88_NOxy3UgO_djQTm9Zcq z?qA@&mm&CQg07}C+YSy*PjT1G_O_p)HGsm zmcdQrFcOFyqD%0-3t*h42b$p2$0Bu~2TsmTjfEnsWKRf=10- z%GJu#d%2gk08iBdeklrMqAuOf^)RO-yu7k$T0$Pp%$T2$)PMeCkNBc7jjI=(Kl{ zsE~1fu~LDZoO~Fr+=DqxA%A~;EtMjI!pdvPgx)+oz;)ZH$gEvxl0{*v?Z}SXGOspK zm)&ch0&ExJBQGP3D$Rsb>%yw&==aQ{ebJ4n!j2Cg2cQ)bDz> zxZ&X6_9=$b>@w{>_LE*4hCl0}D=0syc+>}Z{TJ0)OTRjsRwFU8k0?EN>$2$OM*b#e zXMBE;le`-2PXLzaIkbkczeyXp(69h2!|<5vM|TTHe8gs#`3}+_Hh-wu4F)B>{g~Bt z!{wd%IEi2dCX9ZP=cWKe4)#r|a{i8BB|C-np$pea*Iub@uZK~~6@FDBuqNm>l{%p8 z0NXz5BaW6p^BUk)*h!+op-EAlWAfr`mCE}O*SKfl5xhaC40ILGF^?L?lial@HG9xn zBbn=96HVx)Vq5f<*c|rL&fFUnEL+4%01@+Lu^jl&Fx;$%Tz#m31fV0>=~Dsu3=y_H zy9L2D#v%j-+#D~|BaTf$mVmywhnoIa8rRX{(5u{&t!Gr8C&Q!^`m{wg#Z-T$gwtkTnJv#YNFeffTG)InkTwt z;mG@2`Stx=^T&@R$`XhU9;mxsXN3V9*a^0g6}^RxoFAM)*1abR^?=+AUd6l@XkR%n z+^LRl|F4M#q^MHaZ_j{9#=Z*;ETNaVraQ9kMprjf{Kre!KJ##L;-#3gA~^N{HIJ)Ruhje-RM;)JH89T2OyvHFZ2H$13&nr&bjRf-k$pX-F42m0tILy^=Vl{OA%Teql7O|~e+@3ZPTLCdzBRFM z=sku#m2mb6lE(N(KQ`RmG_i|*70wWZT1sP)esFx_A{iO?te)mki;vZVUBMzun{aoBqZSwgQdAEHl^8pS z2nuT#CK)0F955deTg?9pXN`eU{nI7uGOm`>SKr?A{&r)#jD2f0nzEh4_pj#lPELP* zC19MQ5MU}Ac-p00C@kMy=`mrlAhU(en^0{B+m$3R&Jg(x&07o6A0e&KD)&oj zZ~=7fzFE$N$dr6yb`c^Uxv=gk%+0o7Uv>}`*&R~d{oAv{%m$}wJgK}VIPVTkLG^>M zo)>3%(R|08do6p0(EXsHBXao_jWul_8;bykVA@rDZY((S6N~wiYeqBysE<#purmb5 z#KlnoO1<`mo-2Wl2D?k}Q%CSg4L!NX?D*-5(jd#`gdX|uH=nuvCncSMS}71DSnN$9 zv)wu43?`s;m&5IeNTR$vf^hmbe@SLH8{06bzg`}8{@cnesvA<=3}fh`;(rN=h}6z4 ztK;~Gc+d3&nL}9t9_^Oe_Yz$!ZcQIQe!%@Drm+#RLSMdoS-dJvQQIp*)=}nmfzm#)#`4Z)dTMGaoU?+Iy4nn4zm`K$k^K@;8rU3CIn!_c$Rqv*GcNz7_Zd!-{-SxJ*U*0<;ycfrJs+IWp%p}OG!z}JnzA3 zfg>lOa0NQUsc_iCVy8$WygSth_>uCHXxjI9w=-zN@udPa$Fb>WHv|CQ!VBRPwR1`^ zw3;lsQ~P4H3@%i2Bd?^=?}&E*hU4Pms>c=@9mpG%(*z}B%RV+J#V0oQ5{rh&ZGs+y z-kS5_E*dJRu^ElJ2}JLUb|It4`!-7!Y>u_CBj3SMczmYS=_rufyNF@DYzKF&*``ql#)`MUx~{`&;ff`KT5C4MgqG` zl)uWuDerP6e3_jI+q3(tV|`x8Np4y!hn`s9rL|xs{X-Q3OOop3aJ;78+EgSmqiQ$g zQ*y8xpcWX8Jp8j79xYP2bU%%9fD1^?mjIR%ecH0J1TQ5Ap%^J^EI%`!Ppe z-RJPtSabkTEc$EpRak|do?gu8-odwRp?7NCCgWQ`0$obBpJ$w?3$0Jk`H<)pZ{P8m zhD7AkDECkrT{v`!&DK~f#I2lmLkdXeOciw6%1Cqn<}iL6hEVL{nsAOVXI zza0Rj3s{I#PBE8U62UFszm}TJ9zTsh9aB-ZV-^_^X24$K;@IwPCu829*2Nl7cf#YA zW35?SGx8HAvV9394Y6GkZC%T3>zL-F*f}xBe~kxXVq@=M`c9I`0}ua6m4!=!KBY>- zDZLJb)z;>UI@-LtZ`YSy4ShjBJA9ibzg?RG+}V zar-d1>HrZninI31?qulv zl%^aTmS$$>Om9YSCb6hqMON}7`K$GaakaDf3T_RuOHjNHWu7q>R&0&${q8%utkUPo z6`1AI?sGdbaKLs_PNB3;tMkM}=jiaSjtr8`u8p?6odGgj^FU}D2+J%PffKm3A6eN$ z$7QGXIi3Lr zb?jW{KQw5G$g~!!s0lUfw6MP^!mr8C&u)O79~Q9)AcJEV|4{=~h}84!S9PblHq5wM zAKm4;sXz)ZxgI*t8hvQn)_ZXRbzn7b)(zpD!_e z8&bN0`q0Az-IWU(u?Yt4-Q4qcAM?&yNVR`)%5>`SiHr-0{L*hkAm2^fR=&QbaJy{p z666_KC*SgX(D?73SIjOqbQ!aY4ym(9dm(PkQ0&e>z$S_U%CwYCh5KaiY zvxi(Mtj(G=QaLA@7~wTe$1;4)av{a7`%oLn_kzpGH=V0dG1?jzO9 za{Vd!ypvPpn$AA?uMUQH6eq3LZ_m(D$^TyPK;u7B`p2s-3+gj50$C8D3<(b-bs z7rz6Ibe$31Gp2lw)%^b^paYjE?z|aGymcyo<#poV^@0JP>01LfVNXVW?o*bC-fA1X z*J_tkD|K0>@hEqW&y|luG2v0Y3Lg1y)(-oW<`rG&wXyVDD*bV4spYowm5SSZ-g{r) zJycrkZlLNdO={U!s_BvMBC#{?VQ+l@(fA)HBn=0gPVb$&>U?|Gxv+_3jj^`Bb_@&S zv^Bf5Lfth+Yp4hIN_;wzbcD8m!Qy9{Ne!dwl9CHo38kEl4|&br!t&ooHVT^W1#RkV zrj7q|{_~5{c2!R^NuflI&$i6y!QYD%53NPk+LFt&Dkyj+n;G|Rj@(cS(0{*8^Ua+F z2bzIryK>0s!C=GVeYr2g@U6=~>X= z@IRs?WeH~F)y8Z9V17Uo2xl+B{-W%CMOT|$L|zT|5UPFLQA!v*=&FVoqZ)8fauUI5 zM6mQh8JX<6s#>C7ax$6ZBw=V0tApda4pO^&8KM-o$@nZRcfrx9Wd<&2*Z(0cY#<6y5csGo8ZC-&5j*Jf?1OC)*StDdK)vl1$L98LrLd-f%_s{f13Wmk3@KJM^QV%_Sqtx#z;muUBTaj-+`78?71)mKl|}+ zrfgcMvdCxvrZhDFxE2m^ScvU`OJ7t#TcJ19LU{zuQ4!s5VBQNzlnen`@_uCAL^(`O zQud0v4>=*r#AZ+MUUXc2hPsX#n6>8e=7(H)jN`E=4jJutpo(Bt&kn<02$ zz~U!rSCLR>j0dpT_$T7m5Ne3zq7P7qUpy>plwVY(`EN#X77cbNC;KM%M$~NDdO`E# z(1H)X0}^H9M{WOSCPW;7Z8Va49w3YNi3Hf?O7uK?tP!+HCCXI?F@agX%xx$7c879ui(HBEXOD zkJ*lcPZ||K*iQW>#%v@idf3MW+zF-*sy&B~LFBBMH#~j(b}*JJi)<|0)na#mc~x$n z*w?xjo?l8Xvl9eyuBy;j_^zA*w1r&#>OKZeHxKNATPd2IJ=XuztgwMTua5i!^CP1L z>A|q*Ad6h_smlsJIdn@n%M*U^NApzR%a~t6RFmO5xkFTX7fjL193+O;zTh$JCDWuaZqb>u9>906IE zffFnorC%dZUjP*)0z82|Y_~OJYu(?Fmvdq#H8=iAMJqCG=pWo4qHZDSuFzHU+}+fK=B`kIT`ZwU5@ zL?xRFk1!Y6v|8HRhKrArl4$?u1BBzB&c}&RNy3%#ENA=>8KE2A3(UL7+4C1$pTV&k z=$dpOShsLzCQ%U)OQ%&&HT>@@!4tEGW`}b!YHTjaoH1%@qi!aKVB#6EJ2I)ci;NID zukj<&4JY@YFzT7LC>nxI9WC zlxuW6%6kBFeZbPb_+{xQm{~ViIYx=un!tu!2fg}6VBo7I;*8PYqd}%8QfDDm!+=fF z)qNX=1_lqj_a(hTPl*N|B_kzia=_8bYBwregr}KVS=l$<8UH^*BBG3gHiVcIFyd!< z#N&Aj-fqI$7XV!B+~gBV!i7R4X(HcNBTt8Oi-@zwJM|{(aFwwB_q%@^nCx>F@oxH; zr+%-Em$Z$`>slM*QNdLmKg3LyA?Gj1auk!PiNJXXUTyr(?oHsPU@k(PLJXQ96x*hz zrnY4()@E$nD!wP&bCk_qa$up>5<@OP#ef*nE#y=fJ48&4CDX3pKR^mt%(BDrH+49EScQbszCnVW;! zicU?H`m4{e4wW`>4-yk;hFjm7!jwv8%hbK{<15kAVRs{D5l~l|HXr+n5d&D#uvhe} zU7CsZRC=s%?fV`S`uT^V-1^;C#EE+FFXM>NjwnNe|-cqv{*!UVlrNOl2_V@`6zA?d@T1))nup2-X(nCv}&N zuY8OgTav+ni9t+jHO5PmD+SHNK?h%x(<#)(_@Q>hG7J?HhZ%zy6qo%o&SL;)W|3f! zeRQIM7+Imq0aX)c(ylwZpk)HqWC~OK*BVPno~Z3-Ui3wWcUv=xj9S%0?m>TY^TyEi zllGZ>d!Nd(%WBKbN?uW47q~0OHlyYEdy%o-s%Skg2p>)?MxW2o7FTTU)!;XZ5X_h2)Fc){&L(U%HD5U?y44 z8gMt!)z?30yE|S*X|Z#(RNZbPjPd)c#s&*>ZbKnlaHE(v^2(X*juyl)V_p1Wi3&Jhq-E&0MFM zR<8U&67l))!3;W|%$@VHX}}zEi%e-^XgRXESROJxMaSK%)EM&GA2V?>-=DIyjL4lU zF_X7t?Mfw6r}0G^JGd8j!;Rr!UjGodh&bMPms^_^S|mSBFDqMpcI90_qlZS6rH^7) z1WT}XkaSUED!7{FibkJJh!6SjK%g|DcIg_3N7X_W^5+Z)KX?}vpj^!CpMhfq;5p~o z2=>#*)ckES@|{Dknnw#wZy~8u;w|Hq9_P=2OCq;3L~#UsetWYtJNvN_=VN1hs}1hPNp(&4_p}l`dy_vH$mKMknYCZ}HQg`hopV9?tk4 z)qINbdK!~89=5w@eD_o$G}>#o_~X=R(0*g+;MrNn@{v4LWrv)2qxv%{8Xw;0&o1bZ zR;NKlrLlolLdB%h`dY}P!Jv;Zn~iB7>wjszXnIQW>&Gn#Brx#vzpYpt;3q>QhttKt z8K}~aY6?57;*T^rn%K0C>g(_5>gvjfRX%=iJI{4BrE!naY!IX8A#sq7Fd7&5?yBIr zIIc(dIzr4T;j1J>WN<9pEctsS^IDB?mg>Pq7C$0#6&7t|u_ej&SZvp%!N`^f+!|X% z8>(6zyJh8Smh?~Tf|f;6Oj45Lf#GP;4WQ!WYHTr=A)$(6%0t-lDg}`jqeLf#c`J8C z0yrvv!o^MuF?UasOfX>Sh5gm?&3^2E{$CbHP3T@1wiM_H9DkA=r^6)+G!Rktcc4tF z>p#xk!vJa3BHgcksA^BFS*Vmf6k`ts??0UUInZUZ+o<#9Bs*qkTq6z3S-!*|8m3N_~5^;bM4=@ z1+H<@{+!Z#R3gkTE<%Sr2dYMdY5Y_4GkUHTxSwrD6Pu6K`l->h=lyC`9vKdQ!pGMQ zNK^>$_*^lRe8k)-GAOJ{Hsd|ZIAI=gNTkO* z>?ws$YR1pP38?Q(e{ZH)j`75I-&tScV7##8-!Ow?CPc_M|Q^Y}U zcS5CMY_7bqnO;(p?RqgId#a*CbGae^C_4+f6MXaDBLBIHNX)Eh`VT*&>T02kq`MQN zt9d36uITd$5sV+D*KPqx1eAR8lVcmZT3}+m6^+>iDGIKVoy2yoixOa9yR*}%9Cl!= zeRF}%C#*I`-4J}bLQzH$VkMBWQ}BF+wIl(RpLwhFRGh`c$U(>*zXJ*0+L2$Zp|z9Y zf2YfngY2xf@7uTU;L>h|($g3b^pTGLCiHNmZ%;H=A;fH<*{9EB^wUt2=5+BTQbRiM z#rS0aSrF%_7= zDh0w`UR+$vS^C!+wKnP*T4Hk3U(<(GPN*2@{pK*NVRUQ^YCZb&R7f|gkz4jc!wGr$2%Rj0uxH2@VwtZhVC|u)d1bie6J@EL$m(p2N6)SQ&~*TU;i`r%r?yz zXWkO9$@#0Oa-f#Q`TY`R;C*r)%n2S|%5gDoev>(bnBl}Gx&=bx^5Kied)@RT>uqY< z!utQ!yf$LSObtxUA{jo^VKGaBa^u0$Se651u>iV>`p38Ld@?(cZzrk$h`v;fWf1TB&yw_ z4~MxKnsVo-6hl5kZGc>V-N>kdYJ181i;t4MQYIONc9YH@K{tcQpgOfn&qKZeWp_m> zY2b4I@SER;1{Q<_Rd6AD^Q4yHNxPd$>?l#dQ@Mn&70rsf^%CrnH-M~7AQZ%~ zqU(5DOgBHK*LwX=1_~sCT_GE{S+t&_wqUU-q7JUbHRL&XF@&vK5wn==`Irtcd5AMa zEoEZ?!X8kKDGu}KM)y34%I@}hGf1SG5JDm}#!XF0UJ;NpluagICaTiA4diaGH7|wC z&zrW*@^drj2<84q(c7DLlv2Z{#+C_|CPgA;g#gMkw7G>!b}4wAh{SL=MMXu>Pnk7j z&+^0w4az9CUM+Zl=oIZNEf0-rJwN_}hoG{F`JwK6Kj*wL4Lov}oi6Ssuy;ba3!zp$ z))=AVU;6%q6`JHDn9LT1FI#ZBlmQLn0=iH=K-$Z&rTXIB6mKf1=B3@h)}z=OaD zQQ%AW34Mvv|IrQk|J@J&Z6wGlYmAR2?DQ~Xg+W8Z;d|`zY?poJpK9SOb|!n{FpqHi z^GCU}lP*i&<*pCV@8e*R4m|*qzVwqJ6V1_^67!4YhrUR3CCe+GOl?w)4T8DI zV9@^y%gz0N@wpyAoN{ffu&3Y&{QraS{;4+e$~inWUvwfPBV({Tp=WPoL?(t`)8Gg3 TU)Qk*#7}x!#+rrdws-z7$R;I5 literal 0 HcmV?d00001 From 2cad65a860552673a0e70eddda2094b6f1fc1c5c Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Thu, 16 Feb 2023 22:35:13 +0000 Subject: [PATCH 050/130] Make CLI string input uppercase Convert strings input from the CLI to uppercase . Fixes issue with craft name and other settings where lower case entry was allowed via CLI. --- src/main/common/string_light.c | 10 ++++++++++ src/main/common/string_light.h | 1 + src/main/fc/cli.c | 4 +++- src/main/fc/settings.yaml | 2 ++ 4 files changed, 16 insertions(+), 1 deletion(-) diff --git a/src/main/common/string_light.c b/src/main/common/string_light.c index c4dd795ac3..b99dbe7581 100755 --- a/src/main/common/string_light.c +++ b/src/main/common/string_light.c @@ -17,6 +17,7 @@ #include +#include "string.h" #include "string_light.h" #include "typeconversion.h" @@ -50,6 +51,15 @@ int sl_toupper(int c) return sl_islower(c) ? (c) - 'a' + 'A' : c; } +void sl_toupperptr(char * c) +{ + for (unsigned int i = 0; i < strlen(c); i++) { + if (c[i] >= 'a' && c[i] <= 'z') { + c[i] = c[i] - 'a' + 'A'; + } + } +} + int sl_strcasecmp(const char * s1, const char * s2) { return sl_strncasecmp(s1, s2, INT_MAX); diff --git a/src/main/common/string_light.h b/src/main/common/string_light.h index 005a6c6b12..6d0fd37d34 100755 --- a/src/main/common/string_light.h +++ b/src/main/common/string_light.h @@ -23,6 +23,7 @@ int sl_isupper(int c); int sl_islower(int c); int sl_tolower(int c); int sl_toupper(int c); +void sl_toupperptr(char * c); int sl_strcasecmp(const char * s1, const char * s2); int sl_strncasecmp(const char * s1, const char * s2, int n); diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index e1633983b0..cf054bc0ca 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -3194,8 +3194,10 @@ static void cliSet(char *cmdline) if (settingNameIsExactMatch(val, name, cmdline, variableNameLength)) { const setting_type_e type = SETTING_TYPE(val); if (type == VAR_STRING) { + // Convert strings to uppercase. Lower case is not supported by the OSD. + sl_toupperptr(eqptr); // if setting the craftname, remove any quotes around the name. This allows leading spaces in the name - if (strcmp(name, "name") == 0 && eqptr[0] == '"' && eqptr[strlen(eqptr)-1] == '"') { + if ((strcmp(name, "name") == 0 || strcmp(name, "pilot_name") == 0) && (eqptr[0] == '"' && eqptr[strlen(eqptr)-1] == '"')) { settingSetString(val, eqptr + 1, strlen(eqptr)-2); } else { settingSetString(val, eqptr, strlen(eqptr)); diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 99eb42f71d..ca75876bcf 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -3589,11 +3589,13 @@ groups: - name: name description: "Craft name" default_value: "" + type: string field: craftName max: MAX_NAME_LENGTH - name: pilot_name description: "Pilot name" default_value: "" + type: string field: pilotName max: MAX_NAME_LENGTH From 2941f7b3b2caf5e3b43745b3038b86eff3dc2f62 Mon Sep 17 00:00:00 2001 From: tiriad <42714516+tiriad@users.noreply.github.com> Date: Sun, 19 Feb 2023 20:03:54 +0100 Subject: [PATCH 051/130] OSD updated leveltrim --- src/main/io/osd.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index eed14a2764..c871de4401 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -3188,7 +3188,7 @@ static bool osdDrawSingleElement(uint8_t item) } case OSD_FW_LEVEL_TRIM: { - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "LEVEL", 0, pidProfileMutable()->fixedWingLevelTrim, 3, 1, ADJUSTMENT_FW_LEVEL_TRIM); + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "LEVEL", 0, getFixedWingLevelTrim(), 3, 1, ADJUSTMENT_FW_LEVEL_TRIM); return true; } From e2810cc9f5569bb8cbb00874c87f7a37c1006391 Mon Sep 17 00:00:00 2001 From: WizzXfpv <40316777+WizzX-FPV@users.noreply.github.com> Date: Sun, 19 Feb 2023 21:08:46 +0100 Subject: [PATCH 052/130] Add files via upload add better picture name --- docs/assets/images/CJMCU-75_address.png | Bin 0 -> 138749 bytes 1 file changed, 0 insertions(+), 0 deletions(-) create mode 100644 docs/assets/images/CJMCU-75_address.png diff --git a/docs/assets/images/CJMCU-75_address.png b/docs/assets/images/CJMCU-75_address.png new file mode 100644 index 0000000000000000000000000000000000000000..fbeb449387d6da631dc716b56484c27036c0f910 GIT binary patch literal 138749 zcmV)cK&ZcoP)60eOUFZ4vxqC!BM_!egb$3_wp}y1-QX>HpvS9`o5Hn(Jk%n*Y}wCWC|I*EIhish3wjEB*VL zR(b_7lFyOfQ$U@$#n5D`?B7$e3kUyl;;G#J2QFwue<(0pc%ph`r+ zbZtF8I#$oELVy0K5kV3|5y6NMRf!=W>1zEwsm6R?>GKN5CWdP6*YtmkbbX>|RIGxA zbPi+8@;b((&kDq-1R^o_Et1+EV_g2-w-2@6OZphpOgt zf+e8J^7a0yr6(Dq5@G~fV8rzI8Z{C_#8^WJA@wm3CG~*<8uLA|WP_@T21R0e9-w$1 zP>p~fLT*p&$K&dEk3HKw9#tXcHW*`Y&h`BlLg>e4>fbybx(7zO7meu;W70g*7>QAd zF`c(4%D&Ge_i+q$x_*qybBJKA!AN@6!FvoX&RDD%G(v16&NwiZ04zeF^#Qa%j3Oo= zCW7QXpg@Dcdx&0X>jl1U(6%MCExu`qUWjT?3>b^WVWQwogL;oshqI31R>k_GYYcY= zoV$3Q-R-kj%(3yj`n(=eAWa>+IGSRD5?iGS5!9e6X>dlsrNLpX1)ymfV$6WBV%{{9 z2}T5CEXG;H2=n;@Tev0Ygn+dL^n?UrD=p#l2Clxw$noOdIO%t+d+XP-uGjtEK5X$ zrfF!J1`(mEDgeA+juUHb|Lj-igS9p!o7M1l{rzD>{4dy1l_NW?+m#qY^ThbgazBkSD(OK;|=}aLy)R zMe&*johmr%Fkc?Y(=-?nTv22IAd^Gs0lEX4 zt_|H!*MA~ljO~F#HRit)xCfs;M|VCk`E=S}YxN#Q1W{<}HUWC!uqFX~>X+2NZQIf| z4Hm)VMW+M8t`E|)NZ{f_V#)$5?0lt9J9eJ?ezmW=XJU-OT1#1$M2+}%Irh5G$Bq@B z=(CRc_5>rhK}6D`(Gk|X03;A^5E`s=IA@XEj_x|CZFN6hy0Ku*kPs3eM_p~Z&*Lpw z6?OEGZA?+cplQKV#SoK4AVP2?b}J6VVa4E^1m0p@0(0ZQI&2WEA%VJ4TGJ9{ff9#} z0(p*i&#JRpy5pe)(m;c=1{)lcTQg?wHH2EwXb3@j6U(|t)6{tqt(eQ%RO#8EE(cs^ zf{O?t16a@mKS2{KNs}Y7H*1sm6=G&H8ZntkCDX|#K!SdfXbdPmftn`JS3*A+)58qJ z*b+kre32-MNMdVI6^jLgCf3B@)4&rU#>Bkp*r2KuWq~o47z3?FqRFOyNNiLD^aRK& z5TeguL(gnG(=VC&OY43WNTUkYg0)G&h|y6Pi-crJ1QB8kxi6H2XK4U?=ZFC!5L=6? z$r40o>MBa4EQ$n(8H5t+0aXj6g`p!CQ3cfIdxIDSk+T0z%(l3&0x*z3GA7xid)A5Sd^Z~2uU_GC=wOXfFWQ_GTVI+oE1C~XFSe2 zgtYiuq&M%&SP`?CYDAz=+F8Tl;f%&dqGaBy%f2~zJd{9cNzc8VwM_0VaP1JOAx6*; z2qA$bjbJsIH!-GR8$uw2WNJa0yme<@v6LQt@EGI3NHS@nCx~XS40$DWXcLo6iNQ#c z1?nbEm|mA$VRGp(naQL z_!Y+1X_Xw661WRj z(1e!Q#$KD&*b$NLKP>fkBbXQw4@LAiV?hi)Mw%w#1*~%vw!mVL2!T0n9D>aYS)>htLcti9?lB5hg&;!V6!ifsia1As#j9oRJ>FVcD>Nu>g%q3w(}xmB z0i3bKRxzQVodqOxt7{-=NNg`z2>n1vt7HPH7$liN-lMkYT}^4l1Sn`iB({m&MnGM+ zS_?4)Met$8Do(%n7>;RZN#E0BCK9R`QDSWS$(H79Vi7&SkSC@|pH&UL?rIGXNxGC3 zLLn<=6H9Z@bdD*7;4wa#kkIGS%<@5>N#R!mKpLOw=ONv zQSeboKBxfRfl6YwzCe+z-2y&h3Z;=LVih$88vt+cE>Jg~h@eIYG2o2r7q63J`=JC< zgF%c#)zF53n351YkwBm&Xdq}}oIw9@69@=CkFS^~s)RNTGFAqn(0g1pCetGj`oXuV z9l}ztQYATl@<8piqs-iTAkr)qsA7%Hljg+dGQ@nh*gS^bxlb9VoBN2kq&#xK7Eh(t

    @GUfzGHJ;S6h-ko7$XyS=C*;*L$l+AMBk~mflIu z-S1r#Mn4WnbEac~ot`NtpJDzt>hVSMukZNWWJ|=Iy(U3L93~W)6aGZ&1$I^&>h)9f@&8656tS-<(^Q)`p z2+{YeRj+~e?}cTUOExci@aTYf#cWK>qcgX%{v`>t`!FKaq>EaM4UtM~EiuPu5cVC)h5$Gmn z0tBZ^4U+u2F>(xGQ3%A6kcioHi9s`&@|e*t1BgNqFGAg)3IVdD60M zyZ*{>6nn5du3O5ACcoN_<9cak=qv29Ux-!@rDx;aVXRHhX~pbreVf~pda7IVJNDY$ zuQ9e~kKH1vs>dB&F-O6~7}uJFY&y%_CPf8H|)j&2)N1+bk#x%dj$xMq4Svl$?CZB5e+VbomsgD!^xv#chCWCCs7;+kHl{D*ylqN`bpXKXK9yuEg4+mBAkdV zJ>4OoQ6G5i)XxRqKZovLV_m-9^4ziYd4XImuF2Yt{Ucg+P{fsms0U>sI}`O-dyAP8mkxu?uvfi{P9RFOmXs2h_-EUYK(~`!YK%|SuT{2fP3-4~& zh{*$L*-z42LC~oHQ4}PDe;$Cr2TC<*tcrrQY?Nc}$c#pnfFcEygN7@Q?QrF>EnIoT zy~CGj@9k4BCd3eup6UuhY*8_+Z=PXm>jF3k@vxWbXvl>ihEjFs+qD1kKl@o^O1>0F#LD7)S(GL7v zdQSy34`&}c?Ne3;hh)|pNSGqT4h%(!CbIz(GHXsD6&+JsWe+M!6rc4SfUMnWr%5hN zY9|g814CQlJow3iA|_4CW`~mIiJTaA))G6DEqmd+pzzLt;IgAegZ7hF$fk2h6C+4+ zIIPCsO1c3cu|?=WDNmRtbPs9?N;bI&b)_Gc5eiFYWwZm=bb^y%LvWl0uO26vQ|iZ4 zc&Z-%R}q?yZLgTHB9a|uv1e?~NcQH(W1&JK5ORct0W>t(F_*M-fU+$63wP05BA~`3 zZ*{tfmHwa~M+vTS_*Z6-Xk0ETBKVLOa>?FqNnvh^roifCW@W}FDH0=FQ<$aZ*{@kS zG_Q-?NY~HqF_XqH0zRbgi5OH8t5YA3u~9XG2E~Yl5HVUqSzrbgF&Mm6TH_fEBOm+3 z8Me0z4iEpF{rz{T%78Hq17}jqwg+PhTCXgc32i&2uJ;)Z*4a68g&+9rRo>V<;?}!? z$^Du(I-ELG9BNz&CoutI3aYZi77jgSn5-TTC6IzmAw;2}K=DmLy@$-s0)m4X6Nfyfn!KQd6#!C`fYL^ijw+Fu!qq{Olh0rgwOFwPg&-X>&sv)6 zVmHC&P%HJG(~h`eQYwPi(1R1uYrU{yQfBAW$s_x)mod0uMJCB0*>TG*45!m?)yHFJ z>i(;}qa`g?O};Np8b<#OF_L8!NG!AHP4|usw#|wcjIi39|qrJ%sY7PX2QK%*@h4TCsf9z2D!H1h?eGe{wLlOi>I4ws5* zu$r}Kn_wh(PusLqRe>oDa~1>_v2lP!2)<1|3!5m6YXe3sS~wO)88n8OdWu4^G*m8m z?t?0g)C|uAp8e<+n`dq@UF@@H4j5Jjf(7rGE@ogY5kuR0+IEf)4K$Yd(UiNlZ`1li zMr$=szwiW93+h)J;=aeo7?0AJ1n|xjNG;f4Xq!keEcu}0AqCPjkb@8S;IkRhC3&)9 zlE?nDF|Y6`)-5r=sNH9pJZZAI8xzG>&GDX+%y92ZV)S_5f*72uvRAjpm4P$c1>3tL z2BQUo;gG5<`wWmS`w3DSpAUigqG2|xnN4e^vpMs5WIl^57McQ!O@a4{ah?SY_ZFVg zDr>Hy^@SP|cD;4m$27gRJLvX@bd5CB5nGqe2FvNCE(74S^I4 zEt=$zj@ftMl>S{hC%O=@4}6v@dgan7k}#zUe}aziKFB&(kCbSTbwHNa?#|g6=zUlZ zWDq|^w#b%qXVUlKY`HQ0`XeAQXP0#h>_oJ{X##HNggh;Mv;%mYoZ z@k(sk1m0_ox{Mq#Vf*S?YU_z=Fjz_*!@T8S?-09)tck9 z(=b{yJpRNEo9ltY$sL;M5tc|<3iaX;DWMcYP>(YW^Tj=iV#siq(ndAHpcr!Jy}M`> zKKHq2`Sj-=!MCro_iBT$Cm2dpi~I~N#;#gEr&~GQ@z4UPki3bB`A83zF-q0|Lk@9D zppjzsmLS>%A*ax$Hg%*5+I?RVge29nO_7_yWp)riJ<5XJ-3=~YKF_&}BZ3|fnGkeN zUGFoU&pDh1thIfLVV61=Bb3#MGdm?0E>)yQs_s0%hI(+*3?-%$^b6s&Z<;5yyry`oY=SENy zkVsyXyz$jJ2clhT& z_wzjZ{9`aQn4&~HR8sNIcdzlKU;AyYz4SWm-6>n;5N!ey4H^wmQY@~kN{n?-J#sBPIu&6Kdm4mmrcXNh%h-zqk(n-Y#)}c+l(EMX8p{W04&(t7S3PTVrO^A zaHurxZ4M_B7WF-RoKn}*%%nnYtI5ILfp(EiMTFVhpc-(6r6@~`sThrRc;w0k=gw`i zf4|}Oohkc=HBB9v2B@cjN!_w;9A}CVYp%f8k=6%de%hVh6SJpTGGHWGEvCeRtVzZ$ z06TYV=cwqk;?&Z#$fWpf&CZsXSlkNP>{uHt8E@ykK8=&6$O4lbfBCy&ZPtd9nH##I z9o@6<*xUOJj*fA!=(@+FCAx)TIhMLHbaIeozsoV*5;|tw{oV1^-2Nr*aq@&Gu{!DG ztKnZOzw|n3?6a<-fEq=O;-zKh$}V60Z+?~wPh95Sy(9kB+y5i8w-0cVGJb-IlsjXd z{GsOwJ0&mt#An#MyT_k@`9&J3`LTcg1zz}xAI1zUWmOQP$5@l(2BSRvi5IBOjQGlL z{XQ-RLi9ZQBcI^;AN>@Me)35|rHECi1ixr$HFECxi~N^Q{a5_k#hYn>`Afq=!LKGF~6Def~V>uRhIi?IQD8gNYv1 zIk)fav3cee`?v0Lcy}LbQv9kb3f{f`Ixqd%AMvCA_-ELAcf!%+7K{6H3UxS1g;y5! zoVINkN=mHwAZzEL1X9Sk&3#&6?9C*NT?(kj$CPiKfYhff49EbP9UdK1=|F|fqn^Q3 z1CfYGq#8}R{KyuUA01=M3G?||+`j)Fv)MjnVQ@|`77C}J9&)CNb3)t9(*()E`qny( zDo8-ACx$uR12RK&NLg<1=wmxvd}N#3do4HLJLKRXFrRsv)-y+v=eAg*Dhdb&(YP!M zmH(@KNJ~P?pec8MsTMB7yn2e2P2Z%2B!Nz{rmUpOTapt66yYS*>T~*|(gl=q1dO8?D^ zVG}(U9=*!i`7=zUX0Scx%CnF0@{2F>`Tz6_Jo%ZAGZ}gYg~17w<&cQ7KfRCIhz>13 z_Fw!IDlLEV+ke2;&MsGf@L3-J^fN4^rZ9#zR}p>^6^FeUb~0Kgas{C#lvh zFdl4D7)w(haX7ujo zxG|Z721HWyO^6X|UGnDp0Ok9e_YWzMc4?XkAdcx^kn^dNE5YZ270Gj*<2}ia5deXp z9wcS?U<{4-SZ9dZ5~X2nW5~Jln_Rx=vE`gu^A7uW-@!9g-9(9CT`o`7dW@fOYlBV(1^iM z7zZ&Bq>I8`9x0AA>9JmO2%0RjMLO*0Oxaa{Q8YzNtWem~HP-iM4}G?i$Zh0AwwA$vrgk9$?Up-eZC*=8G)u7k-7nJW#!c#6ugXs5WU1nY=x8vE8c4kkw&OeYLCH)(>$Sj+IjI#<5`BMdKW zF!v3Uy?ws?JO7?r*KQH5;dB4^N4R|T63wPE)fqqib6@0@S6|`#KK&`a|HnVeetXFJ zaLBzkuk($szRcoCnJs2)Kf2AQe*A}6lnbUBc>H5e@Y+{iX1?Fz#38Eq7_n}MTBt=S z*Gp_!v$a*Qck>#B^$e>q>ziYCFFwMRXI|jU#pkgb7YTMiBL!XyWU$5hc$dNWJW#N< zHsDYG;7c^~8O6LHsG&KkdF|WZ=J`+mIF}wj%iU|&ka=?UI(6AfP0u|gOT539|4;&{ zB=Ig+H%cKOT|mBKayH5e381WiVmr%qm0(}m0#LTE8X!}i&dC!adUXdG!~ z?@&(v58%kMM3LZwDpJ;j1`oY7=7~CN0Xur6s$`* z&-?p(Xfzb|K3hAxJoC&MHn-r~TXXjJ41VU=ZyRP)Pdgm5WvV18v_64&vT<|0)=V%v z4Nq4ltK?dwq)Ban=p)uyn&>fwfr3&Vj+wu%V>R{?mQKm;z0Ub_>XEY;mwM~!iuJ&i=;VOa(<#RT?w8D4mWyD1&t{fh zmM%MQ0;Mfeo`uO{P7O%Qcx_DS3WE0x+<>YY@Z2Xp&ieKyzNuNa6@Tz=e}}LC`X5q; z0csq-_N`y$pZq7E=i^`eAv`VhY{9|@=HfZ>b4F`x9NxUgum5kq%HB8L#?}>TB4HG` z{pNK(|8qah`sRqS8{%7!1VzN=3Tq%HB@eW*jH0l_dYkT&6rMwn!FECf3HUZLFpZC?jge9PMG(v;2v9U?DHlis! zZQT;R$C?yU6-AN4u)e-V;Vg9ss8c43Dc5e?V6kWzRcrkDH(%jvzxVGMHx)WJ)NR9H zW5B=r<=^DRm%c{1Hss#zyWD!~I>R6NY*No#k2cEw%>#;NK+!scNL0gXfABKWSavU5 z;9Fn$26iEo;y?od+gp)sTcZR91HIWz0Ivc7eRy&DHS_sP%ko!8#r=B?LKDMkZ#?%k$Q;gPFX7_GlZeSd~%AVFhl zix5Bp@OLh=DaB+C234*;6MIlp?W(#*z%H5TO6W@eldGP$YOu~ARXgmV8a@Q-W|kZg2;O&qogxKt#B(wujYTE3wQZZEwRYZQRfslMFN%b` z5LhuZO^Y_3<*ahFjd1JwZH|T$&YnHbN1hxr7&_j0r)GcOFsWNYJEtbHIcN^J@#=eQY_4(f!e!oi>Gc$&8bQs2pea3a zobv2+MO!?D;hhGMf6e5xmvs7ZAYJZydZSNH$jmY=vgx(casiHmVFu)0SI#|=@4JgN z?Hzpm@7f8e8834HTb35OPB5fh9h`H7sLb02EiG$nYgB`RnTbRj({r`Tyq*J*vaE*3o*8 zE0nD>C68WR=iEh06K-<<;Jb*OL#PS4k`1IfrBQ8)aqO5xHz7$81zk1yWIC5LP0C5` z3Oz&&*4b3OJ^D0XRC+IaQ8?O=YKS_i7?u^Gskw9eZ8pwqaOKK5th2oR_JaF&VLET| zv8Av!Z3&^8b_>X*-=JeQY1nia=<`JGLev9FtC6Oy8EvewnAb#!j5pUffB6D$fBQ{h zQ0lf>nzA4I=%D2kPdV?GwX|aL_Fq|99o~=qc1YEKPF8+f4Xrx)@6yy(>DroKJtYOk z8rvuP_E8UAdM?=l$f%mM=ahLA^Y3UE2i?PN)_JF&K?#?k^AuX48hUbW~DOXpTS# zLhTz|F2>RXPYjXSqG7BhMQMpXQrZDch*%XyrlQ0UW(^LLs`lF|kp?`T2J1Aj!w{KG zXG~^u+%V1Qq8w5VHmMm9f_-4o6^#TMtQ24?)C^Duiduz9|J*Kuq}ZA zCNLUXu0FQGrOSr92jAgvb`9qiV8FVH*0(rUA*M_dAt=tKRJ^jXSPP@!03(L^Y)(-Y z3281TLMw zgcEqvw;Zv?bbi3TpA*!vRgBTrQ%X#`FZDv(s%=jK3zyRwJG0&jftGK-@-mZl!sOnB zdvcd+@^;EWmwEGlYEZuGq#>j_d;NyFw^k z9fXtydHj}*q_C}S+mO^F+PA$A;p(oFP4S+_9%~z^tU`WobxRS+iz?6qYmC|RPIfTG zmAV09`bX5q;A*ZC9|e&D(SV4@N<>48Hfi6ZHCtlE5dyeiFg{QY9ea0fGo4OwJ7avC zGVzY4)3im(XvF0H5&K66Y!1gT4^+l zRkxlXhDD5&rogw6fh!5V#W)8|N(J@O;$2HDLdsBV1Fk5Dg@Mt4&CLsp25S%_zHOl> z@eVMl^kic2f-yrhI=Ya&Sv_aGF-}rh1cD_rf=Ed)foNKSdL&j9THu1>noFrdqohP16m zR3)^LW*XVQf1AVoyUeEhwCx0I3l>FW(F!3tkOD$W6h|sR3egD8I+}WhA53`Uk!=Le zo3GFD3U%wzX2N*GQ4}Oke#jLHBr#!Ox&1^k_Ln|OL9oUV)pGmB9fFOl73=s(;KrM` zFtG%2h$&NPxd$H5DXaSjfa~$Ez7I3#5VH#nN+mXyp-8LW?R81{u$MjcSk17KtdpMB zx+TEp&*+j{_Qh&e*l@R|om4=Qb}!l7Ke5<#j?8>1V+yu5&k%AE?!{t`DGOXVOqIcW zL+d@ID;Nxic$+GcRl|z&XU{Sy3PRJexw*x7ya9J3Rt-^8*pyf(wZKO528$BOXzuR)Z5uWgIa^TuSnXT&k2t$Cz#15o7Bd>7 z&Jd_6hN)I;DlHgDyFdg~4bcx0(btx+IAZ-w#T)l-5!xvt9%F^^+JLeUrn5P-X`Ob3 zh>DMGPOYV{Bl|&?)k6xTDX_PyDn^4LvvAPI-*xe&QS*+N5zx-*(`luG5t}M4Nu(Mo zS03Nw^3{_4>8sp5c#Wzsl;wc=B5j=JW58A;qW3tHFwK<(ic+nuv$4C)<*QdYf9Wb> zciGw5VKg4~=6z8Vy-r)#HH+DV#pE8op0Jqgar^q~+`jn^hll(4`-hay5)m375nJNb z(1zq7b0Xk9!>VAu*vH3)$3OBo^TmQi6WPDtV#IK7b|0w*SSgpL%nI0azbp%pD=PDOH=Ckt)n4GZxdD z(v>ViiyauudWjA!b!Zuk95R4nG=RKMl|;cW7Tnvr#s0lJZ0+o_ckdpv*__Q-;bPhW zAy{Z7?S2p>rMfR9P;11;$ap-)#UYz(WAx6HHdqP_zL{Z5OHmmni#dZ~l^mz75R-m{ zQNaX*iv_-!6R_MqIO5Wyy9}z5u$Z!#OcBo)Yyu(^)aK;aO3WMW=AzK^hVsPPDkzr#^E?Aoi&6evh))r$LLOmtS z?sN9y(>!|TI`3V3o%e3M!=1Z#n9im+jkJMOkU~-%UI=OD#%5ll($Wq*ckaB!)6ZVP zha-IS9NnKGv7k^W$^t8b>nro z1`?+*x6|~{(~kH)pF5VF)SLImvyHmNGJhlI?LXMO(~eW?o1UnY{()>%mNiAY*So)0 z;deDgv|{J@f#s#9Tl*#hX>dfIBz$XpR=RszgoTXMX;l@ugq-5^sI$Rc4bZ z+ZT8Fr$75Mv_wiA23o+{&IUUdcH!C#nt=BW!3wRkOp67>wJ~BX zlj)q+Dp-SWJ@s_Pbg^Jy4dhHgGcp{-DXb0n#E*T3x4!cRciy}=eI*1lyh*uV#$ih%%;3asFY zGYrQU8LVGn`}}<_UHLeNci!RkS6||d?|z%Rx8Gyo>l9%?+Mc6;RAt;7f<`(flW`Yf6lZ~_tnE~bt4O6Mr7BZ^`L zd?#qGh?Nfz-md@kI1pv{J0@QW(C-1YLL{XFlVf!~GoA{^!IUL9b$WPr?vvExw5hZD zTIa<-?YqYtxN?ujKDJ`kckNwSctoU+!%c;&@-KgyU-`v-Y=j^G!cS7{u3@W!ih@7;Y2Bmr$6~D zufOmdUw`MzY;UYVv^1vW$}^AieV_j{=PzC2=-v^({BQmbY?;gbsZvLe*%&Z6m@w3W zMLoxi3_DjY^SPh-3I5?v{3CwpfB9vuy?dQuXeq=XlB-um$<8cCJrC54<<{O2ZEGlv zWp?i_x8Hu9qk{vE_7Blwm&cy^G{xF3seWHTb;07`27mU=uW;wa8@y{h@4Wshw{G5K zI+-vWuQ3>mc>1Z2GQE4mt#|HF&jK-+B(I5LiWK?K?c(}D$3qIF>3_i|@1bJ)$=p>z zT2^1r121pU8hws?G%e#bxcKOp@#c&>_pWp2?t3XPKZ4}#U4u_ri@{JzU@%(a$!9;# zm8YKP!qsOPZd||?8+a;WbQoJ8woQA&=cBMi+NQ(`Vmo$Y2ug2m2HPip3g7TPryy2j8S(D7S9jWc#e;+2_ymr~lywwzAZ% za8Nf4M-?%8N?Z?L{T@+$LE_v`d9GWR_hPhZ0y)*b9A3~!w~3vIS!P5@sxj~&N-cR= zSL7oB=L+*$b+M=g+F=KQUC>Z>*P@Urak|cK6j4Am$>;yY7nn~MTzv8>jrR=8Aus*mpYmJ(`d8U#D#AfcY&bvM8W#t&V0h5Cn&6yE5 zZcKP&XBVvlv)O|A^bj%dt*`z&?jA=c6C}D7zQ0@W;RRGB@7bqn<`YZK`tR6jKywT$p9n+xs04DUi|^ zWrnn^K}_z$elPmam(c52X{rQetfBT3);0}KJhj8+t0ir?&b4dbW>8cROROo;kXCdWlid5;ikTHoShl~}D9VrX>>?J-@2{LaK@=?dv#UYFJ0owbQL2|3vz2TH9ZJ@lUU??I64SzAx( zmTXLWwzdMKvf>)+ojZw1FZ1!!Ipx?sQ|~`nK3t~M>8Sw^zLHAnXEauFBokw;-EOp&ds^d?-^hbQ< zH~#?cc?Q1Z;GO%l_iAiWayU8S$xlARQ_ubnET%PfI6y1G4jp@kM~q{|x4!ZU)9XjP zy#FGPT)N29KkzJb8rH9D@zek97b!w287WSgkCi3{w#|V1@4km^0^$R08!_UNJYmyr zp+j*@7cjdY7!;2ATE*tzEPID<;_u$$yb*SHb{Gu<_YU6W%U}9MVoWjFRZ(!^(j^Y| zZZSVPVlkc3EaueBoWZza_uMWoeE+Ap{@S~|{M9$uzr6r&an2$R%3+1I8A$(v5_$mk z7k=Rve&IumkiUIL8@T!Ad%XGbJ7{ePKJ5YTgW{u-{EXeEY1!GNfv5rN0$aP5r=Htp z>ulilH@<;L#2G+SzIj;|*?bI$QMPt=c;-_-%xC}M7dUhNNo=)E&;gPw$y9~l94HOO zq#`FD{G(V>C`|ujlDAxp!xSUR(HYjyY%^LPB;bmkdOoLVTUv!+1mgsow>B{d#wpHO zKJt;Lxp)7N*}P5LLr0}73oL?-(lf3l#7NHJPX9VdkqJfw>1vSXaPUOFa$b5T2FS9u zFY1?%yZ8$8V>P` zKuN(^OWu9)yZqiS|0eTm2Mqmy*c$5jf;ZoIi^o6mB4Oh{x#v&96fB99UgLScbhX?TWE}2IDdh)GiO-aTBoW~Sm2pzov-}H@AKt< z^INRd14>_}t&>T_AyvIe^B|&3>IOGR@u)#t=1f!Ua!5t5MLpIj>*JE~z)=}6!E@{8 z9@E1kCWl9~Z7SMsoG@Bn+t76%3D1?$qz8pHK5>u0z4$j2UM zyg9-+)9-h7S}gO!38b1fx4ZTBEna{59sEpb>IFUoeAJ|Ss7EDNGuMtaMSN_jM#7~> z*Lduyb@uLmhx>Q;5ESogoCDEF;anc-}Tg!?|OE9IE8hWq2$!tSbmyGurQm6bp0IsM0 zDaT$|t#ZHG?%s6FAlf_CG70bR({%S|dO)^05I@=oMM^y`jl;B>3e|XU#_{5dU+2-w zk8pAKBE}0hUU`fE=YRbr;_U^)rbHV7S7HMk+&|#mTQ?buD=uHUz^EE9EC-Zg8K|YK zm3P1M2EXx3|1bAnzr|=_akX;i)-CSr-Qm)Oi)gFdzIGdtNM(|~SxLcf{K~KK$G`gj z;qFJO+Tj<_rc7)C3RZ|QrL(FC^BAc^izy_Lob8fkQ8PO{A~X##2I{)TYh-dXV>YRo zO%^PsQ<{377A)&1s*3G%+x*l|{WOE(JYWCHb>8~(347OP#JWle2&LdEiyc%{YeSy> z**wes^-Z3cA2Dr@SiE-|zlcCVF&tuC#D^voiI5p@efJwY z``l-F_2oCYK5uAd%G4|4%HeF8_XS_62&GGgs!N2U3o+_`r+1jpGp3GUt)}C4ca%Un zUF4WT*k$^xkjPcjH*H9mE@gWr*Y%XHIIoTa^XhBD1K79H|EsrhT)*t!f1kafRGA5QC?XRP&*-1&iQ`v&gUi z@4v?S=I_%sEt6aOxVc~!772zJl(zAd*5HEU-Iw0tclVFD@y$0uplLn6@r1@R*+1l9 z?;iKB-(@Wh(1php1%syG-LJpJ|NPDWiLG}Ru_1=Lhx^>M4bBe1Em#{|U^c(S{ezlCbBN->IE+;I zM(|CfZWgpL1^W*M1J0hk$PazyhiU5(FTeN>dp8U>-kA^=hSC^}OB%EhgVrrgGY9$q z$$PUWOOouo?|0limb>Osdv#Us)zdwL?g3`QV2lI^h!_w8jD!f&g9wSD%xE&19`x7f zg^(F3nPf7EA|O!^VC0aXVFtipu*}l4cX#zt)m>{=u6K{M@45!ceVJ|HilTJY-r2nr(J>u?|#hT{wGQNMnh37uPwfSwTZ4X%y1No5t#G@UI8T=h>L>~;@3IqnPM^`WOm16u6ES_~Q(<#D zu9xUZx1Sk^R5u@@K0`2qFBJ!F%Cw%dkq_7?3aYw7OU5iz92`!`=L_n+ioVb2*9KpE zf|W!*7sLw{HF!tSXlAb+@RzUuDcYo_b%_}fd?2&J$d_?K#$ZDLtLZsIPe5)qY)H<| zS8lUw?suJH2hQM{GCmh3lHUmqCsCi)1W*!9ledn6QCKx#vR`pOKwwCIcEDg`gsmU2 zw1-rSCC)DCm%?&k2?)#JF?r52&pyjXKl%z+E??t~@89L!cOG!_ojE&qYg}b0B(@hJ zQ&I7$2?!0E1}6<#7bx_p2zWalOG7G3fosXwQ9&tsrGDi(0c|x%K+!ZF=b)Fv_L(7r zq2@2Y{+);oc_Anhn|6hO7Kawine&%;{-syAc;#ul%77Ix{iBv~d(>!gHmx+3- z2fX<5Pjh%MWj=qCuuv?g6QX#1K>0vvpv(()_xJeh=YE=3zxn@?_cYEyZ7t~3n#IRt z$Z?v_2h8V@KM&n}BVI{5wmfpJ+NN+ZOmDO53ZFWO8p&|hp|oD9{1cm{#m9dA*livB zddcM@CVVU_-X7z4i2l&|g-8DCm_yqdSm{<}<-H>kmAKmQKDAm=t&nv~OH(UuuM)xM zo@G`u@iXpKdo zY-|+_M_}Cqut_7a6_W&fLoTqjvB{Iqy~tB9d>mD7(gdAq;UC=&_{TMj&TuYZdK>iY z6X0r|eC}o5efK_&C4S~;fTfRw<7EIRH4papc+Pmvoa-~0z~sPDTZ=QH<14P4lpxY& z=hyqsuio(J9lPDYd{;Yu0A}jcsvEf1;mK3vV13oId?rTEp3Sv})~GVeKyyyC5>o5>G+ae&78(5S&ZJ z0I`W*qdW(8%I@-z!)8H0E2D^b16WOHG(l&G&Z(OPM~el0-9zg>rZbB1^OeMqnstXj zR(p;Ltp^=TLr

    d+&E*>V(t+ycJW4ISLVpkztGf2GB{Y1&Pp2r`%>8d9K;cdKect zJgT`fpK`FbVC#I3;bzWY+-KO&kjhYIu{`-`-?P6{(Nqn~nXr3*!TmcECI^;W4=^gn z*AVh>?81eX?$>T&67RkDqd+~jhBWRfx?2d>bp~z4i@{@Qd<+8+McGqaeqw`*mxkQk zc`J%7gb;C(K-`ssqbPDVH_q_fi$94Oo?})kRHn&JR=UWeGt@t-A*3XV3ix2idgrOC zIZs}DnRnj4&KuwT9vPn6T54O7>mJq#^|Il?-UHsd^(H^{sh4=?oj;{=js=#+J4%(I zRH724_9u{%ERQgK-f=Fd001BWNkl2~alIg0atI_mPM2*zQzDaA|N+n7(rdk_{qUbjB_ZyF;A&otTI!W@*dsvA+B)Su+ z!5tCLEP9H;2)56bym?~}!BOTp1dkTF=2@fRh^x8@(!Gx|exr>ZbD47( z4q_%*7i7+W6%09Et$8~FttdvICC9fsPI<@x#s?~_Y^-psXVXKRtF_Uc`>_={4qqI{ z+LBl7<6kPJ)59zsKUR(%BXoFg+t%7!$b8ON8}cl}c*v9nBZ$s$&Xar1rY_kS7*r3m z6^sLMYeFbOEU)w-)vb3s4lS)~{Tb@cCanJH+I8xHsAu&Is zZ7vyN-&+xI9$#CuKwm4eypQpQgJ#ZTx!`b8vnw^F&d>pj(l`|2HMuFko7m38NA^S4 zoz1(X(6&0CmaC#o6q;@~{`Y&f|7v5d*U z2w_gOn2=|&H;)TZmox-Nmgj7oxxkap{{$2p)J`K9Vs`z9H=^r_k&_NA`S^5>NSS_}+SG^_db*$=a)vHP<_%>pCk%u|QDgH4B^BASp}&No zGYlo83?>S{Lq{g@5 zw;qUW8zeTqq}>$Sq+hyzN+~j9aL%8g*PT8dOGDb4p;rEC{ics0Wh`Mt2V5f5dum1- zIsKvH!Gk-@=M(TQlC`r8QJ}TZ>kqha^?5El^%5cEQ7TRpnL4hv|9*VQALR(?jJvZF zKxc>s?3kAsPI{WFE7Wc-?YSQdf7g!VTMR$= z1ZlLGV+y51>;0{5M*$>wRB(uG@V25T4bQ*)91}g`o!PtSZA~!}3W36EbOlm*LgTxu z8LR$?C8mc& z{bOlJ+lwz+rI(Ij3#%PH_<(isouWM^_l!0&hQos0-TSfqYDoT`(d4@|j)Bb14Crs5rf!zdv$2BQ@F5AO5y z)hFonGJ*=!&Zb)V)y;G4Hu?b>3G02*n_~% z+k3qA-5V5AqLsqrZMD+MIJcPSy1{=G?xmFK@O9mKlBbOJ0c_{{C_A!#E^Pwr*w4}{ zbaG_fj63hNHSDd_qW2Ex;!B)^szE8i22VNabK&Y`To#~ETzTdyg!#^L^p#-uy~BShxLHA7W--o#IBXjPIk3V|pXU z-VoLi($#XsNMQwwbiQZ^5iVgRrMI4-jJND+4#z#<(5;s7AYNgWq7j%^4R2h3i`its z(f))t-*|^{W$>a1nV>~S!{mIV35G})Q@%xLLRu^7JW$djv?{;~ID|-Ijoeu!>l?)S z&UkzgyG9JM`aDlqZCLGX9Ab133ok+!wFDB58XO)=@O8TP6U-$Fg~lXkf*`3&LDbxc zs$WfH3J^PvdWkf!=m`tfT9(Ttb<=#PXZW!+q_BR&3eG|Z5$kjz?pQ8Sn!Jm>?6uC& zhS*=mdz3OL0p~2*D}r}W6coKN{n2@RFp1CS(uH0JtXJblX-FS|%Eg;VRzZFUG09Mi zq3918Zf&77Wa7z{!L=cK@D!P5I^AbuGovUxNMtg274SNMgLO5g*l9J9-NPyy-@PH( zNC~Za)XG~^(jMbOoa|bd-(`0tdeq8!3N(HZp_fc+GL;it)EGs;Tc14L1oN!5QE917 ztQ$3sdzY(uuRN7?-O-aMwyb|`A%S!rtw(+`{BIr4fbSA(DnSV_ z?V*#wlS~LE;FV=oFM0htZ&21bm&yyw?#~F4Q;hor70}LM8W7uN(tu&*Uu-Yj*!|>dk9|PgwAkBKUQI#qFFZh zrb48_hYC&k$lLX?G^FiK?VL*$BQX^4-eW@(m6V9RZhQbyQAd>EnM{tD98GAd8dYQv zKv@sU6GYP=ZBrB@f)|2v37}UXI+2!tbmPMqVIhFH?txPwd3+*RW$0ynh8x=;f#55& z&(kLD(4r6p)-N!*MO01MGgLJ52;NpOdFQ)!9>=g(5@o5iV3Jx?2;JYdpW7yh+7P>C zMRo=~{i@qUQgUjQn0S~nb3DXfC0|;_dzC!*;M$2qgDtJ+7FJ2Tb(q3w%~Azw9lde9 zhlQuGhRo}@gY`3Z!<5-_j$SxMp=3KBBbcs3ZQC+BYB{K=Jl5JIB+>sO%f(An03$^1 zi>K9Jh_ARLA<+#Z&MP4j-kgtNd^CRXzS0Q6R(Pcn^q>eqfzlm~yNf2Mu}U%b6$`O6 z3T)#kGVm(S#)-oQPiCTSFsVWg6t1zDEJsi@&Y}Bx?BA8-He&}fgRcYPJxW;+`{)~% z$JCIvH=FmKrfH6aYU{)M)ozvN875PhEYR2nZA`37hq#ODC|WQa4$1SJI(eb-fg$eR zAIjDGQIGbaTZt4Cq6ckshA}0>!I;r-1G@;!W`SkX(6|Oi%=|_iC_c!U$yf%5vlc?W z3d=cuGlzsftgv61!2Rfetuz0nYx!K^vp!E7Hh4-Ccyk|}(XHbNhb=kX$g)rKeO9w2x$ zpp%w;L{|Np@ORA6$F6v>o37F^38WHKp#(I^`wpp)Du5G1%Y9J^dQ-CM$rO|jRMZlf z*AZHx$D%_M@s}kEr>i#x)A>GmMmI6~)+54wLE5?~h9O(G!mL zBLF5n2l>gn@z{7g4QW`Fw#6_shTyID6jC@vhmd)U(I_1-2E1=j;t4+KE}59^&hm_2 zua`b$WrW*6@3e|0{|JiBk8i~Jcn?Z)f>S6}U`&qIk*MC*x+@bOoaM5@xmZdYb*;lH zJZr)F_UK{dBzEU}A|zfPtsQMWu+}^MFvGhO2|S5S4O7eygIq|9U)9c=*AM=OyUW$S;c-Zy!4bAOVvZGGn@OINP+ktSPah6rq*p59ye) zdXQs?7h32le(Gs9qzg}5;<-N_uD{PXbz_p1fy2i+=#;=()ATr&9bYAHQetOqGia-( z9`<0@Hii>lTbfTtvrBl~Y7JWK__%lcew(V27WZtsw?=BxG2A`Pv-4(k+z6F(^ptR} zH$rEM*=$az9L_`y+NN%BG!%_tdobo)Z-b%|v=tP&z^ml7J2+ zo$(>G?~VV(U_XFL%Kbrg(V!P1cA7HuF=-X>N`NR6DR@+fK~`MXWQ0{9=s@06jJ8ME zY{KA7PLO@d>;RK%tZ$f3GMdJL3-ro9o98w;bFRmkvzo&_Vdw6G*^$Eg9(AM0b=$iu z-v7=!(yYj`EJb*{FURSzG^9Rwv}$+w_|$vvIzTx7qbJL_U4O$H?Ss;L4+YLArH3&5$bSG*2NJu{Qja700y| z&RAyyh!SF{Omyj_t9w7OekYBpoPK@UvkvWsN{h3$RY$R6r`=#hq~nRwvKLqtH?;R< zJogAC(AJ}`C*P9C+Db#}pzw8U4|l#drWy26PGfxRqa_}ODkI;xh|w8^RcPnqCMtl5 zy}d-m);Z!O33p4RKlxZMuT_Q*Hc{B(T$K>L+K_VmAs{+ck%fR3P2&_sXIN|F8Hbf; zAGxBE?xEPaMvKNb4iOEKRF||Th{g1U!DUCIju3OiaBQfWeS`&d6O+fm7NEd~8H>uW zSlnhX*rXh7a&b6jwAtg%P0Qi#5<*(%wjv?K;t%H4hGPI{P9t9Nm#+T2n8s$dI)2;NtcpW2@g~4&D|R1@JQqELyaHED4%cz(?6pI zs;6mcoQu7sdi{dRH4&$?E*acNOIj?eC;B!%~FvIAhvfUQF2)28;Yr@mgf z)g2;4RijqK-lc@mX{XxFt26MSJEmHX4%RM6+j>SMZW67>_+bQQT95j)(Hj1CqtL3Y zCvUx0h4nE}p|y?=YQj@ngLM4((JNXp6;_+nda|jFqzD1g(UZ$uK-ZeWsVKAS0p-Xt zh1NtBGY1MEp^7|a)hEk2Sy|B36{3VPD_G3tm?C!54c?>C=pY0P!8PbiBSvGJ2pxFa z(1K|}V)dDrh}Gv=K~>dY;>L~(;2c^R6oPGR;y$;MiD_HPGAidGH+WrBl!js)xWD)g zrt}zNnN6YB7jQ1FftapZP8*9L)OF254)A`-aIoa!)vJuhBktdUci)-f?GWoSyww;L zA+LD70P%)$>&e8{ha)?Bw zA#1DHbH1*ApoGa^%{UoT2ecNf^&pO_o>SF}w4qoC0qf$!twa*;8~JuBaqZTn<64}o z#W){5jfZcx7Ak17-K}g|`(Bm4k0q|GGUn1kF~^5b6epzx(x%oLuWp{LVNJ%q3oF|W zq^$w&rg41Ur(WMv&dvJ{_gKBHJ8minNF|)dE8V0sz^V;%)8cjr?i$rWWcAPXGeW{B zfmBXu(7~e{g?JCXEe96zT+!G$xlyP*&akPM1Px9g8yV_qfmVVzVX-*E^bAWsCokgs zvXsom7!ce&yubP<5avsN&IvF)_Lcb`0BTT4gBFSm&whn!X-9be&I*$I_5?1^`k>AIm^t zg^5M}T1)m8mdl!Y>2NksmOUni0q}^5I;Fu|oO3J}%VQ$H|Nk3t-bz8BL6jqe8eD9P3YG`DLKIgbg5a$l1X9N*xn%2Fkde4 z!LxCGgLB(M%5fi+#R@S~AEXQI@@~AzD<3iSPH`Gnr1Ps*0@mYdy8K(PC%oA!^K`T3h2(jdfKdoNfL)4;dU{5d)lq5 zlM0ki$53nSq1WfpDn@lufFyotmmN#^ocfU4!fA{I-)6VgN>NiXt;J}e1Al0d!8q@g zSK8_kv>yMllG^pPB!#>pU1wAwkP%ho1F4Is)-<7^4h;c|I^W~xf9)4};+3Z#wny4>{6v{_B7G8+`WjpXCq#!e^E1lI7llbI)Gl ztN-T9-247}^d!eF9GS_Xa%imxIzXmbx+O>T1T_rkVZ-I;hAfo@Z7DK?Q31Rs%MDvw z+l)t>3l#GBx(1~c@4R!JufO^ge&rwjV-6pDk#GLVJ4|Ow zBq+Q$I2Y-WO67Pb5wCrp`{eO7q)t#lQ@IAG0#=|=v1URAi?1s(CAhEvF;otM6=uu8 z(NV?b_$+tTJA_b2t{I9f%TOv%RfkNc?{RMXEKMkZ41#<>BZ8CTVH0s02KQkh1Qh~a zTqHj$l~m~(G)uH!u$&wbnph6#n+nl6^SZ`l28HF^nX`QR+uvtCw=Aogu`0-Xpg_@h z7ln;O>@FGzxE9Eyy|q@P`%}+Uj@Op^#3gLoh(tjXi5`P!LQ-rpS>yq>%1>INzGe_l zP$6bkB~|C3qgUcpluDCCy!W9iNfZ^!BYlWE3K36jjr%HMY2^ZAPAg{9Tf^O6mlj_= zUNhewZ

      )iu<$}SPEBn+U@)YR&NiK&pdst6+GxuHT5N=XoE%EHp`l(d&D?L|kP zcvg=Y68t?6Mq-7;3Wg8=UW2eQRMYz9@#eb}NF8Y51rW4G2|qt8Skno z1lSyD1v)CI*8_4BQxrA&y*|cDrY0wGEF-L8tQ9adUB{&Z>S0Wt6a^CUc8jvNXX|YF;rN zKeO$I_8Zn3R3Ipe604v&(W2MsQ466GMi|rQ)_phPT+ZUs9BbChke8AdUwW0iG!#~1 zYB963U8W}2Gc_GD=v^eBcwop;ev5#R{iR zE-*3KV$F1mB$-F6lFgfA_T90K<((2kIAYnpj-!tf>{>~NbFr!=MW zIoNs==UJ=i=Eu zOY;M)2$3rEB?l?7NIxO!ydH0eUOZejrpRn5ZEDi#92pK z8p5h(}6$Wm+x4)$7;sR1lkg)fR&XVDhQF%Vlrsfnv`yUh+ZPR;ucgy2D5{cFg^bl8j2x||r50vjml&UJ zGBz=w-MK{HoT3^OY}rwx3}T8R;?itNT!Hbih<<*G%^MpGI$g#a74p>3ny8YM8F@Zn z?V2XtcAx97zm;xJ@uMH_r^wqVBrs$n2(Z#WqM%mDFk_wTk5WYp-T;?i6KF zFu(i?N?InSTFfoH%GPbWShuNQ{l=?VyKXy=ef1|qm4cvFu+qK2t$Q|-E}x~}Il!5d zA!*S=MIoJ3ar($>#C6Gz?IByX?&ka7KghzO#uN!b7%(%_#F~`SoMO2PVKYZbfh$*d z?YW;(tJK(g>mELK%Y%ITJFoKXuRiaiIqQKOk1h_Wk&%9@bKol$U{X*tjW`Z!}5V zun_8ossCkI_lIVE#EJ%I{qT&G*m8Kh!lJdI-qc(@Ge)JFV#GOeYbnbv))}gCgpk^6 z1DK8vEQ}&^18`Nwrqd7K?#X1y#uk=Mg51@yONN< zYFjG=fz||pAMv`Zq~piiGTS3+7&dRIQE&BFTs}Z2IYQW4AsX)>8cWO#4)fNLACjd< zS-0Nsfe+qE7?;Eq1@xGjhHG~;=yng1WQPf(i!^Ergz6koaDgb8rB>@O*2;MBp}o|a zmZBUW7!c?I*Y94-+BFt9&)L}*G3p#k>0#RDII6NhH$BY6x|Bygu!r04*nxAIk3xp( zK*M-pIH~7PZ0kxNO>03MOSCGvW8W^~dYh?r1|2OC*4j8dhl&>HC2!Ga^;o~&@QF{{ z%k8&q<^Ln^&7Lf~uJg{{+QS*{&9R2eDilzds!$k65F)|B1Zh#GDYIpgk|kLoTXM8J z+TAbR{ZDj6zjX9Vhr1uTt&lA_6qGE<6lIDugOVuD;slB_P?!oeXXTuEhjY%J`eC1Y zGm8Kb>{sYiWF>GbZ{B;)*?XO}zV)r|!#BjX!*?T|eDZ$Ip0gygiDQF1dzX3f>NmN$ z{Uer6C#Ky^T)fRQ?|Y12|Md?M!Xd6bK&y@i?p@-UcU|D#bxUmzsq_Kj?yxdwIJF$9 z)E<@EXLRr)?|bGE78gBA8bWkOL9`cjjw%w8kYdhwLdcLn3WuCotGMr;l2fam6Du9s z?4Z;>lgUkt9&xyTh0`Y!Yo|5ud+$@!rRnKMP@2R8_n#o@UB>P6nTa7I9WsY{K~871v0!$S#F9&XVj^vt%0+0cNVF|qpBPnZ-jdPeC^7>Q_!*;w$H`#};R zPirYaqeS6qoE0rAWr&(|y4XCb+)>m?ks{-i{V&Sem!Z0npF>QeBoB^p8Z zhF;Nipfq(+U}MBZPh`r{i5hJ!RlP`26x723d$*@_&QsYTq3dXy{Gtb22P`a|AgGqT z?K?bn@jVy>)AK}C3i#<5e1{62#kwFSkDE9`>`2{&+77sJ?K!OZ5Jr1SYlx}nsVb6* z>U~f};=DoPeI$~(vkPU#^x%NnXu6R{mx}3R!ur}7iiL`%X*jtw;P&+^q!3sbtbpHV zAT>HF#05g@SXdZv`_>M_azIrUbg{!wFeoaz&eL@hhJzYwOM>qyK*1y4GcXlR165T) zQYT-Z4P$+{>p5Uh0l7=iR z*|r_E8s-M51e)m~mpTEP#8^UI}%V<1}RITYbcZu14vRNA5bab+Lqnz9g+yTFeqIz zo(7bIH0h91XeSL42N{1#s-N2Mh&B*%Mi5*8C1`DkE;lT+66)GgXjrLhs-nPmj)ShF zFq#+=qO!NTmV~IpV0lO&;X}e0OFM1y>qbp*f|iODvUX%q)C|i7#_gCw3r3MgA5$dw zz+hP7LqiA+Rz+gU!8=3`bJ60Cs#HYZQJ4ZH78eBX6G@Y;aZ@BP%Z_?(WzwjW=hUd+O4Xzo32s7g9YzV-w+w~~t0U33kSYp0VA=(|YVoNf zsR&Y{bi@<}kH;s6H3BMS5e}^wjT>An2`+PAy>s9rgUZm2N8lWl(Ue9*nu#1o^zlif ztjvte02`T=jWYi;FYEjDo{mM&dG7jpn5pE6zBnJJ>^t)5s6i!?OL(m{!FMRDXk!b7 zMHd=dlys8@TNU`$Ln60oQlA5Bg-anj8t6bsAxqKCnqndK(}mfhnUHy)GQ(XZCk96d zMnWs7E6w`)fYsHO;lL9@penLTlalOlHmD1;K{x`1tRBh0g8bN1j3zxXxjVa(+{q&E~%m4E?4Iq|8RVjL8}4v5_-Unp@kt zsl#f87LS&mKGS!;%feEZHs6sGXj?+c;59Mgx+z+%;C*%_+&>s0(m^sr527?7d9>1` z5U>&{B!5>}B?t04;sWuhsS=k8oDcYz(7Hg;(M%^0T1uU=C%I&tEJiT4 zL@A$fe2Mtj;DbXaLy8HN1Z#ytml%ntK4=`p)R@I{b-tX=d13_b5+sFI!suY1$>;#3 zO>c!LRm|YNL0D`)Vhd^Q^X`fDtd=Yn6!@4l!T_6j}g{oP1j8*jG&5yHmT1T zX95zD5Oa3vBu|&2b7?EOXHs-N(`V2KHtS=?*^Kn8p^?uS;t{getWsH$&4-pKf(rp3 zC-|61Sc;-zak$86?*P{Yl1`-P=-Lh+JwAD&f?zc*&^b@Hf5@Ugwntl()?!s;k{nKhE-a>Z$b?7~L0ipC)v51)&a=aO zWLRcCHhL^uJ7RP80d+>rk=Iu-dhO20zf(z1uIfqZ!ja3a3k}s`i5eK5`OwevYrpjy z=-OtCR4b-!%l*#r)Cb-rL`8l?3-^3bWJWdov&8siH!jFIaEbn~(M|ttZ zYg~3)jPH1q?#loL%4kIEzn_5=@}dkeFc=PVwxu+0dOM=I+JB4x6aA#|eapN=Bug~5|+4lD8=yM#5G_TyeLU6F#)NGBf zayYup;o%lanR)51m9Vt1z`1j$uwrOqes{5_n`aa{XPH_G2${>Pr65T}h<%2mNG1|u zIz~26eWn?EIX0caI(%+4#WW{JtC>B77ED>>?s8K2;24b$NhG>9pbJeD15%*0AxdHz zHI*5#AT?*Eiu-oP3=VdQDNvB8U8Ib{NC#|HGx_*uIQ`spK6toC*X?qusaTBroZEht z)6;zl_DMD}P9CQe)HUk#3G8VDSV90qqh?ul-}0H2?ngy->KU5HGDTG1c*@T^%0GXa zcIRu4l#WPDiFDM^lFU<8qAJ+%D7M?SXaWd66^c&M{m$!_ujTSi9#@%Hb(=y$DL7 zQ;Tn=oI3pgCst1J{15(?jT<+ajuVxw8BO>3;SavW+u!#=-uBK*T)n(QS1H=IMN8e^ zZ1c_U?`0s3Db9I!rk_GM8vp9Cp#;O>B0eaJdYPyf`18+wgBPv_Jb*xvAuPNCYZT7C z2=Wa|D>Q9MyrD=q5QkElGK5(XmuVD$1-^Uv6+ZC(chc!awhks3>q*iPqQMqLM*dWR z)f!_GK?NL%&LzsC!dQ*b6-ti0zjGF%dMU7MOA$iovx*!{vp7p4`AAd?eC_+U_}-6h zFm=5}(D7#QY^8ktGiVV6lZAV40N>9dEGk2LgqQ<=RvLh%`ZDkR2M==Qo=Z4yf$V~s z0;J?n%41Bx=!6l$lq!o$gwQu16kbVIbyuKm?xxSQHU;VL8@;)akPYL+Yrp(3;qKn!_#!Ysu6aQ2}iOVm*4HW~e=<_ok$m?(pc%Jys60HFp9e3I-wR zNKqDa-+GaYA@R1sBF)sHw-w>}?{YGFsw%@JqUMsFIIS3;T;{+IVA@cqK*Z0>qo1TX z%`Zmg9`$qOv+jKFJH~8gzJK1AL_MV9&Vj>7^oq3AZY{PIUW!Y}{!ue0k%B<~q- zZL@!SgJwKItmee}I%ghvn26^$|GR&McY)7*>NC9e{m<}^KK5afI1(K%J@*{n`oiCF z@zSF#ub)IJ!|8j@;$z20KK2nN8;5-HFTQ{d`PxK$uYv_6A;!qc%8=C+M^#3wjnu;d zM2Kz97Um>l(Zm#K`)sTicI@*;;qtAP z!@v4AzxkU}v}i~bA{wnBNlQ^h3M&lif}&7)GqxUyLeYco-baG(FseprA!4##XYv`w z5TSR~K_S$l7=}a{!CJ##e&MTp^9MKZy{LIiy}{b7t|XDeYc@BVWj*~F1qt-}6Cjq5 zW)>iht!d(~zx)c1J#m}&Kcf-j2n4$1Nj|}}WuOwng^HqDU}b5ENMiTkfc?D##CI57 zP>7(S$4FNC&v^7KutXAF&UIbDiZDblVmWCQldbFQr$Av8%PS{2_uxs^R#phD=eg&e zXM1~_=sFUbX*(vyhzSbDEh|NXeD&KrdTodGy^e}3m*^Eh!o)=CKs6n8zpheyKn1-Z zV?L61lzr1(r`Z{eEN|^0fBh_6yTQm2Bc$}A8}lYpVvh66v95l8 z;dFGFW|->iA=S^b$K$$B$DS+w4Ga1TK;gu5`urKjZh|s!=lT}^&;R~!ak~>@>xdG0 z=+O)O_W$xfuy}HXMB?nZbCjmwskgqB5FI`_KL1}o&)MZ|yXP$| zoW4l0e2&fvNXE2FEP^4K%sXBa^ZpJVO8b#7hR zrf4-b84MPbV6~vr8;8<2C69D=XZJp)xX7vK(r`jv(HX+7z-<_i(Gv4 z5uSSb9lYm#&+x#*4^h>I=sMbFO4qp_7BE0Tq?gZ&fiTO!l_I9heOo9CR;!wO*VkBG zUE%Xz{8GNtLZ9$t)u@~{9({(n0>xZCJObfpV*--0wL>E0%u*Di4*u#3U!!&YSO%r3 zicHz6ih`x3WgdUalU%s)2p2D2;_)Zm%JPX*3xVv1m2XO;|m##6uS^a^L+=@cY02XMFyP-{S4>{(0)9Rgz?jVo_PRR|TOG z#me58@<%Um?_tM)+03`hd7a0U-sWrJD0l3=kU2WH`7~w>Qvri6anH>IuK&>|DW_R$ zR?Rq=X(rVzbIerr0ddX^o!#f=P1C!-((!jB$G-RYCmfZg^WOjLM>!HhnFaEqDzK%+ z76z*|u?y^P9wJ?VYAdv>xN`X#pZT*-(@dr~@0c_b3TtFmDfAWX_i9uQS=XnO>WFD;+g|U#Np&n|Q=@=~rCD}CZ z+`SKT?)>AF!*#r>2;`=tNf8@CsQ@P66$Cq^UcQG%-tshO&!5j??UKp>axa zWU{mn`p=N3YjWd1BKZFM?2CC&If@xG5CcFH1itsfO_UzuJ4K}iR8r7%9a5GopIqbg z+536;ktg|`|L{lrum9WsfhvYP_0D%?92kfp&Slqr+R=tU=R_;m!x64^Xl)H7*}tO`TDnC3Z_;^&2MyKEgff7Oc>yFje)G)l zFRzExe?d}rKPLV4&P4KjPE~^Fp^k>{{`p_Ck}T23BPx8ac0VWAa}-2p0>eMcSB{;> zO7_{~{V{{OM9Ewkel`(x{P}_qI!E#z*EA3#ql3fDp=~`~7a-}LL#wF=c}lHXs?mjE zZG9bMEfY84L%;GNF23_&Hrjm-B(U91iG^i!IOdQ4;~(;S|JVOZ?G5puqf8~t-B0?x zs)VA*Bb-%T({?S^XjT>%(OR)`>LgS(N|&fqVq=Yo6*`t^3M^z;CJE>gGg#u}y$^D7 z{a*ZR`ijVSypJNY3TDGQkcFSyw&|-o6oTp&SZ3R4mdWNX+I z^8(HzYR3X9F!wOdt)bVxV48)eqacur`+oXF0wF>**qwfH}_2E(E=!>0000W07*naRK@%nBDq}m zF_21)3jw^#@@z*g3$xJ4Jd^G}?_Ju#cb(MN`OLG%M>2q;sz9VS8H*9sd5Xd!g=Oj^ z<#2_SQ}?p7-!O54sfMhdJ&h_Xe%dm#5_v-{N>SNrTM1gts4|MemN-A5^&O4xSUr7) zg{6~Rx^#hh`2>h1p);(UFkvGgM z&S#-}2D%DWSu(6Eg7+A!*t)YtWh+dyprC6ys1;4qF=-}LixovLJ^9VAe~X8oxJbEN zar)j>$LQ#T z#|-741yv2n;BiNfi6$kL%Z(lld*^%K&8-(Vvb8~o7+vH|B`_L|(AKcLvVt-NtE(s2 z*?yH61*J7bQDiZRexoR*Im%;lmXXQ&d4@aatZ)E9z4U}y>$Cn8F-XiA7OJj zvpQ;(^_y*u8%zFtl9i#;aEtuAJh%@4m!S zPd>@bD?jAg)#o93v@Q`eDXQGOL$kHE!2a|k2h#(V+JFjqEY${>mCrgaD1H*2oSn^C z&69v4%rf|Ve#K~Zwc>66`d8U163ls$a^%UB;CS4eU)S{iqiF1Z&s-21AkFNY`3Wh! z*sswze=W$|R+l18*HM%O$`}UqFk{^TR1^kwKp=4Y#!cF`VR3bckg!pB_KV-f>Vl8{ z)<;nbipMWq;)zF}Af)U};o6Qu-pSxp&7b^-KSt}4@wUU-LH3qUArEWJ@f1PC(lkDE zxg`+0?4E#uWCBSCh<&GDMKZNoA*sk>Dv~QO=Q>OqBwq8m?pL6vNL z7bOeqXr+5mmY;sSDFbOtF=M0ivgLTGbF|3vB97d9Zk-SR<9G3y&wT?IkM7m8Fd50z zp#HidsU#sNiI99&UYd7WkDeuD|7;cEtxv4+)Z-V}eEC);-iJKDn@Ef&hg`k-GHuuK zp7%aYRWER7>lWYq<~Ny6r&J3yB2bn^uk@2kd98E9i4cgY7ao)RxjOGT2pws+LoX#h z{EHvtNB`~*2p&XbGJnSXj_|W|?C)$v+NZH9WoAH}frcPDkV2wR2^Bj|FTn@i{T8e= zSer{Qbem;XAR*(*5~ zsr$frl))yH$}{e^tSAOGNra~B*grU+C<;`Y$4BTH73a>LWms3ZwnaywOqQi;h3|an zSsr-s0e=3&|B&&j1Z3urMJIy0J(1S8-a6ec2Jf(aA$wrNQ}D{<04wuyyNYU@N2*Hc7FJS=Xmw%Bx8YnGfeu=2F$U*d}tJ1R>esP zW5E0T0b`0N1w#uL&MolnpL>k;6^jZDMr)EN&^2|X8I%Rlcig`5D%Y;x!~m`9xcuWW zJ|v3Hk;oLT87Vx^ULV8x`pVNvR@qM`60O21Ayp;1Hkd+~jwfv1yv5e7K%6$T(-ud> zDuwi-(DOB*H7aU4UC=(V#^z&Z2{-l_9JH7eNikbps|10PC=pv$OeR8MPZAs?MwEre zyGieG+UseGkhEr68oF~QsNefIoL*vj6qp4lT;odf9VvC>b6IjAji&$IE_hF1s6rfW_>h|ak?yz;^W%jpj6I_cf zEra0#r%tWWO*}grdxTany6n3l%+33bRQ+H7cvA*a$O~x}NR^sVP4c1ol1hm}s{~<0 zGrGx>m)3auk9txKYo_3fkz)d%j1uqVR!EaTbmob1YtuoHMUUr@fN3sOL=0;Pjc5? z7x^xvYK+NwZPzsDo-#F_PH5VecsOEdd6lXvz&nhwSYvt^rWf&@yHe)S*BRy|S#p4= zaw(cbBii6YWHQb|)!K!u^;sB{Q5dZ-)}kaE6N)4%TcDz2XISv^#S`q@GvrJsSUF@;7noLD=FwiZFLxVVHV3Z|0=uM@8AxOwe1rMJi!s)ZrfH*fNL z|MvI!=l|w6xc8xR)WeF8{p!c~+s}O!8xpRELuONKg5X@DX%q+ho~6YBqACuij(R+1 zZ)=0CS6^V|)T8+6K2lcT6@@W4AF6-MI#S zL@634Is1}EaNe_ea)1syoLwC--r8e9Eh3YI@s1M%g|xSjW<>IPI65$fgkg1Yh@b3I zSBt2WsOv=nQ^E`;=!2h8I%koGV|KUqsp}!LhDcpk^D=GLvCkv02Bi`q`J;h@6iF(p zlgE$<{objxVyK}oiME>}$unHCBpR&tEDjeiCNVG_njscL*92^Ufk_-fNo(1Ds)RCkTIuF?+y^Vy3;QbUI6`l7Kw#XAMc7W0aK?zC=F0@qjpwGH(@7NfR zT{D)3mh*o(sBMN2vW|FpO?a?WbjGzqIQlX4OG$7d#!NnF^TE;}K+rai( z#dR0Zu|OL^*@Bn~3Mq*S?s@1Qp55?#arFwaQge821v$6IwXngobtI!0N`_8+0%r`Z zRa_WUVC)>i$e*ZRi~YS~-ej6XP_yjxjgMKI=&r|p%EmtmrWwGJp5&kJzxgIr+LB>W zV|sqHF$!fsm6?m3Od^(f(9DH^vIRT)2XxAF?$SA)eAiQ`Li6=6f0ON(wpm_SX4*^` z4l52ew(+BUQ}xbsaCnd#LBVHn5y>WXVP>Tq61Q*eaN^_|&VeyQCSl6P<|Zqvi#+%2 zS2(q{iD!k?_4~Nz{6ln6^+GTcwl{C0#c|`xj|uIVYgeyucsN39g9tqO$fF1)mw)sU z`2Y#pUapaL;C%A!V$ zVbV<~1{Uu}#LxhV6g83tXuW`I14>|V!J@s!b>N8v6$qj@y|zMX4ZFJ?VuwsaZa~F3 zHmT6cpiM!F*~F_f*o(R)N3*7luP-Q(IZ%;`@vRst}`xD`UwDwpJ1FiK&P zqU^0DX0Sw1(4{d}=ivk~28`qkHhGlFnTAq|PC44jVvJ&?)0ADLtqLdvlQJGoS(3sO zT^K@Yvxtou;yaBgvg@g~k>mm)X>1#qlJEjmQY<^eYAT3Y=p~C+fSP$8~d70~*BX%b( z=O4Vl($XrS^Z0{3ChdfGz4u-C?vTHG_E~OhY#>P}tBSK{&+^tM-^%6ZU*h>6zs%&Y zL5C7;Eup8eh2RL@*L6e}D5W5!o_k8BUMy7uaQo;$R*E6voMUBmNYivUUy{TUlV$799!j-T!xfAe z22y5na+Pgsi(-(;`Pw5kV9kIOG~R=scC-s!77hxLq9}+e6V^>kNa#r9kwi%boitX2 z5F>>cEQaViv>BkR!WhMHxWKe&awg3Ovenx^Z}HqeEZKu1Up zWhz7~l1hk*XeqE#;3Gtxh?+e8q#~i4&`cC|t;8o!Z7o$=z`FyINrc#;7!p*8Ya=EZ zv`ZAKpa_<-H7Kuf3d-7M;-@5{%7QN{CL95SVz4;K@vYaj^&yb81GCMwpxAM-S2Bh+ zI+BLYYHX~qts*!!t;dd( zW+2ckkm^32&A&LMUMkTme(=4^TzKqp%Egl5$^!rNw?E3{V1yQ7VPVM1@-oHA8s`E- zRWrJ|PvtFFpS!}r?LDg11yo#>>uDC(R*6nH+#KhQ=Q+5Oc>c?`*?Q@aq)K8EBzYA1 zy+qd%LUtp4qvOpPNE1CVJ?4_m7-FxibTo&e2_|F;g;EsNfNHSFXzG}>J_m{vFs3F5 z6lKY9ah36CO4GK4*kMcE%XQTxRj_lo3)1#N95FY9@RS3Esw~PtI~ilJNNO>vpeTl{ zpFL00Y_fl_%Xm5_c$G_ulxRYON(O6drc;;IqO?KBOz1aO<;H-@frsSgRuNs}D3c({ zGHzOQS>ym_6v+jUOqFUnhd9rv)9VZd3rr_F7^7)ZCcdX6Xj9@`B)SeQ22*NGS>j?= zR39uZaNqfdIXGyDL3$se3LhM{93ZB`_YJGAYZ)#qp|oMzwG@LzPM$i0wnGq$_pxs} z^npwS9fc?wA>vU)r4VgNp+Uq@mBUQ7PXoHC!eFU~tB4LgrL9C210K5fKAP5{v?ir& z$~LeyT^FgBPty7k+8BgDNDzXM0+@1@^Y`CR(`a_KN2I9eI*-vcZL85{8Ep=U(c!K1 z+|)!=f#K;>oWAdV*q^d{XNRWgh(VEJCdlXJT6}F5IcJ-|ERcerR61&a9D_Y(Fo2RH z1=F9{7PDV`>?PE(W{LtdL%Ya#zVs}WD*45a{S)dFH5V>jBuYTdyqkQaK^U5fkN?ic z`TkeF$51VB`R^|CsXzJ@zwl50G1c+{kGM;oY9%b@%OUX zG!K_bqjWBJ)r_;J1W^fP15v}I^(-#0qg2IY+~9&m>)fW1C6ma#uSDN-DOurYsE4 zMxaoW199s#0eSNi-0!7Aa?|K)3J+zO;r^mL&i z*RLM1vbx5F3-{56QD#r{^Yg|C%O_TW6+ZJ9Uu0{$!FMnJ{`b0B@K`ue;9#k|Kj zui$6HC3AceHII)oCctZd-)lQnYTnE{a*mL3qE;1O`Sh2W?oavUfB7rKA|eG;gR-Xv z!9uF}#K%9$*Z=Apa2Tj`MXfa7`O0^BpPxe5DHS~7>y4o>x$TT4o8Q4^M|DV2e2)sw4L#KlO81;H<{ynGR>#w-jICswBv1-+`e z!N(F(V0$w#KG;U|0+C&O6p{?Nb*tm-nV$nXQfhJDlafK}iq&6HPPZJCU25aS{- z?qXGeQA_OY2=&5Q7KW=iL(-bg1r&4QvdPwMMqw4GB?acoHdaV(46? ztS$R{4PCp0_Yv<0w9O*7Zym6=2gKMzC6N>(DRz()F({A@9~JGiBm~2B>e$=!G_A0= z*AN*Y1*D`&!Sy4c3FH=4b-@09%f*XNGCjCPN`lcQm-eDEVf818{&$tuR386Aum?T=Y8OH2$p0gpd%WnH;oSd10SU)jW9N4Cl_RGH!0NyMK*?!!2BJOq&Ul z#?v$ogC?fzIQ#I0hj{WWPjKIT58=i`uD(3w2YR2k@U?ONPFC8HYR7SB}tgmgJ!eFmLa#VO-UhARH4`Lj98}cu-x3ML6lta% z?jLFhz{agS@L>HFSWkDLH zEib=xi@`u3b|mjH+Mvu5K6Ho@oChtItSOagJ+9SASYUFX`2MpuP&$jpWQtY4EmC$P zf<6OO9f?SAnv_aJ49`D*6=MUWOnD1RK{7;_GectpA!5vw7=#zT_f?E&j6T+In!AAB z9r|W-_%pqTncL`WjnAlkGpzf_^ijQT_LNxxubq^-i`A0y#7|ijw9a9)rQPW;rDFTe z7Po(RJy&x8&Qh5nWh}Co2pU5|qX?tG=D`Nr>JFhFl8eEk5+olfq(DSbnL(C(v;}xW z!uN?!$R>v6ijml3ae7im6fGb7GXiMJ0^Id>y@ko zV%uMXlo!#A8k7WLEJzAOd=7jm&-$mNab3Roh|805ppcZ`M~Zo4Mwj}AB|ZQBNH8Qf zj$TWk?^nS*^L(SyGP5;~J#R**dY#{R{K%7-ch5iC$`A!?QRG14GYzR`zSs_DzP^ zlk^gKl2Dlbt}S_fx}See7>H{AZy>$$JIr*VGVjyOUNNr^DKgjPz?(tB%eg ze%rFPx&)mkiN+|)$iZRP(KweUu9Svk`vBVW|3c{Bv-BlfF4d&>OwW}157hH$9W>2%@<=E*q=6x_cyrq@(!oh7dd%)$ikw@ zLm)Z=Q-V|fAA4UOCPj6%|K3|w-8~Bf3^0HUo3h9biXft>5R{+$5+g>9Q3+9_pIgMZ z#xK#B=oe6vsAz~QPmF8aP+UNE7i5)P7)Ex6ZT9Kzs=B{FZk^k=x~pMuKw+r&dHR`| zo~pawbI*3qK}}T+cJHXc_APtB+z5o73oasH219Pll!q*H!MXgTT+h5c>^S?3lh>#T zDLJphQy$B~^7K|hUj1aAQd@Ft!lP*vO`mx|9b}e5z_TneFUr0m8oI?X#pg+*ilI17 z`qptRZ;cBt7((h!If$4FFH{?7VaxcT3>@4rkaTU7S0@n>1{_m5qdTrZWx_>8+(oS| z7laHX%{)%PQDZ~nk^#>}hEZ@5T0tV!CmD>`^)|4BRMS(dO>z;blo~=f;LJNv7?T{E z0N~}XvV|cDo&!KgPOrQsfl_xjk`7=9c^k|XNmSOls7N?)VZk(HOjhP;Rb|XkR}lzm z6N4NJ&l?qFs1XJLVMz&sNx~p!KuQ#H>Rjm#4WZVjdMzu8sQ>^V07*naR4-tDSt>5%Ucs21>Ywlq70NKc z7zC5)ZwwB&%<(u{SB{OK)G0D1x5H(i6A049dh@|#22e^jB|Q*i+*|SqmeN3g++@2j zxd|&;02e@Qxr6U2s>Xo!CNG5AhZUF|9qGV0NMXkeNGfRn#GL$`2>M<36GGN$T+H6dUq%w-WM~orI zNsg#IP#B|Y1r(-G{+B6zs~jH}3@(#Fu4P(aLuM;r%rnRU!nGwAAPhLnf*CbY<=80M zUMV-1!92IJD3XXma0cPjfOsWAPWg~t0ib+Da_YQv+GaA|(R%%1>SD1-N<6Dp9 zpJ1YnCZ}R!9LtjWU}!{=Cq~q=+n2w><~)tucK^t#EJ0l0{`0FFt-On4$6Lo^5tTn~ zT6D!BZ4YMJB{b=>c5X3|dG(hSRB(L!j`w_@CAN_gRNH!%x2DW<0Tx+Yy)XXa%l5JU zXp&g#yX-6^oFN{WvB9P355j9xnOZ2)t4S-OnpE>HrL$;X(Wb_X=*M^I2($Tqcn>os z$bGs$Fa=|6xOqS(pRJ$*udSBYMmy5l*!0|*(zx5^kWECum?2*E=w8xHG#=s8(Qm1A z1$XH9k|J$Y2RZ1+O*}Ppv1vl(skTt<8fDsC!|;bGVpP$7G+!*ywfvN){AKqe6ye?b z=PO%4#ho@|nzji(Zqasf8pfcm!jP|yzFS9rxT02k4J9lc{rA-NcK&Eog!L(j711H~Kp!x$L(C)^2wOzw{>}q^OtY7+fqKtIx@@-3;sTMhWWG zx#SaX)tXXpV-w+K(0D1F(AjfaEqv@?iW`-TPW#=bP<4czg2u0z@U$eNr)ddk8lT+{ zUcX6D#nFrYUSuQ9XP~I>CH|Uz*_=o2)p)zBNxi8iOZSSr?u-VZy^2Tu*2mVj=Qx7m z%%Sc>+bV2@$@7!snlpUn*m!8{bX$ti_OMflhJhT5Rn*{*n~PH0USyeGpZiA%op_a% z*!COv@J8s;kEK5|LTK>6C6^L}(3G4po&Q`=b=7!4>`_No&D1YabhRqC$D`}Nd)TdB zAi<#(h{?%-i*2ZgPpmwP>wd%X5qU;2i%hUeoW8eS5s5j&_861o;iC*Y-D`qLOiH6R5 zCKmn~!P*JR-%sNZE9)T5(r9~t;i0TzSV7k>WRaHgRg$}l(fOzAyA+(BKg8ekFdmhv z>0sUX(j~Mq~yHfrE)gc`$T6A-tGuz}u z=}`p`Z3xm@`(szWk$zK4lBK8kF)V zRnrpNFr}oAS&nL1Cv2g9|54ngcY_smh>J}q^CX49O6u-DX~(nyf^aUj#81M7Zihza z;u%^t@viz-$#IChmW4Gpw?pg7x%jsqiKMgQ%3frm0VMrz8=uFA+{fn;)&2gOsCz+d z*Es&``HC37#gC?!Z^TyWi-}&)zigMme3~*t?&@5#tS)#@iPNM|>4S{>U2}!6E)G*7 zoD3=?0*f>pHvIS{(o7!taZV{|om({4*vT8W=DlCx$Ic-XNY!Zh^_4O;hnmY9h^_yk zFZ8|3D`3T9TT`KT4_iSa=zpllx7awxU`}kB?mUpjf$BoR*OT8!Ow7mqQu-+35feQg@jD}AJdVrz~OX;Nf=a$gih-jct*;!aZY%et_!Z%3LI z2G}AM87?8NE~BsbE=E@ydFWUgqfvY<1g2jsGw)wlN=h%3aZ_@{050{ zh~L?l2B7bbk(C%?@z}aFY&r(C4$Oqz?Rmm#`F2^22u&92*%0ln>-$C-t*fP3Of?cT zL^A5ipFb?LuUXR6nHb`IWju8f@|ufu$0D1Y>7|PlnJ-zbHtKhSvGHBIP(tpK^5GMX zzEu=T!~7l2hu@Wm%f7&e^G$7VR?0E^VFy))pl0Rxt#{I#uCF&mYKLsCQBpp*gKio_UU~1m4sRQL5+{N zLzf-P+)?t*Ug(AM&Z`@KUbmU;aM4@Tk}^;+f1$pw4rqBVqZ2juapzp&n4j5Ay?yU@94$8@y<|Uwh z(%@yc|Mbj=m92nKKH9tyts)a4#qln6jK^^?Nx3ql(|X5TTB5xQOwQ zW?MK;xm;vh^UV{dA)kSq8(I06lGA1%AlOxpEa}PwkacmhJ5LiiKV;lOW>;gR^ zh0D`a@)F%~H{Mbmru47$T+{W7t0xcsk(}zTE>GUUNelL5B;p?=yB~t8oVu86eE9Dl zot!^TNd{iBj>1bcK7=dN!i^~llu0MdqRDw`oDvQ{)&AVO`4x8x#STRY3{MDt8y-E+ z&XQ8ap_e(r{6r%|$EM}X5S8I$gfereLE|x%^u4fEt@?%H&m)BEWn_%miKEE7Kci~O zUc6$vebw2r!>R>Q9&~z8&pTCUwaMc5*cs%{$+Ar^ zuC=s&lDkv*K80K9g>=Hr=|oxOkR0yXv(hq-;T2Rm`#(kU&Fs`el(EV<-fUL|8>xy# zKhQ>R#-gNA1pBLT6lCxZGAi8BESOL1Wha^N`aR}s;Pz)$NQ^0=LOr-fiavPXTB7VU zYnjCm{pD3ivlUSdZLy@SeXZCg$8TGnMAz$k{=4>?v=`{ETbUZ;&y^I^CQ zcJ;#;lwnCbr&svcN3$gDrLF$))nkq0`F?)|A1VG5do`whRG5I3o`A_mEki7W!Ig72 z*k`Lo(RTTd;6^AO&8h}wjRk^%ok@@#E!N<%|LeqrZ8FXxUinDk*OW)M9Ob!!chtyf z3(rR-Nl1r?nd4B#yz+%JnEcFonc*|cvfkJ@_Q=15h?$uQNLb_}FyvR8{t) z?0$P)REDhq5)&VvL>O|1UtIWkY)w(1V-d=y@|c*Xvp=5>UsN!xBvMsVtMWg8VdmSw z%l9#MeXKPw&@5K#%uMV}FB^VG+d$@ny;-mM_C1!B(c({^h%+B}5z<*nNS1CkB9H#> z@9(5NXj`*iFQ zLVo+Z=d908b_eZ}QV_h{+?B4%aT?qg6*3E>N8M|uYuQwB%h;2iVVjN6&!TO!{U5=1 z;0!b@WRyKQNK}@08BoyFjPt(O>(Qsbckf<{SQznAFct%`#{2sevHb0#R7Li<0}Y?J z)li754AnDUOxas5cfV#yRQ_*n*{ z?-m*>h-E)~VGkv~zT62^kdX=I)6nJX9ur&6h*4%^VM&a%8_o;!zB*kSKP&LMIYQXu z+S&d3rb0kKOFCovjv+UD3%t(>^SF+Ai%A$&TJ5w+M6vHY=aPBxxFVq><_b917XJN7YS7^QyJnUSe! z9J@w(0ZT9hgFGwHe4 zNv5?h=ewie==kxC-AIpEntI;XuXF}x{`cU@Zi=5Qge-_BcP*UPhVaw0H#auY7TLqi zExkr{+wO|L%|B$ykB>fG=iCE#JB4OM3)>i`ed$M;ANfg zqA7Qugu|n}7(6{a9dztu(uztV@tJUb-E{sMJe;qz{0)y+&r|Z?hoJYtPhpanu7^*a z;Ef9ThlXL}kc^Ft=w$e8lo)<-NY>&1i#P9oOwZk~)A{x+g{RwjzJ>m0`n`VYcn^$K zY?i$&O1q)%yjGR+JnH~N?lrYl>BmN~CFNJUIxW9yU(-K$v5*_VAj^{YQ2upyXlG!L z>)WXa_qeqzU&2YVK>wU*n?UJU)GtvJQkMkE;R`+KjI`*bfwPUC^%wj7f)je9MH;Su z(rojLK0j5$K)rRbATci7U}MyRGa}WgfZFChC=t=vDE8%(J^y^*^(D1bfcWDYyTsi1 z3_c4qYAa0Mv&*WB#rMVqR*YNmCjb)p0D)FAhxL>vvktU0`V~{}3EJ zOy&q}n`v;ba$nP=4iAR<@`ZE#I&PVXg9D4vZx>baVpncuWu<_$>E$3>k_xv;qtG)m z57}DFF5E)dp-mit`*+P+X0nwvvH#9AkOiLhn+=s2@V+a;>92O_rm|QBaE~#1`cvYMl`UhLi>4|@IOAO3%4FY19rkZtY1)k~J{D@J^ zH;=U#`=IT;o*VJ$#n$6_v3(oYp)*x1E`Kf3aK~xG7C+JL=3~|xziw)=7k?x9 zt-8(kS9(8GR6M$5vDC0JFfdq7HZW};H!yphm&fAyiHeePDZ_oBUFvF&==twzg`YRA z@MEZWyYm!c{N51y)Ajr}bk@CZSfdlJZg;cm$fqVJ+gqeuW~Z9^sEEX|mX?)uA&Rqk zsI4~S!YL;`6--Pr;Wm^*9es+s8;hP|6Ls&|1U7T1_x0s5`lj73PXGBR20doL!9 z-CqyxDlg0W=eUIv++^qC;u>p0xW7|ogDxe0JmX$kZpd9UCFQy#zt~ve4eKa5mzRS> z>C16t;AI(CS#9m3=hL+sbb%Lp-}vyyc^_woTSVFkadG#PI!@J)F!~=RZln^+!i~CR zMX%HP=;Px;e9^e&$VpRQjhg4bM}%z;lQy7rT_0axWeZ4dESs5{^7tHYf6SWfc{7K_ z3&SlrXbIlJv&35W< zIAEH5t*of%mLrk~^%k#)b?Y1kY(UU@x#dj3A!~#BFr2D`FF~0Np7me31W!E4U#fv7 z#|OjtBU{Ss=Z&L?nZ?8T?0_@-uSXM49Pa+Nv|u8=JyE-4zK8vhU_kWGkF*dfGe2z! zIY+jr2z-r3R}N@rq9^W;79Wxs9~GKGh80 z?FLwz4GxU1(?SembNXeE7Gnhm+Pvod*WNETf6<-~R6-*(k}chgLAgB~9C_>RJ7{)4 z(gc<6+Oc4!*yMir@O@1!oiKA36Tx|OHj;aOjHC6H;9FG>!~5Jolh%M{0YhwNWJS=^ z(+hHsgMr%s98sL%hKq}b_t{Cvp$Fz7+{?F`uQy;9ji{!`B8HIt2-~hd>E!nWnWOdP z7Qk_Z4#UlC@T@`=eJv*^SkB*jd)pJ3ZCK^?7BcD>67=KB@*ue+#uTBZrWK&(voa1&JKtsk~~47GIl{l zDd{(@cVV9MKQ@6@0~6Fv2)D--4jP&(7l9U}BZbZU(8wr?Bim2F#i_boNJIQ$x8ql> z<9k}+^!EXmXSr&rJkfk3)Uedm=pSde|9Hob4oTyG^xkpHIdDg)#l1fb3QxGw`5n)C zc^{1%w2La0J^DEG_2ohNW)&bU2f{dPMjg6up?Y44K7j12oMy$!pVSe~2b|wkRaJGF zH1P`N55MVDFXQ;!r^nL-S%v#9?afj&GqKSFtTgVUDP~YG5$Ki~R1*4CD8)0BikDgq zWQazaV~(rf`TqK3adNU8&+jxNvZ_gnF*F6QSg0;02EPd-(VMT%HuvBQ^R%)hTN?N^$jkyS?-@^aNnM|6eLWme z3szTz84G1UqK7eXrsuiP3%cr1Jt_N`n3&-bU5*;(d4^0ePgz%2{&XSxSGUws%;DHA zWXY6#t~g@+-!VziJ*&vS50sGFB>_z7+IrZeF)IK5zT;4pm6DBkZewX_Da@@B?9N8d zO+Q8IDY}M+20jh4uC6XgZHeZs6dQ}l3KPj?G8#EIcXyK4io-SbqitR)82K8N?v{<% z>PKY7)jmfKB60bh3QLC5HTLMELav9yN@e$nb1{R6q%MdnHn|M=O$wp1!E(bM5Cy!L zTW^wXz#{E4{lSk^1r_m1&PojJP`mpVBvfdzv6w24lcUE(nz#93HMJ^%>ts_2Sl-i=lwo6uH-P<)jBS(BxzwTq@sip|EhOoysKh=B@(_}z zD`bDCzT9!qNTibXmliG`Y4Gph<8z!6^85GOHaLUb#DO_k_P(VZHD;FYwy5X##OUyD z0k*s}SiCJ z3kwTV3D0_vNnT&LR0w_aqthhByWW{3KI3-spIJ^6WcU{bH zgX*PVLCm?>VFNRd_{|X$92%>Z_mStLbF8QlVRn^dIY*n5%g|DH?>eyLfxd9RJCq~i~GUfCHoUvnT#%X}zt5|ybY1_lx7 z>9pkJws9X8xUn4$u^*S*;Qi}0O*4X#tm=~MOh_kR|* zjztYYZ4H8+v5;n)C3Agsnf!h%mPXKJEz@fWhAnkaR!b_Wm#s)EJ8n7d0U>hajBGQL z`CH|KJeMgxrfFu1EnXha_bkUt#UUFjteyD%m_jd+HSaS-F~4Oe_PEoM?9tu^Kw!`n zK`2bI7!t%s?}2U_Fc>q3nVx+xD8)EzH`WtYe4MODi*S00;qQ!y#igN_yR>5`w3k)A zsWu-QFTRfrY~!sdc>Eu1T?=)kbKdXZ z=WQMy%mkJ;a)!G%Jrdtz)7`D`&-~gr-3tnbU_D)rt4sggx;9UfLWiMQr@sDvZ4lh@ z^70hj&qMG111!1l$LPj~<1W=oT*lEx}rtbS1Mu zvikw4Yri82`U0o}ce8vp;8l=(sHw(oQG+5+sl%gLi80ch9eVtaXCpwyGWlpPM$X{3 zD`V{b^WMDg-zd&cjyFN2fY0NA8l1XEM~_j{9U`LBO^rlfQkMv=7QDMf_Ll9hZfxu; zM3N&J$rDzB4rzUT3a93yM>h16AG8bm|7~(|$xf7^J}?!2ntO=22ixBx zT|7ZwwSpOP(#0E)>!E8het_kygP6Enz;yRfzBB4}#qfwY3-V?rUt{Z`{5M z%zoAyO=oHR-_~@pMIQ6A$88y}Ff^UI7!UuOB%E$$tnw@*9?M9&FdkneY}8 zwAv0bxD4!p0Ja=PWx7k!BseHe2I?CY@aOo$n_ z&QZ`e-ugG~+}Z^TIES*jV)FDL`#KhQQ_0VwrY|l7fNIC@;*s7!9D|q+x>QLJ-C>sL z^{^5n{V&PK51-UI9U*j=_v+*M$a)eh3vDID)Ro_8&s}zSZ02EVH+_4VTpac{rv~7yN#Y{0UQ#y ziT{4hc2dvX>m3|a5~4k7AVbyBkm;sD8&^sdnW}Y+0V4*?m2AQ{6MW-Jp{Wzh^k;yR zJ{Oklavy2`0$V7|FcejGGC1fkne*AcY?ATsA0J`)$N&m(X;o-qVR;8ss@14V!MWAr} zLm*fZvB9u`8oUc-hyh%hN5=5_C|Ez||F+Plm2T>^P8GXbynOl6u*QxADGcr{_bhw0 zo@Z*Q+r(PTeSHb%0qFH$T+Pv>(SsA9QS|lIajTJurd%r#Po0SL=CSRN6G(c&`YM?Tr`73J7^@V}ps=29yxuMm(GVEvua zog&hfCV7G7Q=7@p{d0^NL8 z-T26og9Jb?{{G5!(z!*7b0kTVJ|MQqt)3}1UKf6Q+t%K`BzmP#O&zEy@UU2@~GSpsTKp^ewK8ebEMi$1pZ=4T<`HNAEDmS5OSeYfu2 z+diYUo28ycU7LSBoYJ3&jT~^6+b)JR;Ag#dy+@lKE7Z& zx#|Cb3ansinw73b+X1!~ESgQ!13R>kTxh@|DChTB-YiiTAD65md}~627&(1ErGez+RSYrOwlU zwkWBqkH|f$;m{7#yv&&vk|i5ne{jhv#BX(RvbR1`s21+b>PofpMmEpZ!h#vxCken} z0?%&d4}Vz7Sa(BV=H=DOJbBCV*!cmI^XKQkKB0nVgLF+nH1J>Ix59_suR|w8tfZRJ z?%G3Ntn+l8F5Ypv<%t0nZiYJ&J8WDv4g7ZeU43KE+qgt${ot2X{386(w~3|ZM*}2d zaG*eEX=IefyF%}(Xw?&^Z+Q(WhRcj=kIe^enDs^7iJhj4G*v!_>$&nK&Bn973m}`z zz-@VJV@lQUd96ho0%Q8$`aKH-p=cMV!db=eo2ryBrvywEthl&yMp)EQ~j9jjf} zi<0BDGY10}GdLcLl(&HQ+8pURzCBsAdx6`D^L)N#*2`ft`#(KX>iI7|DAWFkq}Am1@B!RTxxVd@}YTP@=HbUok*clbEP*gi&z5lv0MRW zbZ1mlVks~Ez9SbVJ~b08T0hQL_5>qzqgr6nf)L0O9TO8~V??u=)OR0WuEt?p^+%S( z6KrO^4X4NMyv>Ji?8ZxzdCSlX35r|Kk2X1KpZ{iA+N*b%1|`X#G)i(_Ovz!o7Q8w# zfSZlLG9TJ(_@V~cjTA&t3qFmloCkpy2y=`)3p27UBYkkQxBmWG_v}aHk#n&0^_UcM zsNv_Quh%Clvp1;338{mq?>~PBX3Sir$Datncf?q~aJ7kuy%3E&;5pIS(d>*C6FshT zA^=Y4wLNngmoV1o`Rs6Wl2;A~l>9hQRgvrQ1k`Un(0M@a&4CgNhSqHu%qWYFaL%%# z?VD+Y%+|Y!0B`OPrfxrdk`kt?B|(wlj+Ep<_li~{Oxc@+sfhN{p|V*6K%R2bW?J{PfiBPxW8lES?r~sc<~^INpcb+tK08D#3r>)50Qv}n zNxJ~FsAprmtO|5*aN#_*XK3J(dvG{1g2*&QWJHH2u_`u^vkqoB<`Km3H#{m$)qvDfhgFMZ=ZhU2|(JKRl{8yfo(}K3dc{;y})(;5aj{?Gf55Q7L$+i9uS1X8$4xZj)pto(aJAcN-; zn8PdUpEUX{zcoa2xHcqlIl6vR;yfB3SuIZ&9qiV3eB8) z9}$Idj?u7Q<}hDAm%At+qPnbt6dBKr znaCDpPexTA&0_+Mo%n&Y;hmb7Bh$s_8wk1>$@`s|h|7tFZI5+}rAX;L z_R^krxJ4|!HzEUGA&8*!_OIVNd^tu$blK#wZZm3wVG@liIue4Nd5N{~d_v0m=>pDaZrBDtD6z6cs174S(on3!F3uH>%7Wvq;yw0dP zQq*LmJ$;Dbbf(qkuenov+#tzRcPo0jluXs1`w+wJY!DrXD=Ck~=4M$=RoS3BbGxG- z_Q!u%G&Svq?>P~>m*d;m*cjG6 zrwJuSsw`q2>p_4h$|85MtgNPLw_?7~$d{W;D!@}y!ksy9*-wMHI#FpBPjK_TImn-Y z1nH3^0!)19Y<*PqhONK#vuhEdsY_h|JnDYc*puCNnu+8wY0NRGG`-EmrSn^as9R(> zx61c;yLoQd8QNIs1BUqg#>PfdDq8hXy*)iSAwr?6rYBMYhtrDA%}10BFIPxF7!d{! z{>U{K@SVt?cUDNJYq9+EfY|NH4Tz@!c#Z-KgKu*+94S=AOI_6uo<6~*$yjYU-|j$` zIzHRWZ*m|541alMfYg#jkfD^Y;7e2!7DMnJkdXyHFx?ade!m{{%C@H!3a@vg@yVK?v~68`xqv8*|?1c(|uZ|;+X7}FkLZu;H(5hoX`)pS23BlFdyDhLN&GXU zaC&_MqlZDlrv_Xn`0b;sz^emBGinisK%W!Y?sp;^AM%l?V(FQ!zw{zuF=Rx*;9kb# zQn%TZLXFhb6jdlUX?m0_!#q85Zj$|C9T|CX1@9TRzuHfx?MRD_l*ISnUv2lptMeVK zxZwqIeY!G4-Tma>ZcIw0n!HG>%m7wC+~lcrTz9mK8Lr zk0P^mRUU|uOInV}7>y>24opw2jPgIoE)038p<2f$*=s0kbV(dq-N0ApauxnhV-vt!Qg_?S$-x( z^AOIq>gB;xpmpN^epx|i#bzv4o&}jB0`I&EVmj(s;=c_ztniWI_Wu6m<9sk7%jZ8ZpKQIaM?PV580S$sgU!j3S29Ym%4B^ z5-Z_UaB*?{S_(QzCjO@;2YT}rL>`ylJGW>j7NH=Ega`yw_`!>ShkG@*h&_OUbbXqA zy{Ax_H#XQfZ*yN(Rerjf8(90(qj3)tgViX={v0SUmja&UrQ%`6;JR}MCNYY%YoRQ* z$Icuw;>mTBeSzqcv5pQJieZD>Ex5gF?rDvXsNnT6e*eBK#b zwGqOA=e5ultg68h+6KcH1sRXRN67ln;$?0p3yd~h*g1~!?&BOljKCIDLi(UTF|!q5 z(LiE`W**U~ex~Bn??KP8MhE_b9*<-vXESJez?)AFN45OvsMqM4eU5Zm%2pm;!9?R+ z8Uwcu8Ga1jy2X;eCObK;-YG&Fl~Ykc2;?Ywh`6c}h9w~2DqwbCB;?6vXh!{%N2b%+ z2@dlR!1dT)g^*;C2H=X6Q_UnY+>xF<(!K6EhuBwq^a2#s7~Yn8nSfG{ll9=#__x%V zN~AD{BIU4yfeh!FwFaQ*&^d}T^neIb1z;L~?GzF&TBp`v)A6>P$lhwPip_=W6)-CO ziL=A^68Va+bvR2sLk1u}@er5`tOvtO#-M0pDVK#d|3AxO4|BwTxkV#AO=+%G$Pq&) zOjFfW2X0_s`m!*d7-D7?P@|%Az>m%F+waBdT+C+q-elUBO#B*;nOPzy0KPEdl00z*4a1O$RwbuB^bTm+I+4IG`EfR=&9}8`@pefs$gg_*Pf59kg3? zrmkTBlf?*#Hrot(m{5U?t^^$sRoPNUTRZslVC{S+r=ord7l=0RCms`w8`iS5pakVY z5*NZuB|e(*RML5$h|!Rj2qbPtSW0q2x)fN^y^aa3EcRWQ2$ZF~jQ!zDVMRiWs1Z zbs0_W;x4hCBDK&!jsQ-k%M@Cyav2o7c zh!T|ikihHn`HhEg_c^k>Et_MX7U1?`s#0i}Qsu_g>@lw>6Oq+8PE#V|J&+C|XmcLN zWK()-L|^|T;JH#Wt zMg^9LrGhd}W0I6(0E-KhMQ^|bei*SLPjs-XmkU5S28$m8->=)=iy$2qz(B~RWdSY- zmk3@|ADjUV@?^cm;icRhw$zN9XpfV1ERAKfo4|c)R+{1YU zvK@aOl#GE2Q@Ve%&p$%skeGBtjv8^=2b1CYskq!s>9Po@CEd{!cODuWL>TOzkj zCM-2FJ zQ|iv)%P_q<2PI;uAW0K#jSg~rGBB?Pz3+o^wTdI%ULMj{?fArXM+PP$Omv8jRPpjS zMs|n&2i)al=RY(KI5{&-W+2r9P{)kAT&sBov!xiNPJ6Z5s5<}}_zg~ujV(Z=HrRq1 zLS1s^qJUmyK;NFXwE>%7a z_iP6gS!MZ~jIzhYA+ZoFIjMMt#)*z~tF0e16C0{MNA&Jc(GJLF&IfJ-$mBNU7HLrY zFy2cq+1(eW%jAR5jm{TV`a_Pe_0+(Nv_k;=i6&=?#oi?VkM)k@)&g^1|DmY^Sx;;sJ4|4c#O>G+RO@Dc|7UN$U z^HWT?w63+j-tb7fHLM0;sz_W2&{B-rv?XG2Eyr}VPV23hF*KzvJ#M|y^@j~DNWcy~ z(*=r^73?rFZ1%Z_JPqfTQ%vNB1z?GLu=xXHAl}C49XXndN#>39sx$(WU5uPB>0rXz~;%| z;ff>Op?1dDpyA*%V<^TmY&9*Z%+occa2=j+_)i;u2jt*@hYu**diI6*;xv_mRn(gU6^E@xk^C z8M;PBEmkA52oOHwK>ikyZsdr8j$R2g8c2pbdTk~|t3R^=hW~3=qu>W7-!UkC@vs?U zmf}eC1_4mH5=xJI9ZfqeWqS0;Sg+5>b1Mb9+TD7WMvWB7tj@4a?P^&ep3u)e3GM&o zt&j_6wWCDIlEt!k-qHtV1X36HvIyCB?d-*_TE~n1)Yed9G-&m1ikTIgr5>$~1Mycy zJ|PKCo_{iy!4vO6cH!Iw4-yl*vwqk&V-EP^`_G@VyqV0&!VsV}_TBm-xukGC=~))b zFMhV3kCf|2q5uyWAf!rOLrVjDuam|$gT!zL@Bx9eqJ4CiWhu|>v@FJl`y)O5e6iAI zI${^=*JG6cHgjKGFolSuKr|5<8V1`27a27L)Rhanp&q>WD-DU=kBf)CdDAxQB|FrE!aj28bmwAV(Oa=EtrDO7x!O>Gz(614>)~wA&3#(yv0p|LjoPpM@~{+iBv>M`A#8 z6V=(1vvj>H)H_Wm!DyB;q!+{LqXv9SzuS6!-by1c06~V=fTxTg8c#Q8&XO@65)Jf; zI=sq2tzkD-p8OYVxP!0x*26O_K)E2kgr~@MnVZInONv4Q zuWd~u*L_B22mMWcp%BOKGsRS*P~!8i-Ly-)vdFq`1vg&(TZUz)b=c z$=`iA4svJXnzOl?kpcH7EBwc)#wt9%z56JIu&NVgfsV1MAJX>>`vX30D)DQg|GiyQ z=ziG$eRrt*|3#$yf8JvH|8)>TG3G*bcJRn9HE3vv)@o|rdT3nx24+d=N%#IjxuzTT zlHm*|!Z`HX!;l!%sjX7g8ZEyb8M$)L=nEnjhhv6KoyA|jnd+0o|lxDcf#(0 zC=hF6*N`#Qoceld6oLEK@dQh6)?nqr)&(s`>`|e`MjoGkf1~=rArEpd0#ORUn7$)Q zPJJJel|q%6d6sUE0x7gESZ#PrU4;VOuxt0fBf^FOtny~&SNygEbYIW6n;d2wr(tgx z1VOqXj*UKWDwFI$$Qc=e+ze|${Y^*%Rhq9G0|iK?IkIJh66aM{>mZ{kD7*f^XZ-oz zPniFzy$c(Zpx1%g6`db1DV9%!(h1J(nEQX*p923DoiB*Q!L9<1u^E>Eh$8THcXm;k zantpP-u84G5S)N-T53L?)3r+8G64q^Vr%d}kOly0*9M+45e-rR1L&jQJK>5m__1R7 zksAt-8)!Eh|3_Qz9nNL@#}8YHvMCwiV~0p&C1mdvT9gK&$V>^PWM(ESWtWvo+(rtK zoh>D@cLR}8cwX1{_dL%(&vPF~N8OFjxUTCw&-eSa-rMaqxWf)G3dh*r-xt#<&~JM` zJu8dqu=h_wgz(8*PY~)leGzTD*@^PPd}EdLP|hr+j@}(vE8Q*WRm(#&7fYN^KhF8j zS%4)}v@o`A$uD$nJ=E|ApLB@DUbORe!?}LFmdAUIb`ACQs-VB_ykwDUsOzoo@uNagqGhr7s9)!@ zm(NzNi&NE@!f?vpPw|`F&&m0+-$}!`Y`E+*eRWo#_raOqcW2O5;mco6+%*~}VmaZ#=O%wP< z2MP(gL4Bo50Tk})u}xXO4%_&qeRw+8A98z^>dq5^I|f{jg&*zCGqx6p2{~1#Np^{3 zrntPVSI3KJV;BVMv6Fsij1e${5cQI5-jhE0f_IMO7n$TacXGC@-=<-XppCeCFlotI z_p#{HDE0t3J3uu!)_bk*a~^8;rZGQ^$`Z`J49($XGu8VNEpV>Va33b&yJ1k=zI#;|T z5Bs^~4)$!}=q@-_vI8Z8IrY0ccPK#SGop3Y=j@{Qs53+9iDNSjzFd&pT1G|@dHJX- zroX%vL7AIG`lyv@CL|4PnoxWZj%R!Tvf2aqB&ab0u}5%15VDP|MELdIX3t@+pn%@| z;};;FfYK8_Ck>F_mS;Kl&I)YFQ)Ru$h$=Mrf`-&;?+or<+>`sB`_KBXW$!s)dmEfM z?1tILW#}~Eu&=oGLkxOm$v`F;0cc2B#t}{o%^!~_)FMC9 z%Mb9KxwYXHlaeCQa-2;|_ELwM?|jX6qy~JIh1_{$;dsbS@_VgrYxCDu7@pg5cHO>$xe6SByHB??+x1+=6(~>@U~tJu1Fs-yh&ogk{hqvlD;$Ip+RWOmS=kjg-y|ZSu5GiVxG~_ z(K-#rBZ3eujg!0J32Vhp^5N>Ozo&5nGU^jlG`S&77AN}7^tlRLAa}p2`S&~dj~uay z6eo*H%PFV)Vsl57@>62poOu=uxxWmf^EY=pYN~%Tgej}44v1)tABk} zn?iW-MNFO)6e<6HW3Qg)n5^LcuWaNbr_48={Qnv270=+KC0sCGW=zYJywxHcH>6*(Jhg-*($POsHZ=`OTxs%uTqW$!JxlF0d^x6|#p4VryVrCJUzu5xbIs_ujoluff+j`yu4*@-9;I9+QxT*x3Sc>n(1&TQsO zz#ed1OYfP$mB(($I}AN}f|BJ=^4AxeSWemlp9O2YtM?r>J?AivF7@;0GkP++l;7dG zj<0Z~m@%1xGaJw$r)OQ(&=JDYy)q}}@2)PE7(4iDg+Q<3I~h|%e|~wb!=isG&G;EX z6bTW|zPdWiTJ7EHwj=NFxyx`XxRQ|#ul%KV)-^P&vpjBd58AETv4uU{;qack^qR9G zbFj83n`1NO&{u@xAA(SIv9Wwg9!1%!-;@o`V=5%ld>G(a+P<)`K!kAsB%AOqPQuqB zoE$`iM3<8O*iJHWs{%Dqw!HtO?_X`k=N|pP+mQXKnf{3p`?v>c@4R_`G9W=KNK=M| zl~o$@Oya%TEG4l0>XetwR7B!w9Qkzm>Ie8aC5FZVZ-HB)zDhpZP55e@dPE(Usl^7f zU@Z@Ys9)@Fo+BsJ#e&b*H80+&;UgS@VA0R`H`rtnNiB-T*fH+nT-x)A^N>>@*k3}O z{-5lD^$q_d)pKwz#cR5OwImWWToH?*ds!ty2ew(f^!YyqmX-uY0f2!p05I7NXB^ou zsBIs;TRnJ-$kl17qyEQs*lRY9?vRkdB?WHn^XK_3ED5OsUHGRFS6jS#tgFk=JDZB) z=v$&C8fI*G-pc38=X#)M$W&lpD3WMsXgFO_UPs~PdXb}K^bD0p1h!zGJ+3PPMg3i` zi(|+e{{+^Kc(5E`82!0R>!`1%K=A3-!=tGrP0ftKX@ zZ`BPJutwM8{t8Nujd8Z~iFHP0h<4?@5Zys+?}HC>B;D=!jbpz(OC51N(MEa0w~mwY zS@%9ahg`oA*FAt-rKeIpWf#ur>gq<}VX$sLuKhlB{7R=p9furkJ< zOePNue(HGkGp{7V+6qFrQK`K9z>w{LNpyH3)HFf=C6;qpTGDfCd7b<7F}wxf z&>1PkH{P_qdoDP+oq{|rAwfV=vhb9%K;fq!*KlE1eN|f4(l_0C^~Fuqhz9UJa4i9# zP4&eG}&pk|9R+tec2;0LR`_ z#GqxCq3KT1Yd3jmrh57BM%P5s)NhVE#v%EK{yt5f3hTM}>d)RIwT$+&GA~4SHx4CQ z_b9NR>OGa)vf4zuFZD#)tRSmzkpeqy$`{Y7wU1ZFS2W4W%5+j5-gsqx_|LB)Mig41 zoJR~a8^3RFWGC-CvM`iS`Fk>KS(1IGKtc8A-6l)n%IAlSMvqRodIjy0K5(@sFQg04 zbtFy?j{cLDgO<*6Ke<|mUgh<1zt#AyIrM>_IwfDEFyUMJ4Z_n3W1B70u{9Y@!3z=L zYh-*BhAa#s%00qbX0D@kv^PS$zkg;H5)vX4qjd$PN%-6#qHR887##G}kvLzJ8}s$u zbi|_3$7rZ3JiEN@bx&Qx1CRA8*?$t;`-bSIx;&DGw%u2fkV((_Fyda$L`S_pR8*?{ z$2EaHbow!=y9<&YyjrMrZP@E=3;llVoBWox&z`QG$rIZT>6xTlXO(^~shjZ8qdIwL z%6N@Xot#sJn4QiUhMp}@&^A1>;K=ukkk|CZ$X^QG=7ZfiR=E}{6%F70K);9h1eIipy8Wali4f_%0kr!r5}{eldy zhGPxeC;~(&C(4`Ub?8q@?@|6mrgay9GYyt4v1ij~$V$Bs_Hp0wKsb8yAur#d(73;c zhDCT$F9#3^2ywJMv-hf5mZ>Nl8wuvshUz{mwh9=Xdq!SfhTB-ZCChs-UivFQSQJoe zuDO+4H#RoDWN*EZfyRX9o;vm1H5)3`mwOqu<38O+{cE6c_QnlGe8SdnwADB7sw`R$ z&t{c-OzDq3O!{qLXc*_b533cG8o@ef7;iJ`j*f{z5}ERvw~<;f&+(JY(!yiMY?SG4 z8U7o$Q16z-u8lC*CIy)43@;qDOk;J&CPzr3% zMw6ZUKF#P+DWZ8r5q>MqZWC!htlIbYoI8=9aSegIRf_PGu^6 z1NFS`%~)4zB4jMn^NjQZ<21YSxTh8KMz6QVkDpj}&lHGYwhPR-b~=D7taY<#a;Owu zqrbnZhUOpV<&}-c8k|4%V}|2hP6n57I1He3 z?aj$Q$0wAu72L;ZBw;nFRWj7otp=Na)?jG#tc?He&6J|VqcC4pZWMOD69m5VY~JwGbHLEn;$2gZ-Ad(x%ceA zZ=bh^x_T|`?oGA3wXCdF6!(n#{Y>SUOEa~!w5J%eS^-xF?mQEc2^@s4efzGc6|Fz{ zM6S1AvoXin`j*o+RC9;C(E)KzoWBv~`u-FO+OM=Jow@dQc1;o%OCw+Ma|-jU6H%LA zEYFG^@hc1sSna!$dM|pmBC?=B0-oxMW_p9b$gUdlhc5hNS;yqOzof4yr00tT6t_&= zdFn_*eK%;lM9of+ZOW%?+C=F&Z$>iT`GPqm7<<`&D~i22^VY|*Vs5@N?xLj-Z)5WG z>#~-favCw`j#;K}$!U3ujnV4<(XZr+^YShYR+O;m=m~nGbVSG>9>QSA5mV!Txtk@? z*-dIZ{KR*%zx?!*?io#AU*Ct@uOKInyjpGi61}!_1=YPlVlG zDGlrUYMEuJe7tWeDma&aw(6Zw&1C%f^+ytgaob}>GF8}DsY$$A`Q9Hl^V#o2TLp{L z-&4ny(WSI^ZZD}Vung|%?^fp%656Jc+O9T!eK6&Am%>g`G(P{9$;K$Rz;cX3`PA~_TK1c|)-*q@3iEfR z11{bXf+=Tr`pb2~9g5_yKHGcaY1>9!6$s5)la1TkLGc%rcL>KlOs%pZi4}#Jx3)HQ zjg5nF%>gUz|B9|OP|;&@7}66pKBnkT`eC!>2#B*gJ$-R1Ml<>82$7S5I�%yZjxK z(Hi1lzbRl9A_6G@WOQQxYf&L$D4@=|&EycP*iG%K^tcS5z~#8>$-yJ`4i00GP1b=c zbXdEhuKwQSC;O>Wr@~O~pF`t3)iWd(b_e1%rZX?tZ<|R0F^NLeXSG(?GNBIWhu(TG z^9voG8&o*=-oxb~(5o){3@K7afzuhPo1}~m*W8`x=bx^KgnfwFd(eyhw*H2^tM<}W zc;PMBc-*G)@@I{t%$QlvpNs|%dP0v5_HhkgEeSWHh1(7=uNw$go ziztgZ>mwI47vC)|I;QaWOp`QJ%=0&;tjkP4Y0Z3vc`il%L)_*M!rpJVpzTQSXx#c+ z^H&GAm_zsUUIkaR$(UYQBM1^s{u^Pu#RLf-8@@U#kps4hp63JDZ2DYQN9CEWDxf)F z=(KP*_Ing9dgt(lWrRQnWf)j{E~)zPr*A}fopn?tukX*?RDc&3FJ5eXrv=ak7oqdO zC)t(C=e~a8Vf@fB2pK<7-q*Jb7Ra0L-Y`miEg8W+zuW!Ja_9(h%9cA7Ekc0}GhdRbIkGpcT^@@>t(A`|-{$nq+Xi3s`X>h7lhvCHA%dWFAmEi0L|-*PWt+&7*g z8ULAoxp*aW&kR!JXgN4Iq^E+HoR*ZAga4^0%GW+H>G*7tEZcNo(~9>=!JXOh*n74E zNBkJcu=OBJAmv|V)}FkmvyL_NS1!_YdhLaxoe)I7MCdA^JH;KT1H^D2St2{(E!Bo2 z_2?~qYX{t=iO)cNXi|L_X*pqb`e5Upd#7v_-1rFUoA_T1VPxi(yT%%#8h{sG9nM?h zBx`fsNPbG%w~rR9NFA3;$l(Y`oZ5}^Sx>sWY{G_QRg`(RMP#;55gd3pfHB>}RL9S` zmS`w&*Au+Cfz(?I&Vx4wD>s%Tb2YDT<;@*GJvD#9dP{bJ9!k^m&>0 zS<~Jg0YN|eOY)I3lFO8_m=}Xh=+vLogWo(>H~hc&w>8~-dxo&iD+&jwsSO~V!0hDA z)ruM6h0>~xj|V;cPn}98LNQvew3iEwPJ(n6gUvw-nPN_jWsE6$_I?1qITZR`6(ovY zzy3hzw*kyv89tx80qx#y}L zRo<{_19&7Q!^k|P7NfCi*Dm0|()(`@V4lbt4iXTOsHN4fU6TXsNB9Pbh$`qZ!kgXe zUc~OYKi1sT^gl5xuPTG3B_T9fn(b|gejM_qglT)ptu22z4R!~pkr59!mgZe7*Q z2{;N`QG$&j{vu%)0eO>y<9hs`u8C9ji>x>oWzL|<+i$MK1aB+<>iX6iuL=zG-oXxJ|@)uYNM6df>{a|{GsZxsBv|6@241;7$Q$W9j|E4BrBVPjic zJx&l;h_ZX~k2At6sAX?248)jj_bruF`*}_N@vq5fn!)Fc0O>>%uWMq0-RB4tjRrF( z)qh&aT3uB5i>(}bVse6kqNJu%184yM{qVx|@jb`h)@7Sh@o9>#Un?7q`&sN z{X}=N?lI(1zu`n`Ww5|_q^Bn zxP5;~%$D;LDV5-XJmVjaVfvse7d%8?W%uBlklQkmq(kr<^SZ-x!TI;DpZz!&XPs2Q za6l~Kjo3nmf&X;(YXBA%e-||3``daC$lj7QDVDpTn)6oH<=+A6yS(abvbHMUS1T6- zB|T3(NDlb)Q;J>{9@pCX_Is$T;3QJUCQnGv-QZRhJtD%KIP`B)p6Ie6brg91Pwt8Z zyBw)xA)Ly4jDO)bHoONJ;;xfzg+L&PASU#F(bmIKF&By!#@-8O$@$0dsW;!E=p?3vXy#|Zm$ux)LSv^3p@^R=6lVqW*G``IEr6?G?U;#^a-kD~kG*RH?u{=fdrgLlI2Gge(|dH!%Y zIV$GMy~d!3vxjHdNJ4!NQ7YB^S~;$_RN*;uCtR|kF}gSS%{!dF1b<10;sJnR38Jr$ zPD~7eYxM$pc!GE#8AiS7s(TN87^42pHY!}mXF3YlWN723cMy}AN2354htxYz7;9UE z0vive8And*7#l{lqHTJaD#l)eGO5bA}rN@ zaP-UDX}{#Nh~k3-s`ZT4MCWJh7=Ik*@*|Qnjoq>!DF?6vfHvXFt%5RhEwh){7&T%U z^?$lfcaV@lMFn*>nblT=3xPR0-c9K`*`RwXCck;a`}H?dH+zj6!MB5^<5b>%N0XDBBp2is1i zMEit0A%iEfd9nYX&81(H+%~qDfW&LOPD#lYD!+=1=#Ns; z(#4h=$*U^)K|)`FWH_3^L;*2cG{cu-g+oTQgsmI8gPIXnO}l`D4(D0ahoK7BCOp^O zM)DkWzT!D~VeP701JUWh4!ZoJVRw*&XV#lmSMKzClmh0eNv#QpFM<4nx z;bBm~LqPf(X?a@KNCQ+x<+zch<@m(JNQC^i=%i=Y-R-~0lfd|pMRF_NAp%YaPeL<~ z=9pG+2ed3N;qA(Cqpj}qzlRovZ;4R7qDd=b|@o>EaB8kH>H8*keLULbvU*f(xe1j?p+mY z+qMwrSosf?E=5kI<3m>4NId!tvFz}b|Aah2ky+>|Hz&dth2>fT3g>& z<0I2D!@r4+jWrhvpr^hIruI4L7+HCJyU-@4mWYPokn z4umk8)(aiS-=QK6l9(scw6cmL3 zXsA#o1oq7xT8f(dgKlSc_cIfAECG<3e6#Unvt#h9iGYR?0mmWoYs#s=IJXSiGJ3!4 z&G@*u5b$Tji4snH&b{V{US-0o?jjVt*fXLloW#b6=xK<(b`!skfKnFX2V85+FbwWS zOzdt5HJL$~BZqP;+WBw3+GGAKb($N4!FhS^0iC^EfuYz;*j9X}$@eG4yiA!>M><4l| z?>jDy)&-rdS$L+pp~vFMZzwwjknPL`q6ox11_7J~_`)IO*Ff)rl17?K&Ei3g-^(QY zEl`q!uFj1_xy{N179PzAmyA_9#!`wtN92V9;3h!v#jPsF8OIC6?PqQtwEm!u z6X@tg{>=7{bdAi}om3Qf$`JJf$eBF1Fwg z7f*_%&hk;FXNWEq-u$LB%X-#Z*+b>{u9&=_e2ua_CO}&!;EaK@eLpus4=Mpxrn!OSA)-(Y? zSc&#>6lkQ#{H5o8C8!#DCKab*+S~^AH;%M4h!}oJF zmI4EN+YRevjUKSX<>e7{^IXD8Kr;?_Q3;7aaMpbZ^+ibiK`{-<;Ink8r6YsNmtFD; zQ_FYBaWk}V8GQU*$H>p+VET+^2B?fFGWgTnNt9~%vPhUdN8@b4whi*A_e5lz=kfLQ zVI`qcCx8aT<_lc3v#a@Wjmxv7_&SlZy7NELa)TBWbQ3{TVv4my?3}o`L0HRDr`OM(LE@O`+%@5(l+ zZ=JIX?K+*(b@9}JR8Fg4#ehkESQD)aE)^I^oqPM!$EcdL9?PEG3wBVx#_#S# zF{0;Eb49lw%EGAnBd&$AY&*`uH5_ydjD_r#&rA?HK+{OwxihEd*keWoW+9h-7>1!{ z7(#g&^ij_Rcem~tPhx_S^c>D|;ITy(;kbxRlzb!-IjZB88_NOxy3UgO_djQTm9Zcq z?qA@&mm&CQg07}C+YSy*PjT1G_O_p)HGsm zmcdQrFcOFyqD%0-3t*h42b$p2$0Bu~2TsmTjfEnsWKRf=10- z%GJu#d%2gk08iBdeklrMqAuOf^)RO-yu7k$T0$Pp%$T2$)PMeCkNBc7jjI=(Kl{ zsE~1fu~LDZoO~Fr+=DqxA%A~;EtMjI!pdvPgx)+oz;)ZH$gEvxl0{*v?Z}SXGOspK zm)&ch0&ExJBQGP3D$Rsb>%yw&==aQ{ebJ4n!j2Cg2cQ)bDz> zxZ&X6_9=$b>@w{>_LE*4hCl0}D=0syc+>}Z{TJ0)OTRjsRwFU8k0?EN>$2$OM*b#e zXMBE;le`-2PXLzaIkbkczeyXp(69h2!|<5vM|TTHe8gs#`3}+_Hh-wu4F)B>{g~Bt z!{wd%IEi2dCX9ZP=cWKe4)#r|a{i8BB|C-np$pea*Iub@uZK~~6@FDBuqNm>l{%p8 z0NXz5BaW6p^BUk)*h!+op-EAlWAfr`mCE}O*SKfl5xhaC40ILGF^?L?lial@HG9xn zBbn=96HVx)Vq5f<*c|rL&fFUnEL+4%01@+Lu^jl&Fx;$%Tz#m31fV0>=~Dsu3=y_H zy9L2D#v%j-+#D~|BaTf$mVmywhnoIa8rRX{(5u{&t!Gr8C&Q!^`m{wg#Z-T$gwtkTnJv#YNFeffTG)InkTwt z;mG@2`Stx=^T&@R$`XhU9;mxsXN3V9*a^0g6}^RxoFAM)*1abR^?=+AUd6l@XkR%n z+^LRl|F4M#q^MHaZ_j{9#=Z*;ETNaVraQ9kMprjf{Kre!KJ##L;-#3gA~^N{HIJ)Ruhje-RM;)JH89T2OyvHFZ2H$13&nr&bjRf-k$pX-F42m0tILy^=Vl{OA%Teql7O|~e+@3ZPTLCdzBRFM z=sku#m2mb6lE(N(KQ`RmG_i|*70wWZT1sP)esFx_A{iO?te)mki;vZVUBMzun{aoBqZSwgQdAEHl^8pS z2nuT#CK)0F955deTg?9pXN`eU{nI7uGOm`>SKr?A{&r)#jD2f0nzEh4_pj#lPELP* zC19MQ5MU}Ac-p00C@kMy=`mrlAhU(en^0{B+m$3R&Jg(x&07o6A0e&KD)&oj zZ~=7fzFE$N$dr6yb`c^Uxv=gk%+0o7Uv>}`*&R~d{oAv{%m$}wJgK}VIPVTkLG^>M zo)>3%(R|08do6p0(EXsHBXao_jWul_8;bykVA@rDZY((S6N~wiYeqBysE<#purmb5 z#KlnoO1<`mo-2Wl2D?k}Q%CSg4L!NX?D*-5(jd#`gdX|uH=nuvCncSMS}71DSnN$9 zv)wu43?`s;m&5IeNTR$vf^hmbe@SLH8{06bzg`}8{@cnesvA<=3}fh`;(rN=h}6z4 ztK;~Gc+d3&nL}9t9_^Oe_Yz$!ZcQIQe!%@Drm+#RLSMdoS-dJvQQIp*)=}nmfzm#)#`4Z)dTMGaoU?+Iy4nn4zm`K$k^K@;8rU3CIn!_c$Rqv*GcNz7_Zd!-{-SxJ*U*0<;ycfrJs+IWp%p}OG!z}JnzA3 zfg>lOa0NQUsc_iCVy8$WygSth_>uCHXxjI9w=-zN@udPa$Fb>WHv|CQ!VBRPwR1`^ zw3;lsQ~P4H3@%i2Bd?^=?}&E*hU4Pms>c=@9mpG%(*z}B%RV+J#V0oQ5{rh&ZGs+y z-kS5_E*dJRu^ElJ2}JLUb|It4`!-7!Y>u_CBj3SMczmYS=_rufyNF@DYzKF&*``ql#)`MUx~{`&;ff`KT5C4MgqG` zl)uWuDerP6e3_jI+q3(tV|`x8Np4y!hn`s9rL|xs{X-Q3OOop3aJ;78+EgSmqiQ$g zQ*y8xpcWX8Jp8j79xYP2bU%%9fD1^?mjIR%ecH0J1TQ5Ap%^J^EI%`!Ppe z-RJPtSabkTEc$EpRak|do?gu8-odwRp?7NCCgWQ`0$obBpJ$w?3$0Jk`H<)pZ{P8m zhD7AkDECkrT{v`!&DK~f#I2lmLkdXeOciw6%1Cqn<}iL6hEVL{nsAOVXI zza0Rj3s{I#PBE8U62UFszm}TJ9zTsh9aB-ZV-^_^X24$K;@IwPCu829*2Nl7cf#YA zW35?SGx8HAvV9394Y6GkZC%T3>zL-F*f}xBe~kxXVq@=M`c9I`0}ua6m4!=!KBY>- zDZLJb)z;>UI@-LtZ`YSy4ShjBJA9ibzg?RG+}V zar-d1>HrZninI31?qulv zl%^aTmS$$>Om9YSCb6hqMON}7`K$GaakaDf3T_RuOHjNHWu7q>R&0&${q8%utkUPo z6`1AI?sGdbaKLs_PNB3;tMkM}=jiaSjtr8`u8p?6odGgj^FU}D2+J%PffKm3A6eN$ z$7QGXIi3Lr zb?jW{KQw5G$g~!!s0lUfw6MP^!mr8C&u)O79~Q9)AcJEV|4{=~h}84!S9PblHq5wM zAKm4;sXz)ZxgI*t8hvQn)_ZXRbzn7b)(zpD!_e z8&bN0`q0Az-IWU(u?Yt4-Q4qcAM?&yNVR`)%5>`SiHr-0{L*hkAm2^fR=&QbaJy{p z666_KC*SgX(D?73SIjOqbQ!aY4ym(9dm(PkQ0&e>z$S_U%CwYCh5KaiY zvxi(Mtj(G=QaLA@7~wTe$1;4)av{a7`%oLn_kzpGH=V0dG1?jzO9 za{Vd!ypvPpn$AA?uMUQH6eq3LZ_m(D$^TyPK;u7B`p2s-3+gj50$C8D3<(b-bs z7rz6Ibe$31Gp2lw)%^b^paYjE?z|aGymcyo<#poV^@0JP>01LfVNXVW?o*bC-fA1X z*J_tkD|K0>@hEqW&y|luG2v0Y3Lg1y)(-oW<`rG&wXyVDD*bV4spYowm5SSZ-g{r) zJycrkZlLNdO={U!s_BvMBC#{?VQ+l@(fA)HBn=0gPVb$&>U?|Gxv+_3jj^`Bb_@&S zv^Bf5Lfth+Yp4hIN_;wzbcD8m!Qy9{Ne!dwl9CHo38kEl4|&br!t&ooHVT^W1#RkV zrj7q|{_~5{c2!R^NuflI&$i6y!QYD%53NPk+LFt&Dkyj+n;G|Rj@(cS(0{*8^Ua+F z2bzIryK>0s!C=GVeYr2g@U6=~>X= z@IRs?WeH~F)y8Z9V17Uo2xl+B{-W%CMOT|$L|zT|5UPFLQA!v*=&FVoqZ)8fauUI5 zM6mQh8JX<6s#>C7ax$6ZBw=V0tApda4pO^&8KM-o$@nZRcfrx9Wd<&2*Z(0cY#<6y5csGo8ZC-&5j*Jf?1OC)*StDdK)vl1$L98LrLd-f%_s{f13Wmk3@KJM^QV%_Sqtx#z;muUBTaj-+`78?71)mKl|}+ zrfgcMvdCxvrZhDFxE2m^ScvU`OJ7t#TcJ19LU{zuQ4!s5VBQNzlnen`@_uCAL^(`O zQud0v4>=*r#AZ+MUUXc2hPsX#n6>8e=7(H)jN`E=4jJutpo(Bt&kn<02$ zz~U!rSCLR>j0dpT_$T7m5Ne3zq7P7qUpy>plwVY(`EN#X77cbNC;KM%M$~NDdO`E# z(1H)X0}^H9M{WOSCPW;7Z8Va49w3YNi3Hf?O7uK?tP!+HCCXI?F@agX%xx$7c879ui(HBEXOD zkJ*lcPZ||K*iQW>#%v@idf3MW+zF-*sy&B~LFBBMH#~j(b}*JJi)<|0)na#mc~x$n z*w?xjo?l8Xvl9eyuBy;j_^zA*w1r&#>OKZeHxKNATPd2IJ=XuztgwMTua5i!^CP1L z>A|q*Ad6h_smlsJIdn@n%M*U^NApzR%a~t6RFmO5xkFTX7fjL193+O;zTh$JCDWuaZqb>u9>906IE zffFnorC%dZUjP*)0z82|Y_~OJYu(?Fmvdq#H8=iAMJqCG=pWo4qHZDSuFzHU+}+fK=B`kIT`ZwU5@ zL?xRFk1!Y6v|8HRhKrArl4$?u1BBzB&c}&RNy3%#ENA=>8KE2A3(UL7+4C1$pTV&k z=$dpOShsLzCQ%U)OQ%&&HT>@@!4tEGW`}b!YHTjaoH1%@qi!aKVB#6EJ2I)ci;NID zukj<&4JY@YFzT7LC>nxI9WC zlxuW6%6kBFeZbPb_+{xQm{~ViIYx=un!tu!2fg}6VBo7I;*8PYqd}%8QfDDm!+=fF z)qNX=1_lqj_a(hTPl*N|B_kzia=_8bYBwregr}KVS=l$<8UH^*BBG3gHiVcIFyd!< z#N&Aj-fqI$7XV!B+~gBV!i7R4X(HcNBTt8Oi-@zwJM|{(aFwwB_q%@^nCx>F@oxH; zr+%-Em$Z$`>slM*QNdLmKg3LyA?Gj1auk!PiNJXXUTyr(?oHsPU@k(PLJXQ96x*hz zrnY4()@E$nD!wP&bCk_qa$up>5<@OP#ef*nE#y=fJ48&4CDX3pKR^mt%(BDrH+49EScQbszCnVW;! zicU?H`m4{e4wW`>4-yk;hFjm7!jwv8%hbK{<15kAVRs{D5l~l|HXr+n5d&D#uvhe} zU7CsZRC=s%?fV`S`uT^V-1^;C#EE+FFXM>NjwnNe|-cqv{*!UVlrNOl2_V@`6zA?d@T1))nup2-X(nCv}&N zuY8OgTav+ni9t+jHO5PmD+SHNK?h%x(<#)(_@Q>hG7J?HhZ%zy6qo%o&SL;)W|3f! zeRQIM7+Imq0aX)c(ylwZpk)HqWC~OK*BVPno~Z3-Ui3wWcUv=xj9S%0?m>TY^TyEi zllGZ>d!Nd(%WBKbN?uW47q~0OHlyYEdy%o-s%Skg2p>)?MxW2o7FTTU)!;XZ5X_h2)Fc){&L(U%HD5U?y44 z8gMt!)z?30yE|S*X|Z#(RNZbPjPd)c#s&*>ZbKnlaHE(v^2(X*juyl)V_p1Wi3&Jhq-E&0MFM zR<8U&67l))!3;W|%$@VHX}}zEi%e-^XgRXESROJxMaSK%)EM&GA2V?>-=DIyjL4lU zF_X7t?Mfw6r}0G^JGd8j!;Rr!UjGodh&bMPms^_^S|mSBFDqMpcI90_qlZS6rH^7) z1WT}XkaSUED!7{FibkJJh!6SjK%g|DcIg_3N7X_W^5+Z)KX?}vpj^!CpMhfq;5p~o z2=>#*)ckES@|{Dknnw#wZy~8u;w|Hq9_P=2OCq;3L~#UsetWYtJNvN_=VN1hs}1hPNp(&4_p}l`dy_vH$mKMknYCZ}HQg`hopV9?tk4 z)qINbdK!~89=5w@eD_o$G}>#o_~X=R(0*g+;MrNn@{v4LWrv)2qxv%{8Xw;0&o1bZ zR;NKlrLlolLdB%h`dY}P!Jv;Zn~iB7>wjszXnIQW>&Gn#Brx#vzpYpt;3q>QhttKt z8K}~aY6?57;*T^rn%K0C>g(_5>gvjfRX%=iJI{4BrE!naY!IX8A#sq7Fd7&5?yBIr zIIc(dIzr4T;j1J>WN<9pEctsS^IDB?mg>Pq7C$0#6&7t|u_ej&SZvp%!N`^f+!|X% z8>(6zyJh8Smh?~Tf|f;6Oj45Lf#GP;4WQ!WYHTr=A)$(6%0t-lDg}`jqeLf#c`J8C z0yrvv!o^MuF?UasOfX>Sh5gm?&3^2E{$CbHP3T@1wiM_H9DkA=r^6)+G!Rktcc4tF z>p#xk!vJa3BHgcksA^BFS*Vmf6k`ts??0UUInZUZ+o<#9Bs*qkTq6z3S-!*|8m3N_~5^;bM4=@ z1+H<@{+!Z#R3gkTE<%Sr2dYMdY5Y_4GkUHTxSwrD6Pu6K`l->h=lyC`9vKdQ!pGMQ zNK^>$_*^lRe8k)-GAOJ{Hsd|ZIAI=gNTkO* z>?ws$YR1pP38?Q(e{ZH)j`75I-&tScV7##8-!Ow?CPc_M|Q^Y}U zcS5CMY_7bqnO;(p?RqgId#a*CbGae^C_4+f6MXaDBLBIHNX)Eh`VT*&>T02kq`MQN zt9d36uITd$5sV+D*KPqx1eAR8lVcmZT3}+m6^+>iDGIKVoy2yoixOa9yR*}%9Cl!= zeRF}%C#*I`-4J}bLQzH$VkMBWQ}BF+wIl(RpLwhFRGh`c$U(>*zXJ*0+L2$Zp|z9Y zf2YfngY2xf@7uTU;L>h|($g3b^pTGLCiHNmZ%;H=A;fH<*{9EB^wUt2=5+BTQbRiM z#rS0aSrF%_7= zDh0w`UR+$vS^C!+wKnP*T4Hk3U(<(GPN*2@{pK*NVRUQ^YCZb&R7f|gkz4jc!wGr$2%Rj0uxH2@VwtZhVC|u)d1bie6J@EL$m(p2N6)SQ&~*TU;i`r%r?yz zXWkO9$@#0Oa-f#Q`TY`R;C*r)%n2S|%5gDoev>(bnBl}Gx&=bx^5Kied)@RT>uqY< z!utQ!yf$LSObtxUA{jo^VKGaBa^u0$Se651u>iV>`p38Ld@?(cZzrk$h`v;fWf1TB&yw_ z4~MxKnsVo-6hl5kZGc>V-N>kdYJ181i;t4MQYIONc9YH@K{tcQpgOfn&qKZeWp_m> zY2b4I@SER;1{Q<_Rd6AD^Q4yHNxPd$>?l#dQ@Mn&70rsf^%CrnH-M~7AQZ%~ zqU(5DOgBHK*LwX=1_~sCT_GE{S+t&_wqUU-q7JUbHRL&XF@&vK5wn==`Irtcd5AMa zEoEZ?!X8kKDGu}KM)y34%I@}hGf1SG5JDm}#!XF0UJ;NpluagICaTiA4diaGH7|wC z&zrW*@^drj2<84q(c7DLlv2Z{#+C_|CPgA;g#gMkw7G>!b}4wAh{SL=MMXu>Pnk7j z&+^0w4az9CUM+Zl=oIZNEf0-rJwN_}hoG{F`JwK6Kj*wL4Lov}oi6Ssuy;ba3!zp$ z))=AVU;6%q6`JHDn9LT1FI#ZBlmQLn0=iH=K-$Z&rTXIB6mKf1=B3@h)}z=OaD zQQ%AW34Mvv|IrQk|J@J&Z6wGlYmAR2?DQ~Xg+W8Z;d|`zY?poJpK9SOb|!n{FpqHi z^GCU}lP*i&<*pCV@8e*R4m|*qzVwqJ6V1_^67!4YhrUR3CCe+GOl?w)4T8DI zV9@^y%gz0N@wpyAoN{ffu&3Y&{QraS{;4+e$~inWUvwfPBV({Tp=WPoL?(t`)8Gg3 TU)Qk*#7}x!#+rrdws-z7$R;I5 literal 0 HcmV?d00001 From 2fd91cc96ab98f0a1d91fd95fc72e06c367dd7a0 Mon Sep 17 00:00:00 2001 From: WizzXfpv <40316777+WizzX-FPV@users.noreply.github.com> Date: Sun, 19 Feb 2023 21:09:11 +0100 Subject: [PATCH 053/130] Delete 218416736-b30f364f-aaeb-426e-b211-ea7ef1f3c20e.png remove old image --- ...36-b30f364f-aaeb-426e-b211-ea7ef1f3c20e.png | Bin 138749 -> 0 bytes 1 file changed, 0 insertions(+), 0 deletions(-) delete mode 100644 docs/assets/images/218416736-b30f364f-aaeb-426e-b211-ea7ef1f3c20e.png diff --git a/docs/assets/images/218416736-b30f364f-aaeb-426e-b211-ea7ef1f3c20e.png b/docs/assets/images/218416736-b30f364f-aaeb-426e-b211-ea7ef1f3c20e.png deleted file mode 100644 index fbeb449387d6da631dc716b56484c27036c0f910..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 138749 zcmV)cK&ZcoP)60eOUFZ4vxqC!BM_!egb$3_wp}y1-QX>HpvS9`o5Hn(Jk%n*Y}wCWC|I*EIhish3wjEB*VL zR(b_7lFyOfQ$U@$#n5D`?B7$e3kUyl;;G#J2QFwue<(0pc%ph`r+ zbZtF8I#$oELVy0K5kV3|5y6NMRf!=W>1zEwsm6R?>GKN5CWdP6*YtmkbbX>|RIGxA zbPi+8@;b((&kDq-1R^o_Et1+EV_g2-w-2@6OZphpOgt zf+e8J^7a0yr6(Dq5@G~fV8rzI8Z{C_#8^WJA@wm3CG~*<8uLA|WP_@T21R0e9-w$1 zP>p~fLT*p&$K&dEk3HKw9#tXcHW*`Y&h`BlLg>e4>fbybx(7zO7meu;W70g*7>QAd zF`c(4%D&Ge_i+q$x_*qybBJKA!AN@6!FvoX&RDD%G(v16&NwiZ04zeF^#Qa%j3Oo= zCW7QXpg@Dcdx&0X>jl1U(6%MCExu`qUWjT?3>b^WVWQwogL;oshqI31R>k_GYYcY= zoV$3Q-R-kj%(3yj`n(=eAWa>+IGSRD5?iGS5!9e6X>dlsrNLpX1)ymfV$6WBV%{{9 z2}T5CEXG;H2=n;@Tev0Ygn+dL^n?UrD=p#l2Clxw$noOdIO%t+d+XP-uGjtEK5X$ zrfF!J1`(mEDgeA+juUHb|Lj-igS9p!o7M1l{rzD>{4dy1l_NW?+m#qY^ThbgazBkSD(OK;|=}aLy)R zMe&*johmr%Fkc?Y(=-?nTv22IAd^Gs0lEX4 zt_|H!*MA~ljO~F#HRit)xCfs;M|VCk`E=S}YxN#Q1W{<}HUWC!uqFX~>X+2NZQIf| z4Hm)VMW+M8t`E|)NZ{f_V#)$5?0lt9J9eJ?ezmW=XJU-OT1#1$M2+}%Irh5G$Bq@B z=(CRc_5>rhK}6D`(Gk|X03;A^5E`s=IA@XEj_x|CZFN6hy0Ku*kPs3eM_p~Z&*Lpw z6?OEGZA?+cplQKV#SoK4AVP2?b}J6VVa4E^1m0p@0(0ZQI&2WEA%VJ4TGJ9{ff9#} z0(p*i&#JRpy5pe)(m;c=1{)lcTQg?wHH2EwXb3@j6U(|t)6{tqt(eQ%RO#8EE(cs^ zf{O?t16a@mKS2{KNs}Y7H*1sm6=G&H8ZntkCDX|#K!SdfXbdPmftn`JS3*A+)58qJ z*b+kre32-MNMdVI6^jLgCf3B@)4&rU#>Bkp*r2KuWq~o47z3?FqRFOyNNiLD^aRK& z5TeguL(gnG(=VC&OY43WNTUkYg0)G&h|y6Pi-crJ1QB8kxi6H2XK4U?=ZFC!5L=6? z$r40o>MBa4EQ$n(8H5t+0aXj6g`p!CQ3cfIdxIDSk+T0z%(l3&0x*z3GA7xid)A5Sd^Z~2uU_GC=wOXfFWQ_GTVI+oE1C~XFSe2 zgtYiuq&M%&SP`?CYDAz=+F8Tl;f%&dqGaBy%f2~zJd{9cNzc8VwM_0VaP1JOAx6*; z2qA$bjbJsIH!-GR8$uw2WNJa0yme<@v6LQt@EGI3NHS@nCx~XS40$DWXcLo6iNQ#c z1?nbEm|mA$VRGp(naQL z_!Y+1X_Xw661WRj z(1e!Q#$KD&*b$NLKP>fkBbXQw4@LAiV?hi)Mw%w#1*~%vw!mVL2!T0n9D>aYS)>htLcti9?lB5hg&;!V6!ifsia1As#j9oRJ>FVcD>Nu>g%q3w(}xmB z0i3bKRxzQVodqOxt7{-=NNg`z2>n1vt7HPH7$liN-lMkYT}^4l1Sn`iB({m&MnGM+ zS_?4)Met$8Do(%n7>;RZN#E0BCK9R`QDSWS$(H79Vi7&SkSC@|pH&UL?rIGXNxGC3 zLLn<=6H9Z@bdD*7;4wa#kkIGS%<@5>N#R!mKpLOw=ONv zQSeboKBxfRfl6YwzCe+z-2y&h3Z;=LVih$88vt+cE>Jg~h@eIYG2o2r7q63J`=JC< zgF%c#)zF53n351YkwBm&Xdq}}oIw9@69@=CkFS^~s)RNTGFAqn(0g1pCetGj`oXuV z9l}ztQYATl@<8piqs-iTAkr)qsA7%Hljg+dGQ@nh*gS^bxlb9VoBN2kq&#xK7Eh(t

      @GUfzGHJ;S6h-ko7$XyS=C*;*L$l+AMBk~mflIu z-S1r#Mn4WnbEac~ot`NtpJDzt>hVSMukZNWWJ|=Iy(U3L93~W)6aGZ&1$I^&>h)9f@&8656tS-<(^Q)`p z2+{YeRj+~e?}cTUOExci@aTYf#cWK>qcgX%{v`>t`!FKaq>EaM4UtM~EiuPu5cVC)h5$Gmn z0tBZ^4U+u2F>(xGQ3%A6kcioHi9s`&@|e*t1BgNqFGAg)3IVdD60M zyZ*{>6nn5du3O5ACcoN_<9cak=qv29Ux-!@rDx;aVXRHhX~pbreVf~pda7IVJNDY$ zuQ9e~kKH1vs>dB&F-O6~7}uJFY&y%_CPf8H|)j&2)N1+bk#x%dj$xMq4Svl$?CZB5e+VbomsgD!^xv#chCWCCs7;+kHl{D*ylqN`bpXKXK9yuEg4+mBAkdV zJ>4OoQ6G5i)XxRqKZovLV_m-9^4ziYd4XImuF2Yt{Ucg+P{fsms0U>sI}`O-dyAP8mkxu?uvfi{P9RFOmXs2h_-EUYK(~`!YK%|SuT{2fP3-4~& zh{*$L*-z42LC~oHQ4}PDe;$Cr2TC<*tcrrQY?Nc}$c#pnfFcEygN7@Q?QrF>EnIoT zy~CGj@9k4BCd3eup6UuhY*8_+Z=PXm>jF3k@vxWbXvl>ihEjFs+qD1kKl@o^O1>0F#LD7)S(GL7v zdQSy34`&}c?Ne3;hh)|pNSGqT4h%(!CbIz(GHXsD6&+JsWe+M!6rc4SfUMnWr%5hN zY9|g814CQlJow3iA|_4CW`~mIiJTaA))G6DEqmd+pzzLt;IgAegZ7hF$fk2h6C+4+ zIIPCsO1c3cu|?=WDNmRtbPs9?N;bI&b)_Gc5eiFYWwZm=bb^y%LvWl0uO26vQ|iZ4 zc&Z-%R}q?yZLgTHB9a|uv1e?~NcQH(W1&JK5ORct0W>t(F_*M-fU+$63wP05BA~`3 zZ*{tfmHwa~M+vTS_*Z6-Xk0ETBKVLOa>?FqNnvh^roifCW@W}FDH0=FQ<$aZ*{@kS zG_Q-?NY~HqF_XqH0zRbgi5OH8t5YA3u~9XG2E~Yl5HVUqSzrbgF&Mm6TH_fEBOm+3 z8Me0z4iEpF{rz{T%78Hq17}jqwg+PhTCXgc32i&2uJ;)Z*4a68g&+9rRo>V<;?}!? z$^Du(I-ELG9BNz&CoutI3aYZi77jgSn5-TTC6IzmAw;2}K=DmLy@$-s0)m4X6Nfyfn!KQd6#!C`fYL^ijw+Fu!qq{Olh0rgwOFwPg&-X>&sv)6 zVmHC&P%HJG(~h`eQYwPi(1R1uYrU{yQfBAW$s_x)mod0uMJCB0*>TG*45!m?)yHFJ z>i(;}qa`g?O};Np8b<#OF_L8!NG!AHP4|usw#|wcjIi39|qrJ%sY7PX2QK%*@h4TCsf9z2D!H1h?eGe{wLlOi>I4ws5* zu$r}Kn_wh(PusLqRe>oDa~1>_v2lP!2)<1|3!5m6YXe3sS~wO)88n8OdWu4^G*m8m z?t?0g)C|uAp8e<+n`dq@UF@@H4j5Jjf(7rGE@ogY5kuR0+IEf)4K$Yd(UiNlZ`1li zMr$=szwiW93+h)J;=aeo7?0AJ1n|xjNG;f4Xq!keEcu}0AqCPjkb@8S;IkRhC3&)9 zlE?nDF|Y6`)-5r=sNH9pJZZAI8xzG>&GDX+%y92ZV)S_5f*72uvRAjpm4P$c1>3tL z2BQUo;gG5<`wWmS`w3DSpAUigqG2|xnN4e^vpMs5WIl^57McQ!O@a4{ah?SY_ZFVg zDr>Hy^@SP|cD;4m$27gRJLvX@bd5CB5nGqe2FvNCE(74S^I4 zEt=$zj@ftMl>S{hC%O=@4}6v@dgan7k}#zUe}aziKFB&(kCbSTbwHNa?#|g6=zUlZ zWDq|^w#b%qXVUlKY`HQ0`XeAQXP0#h>_oJ{X##HNggh;Mv;%mYoZ z@k(sk1m0_ox{Mq#Vf*S?YU_z=Fjz_*!@T8S?-09)tck9 z(=b{yJpRNEo9ltY$sL;M5tc|<3iaX;DWMcYP>(YW^Tj=iV#siq(ndAHpcr!Jy}M`> zKKHq2`Sj-=!MCro_iBT$Cm2dpi~I~N#;#gEr&~GQ@z4UPki3bB`A83zF-q0|Lk@9D zppjzsmLS>%A*ax$Hg%*5+I?RVge29nO_7_yWp)riJ<5XJ-3=~YKF_&}BZ3|fnGkeN zUGFoU&pDh1thIfLVV61=Bb3#MGdm?0E>)yQs_s0%hI(+*3?-%$^b6s&Z<;5yyry`oY=SENy zkVsyXyz$jJ2clhT& z_wzjZ{9`aQn4&~HR8sNIcdzlKU;AyYz4SWm-6>n;5N!ey4H^wmQY@~kN{n?-J#sBPIu&6Kdm4mmrcXNh%h-zqk(n-Y#)}c+l(EMX8p{W04&(t7S3PTVrO^A zaHurxZ4M_B7WF-RoKn}*%%nnYtI5ILfp(EiMTFVhpc-(6r6@~`sThrRc;w0k=gw`i zf4|}Oohkc=HBB9v2B@cjN!_w;9A}CVYp%f8k=6%de%hVh6SJpTGGHWGEvCeRtVzZ$ z06TYV=cwqk;?&Z#$fWpf&CZsXSlkNP>{uHt8E@ykK8=&6$O4lbfBCy&ZPtd9nH##I z9o@6<*xUOJj*fA!=(@+FCAx)TIhMLHbaIeozsoV*5;|tw{oV1^-2Nr*aq@&Gu{!DG ztKnZOzw|n3?6a<-fEq=O;-zKh$}V60Z+?~wPh95Sy(9kB+y5i8w-0cVGJb-IlsjXd z{GsOwJ0&mt#An#MyT_k@`9&J3`LTcg1zz}xAI1zUWmOQP$5@l(2BSRvi5IBOjQGlL z{XQ-RLi9ZQBcI^;AN>@Me)35|rHECi1ixr$HFECxi~N^Q{a5_k#hYn>`Afq=!LKGF~6Def~V>uRhIi?IQD8gNYv1 zIk)fav3cee`?v0Lcy}LbQv9kb3f{f`Ixqd%AMvCA_-ELAcf!%+7K{6H3UxS1g;y5! zoVINkN=mHwAZzEL1X9Sk&3#&6?9C*NT?(kj$CPiKfYhff49EbP9UdK1=|F|fqn^Q3 z1CfYGq#8}R{KyuUA01=M3G?||+`j)Fv)MjnVQ@|`77C}J9&)CNb3)t9(*()E`qny( zDo8-ACx$uR12RK&NLg<1=wmxvd}N#3do4HLJLKRXFrRsv)-y+v=eAg*Dhdb&(YP!M zmH(@KNJ~P?pec8MsTMB7yn2e2P2Z%2B!Nz{rmUpOTapt66yYS*>T~*|(gl=q1dO8?D^ zVG}(U9=*!i`7=zUX0Scx%CnF0@{2F>`Tz6_Jo%ZAGZ}gYg~17w<&cQ7KfRCIhz>13 z_Fw!IDlLEV+ke2;&MsGf@L3-J^fN4^rZ9#zR}p>^6^FeUb~0Kgas{C#lvh zFdl4D7)w(haX7ujo zxG|Z721HWyO^6X|UGnDp0Ok9e_YWzMc4?XkAdcx^kn^dNE5YZ270Gj*<2}ia5deXp z9wcS?U<{4-SZ9dZ5~X2nW5~Jln_Rx=vE`gu^A7uW-@!9g-9(9CT`o`7dW@fOYlBV(1^iM z7zZ&Bq>I8`9x0AA>9JmO2%0RjMLO*0Oxaa{Q8YzNtWem~HP-iM4}G?i$Zh0AwwA$vrgk9$?Up-eZC*=8G)u7k-7nJW#!c#6ugXs5WU1nY=x8vE8c4kkw&OeYLCH)(>$Sj+IjI#<5`BMdKW zF!v3Uy?ws?JO7?r*KQH5;dB4^N4R|T63wPE)fqqib6@0@S6|`#KK&`a|HnVeetXFJ zaLBzkuk($szRcoCnJs2)Kf2AQe*A}6lnbUBc>H5e@Y+{iX1?Fz#38Eq7_n}MTBt=S z*Gp_!v$a*Qck>#B^$e>q>ziYCFFwMRXI|jU#pkgb7YTMiBL!XyWU$5hc$dNWJW#N< zHsDYG;7c^~8O6LHsG&KkdF|WZ=J`+mIF}wj%iU|&ka=?UI(6AfP0u|gOT539|4;&{ zB=Ig+H%cKOT|mBKayH5e381WiVmr%qm0(}m0#LTE8X!}i&dC!adUXdG!~ z?@&(v58%kMM3LZwDpJ;j1`oY7=7~CN0Xur6s$`* z&-?p(Xfzb|K3hAxJoC&MHn-r~TXXjJ41VU=ZyRP)Pdgm5WvV18v_64&vT<|0)=V%v z4Nq4ltK?dwq)Ban=p)uyn&>fwfr3&Vj+wu%V>R{?mQKm;z0Ub_>XEY;mwM~!iuJ&i=;VOa(<#RT?w8D4mWyD1&t{fh zmM%MQ0;Mfeo`uO{P7O%Qcx_DS3WE0x+<>YY@Z2Xp&ieKyzNuNa6@Tz=e}}LC`X5q; z0csq-_N`y$pZq7E=i^`eAv`VhY{9|@=HfZ>b4F`x9NxUgum5kq%HB8L#?}>TB4HG` z{pNK(|8qah`sRqS8{%7!1VzN=3Tq%HB@eW*jH0l_dYkT&6rMwn!FECf3HUZLFpZC?jge9PMG(v;2v9U?DHlis! zZQT;R$C?yU6-AN4u)e-V;Vg9ss8c43Dc5e?V6kWzRcrkDH(%jvzxVGMHx)WJ)NR9H zW5B=r<=^DRm%c{1Hss#zyWD!~I>R6NY*No#k2cEw%>#;NK+!scNL0gXfABKWSavU5 z;9Fn$26iEo;y?od+gp)sTcZR91HIWz0Ivc7eRy&DHS_sP%ko!8#r=B?LKDMkZ#?%k$Q;gPFX7_GlZeSd~%AVFhl zix5Bp@OLh=DaB+C234*;6MIlp?W(#*z%H5TO6W@eldGP$YOu~ARXgmV8a@Q-W|kZg2;O&qogxKt#B(wujYTE3wQZZEwRYZQRfslMFN%b` z5LhuZO^Y_3<*ahFjd1JwZH|T$&YnHbN1hxr7&_j0r)GcOFsWNYJEtbHIcN^J@#=eQY_4(f!e!oi>Gc$&8bQs2pea3a zobv2+MO!?D;hhGMf6e5xmvs7ZAYJZydZSNH$jmY=vgx(casiHmVFu)0SI#|=@4JgN z?Hzpm@7f8e8834HTb35OPB5fh9h`H7sLb02EiG$nYgB`RnTbRj({r`Tyq*J*vaE*3o*8 zE0nD>C68WR=iEh06K-<<;Jb*OL#PS4k`1IfrBQ8)aqO5xHz7$81zk1yWIC5LP0C5` z3Oz&&*4b3OJ^D0XRC+IaQ8?O=YKS_i7?u^Gskw9eZ8pwqaOKK5th2oR_JaF&VLET| zv8Av!Z3&^8b_>X*-=JeQY1nia=<`JGLev9FtC6Oy8EvewnAb#!j5pUffB6D$fBQ{h zQ0lf>nzA4I=%D2kPdV?GwX|aL_Fq|99o~=qc1YEKPF8+f4Xrx)@6yy(>DroKJtYOk z8rvuP_E8UAdM?=l$f%mM=ahLA^Y3UE2i?PN)_JF&K?#?k^AuX48hUbW~DOXpTS# zLhTz|F2>RXPYjXSqG7BhMQMpXQrZDch*%XyrlQ0UW(^LLs`lF|kp?`T2J1Aj!w{KG zXG~^u+%V1Qq8w5VHmMm9f_-4o6^#TMtQ24?)C^Duiduz9|J*Kuq}ZA zCNLUXu0FQGrOSr92jAgvb`9qiV8FVH*0(rUA*M_dAt=tKRJ^jXSPP@!03(L^Y)(-Y z3281TLMw zgcEqvw;Zv?bbi3TpA*!vRgBTrQ%X#`FZDv(s%=jK3zyRwJG0&jftGK-@-mZl!sOnB zdvcd+@^;EWmwEGlYEZuGq#>j_d;NyFw^k z9fXtydHj}*q_C}S+mO^F+PA$A;p(oFP4S+_9%~z^tU`WobxRS+iz?6qYmC|RPIfTG zmAV09`bX5q;A*ZC9|e&D(SV4@N<>48Hfi6ZHCtlE5dyeiFg{QY9ea0fGo4OwJ7avC zGVzY4)3im(XvF0H5&K66Y!1gT4^+l zRkxlXhDD5&rogw6fh!5V#W)8|N(J@O;$2HDLdsBV1Fk5Dg@Mt4&CLsp25S%_zHOl> z@eVMl^kic2f-yrhI=Ya&Sv_aGF-}rh1cD_rf=Ed)foNKSdL&j9THu1>noFrdqohP16m zR3)^LW*XVQf1AVoyUeEhwCx0I3l>FW(F!3tkOD$W6h|sR3egD8I+}WhA53`Uk!=Le zo3GFD3U%wzX2N*GQ4}Oke#jLHBr#!Ox&1^k_Ln|OL9oUV)pGmB9fFOl73=s(;KrM` zFtG%2h$&NPxd$H5DXaSjfa~$Ez7I3#5VH#nN+mXyp-8LW?R81{u$MjcSk17KtdpMB zx+TEp&*+j{_Qh&e*l@R|om4=Qb}!l7Ke5<#j?8>1V+yu5&k%AE?!{t`DGOXVOqIcW zL+d@ID;Nxic$+GcRl|z&XU{Sy3PRJexw*x7ya9J3Rt-^8*pyf(wZKO528$BOXzuR)Z5uWgIa^TuSnXT&k2t$Cz#15o7Bd>7 z&Jd_6hN)I;DlHgDyFdg~4bcx0(btx+IAZ-w#T)l-5!xvt9%F^^+JLeUrn5P-X`Ob3 zh>DMGPOYV{Bl|&?)k6xTDX_PyDn^4LvvAPI-*xe&QS*+N5zx-*(`luG5t}M4Nu(Mo zS03Nw^3{_4>8sp5c#Wzsl;wc=B5j=JW58A;qW3tHFwK<(ic+nuv$4C)<*QdYf9Wb> zciGw5VKg4~=6z8Vy-r)#HH+DV#pE8op0Jqgar^q~+`jn^hll(4`-hay5)m375nJNb z(1zq7b0Xk9!>VAu*vH3)$3OBo^TmQi6WPDtV#IK7b|0w*SSgpL%nI0azbp%pD=PDOH=Ckt)n4GZxdD z(v>ViiyauudWjA!b!Zuk95R4nG=RKMl|;cW7Tnvr#s0lJZ0+o_ckdpv*__Q-;bPhW zAy{Z7?S2p>rMfR9P;11;$ap-)#UYz(WAx6HHdqP_zL{Z5OHmmni#dZ~l^mz75R-m{ zQNaX*iv_-!6R_MqIO5Wyy9}z5u$Z!#OcBo)Yyu(^)aK;aO3WMW=AzK^hVsPPDkzr#^E?Aoi&6evh))r$LLOmtS z?sN9y(>!|TI`3V3o%e3M!=1Z#n9im+jkJMOkU~-%UI=OD#%5ll($Wq*ckaB!)6ZVP zha-IS9NnKGv7k^W$^t8b>nro z1`?+*x6|~{(~kH)pF5VF)SLImvyHmNGJhlI?LXMO(~eW?o1UnY{()>%mNiAY*So)0 z;deDgv|{J@f#s#9Tl*#hX>dfIBz$XpR=RszgoTXMX;l@ugq-5^sI$Rc4bZ z+ZT8Fr$75Mv_wiA23o+{&IUUdcH!C#nt=BW!3wRkOp67>wJ~BX zlj)q+Dp-SWJ@s_Pbg^Jy4dhHgGcp{-DXb0n#E*T3x4!cRciy}=eI*1lyh*uV#$ih%%;3asFY zGYrQU8LVGn`}}<_UHLeNci!RkS6||d?|z%Rx8Gyo>l9%?+Mc6;RAt;7f<`(flW`Yf6lZ~_tnE~bt4O6Mr7BZ^`L zd?#qGh?Nfz-md@kI1pv{J0@QW(C-1YLL{XFlVf!~GoA{^!IUL9b$WPr?vvExw5hZD zTIa<-?YqYtxN?ujKDJ`kckNwSctoU+!%c;&@-KgyU-`v-Y=j^G!cS7{u3@W!ih@7;Y2Bmr$6~D zufOmdUw`MzY;UYVv^1vW$}^AieV_j{=PzC2=-v^({BQmbY?;gbsZvLe*%&Z6m@w3W zMLoxi3_DjY^SPh-3I5?v{3CwpfB9vuy?dQuXeq=XlB-um$<8cCJrC54<<{O2ZEGlv zWp?i_x8Hu9qk{vE_7Blwm&cy^G{xF3seWHTb;07`27mU=uW;wa8@y{h@4Wshw{G5K zI+-vWuQ3>mc>1Z2GQE4mt#|HF&jK-+B(I5LiWK?K?c(}D$3qIF>3_i|@1bJ)$=p>z zT2^1r121pU8hws?G%e#bxcKOp@#c&>_pWp2?t3XPKZ4}#U4u_ri@{JzU@%(a$!9;# zm8YKP!qsOPZd||?8+a;WbQoJ8woQA&=cBMi+NQ(`Vmo$Y2ug2m2HPip3g7TPryy2j8S(D7S9jWc#e;+2_ymr~lywwzAZ% za8Nf4M-?%8N?Z?L{T@+$LE_v`d9GWR_hPhZ0y)*b9A3~!w~3vIS!P5@sxj~&N-cR= zSL7oB=L+*$b+M=g+F=KQUC>Z>*P@Urak|cK6j4Am$>;yY7nn~MTzv8>jrR=8Aus*mpYmJ(`d8U#D#AfcY&bvM8W#t&V0h5Cn&6yE5 zZcKP&XBVvlv)O|A^bj%dt*`z&?jA=c6C}D7zQ0@W;RRGB@7bqn<`YZK`tR6jKywT$p9n+xs04DUi|^ zWrnn^K}_z$elPmam(c52X{rQetfBT3);0}KJhj8+t0ir?&b4dbW>8cROROo;kXCdWlid5;ikTHoShl~}D9VrX>>?J-@2{LaK@=?dv#UYFJ0owbQL2|3vz2TH9ZJ@lUU??I64SzAx( zmTXLWwzdMKvf>)+ojZw1FZ1!!Ipx?sQ|~`nK3t~M>8Sw^zLHAnXEauFBokw;-EOp&ds^d?-^hbQ< zH~#?cc?Q1Z;GO%l_iAiWayU8S$xlARQ_ubnET%PfI6y1G4jp@kM~q{|x4!ZU)9XjP zy#FGPT)N29KkzJb8rH9D@zek97b!w287WSgkCi3{w#|V1@4km^0^$R08!_UNJYmyr zp+j*@7cjdY7!;2ATE*tzEPID<;_u$$yb*SHb{Gu<_YU6W%U}9MVoWjFRZ(!^(j^Y| zZZSVPVlkc3EaueBoWZza_uMWoeE+Ap{@S~|{M9$uzr6r&an2$R%3+1I8A$(v5_$mk z7k=Rve&IumkiUIL8@T!Ad%XGbJ7{ePKJ5YTgW{u-{EXeEY1!GNfv5rN0$aP5r=Htp z>ulilH@<;L#2G+SzIj;|*?bI$QMPt=c;-_-%xC}M7dUhNNo=)E&;gPw$y9~l94HOO zq#`FD{G(V>C`|ujlDAxp!xSUR(HYjyY%^LPB;bmkdOoLVTUv!+1mgsow>B{d#wpHO zKJt;Lxp)7N*}P5LLr0}73oL?-(lf3l#7NHJPX9VdkqJfw>1vSXaPUOFa$b5T2FS9u zFY1?%yZ8$8V>P` zKuN(^OWu9)yZqiS|0eTm2Mqmy*c$5jf;ZoIi^o6mB4Oh{x#v&96fB99UgLScbhX?TWE}2IDdh)GiO-aTBoW~Sm2pzov-}H@AKt< z^INRd14>_}t&>T_AyvIe^B|&3>IOGR@u)#t=1f!Ua!5t5MLpIj>*JE~z)=}6!E@{8 z9@E1kCWl9~Z7SMsoG@Bn+t76%3D1?$qz8pHK5>u0z4$j2UM zyg9-+)9-h7S}gO!38b1fx4ZTBEna{59sEpb>IFUoeAJ|Ss7EDNGuMtaMSN_jM#7~> z*Lduyb@uLmhx>Q;5ESogoCDEF;anc-}Tg!?|OE9IE8hWq2$!tSbmyGurQm6bp0IsM0 zDaT$|t#ZHG?%s6FAlf_CG70bR({%S|dO)^05I@=oMM^y`jl;B>3e|XU#_{5dU+2-w zk8pAKBE}0hUU`fE=YRbr;_U^)rbHV7S7HMk+&|#mTQ?buD=uHUz^EE9EC-Zg8K|YK zm3P1M2EXx3|1bAnzr|=_akX;i)-CSr-Qm)Oi)gFdzIGdtNM(|~SxLcf{K~KK$G`gj z;qFJO+Tj<_rc7)C3RZ|QrL(FC^BAc^izy_Lob8fkQ8PO{A~X##2I{)TYh-dXV>YRo zO%^PsQ<{377A)&1s*3G%+x*l|{WOE(JYWCHb>8~(347OP#JWle2&LdEiyc%{YeSy> z**wes^-Z3cA2Dr@SiE-|zlcCVF&tuC#D^voiI5p@efJwY z``l-F_2oCYK5uAd%G4|4%HeF8_XS_62&GGgs!N2U3o+_`r+1jpGp3GUt)}C4ca%Un zUF4WT*k$^xkjPcjH*H9mE@gWr*Y%XHIIoTa^XhBD1K79H|EsrhT)*t!f1kafRGA5QC?XRP&*-1&iQ`v&gUi z@4v?S=I_%sEt6aOxVc~!772zJl(zAd*5HEU-Iw0tclVFD@y$0uplLn6@r1@R*+1l9 z?;iKB-(@Wh(1php1%syG-LJpJ|NPDWiLG}Ru_1=Lhx^>M4bBe1Em#{|U^c(S{ezlCbBN->IE+;I zM(|CfZWgpL1^W*M1J0hk$PazyhiU5(FTeN>dp8U>-kA^=hSC^}OB%EhgVrrgGY9$q z$$PUWOOouo?|0limb>Osdv#Us)zdwL?g3`QV2lI^h!_w8jD!f&g9wSD%xE&19`x7f zg^(F3nPf7EA|O!^VC0aXVFtipu*}l4cX#zt)m>{=u6K{M@45!ceVJ|HilTJY-r2nr(J>u?|#hT{wGQNMnh37uPwfSwTZ4X%y1No5t#G@UI8T=h>L>~;@3IqnPM^`WOm16u6ES_~Q(<#D zu9xUZx1Sk^R5u@@K0`2qFBJ!F%Cw%dkq_7?3aYw7OU5iz92`!`=L_n+ioVb2*9KpE zf|W!*7sLw{HF!tSXlAb+@RzUuDcYo_b%_}fd?2&J$d_?K#$ZDLtLZsIPe5)qY)H<| zS8lUw?suJH2hQM{GCmh3lHUmqCsCi)1W*!9ledn6QCKx#vR`pOKwwCIcEDg`gsmU2 zw1-rSCC)DCm%?&k2?)#JF?r52&pyjXKl%z+E??t~@89L!cOG!_ojE&qYg}b0B(@hJ zQ&I7$2?!0E1}6<#7bx_p2zWalOG7G3fosXwQ9&tsrGDi(0c|x%K+!ZF=b)Fv_L(7r zq2@2Y{+);oc_Anhn|6hO7Kawine&%;{-syAc;#ul%77Ix{iBv~d(>!gHmx+3- z2fX<5Pjh%MWj=qCuuv?g6QX#1K>0vvpv(()_xJeh=YE=3zxn@?_cYEyZ7t~3n#IRt z$Z?v_2h8V@KM&n}BVI{5wmfpJ+NN+ZOmDO53ZFWO8p&|hp|oD9{1cm{#m9dA*livB zddcM@CVVU_-X7z4i2l&|g-8DCm_yqdSm{<}<-H>kmAKmQKDAm=t&nv~OH(UuuM)xM zo@G`u@iXpKdo zY-|+_M_}Cqut_7a6_W&fLoTqjvB{Iqy~tB9d>mD7(gdAq;UC=&_{TMj&TuYZdK>iY z6X0r|eC}o5efK_&C4S~;fTfRw<7EIRH4papc+Pmvoa-~0z~sPDTZ=QH<14P4lpxY& z=hyqsuio(J9lPDYd{;Yu0A}jcsvEf1;mK3vV13oId?rTEp3Sv})~GVeKyyyC5>o5>G+ae&78(5S&ZJ z0I`W*qdW(8%I@-z!)8H0E2D^b16WOHG(l&G&Z(OPM~el0-9zg>rZbB1^OeMqnstXj zR(p;Ltp^=TLr

      d+&E*>V(t+ycJW4ISLVpkztGf2GB{Y1&Pp2r`%>8d9K;cdKect zJgT`fpK`FbVC#I3;bzWY+-KO&kjhYIu{`-`-?P6{(Nqn~nXr3*!TmcECI^;W4=^gn z*AVh>?81eX?$>T&67RkDqd+~jhBWRfx?2d>bp~z4i@{@Qd<+8+McGqaeqw`*mxkQk zc`J%7gb;C(K-`ssqbPDVH_q_fi$94Oo?})kRHn&JR=UWeGt@t-A*3XV3ix2idgrOC zIZs}DnRnj4&KuwT9vPn6T54O7>mJq#^|Il?-UHsd^(H^{sh4=?oj;{=js=#+J4%(I zRH724_9u{%ERQgK-f=Fd001BWNkl2~alIg0atI_mPM2*zQzDaA|N+n7(rdk_{qUbjB_ZyF;A&otTI!W@*dsvA+B)Su+ z!5tCLEP9H;2)56bym?~}!BOTp1dkTF=2@fRh^x8@(!Gx|exr>ZbD47( z4q_%*7i7+W6%09Et$8~FttdvICC9fsPI<@x#s?~_Y^-psXVXKRtF_Uc`>_={4qqI{ z+LBl7<6kPJ)59zsKUR(%BXoFg+t%7!$b8ON8}cl}c*v9nBZ$s$&Xar1rY_kS7*r3m z6^sLMYeFbOEU)w-)vb3s4lS)~{Tb@cCanJH+I8xHsAu&Is zZ7vyN-&+xI9$#CuKwm4eypQpQgJ#ZTx!`b8vnw^F&d>pj(l`|2HMuFko7m38NA^S4 zoz1(X(6&0CmaC#o6q;@~{`Y&f|7v5d*U z2w_gOn2=|&H;)TZmox-Nmgj7oxxkap{{$2p)J`K9Vs`z9H=^r_k&_NA`S^5>NSS_}+SG^_db*$=a)vHP<_%>pCk%u|QDgH4B^BASp}&No zGYlo83?>S{Lq{g@5 zw;qUW8zeTqq}>$Sq+hyzN+~j9aL%8g*PT8dOGDb4p;rEC{ics0Wh`Mt2V5f5dum1- zIsKvH!Gk-@=M(TQlC`r8QJ}TZ>kqha^?5El^%5cEQ7TRpnL4hv|9*VQALR(?jJvZF zKxc>s?3kAsPI{WFE7Wc-?YSQdf7g!VTMR$= z1ZlLGV+y51>;0{5M*$>wRB(uG@V25T4bQ*)91}g`o!PtSZA~!}3W36EbOlm*LgTxu z8LR$?C8mc& z{bOlJ+lwz+rI(Ij3#%PH_<(isouWM^_l!0&hQos0-TSfqYDoT`(d4@|j)Bb14Crs5rf!zdv$2BQ@F5AO5y z)hFonGJ*=!&Zb)V)y;G4Hu?b>3G02*n_~% z+k3qA-5V5AqLsqrZMD+MIJcPSy1{=G?xmFK@O9mKlBbOJ0c_{{C_A!#E^Pwr*w4}{ zbaG_fj63hNHSDd_qW2Ex;!B)^szE8i22VNabK&Y`To#~ETzTdyg!#^L^p#-uy~BShxLHA7W--o#IBXjPIk3V|pXU z-VoLi($#XsNMQwwbiQZ^5iVgRrMI4-jJND+4#z#<(5;s7AYNgWq7j%^4R2h3i`its z(f))t-*|^{W$>a1nV>~S!{mIV35G})Q@%xLLRu^7JW$djv?{;~ID|-Ijoeu!>l?)S z&UkzgyG9JM`aDlqZCLGX9Ab133ok+!wFDB58XO)=@O8TP6U-$Fg~lXkf*`3&LDbxc zs$WfH3J^PvdWkf!=m`tfT9(Ttb<=#PXZW!+q_BR&3eG|Z5$kjz?pQ8Sn!Jm>?6uC& zhS*=mdz3OL0p~2*D}r}W6coKN{n2@RFp1CS(uH0JtXJblX-FS|%Eg;VRzZFUG09Mi zq3918Zf&77Wa7z{!L=cK@D!P5I^AbuGovUxNMtg274SNMgLO5g*l9J9-NPyy-@PH( zNC~Za)XG~^(jMbOoa|bd-(`0tdeq8!3N(HZp_fc+GL;it)EGs;Tc14L1oN!5QE917 ztQ$3sdzY(uuRN7?-O-aMwyb|`A%S!rtw(+`{BIr4fbSA(DnSV_ z?V*#wlS~LE;FV=oFM0htZ&21bm&yyw?#~F4Q;hor70}LM8W7uN(tu&*Uu-Yj*!|>dk9|PgwAkBKUQI#qFFZh zrb48_hYC&k$lLX?G^FiK?VL*$BQX^4-eW@(m6V9RZhQbyQAd>EnM{tD98GAd8dYQv zKv@sU6GYP=ZBrB@f)|2v37}UXI+2!tbmPMqVIhFH?txPwd3+*RW$0ynh8x=;f#55& z&(kLD(4r6p)-N!*MO01MGgLJ52;NpOdFQ)!9>=g(5@o5iV3Jx?2;JYdpW7yh+7P>C zMRo=~{i@qUQgUjQn0S~nb3DXfC0|;_dzC!*;M$2qgDtJ+7FJ2Tb(q3w%~Azw9lde9 zhlQuGhRo}@gY`3Z!<5-_j$SxMp=3KBBbcs3ZQC+BYB{K=Jl5JIB+>sO%f(An03$^1 zi>K9Jh_ARLA<+#Z&MP4j-kgtNd^CRXzS0Q6R(Pcn^q>eqfzlm~yNf2Mu}U%b6$`O6 z3T)#kGVm(S#)-oQPiCTSFsVWg6t1zDEJsi@&Y}Bx?BA8-He&}fgRcYPJxW;+`{)~% z$JCIvH=FmKrfH6aYU{)M)ozvN875PhEYR2nZA`37hq#ODC|WQa4$1SJI(eb-fg$eR zAIjDGQIGbaTZt4Cq6ckshA}0>!I;r-1G@;!W`SkX(6|Oi%=|_iC_c!U$yf%5vlc?W z3d=cuGlzsftgv61!2Rfetuz0nYx!K^vp!E7Hh4-Ccyk|}(XHbNhb=kX$g)rKeO9w2x$ zpp%w;L{|Np@ORA6$F6v>o37F^38WHKp#(I^`wpp)Du5G1%Y9J^dQ-CM$rO|jRMZlf z*AZHx$D%_M@s}kEr>i#x)A>GmMmI6~)+54wLE5?~h9O(G!mL zBLF5n2l>gn@z{7g4QW`Fw#6_shTyID6jC@vhmd)U(I_1-2E1=j;t4+KE}59^&hm_2 zua`b$WrW*6@3e|0{|JiBk8i~Jcn?Z)f>S6}U`&qIk*MC*x+@bOoaM5@xmZdYb*;lH zJZr)F_UK{dBzEU}A|zfPtsQMWu+}^MFvGhO2|S5S4O7eygIq|9U)9c=*AM=OyUW$S;c-Zy!4bAOVvZGGn@OINP+ktSPah6rq*p59ye) zdXQs?7h32le(Gs9qzg}5;<-N_uD{PXbz_p1fy2i+=#;=()ATr&9bYAHQetOqGia-( z9`<0@Hii>lTbfTtvrBl~Y7JWK__%lcew(V27WZtsw?=BxG2A`Pv-4(k+z6F(^ptR} zH$rEM*=$az9L_`y+NN%BG!%_tdobo)Z-b%|v=tP&z^ml7J2+ zo$(>G?~VV(U_XFL%Kbrg(V!P1cA7HuF=-X>N`NR6DR@+fK~`MXWQ0{9=s@06jJ8ME zY{KA7PLO@d>;RK%tZ$f3GMdJL3-ro9o98w;bFRmkvzo&_Vdw6G*^$Eg9(AM0b=$iu z-v7=!(yYj`EJb*{FURSzG^9Rwv}$+w_|$vvIzTx7qbJL_U4O$H?Ss;L4+YLArH3&5$bSG*2NJu{Qja700y| z&RAyyh!SF{Omyj_t9w7OekYBpoPK@UvkvWsN{h3$RY$R6r`=#hq~nRwvKLqtH?;R< zJogAC(AJ}`C*P9C+Db#}pzw8U4|l#drWy26PGfxRqa_}ODkI;xh|w8^RcPnqCMtl5 zy}d-m);Z!O33p4RKlxZMuT_Q*Hc{B(T$K>L+K_VmAs{+ck%fR3P2&_sXIN|F8Hbf; zAGxBE?xEPaMvKNb4iOEKRF||Th{g1U!DUCIju3OiaBQfWeS`&d6O+fm7NEd~8H>uW zSlnhX*rXh7a&b6jwAtg%P0Qi#5<*(%wjv?K;t%H4hGPI{P9t9Nm#+T2n8s$dI)2;NtcpW2@g~4&D|R1@JQqELyaHED4%cz(?6pI zs;6mcoQu7sdi{dRH4&$?E*acNOIj?eC;B!%~FvIAhvfUQF2)28;Yr@mgf z)g2;4RijqK-lc@mX{XxFt26MSJEmHX4%RM6+j>SMZW67>_+bQQT95j)(Hj1CqtL3Y zCvUx0h4nE}p|y?=YQj@ngLM4((JNXp6;_+nda|jFqzD1g(UZ$uK-ZeWsVKAS0p-Xt zh1NtBGY1MEp^7|a)hEk2Sy|B36{3VPD_G3tm?C!54c?>C=pY0P!8PbiBSvGJ2pxFa z(1K|}V)dDrh}Gv=K~>dY;>L~(;2c^R6oPGR;y$;MiD_HPGAidGH+WrBl!js)xWD)g zrt}zNnN6YB7jQ1FftapZP8*9L)OF254)A`-aIoa!)vJuhBktdUci)-f?GWoSyww;L zA+LD70P%)$>&e8{ha)?Bw zA#1DHbH1*ApoGa^%{UoT2ecNf^&pO_o>SF}w4qoC0qf$!twa*;8~JuBaqZTn<64}o z#W){5jfZcx7Ak17-K}g|`(Bm4k0q|GGUn1kF~^5b6epzx(x%oLuWp{LVNJ%q3oF|W zq^$w&rg41Ur(WMv&dvJ{_gKBHJ8minNF|)dE8V0sz^V;%)8cjr?i$rWWcAPXGeW{B zfmBXu(7~e{g?JCXEe96zT+!G$xlyP*&akPM1Px9g8yV_qfmVVzVX-*E^bAWsCokgs zvXsom7!ce&yubP<5avsN&IvF)_Lcb`0BTT4gBFSm&whn!X-9be&I*$I_5?1^`k>AIm^t zg^5M}T1)m8mdl!Y>2NksmOUni0q}^5I;Fu|oO3J}%VQ$H|Nk3t-bz8BL6jqe8eD9P3YG`DLKIgbg5a$l1X9N*xn%2Fkde4 z!LxCGgLB(M%5fi+#R@S~AEXQI@@~AzD<3iSPH`Gnr1Ps*0@mYdy8K(PC%oA!^K`T3h2(jdfKdoNfL)4;dU{5d)lq5 zlM0ki$53nSq1WfpDn@lufFyotmmN#^ocfU4!fA{I-)6VgN>NiXt;J}e1Al0d!8q@g zSK8_kv>yMllG^pPB!#>pU1wAwkP%ho1F4Is)-<7^4h;c|I^W~xf9)4};+3Z#wny4>{6v{_B7G8+`WjpXCq#!e^E1lI7llbI)Gl ztN-T9-247}^d!eF9GS_Xa%imxIzXmbx+O>T1T_rkVZ-I;hAfo@Z7DK?Q31Rs%MDvw z+l)t>3l#GBx(1~c@4R!JufO^ge&rwjV-6pDk#GLVJ4|Ow zBq+Q$I2Y-WO67Pb5wCrp`{eO7q)t#lQ@IAG0#=|=v1URAi?1s(CAhEvF;otM6=uu8 z(NV?b_$+tTJA_b2t{I9f%TOv%RfkNc?{RMXEKMkZ41#<>BZ8CTVH0s02KQkh1Qh~a zTqHj$l~m~(G)uH!u$&wbnph6#n+nl6^SZ`l28HF^nX`QR+uvtCw=Aogu`0-Xpg_@h z7ln;O>@FGzxE9Eyy|q@P`%}+Uj@Op^#3gLoh(tjXi5`P!LQ-rpS>yq>%1>INzGe_l zP$6bkB~|C3qgUcpluDCCy!W9iNfZ^!BYlWE3K36jjr%HMY2^ZAPAg{9Tf^O6mlj_= zUNhewZ

        )iu<$}SPEBn+U@)YR&NiK&pdst6+GxuHT5N=XoE%EHp`l(d&D?L|kP zcvg=Y68t?6Mq-7;3Wg8=UW2eQRMYz9@#eb}NF8Y51rW4G2|qt8Skno z1lSyD1v)CI*8_4BQxrA&y*|cDrY0wGEF-L8tQ9adUB{&Z>S0Wt6a^CUc8jvNXX|YF;rN zKeO$I_8Zn3R3Ipe604v&(W2MsQ466GMi|rQ)_phPT+ZUs9BbChke8AdUwW0iG!#~1 zYB963U8W}2Gc_GD=v^eBcwop;ev5#R{iR zE-*3KV$F1mB$-F6lFgfA_T90K<((2kIAYnpj-!tf>{>~NbFr!=MW zIoNs==UJ=i=Eu zOY;M)2$3rEB?l?7NIxO!ydH0eUOZejrpRn5ZEDi#92pK z8p5h(}6$Wm+x4)$7;sR1lkg)fR&XVDhQF%Vlrsfnv`yUh+ZPR;ucgy2D5{cFg^bl8j2x||r50vjml&UJ zGBz=w-MK{HoT3^OY}rwx3}T8R;?itNT!Hbih<<*G%^MpGI$g#a74p>3ny8YM8F@Zn z?V2XtcAx97zm;xJ@uMH_r^wqVBrs$n2(Z#WqM%mDFk_wTk5WYp-T;?i6KF zFu(i?N?InSTFfoH%GPbWShuNQ{l=?VyKXy=ef1|qm4cvFu+qK2t$Q|-E}x~}Il!5d zA!*S=MIoJ3ar($>#C6Gz?IByX?&ka7KghzO#uN!b7%(%_#F~`SoMO2PVKYZbfh$*d z?YW;(tJK(g>mELK%Y%ITJFoKXuRiaiIqQKOk1h_Wk&%9@bKol$U{X*tjW`Z!}5V zun_8ossCkI_lIVE#EJ%I{qT&G*m8Kh!lJdI-qc(@Ge)JFV#GOeYbnbv))}gCgpk^6 z1DK8vEQ}&^18`Nwrqd7K?#X1y#uk=Mg51@yONN< zYFjG=fz||pAMv`Zq~piiGTS3+7&dRIQE&BFTs}Z2IYQW4AsX)>8cWO#4)fNLACjd< zS-0Nsfe+qE7?;Eq1@xGjhHG~;=yng1WQPf(i!^Ergz6koaDgb8rB>@O*2;MBp}o|a zmZBUW7!c?I*Y94-+BFt9&)L}*G3p#k>0#RDII6NhH$BY6x|Bygu!r04*nxAIk3xp( zK*M-pIH~7PZ0kxNO>03MOSCGvW8W^~dYh?r1|2OC*4j8dhl&>HC2!Ga^;o~&@QF{{ z%k8&q<^Ln^&7Lf~uJg{{+QS*{&9R2eDilzds!$k65F)|B1Zh#GDYIpgk|kLoTXM8J z+TAbR{ZDj6zjX9Vhr1uTt&lA_6qGE<6lIDugOVuD;slB_P?!oeXXTuEhjY%J`eC1Y zGm8Kb>{sYiWF>GbZ{B;)*?XO}zV)r|!#BjX!*?T|eDZ$Ip0gygiDQF1dzX3f>NmN$ z{Uer6C#Ky^T)fRQ?|Y12|Md?M!Xd6bK&y@i?p@-UcU|D#bxUmzsq_Kj?yxdwIJF$9 z)E<@EXLRr)?|bGE78gBA8bWkOL9`cjjw%w8kYdhwLdcLn3WuCotGMr;l2fam6Du9s z?4Z;>lgUkt9&xyTh0`Y!Yo|5ud+$@!rRnKMP@2R8_n#o@UB>P6nTa7I9WsY{K~871v0!$S#F9&XVj^vt%0+0cNVF|qpBPnZ-jdPeC^7>Q_!*;w$H`#};R zPirYaqeS6qoE0rAWr&(|y4XCb+)>m?ks{-i{V&Sem!Z0npF>QeBoB^p8Z zhF;Nipfq(+U}MBZPh`r{i5hJ!RlP`26x723d$*@_&QsYTq3dXy{Gtb22P`a|AgGqT z?K?bn@jVy>)AK}C3i#<5e1{62#kwFSkDE9`>`2{&+77sJ?K!OZ5Jr1SYlx}nsVb6* z>U~f};=DoPeI$~(vkPU#^x%NnXu6R{mx}3R!ur}7iiL`%X*jtw;P&+^q!3sbtbpHV zAT>HF#05g@SXdZv`_>M_azIrUbg{!wFeoaz&eL@hhJzYwOM>qyK*1y4GcXlR165T) zQYT-Z4P$+{>p5Uh0l7=iR z*|r_E8s-M51e)m~mpTEP#8^UI}%V<1}RITYbcZu14vRNA5bab+Lqnz9g+yTFeqIz zo(7bIH0h91XeSL42N{1#s-N2Mh&B*%Mi5*8C1`DkE;lT+66)GgXjrLhs-nPmj)ShF zFq#+=qO!NTmV~IpV0lO&;X}e0OFM1y>qbp*f|iODvUX%q)C|i7#_gCw3r3MgA5$dw zz+hP7LqiA+Rz+gU!8=3`bJ60Cs#HYZQJ4ZH78eBX6G@Y;aZ@BP%Z_?(WzwjW=hUd+O4Xzo32s7g9YzV-w+w~~t0U33kSYp0VA=(|YVoNf zsR&Y{bi@<}kH;s6H3BMS5e}^wjT>An2`+PAy>s9rgUZm2N8lWl(Ue9*nu#1o^zlif ztjvte02`T=jWYi;FYEjDo{mM&dG7jpn5pE6zBnJJ>^t)5s6i!?OL(m{!FMRDXk!b7 zMHd=dlys8@TNU`$Ln60oQlA5Bg-anj8t6bsAxqKCnqndK(}mfhnUHy)GQ(XZCk96d zMnWs7E6w`)fYsHO;lL9@penLTlalOlHmD1;K{x`1tRBh0g8bN1j3zxXxjVa(+{q&E~%m4E?4Iq|8RVjL8}4v5_-Unp@kt zsl#f87LS&mKGS!;%feEZHs6sGXj?+c;59Mgx+z+%;C*%_+&>s0(m^sr527?7d9>1` z5U>&{B!5>}B?t04;sWuhsS=k8oDcYz(7Hg;(M%^0T1uU=C%I&tEJiT4 zL@A$fe2Mtj;DbXaLy8HN1Z#ytml%ntK4=`p)R@I{b-tX=d13_b5+sFI!suY1$>;#3 zO>c!LRm|YNL0D`)Vhd^Q^X`fDtd=Yn6!@4l!T_6j}g{oP1j8*jG&5yHmT1T zX95zD5Oa3vBu|&2b7?EOXHs-N(`V2KHtS=?*^Kn8p^?uS;t{getWsH$&4-pKf(rp3 zC-|61Sc;-zak$86?*P{Yl1`-P=-Lh+JwAD&f?zc*&^b@Hf5@Ugwntl()?!s;k{nKhE-a>Z$b?7~L0ipC)v51)&a=aO zWLRcCHhL^uJ7RP80d+>rk=Iu-dhO20zf(z1uIfqZ!ja3a3k}s`i5eK5`OwevYrpjy z=-OtCR4b-!%l*#r)Cb-rL`8l?3-^3bWJWdov&8siH!jFIaEbn~(M|ttZ zYg~3)jPH1q?#loL%4kIEzn_5=@}dkeFc=PVwxu+0dOM=I+JB4x6aA#|eapN=Bug~5|+4lD8=yM#5G_TyeLU6F#)NGBf zayYup;o%lanR)51m9Vt1z`1j$uwrOqes{5_n`aa{XPH_G2${>Pr65T}h<%2mNG1|u zIz~26eWn?EIX0caI(%+4#WW{JtC>B77ED>>?s8K2;24b$NhG>9pbJeD15%*0AxdHz zHI*5#AT?*Eiu-oP3=VdQDNvB8U8Ib{NC#|HGx_*uIQ`spK6toC*X?qusaTBroZEht z)6;zl_DMD}P9CQe)HUk#3G8VDSV90qqh?ul-}0H2?ngy->KU5HGDTG1c*@T^%0GXa zcIRu4l#WPDiFDM^lFU<8qAJ+%D7M?SXaWd66^c&M{m$!_ujTSi9#@%Hb(=y$DL7 zQ;Tn=oI3pgCst1J{15(?jT<+ajuVxw8BO>3;SavW+u!#=-uBK*T)n(QS1H=IMN8e^ zZ1c_U?`0s3Db9I!rk_GM8vp9Cp#;O>B0eaJdYPyf`18+wgBPv_Jb*xvAuPNCYZT7C z2=Wa|D>Q9MyrD=q5QkElGK5(XmuVD$1-^Uv6+ZC(chc!awhks3>q*iPqQMqLM*dWR z)f!_GK?NL%&LzsC!dQ*b6-ti0zjGF%dMU7MOA$iovx*!{vp7p4`AAd?eC_+U_}-6h zFm=5}(D7#QY^8ktGiVV6lZAV40N>9dEGk2LgqQ<=RvLh%`ZDkR2M==Qo=Z4yf$V~s z0;J?n%41Bx=!6l$lq!o$gwQu16kbVIbyuKm?xxSQHU;VL8@;)akPYL+Yrp(3;qKn!_#!Ysu6aQ2}iOVm*4HW~e=<_ok$m?(pc%Jys60HFp9e3I-wR zNKqDa-+GaYA@R1sBF)sHw-w>}?{YGFsw%@JqUMsFIIS3;T;{+IVA@cqK*Z0>qo1TX z%`Zmg9`$qOv+jKFJH~8gzJK1AL_MV9&Vj>7^oq3AZY{PIUW!Y}{!ue0k%B<~q- zZL@!SgJwKItmee}I%ghvn26^$|GR&McY)7*>NC9e{m<}^KK5afI1(K%J@*{n`oiCF z@zSF#ub)IJ!|8j@;$z20KK2nN8;5-HFTQ{d`PxK$uYv_6A;!qc%8=C+M^#3wjnu;d zM2Kz97Um>l(Zm#K`)sTicI@*;;qtAP z!@v4AzxkU}v}i~bA{wnBNlQ^h3M&lif}&7)GqxUyLeYco-baG(FseprA!4##XYv`w z5TSR~K_S$l7=}a{!CJ##e&MTp^9MKZy{LIiy}{b7t|XDeYc@BVWj*~F1qt-}6Cjq5 zW)>iht!d(~zx)c1J#m}&Kcf-j2n4$1Nj|}}WuOwng^HqDU}b5ENMiTkfc?D##CI57 zP>7(S$4FNC&v^7KutXAF&UIbDiZDblVmWCQldbFQr$Av8%PS{2_uxs^R#phD=eg&e zXM1~_=sFUbX*(vyhzSbDEh|NXeD&KrdTodGy^e}3m*^Eh!o)=CKs6n8zpheyKn1-Z zV?L61lzr1(r`Z{eEN|^0fBh_6yTQm2Bc$}A8}lYpVvh66v95l8 z;dFGFW|->iA=S^b$K$$B$DS+w4Ga1TK;gu5`urKjZh|s!=lT}^&;R~!ak~>@>xdG0 z=+O)O_W$xfuy}HXMB?nZbCjmwskgqB5FI`_KL1}o&)MZ|yXP$| zoW4l0e2&fvNXE2FEP^4K%sXBa^ZpJVO8b#7hR zrf4-b84MPbV6~vr8;8<2C69D=XZJp)xX7vK(r`jv(HX+7z-<_i(Gv4 z5uSSb9lYm#&+x#*4^h>I=sMbFO4qp_7BE0Tq?gZ&fiTO!l_I9heOo9CR;!wO*VkBG zUE%Xz{8GNtLZ9$t)u@~{9({(n0>xZCJObfpV*--0wL>E0%u*Di4*u#3U!!&YSO%r3 zicHz6ih`x3WgdUalU%s)2p2D2;_)Zm%JPX*3xVv1m2XO;|m##6uS^a^L+=@cY02XMFyP-{S4>{(0)9Rgz?jVo_PRR|TOG z#me58@<%Um?_tM)+03`hd7a0U-sWrJD0l3=kU2WH`7~w>Qvri6anH>IuK&>|DW_R$ zR?Rq=X(rVzbIerr0ddX^o!#f=P1C!-((!jB$G-RYCmfZg^WOjLM>!HhnFaEqDzK%+ z76z*|u?y^P9wJ?VYAdv>xN`X#pZT*-(@dr~@0c_b3TtFmDfAWX_i9uQS=XnO>WFD;+g|U#Np&n|Q=@=~rCD}CZ z+`SKT?)>AF!*#r>2;`=tNf8@CsQ@P66$Cq^UcQG%-tshO&!5j??UKp>axa zWU{mn`p=N3YjWd1BKZFM?2CC&If@xG5CcFH1itsfO_UzuJ4K}iR8r7%9a5GopIqbg z+536;ktg|`|L{lrum9WsfhvYP_0D%?92kfp&Slqr+R=tU=R_;m!x64^Xl)H7*}tO`TDnC3Z_;^&2MyKEgff7Oc>yFje)G)l zFRzExe?d}rKPLV4&P4KjPE~^Fp^k>{{`p_Ck}T23BPx8ac0VWAa}-2p0>eMcSB{;> zO7_{~{V{{OM9Ewkel`(x{P}_qI!E#z*EA3#ql3fDp=~`~7a-}LL#wF=c}lHXs?mjE zZG9bMEfY84L%;GNF23_&Hrjm-B(U91iG^i!IOdQ4;~(;S|JVOZ?G5puqf8~t-B0?x zs)VA*Bb-%T({?S^XjT>%(OR)`>LgS(N|&fqVq=Yo6*`t^3M^z;CJE>gGg#u}y$^D7 z{a*ZR`ijVSypJNY3TDGQkcFSyw&|-o6oTp&SZ3R4mdWNX+I z^8(HzYR3X9F!wOdt)bVxV48)eqacur`+oXF0wF>**qwfH}_2E(E=!>0000W07*naRK@%nBDq}m zF_21)3jw^#@@z*g3$xJ4Jd^G}?_Ju#cb(MN`OLG%M>2q;sz9VS8H*9sd5Xd!g=Oj^ z<#2_SQ}?p7-!O54sfMhdJ&h_Xe%dm#5_v-{N>SNrTM1gts4|MemN-A5^&O4xSUr7) zg{6~Rx^#hh`2>h1p);(UFkvGgM z&S#-}2D%DWSu(6Eg7+A!*t)YtWh+dyprC6ys1;4qF=-}LixovLJ^9VAe~X8oxJbEN zar)j>$LQ#T z#|-741yv2n;BiNfi6$kL%Z(lld*^%K&8-(Vvb8~o7+vH|B`_L|(AKcLvVt-NtE(s2 z*?yH61*J7bQDiZRexoR*Im%;lmXXQ&d4@aatZ)E9z4U}y>$Cn8F-XiA7OJj zvpQ;(^_y*u8%zFtl9i#;aEtuAJh%@4m!S zPd>@bD?jAg)#o93v@Q`eDXQGOL$kHE!2a|k2h#(V+JFjqEY${>mCrgaD1H*2oSn^C z&69v4%rf|Ve#K~Zwc>66`d8U163ls$a^%UB;CS4eU)S{iqiF1Z&s-21AkFNY`3Wh! z*sswze=W$|R+l18*HM%O$`}UqFk{^TR1^kwKp=4Y#!cF`VR3bckg!pB_KV-f>Vl8{ z)<;nbipMWq;)zF}Af)U};o6Qu-pSxp&7b^-KSt}4@wUU-LH3qUArEWJ@f1PC(lkDE zxg`+0?4E#uWCBSCh<&GDMKZNoA*sk>Dv~QO=Q>OqBwq8m?pL6vNL z7bOeqXr+5mmY;sSDFbOtF=M0ivgLTGbF|3vB97d9Zk-SR<9G3y&wT?IkM7m8Fd50z zp#HidsU#sNiI99&UYd7WkDeuD|7;cEtxv4+)Z-V}eEC);-iJKDn@Ef&hg`k-GHuuK zp7%aYRWER7>lWYq<~Ny6r&J3yB2bn^uk@2kd98E9i4cgY7ao)RxjOGT2pws+LoX#h z{EHvtNB`~*2p&XbGJnSXj_|W|?C)$v+NZH9WoAH}frcPDkV2wR2^Bj|FTn@i{T8e= zSer{Qbem;XAR*(*5~ zsr$frl))yH$}{e^tSAOGNra~B*grU+C<;`Y$4BTH73a>LWms3ZwnaywOqQi;h3|an zSsr-s0e=3&|B&&j1Z3urMJIy0J(1S8-a6ec2Jf(aA$wrNQ}D{<04wuyyNYU@N2*Hc7FJS=Xmw%Bx8YnGfeu=2F$U*d}tJ1R>esP zW5E0T0b`0N1w#uL&MolnpL>k;6^jZDMr)EN&^2|X8I%Rlcig`5D%Y;x!~m`9xcuWW zJ|v3Hk;oLT87Vx^ULV8x`pVNvR@qM`60O21Ayp;1Hkd+~jwfv1yv5e7K%6$T(-ud> zDuwi-(DOB*H7aU4UC=(V#^z&Z2{-l_9JH7eNikbps|10PC=pv$OeR8MPZAs?MwEre zyGieG+UseGkhEr68oF~QsNefIoL*vj6qp4lT;odf9VvC>b6IjAji&$IE_hF1s6rfW_>h|ak?yz;^W%jpj6I_cf zEra0#r%tWWO*}grdxTany6n3l%+33bRQ+H7cvA*a$O~x}NR^sVP4c1ol1hm}s{~<0 zGrGx>m)3auk9txKYo_3fkz)d%j1uqVR!EaTbmob1YtuoHMUUr@fN3sOL=0;Pjc5? z7x^xvYK+NwZPzsDo-#F_PH5VecsOEdd6lXvz&nhwSYvt^rWf&@yHe)S*BRy|S#p4= zaw(cbBii6YWHQb|)!K!u^;sB{Q5dZ-)}kaE6N)4%TcDz2XISv^#S`q@GvrJsSUF@;7noLD=FwiZFLxVVHV3Z|0=uM@8AxOwe1rMJi!s)ZrfH*fNL z|MvI!=l|w6xc8xR)WeF8{p!c~+s}O!8xpRELuONKg5X@DX%q+ho~6YBqACuij(R+1 zZ)=0CS6^V|)T8+6K2lcT6@@W4AF6-MI#S zL@634Is1}EaNe_ea)1syoLwC--r8e9Eh3YI@s1M%g|xSjW<>IPI65$fgkg1Yh@b3I zSBt2WsOv=nQ^E`;=!2h8I%koGV|KUqsp}!LhDcpk^D=GLvCkv02Bi`q`J;h@6iF(p zlgE$<{objxVyK}oiME>}$unHCBpR&tEDjeiCNVG_njscL*92^Ufk_-fNo(1Ds)RCkTIuF?+y^Vy3;QbUI6`l7Kw#XAMc7W0aK?zC=F0@qjpwGH(@7NfR zT{D)3mh*o(sBMN2vW|FpO?a?WbjGzqIQlX4OG$7d#!NnF^TE;}K+rai( z#dR0Zu|OL^*@Bn~3Mq*S?s@1Qp55?#arFwaQge821v$6IwXngobtI!0N`_8+0%r`Z zRa_WUVC)>i$e*ZRi~YS~-ej6XP_yjxjgMKI=&r|p%EmtmrWwGJp5&kJzxgIr+LB>W zV|sqHF$!fsm6?m3Od^(f(9DH^vIRT)2XxAF?$SA)eAiQ`Li6=6f0ON(wpm_SX4*^` z4l52ew(+BUQ}xbsaCnd#LBVHn5y>WXVP>Tq61Q*eaN^_|&VeyQCSl6P<|Zqvi#+%2 zS2(q{iD!k?_4~Nz{6ln6^+GTcwl{C0#c|`xj|uIVYgeyucsN39g9tqO$fF1)mw)sU z`2Y#pUapaL;C%A!V$ zVbV<~1{Uu}#LxhV6g83tXuW`I14>|V!J@s!b>N8v6$qj@y|zMX4ZFJ?VuwsaZa~F3 zHmT6cpiM!F*~F_f*o(R)N3*7luP-Q(IZ%;`@vRst}`xD`UwDwpJ1FiK&P zqU^0DX0Sw1(4{d}=ivk~28`qkHhGlFnTAq|PC44jVvJ&?)0ADLtqLdvlQJGoS(3sO zT^K@Yvxtou;yaBgvg@g~k>mm)X>1#qlJEjmQY<^eYAT3Y=p~C+fSP$8~d70~*BX%b( z=O4Vl($XrS^Z0{3ChdfGz4u-C?vTHG_E~OhY#>P}tBSK{&+^tM-^%6ZU*h>6zs%&Y zL5C7;Eup8eh2RL@*L6e}D5W5!o_k8BUMy7uaQo;$R*E6voMUBmNYivUUy{TUlV$799!j-T!xfAe z22y5na+Pgsi(-(;`Pw5kV9kIOG~R=scC-s!77hxLq9}+e6V^>kNa#r9kwi%boitX2 z5F>>cEQaViv>BkR!WhMHxWKe&awg3Ovenx^Z}HqeEZKu1Up zWhz7~l1hk*XeqE#;3Gtxh?+e8q#~i4&`cC|t;8o!Z7o$=z`FyINrc#;7!p*8Ya=EZ zv`ZAKpa_<-H7Kuf3d-7M;-@5{%7QN{CL95SVz4;K@vYaj^&yb81GCMwpxAM-S2Bh+ zI+BLYYHX~qts*!!t;dd( zW+2ckkm^32&A&LMUMkTme(=4^TzKqp%Egl5$^!rNw?E3{V1yQ7VPVM1@-oHA8s`E- zRWrJ|PvtFFpS!}r?LDg11yo#>>uDC(R*6nH+#KhQ=Q+5Oc>c?`*?Q@aq)K8EBzYA1 zy+qd%LUtp4qvOpPNE1CVJ?4_m7-FxibTo&e2_|F;g;EsNfNHSFXzG}>J_m{vFs3F5 z6lKY9ah36CO4GK4*kMcE%XQTxRj_lo3)1#N95FY9@RS3Esw~PtI~ilJNNO>vpeTl{ zpFL00Y_fl_%Xm5_c$G_ulxRYON(O6drc;;IqO?KBOz1aO<;H-@frsSgRuNs}D3c({ zGHzOQS>ym_6v+jUOqFUnhd9rv)9VZd3rr_F7^7)ZCcdX6Xj9@`B)SeQ22*NGS>j?= zR39uZaNqfdIXGyDL3$se3LhM{93ZB`_YJGAYZ)#qp|oMzwG@LzPM$i0wnGq$_pxs} z^npwS9fc?wA>vU)r4VgNp+Uq@mBUQ7PXoHC!eFU~tB4LgrL9C210K5fKAP5{v?ir& z$~LeyT^FgBPty7k+8BgDNDzXM0+@1@^Y`CR(`a_KN2I9eI*-vcZL85{8Ep=U(c!K1 z+|)!=f#K;>oWAdV*q^d{XNRWgh(VEJCdlXJT6}F5IcJ-|ERcerR61&a9D_Y(Fo2RH z1=F9{7PDV`>?PE(W{LtdL%Ya#zVs}WD*45a{S)dFH5V>jBuYTdyqkQaK^U5fkN?ic z`TkeF$51VB`R^|CsXzJ@zwl50G1c+{kGM;oY9%b@%OUX zG!K_bqjWBJ)r_;J1W^fP15v}I^(-#0qg2IY+~9&m>)fW1C6ma#uSDN-DOurYsE4 zMxaoW199s#0eSNi-0!7Aa?|K)3J+zO;r^mL&i z*RLM1vbx5F3-{56QD#r{^Yg|C%O_TW6+ZJ9Uu0{$!FMnJ{`b0B@K`ue;9#k|Kj zui$6HC3AceHII)oCctZd-)lQnYTnE{a*mL3qE;1O`Sh2W?oavUfB7rKA|eG;gR-Xv z!9uF}#K%9$*Z=Apa2Tj`MXfa7`O0^BpPxe5DHS~7>y4o>x$TT4o8Q4^M|DV2e2)sw4L#KlO81;H<{ynGR>#w-jICswBv1-+`e z!N(F(V0$w#KG;U|0+C&O6p{?Nb*tm-nV$nXQfhJDlafK}iq&6HPPZJCU25aS{- z?qXGeQA_OY2=&5Q7KW=iL(-bg1r&4QvdPwMMqw4GB?acoHdaV(46? ztS$R{4PCp0_Yv<0w9O*7Zym6=2gKMzC6N>(DRz()F({A@9~JGiBm~2B>e$=!G_A0= z*AN*Y1*D`&!Sy4c3FH=4b-@09%f*XNGCjCPN`lcQm-eDEVf818{&$tuR386Aum?T=Y8OH2$p0gpd%WnH;oSd10SU)jW9N4Cl_RGH!0NyMK*?!!2BJOq&Ul z#?v$ogC?fzIQ#I0hj{WWPjKIT58=i`uD(3w2YR2k@U?ONPFC8HYR7SB}tgmgJ!eFmLa#VO-UhARH4`Lj98}cu-x3ML6lta% z?jLFhz{agS@L>HFSWkDLH zEib=xi@`u3b|mjH+Mvu5K6Ho@oChtItSOagJ+9SASYUFX`2MpuP&$jpWQtY4EmC$P zf<6OO9f?SAnv_aJ49`D*6=MUWOnD1RK{7;_GectpA!5vw7=#zT_f?E&j6T+In!AAB z9r|W-_%pqTncL`WjnAlkGpzf_^ijQT_LNxxubq^-i`A0y#7|ijw9a9)rQPW;rDFTe z7Po(RJy&x8&Qh5nWh}Co2pU5|qX?tG=D`Nr>JFhFl8eEk5+olfq(DSbnL(C(v;}xW z!uN?!$R>v6ijml3ae7im6fGb7GXiMJ0^Id>y@ko zV%uMXlo!#A8k7WLEJzAOd=7jm&-$mNab3Roh|805ppcZ`M~Zo4Mwj}AB|ZQBNH8Qf zj$TWk?^nS*^L(SyGP5;~J#R**dY#{R{K%7-ch5iC$`A!?QRG14GYzR`zSs_DzP^ zlk^gKl2Dlbt}S_fx}See7>H{AZy>$$JIr*VGVjyOUNNr^DKgjPz?(tB%eg ze%rFPx&)mkiN+|)$iZRP(KweUu9Svk`vBVW|3c{Bv-BlfF4d&>OwW}157hH$9W>2%@<=E*q=6x_cyrq@(!oh7dd%)$ikw@ zLm)Z=Q-V|fAA4UOCPj6%|K3|w-8~Bf3^0HUo3h9biXft>5R{+$5+g>9Q3+9_pIgMZ z#xK#B=oe6vsAz~QPmF8aP+UNE7i5)P7)Ex6ZT9Kzs=B{FZk^k=x~pMuKw+r&dHR`| zo~pawbI*3qK}}T+cJHXc_APtB+z5o73oasH219Pll!q*H!MXgTT+h5c>^S?3lh>#T zDLJphQy$B~^7K|hUj1aAQd@Ft!lP*vO`mx|9b}e5z_TneFUr0m8oI?X#pg+*ilI17 z`qptRZ;cBt7((h!If$4FFH{?7VaxcT3>@4rkaTU7S0@n>1{_m5qdTrZWx_>8+(oS| z7laHX%{)%PQDZ~nk^#>}hEZ@5T0tV!CmD>`^)|4BRMS(dO>z;blo~=f;LJNv7?T{E z0N~}XvV|cDo&!KgPOrQsfl_xjk`7=9c^k|XNmSOls7N?)VZk(HOjhP;Rb|XkR}lzm z6N4NJ&l?qFs1XJLVMz&sNx~p!KuQ#H>Rjm#4WZVjdMzu8sQ>^V07*naR4-tDSt>5%Ucs21>Ywlq70NKc z7zC5)ZwwB&%<(u{SB{OK)G0D1x5H(i6A049dh@|#22e^jB|Q*i+*|SqmeN3g++@2j zxd|&;02e@Qxr6U2s>Xo!CNG5AhZUF|9qGV0NMXkeNGfRn#GL$`2>M<36GGN$T+H6dUq%w-WM~orI zNsg#IP#B|Y1r(-G{+B6zs~jH}3@(#Fu4P(aLuM;r%rnRU!nGwAAPhLnf*CbY<=80M zUMV-1!92IJD3XXma0cPjfOsWAPWg~t0ib+Da_YQv+GaA|(R%%1>SD1-N<6Dp9 zpJ1YnCZ}R!9LtjWU}!{=Cq~q=+n2w><~)tucK^t#EJ0l0{`0FFt-On4$6Lo^5tTn~ zT6D!BZ4YMJB{b=>c5X3|dG(hSRB(L!j`w_@CAN_gRNH!%x2DW<0Tx+Yy)XXa%l5JU zXp&g#yX-6^oFN{WvB9P355j9xnOZ2)t4S-OnpE>HrL$;X(Wb_X=*M^I2($Tqcn>os z$bGs$Fa=|6xOqS(pRJ$*udSBYMmy5l*!0|*(zx5^kWECum?2*E=w8xHG#=s8(Qm1A z1$XH9k|J$Y2RZ1+O*}Ppv1vl(skTt<8fDsC!|;bGVpP$7G+!*ywfvN){AKqe6ye?b z=PO%4#ho@|nzji(Zqasf8pfcm!jP|yzFS9rxT02k4J9lc{rA-NcK&Eog!L(j711H~Kp!x$L(C)^2wOzw{>}q^OtY7+fqKtIx@@-3;sTMhWWG zx#SaX)tXXpV-w+K(0D1F(AjfaEqv@?iW`-TPW#=bP<4czg2u0z@U$eNr)ddk8lT+{ zUcX6D#nFrYUSuQ9XP~I>CH|Uz*_=o2)p)zBNxi8iOZSSr?u-VZy^2Tu*2mVj=Qx7m z%%Sc>+bV2@$@7!snlpUn*m!8{bX$ti_OMflhJhT5Rn*{*n~PH0USyeGpZiA%op_a% z*!COv@J8s;kEK5|LTK>6C6^L}(3G4po&Q`=b=7!4>`_No&D1YabhRqC$D`}Nd)TdB zAi<#(h{?%-i*2ZgPpmwP>wd%X5qU;2i%hUeoW8eS5s5j&_861o;iC*Y-D`qLOiH6R5 zCKmn~!P*JR-%sNZE9)T5(r9~t;i0TzSV7k>WRaHgRg$}l(fOzAyA+(BKg8ekFdmhv z>0sUX(j~Mq~yHfrE)gc`$T6A-tGuz}u z=}`p`Z3xm@`(szWk$zK4lBK8kF)V zRnrpNFr}oAS&nL1Cv2g9|54ngcY_smh>J}q^CX49O6u-DX~(nyf^aUj#81M7Zihza z;u%^t@viz-$#IChmW4Gpw?pg7x%jsqiKMgQ%3frm0VMrz8=uFA+{fn;)&2gOsCz+d z*Es&``HC37#gC?!Z^TyWi-}&)zigMme3~*t?&@5#tS)#@iPNM|>4S{>U2}!6E)G*7 zoD3=?0*f>pHvIS{(o7!taZV{|om({4*vT8W=DlCx$Ic-XNY!Zh^_4O;hnmY9h^_yk zFZ8|3D`3T9TT`KT4_iSa=zpllx7awxU`}kB?mUpjf$BoR*OT8!Ow7mqQu-+35feQg@jD}AJdVrz~OX;Nf=a$gih-jct*;!aZY%et_!Z%3LI z2G}AM87?8NE~BsbE=E@ydFWUgqfvY<1g2jsGw)wlN=h%3aZ_@{050{ zh~L?l2B7bbk(C%?@z}aFY&r(C4$Oqz?Rmm#`F2^22u&92*%0ln>-$C-t*fP3Of?cT zL^A5ipFb?LuUXR6nHb`IWju8f@|ufu$0D1Y>7|PlnJ-zbHtKhSvGHBIP(tpK^5GMX zzEu=T!~7l2hu@Wm%f7&e^G$7VR?0E^VFy))pl0Rxt#{I#uCF&mYKLsCQBpp*gKio_UU~1m4sRQL5+{N zLzf-P+)?t*Ug(AM&Z`@KUbmU;aM4@Tk}^;+f1$pw4rqBVqZ2juapzp&n4j5Ay?yU@94$8@y<|Uwh z(%@yc|Mbj=m92nKKH9tyts)a4#qln6jK^^?Nx3ql(|X5TTB5xQOwQ zW?MK;xm;vh^UV{dA)kSq8(I06lGA1%AlOxpEa}PwkacmhJ5LiiKV;lOW>;gR^ zh0D`a@)F%~H{Mbmru47$T+{W7t0xcsk(}zTE>GUUNelL5B;p?=yB~t8oVu86eE9Dl zot!^TNd{iBj>1bcK7=dN!i^~llu0MdqRDw`oDvQ{)&AVO`4x8x#STRY3{MDt8y-E+ z&XQ8ap_e(r{6r%|$EM}X5S8I$gfereLE|x%^u4fEt@?%H&m)BEWn_%miKEE7Kci~O zUc6$vebw2r!>R>Q9&~z8&pTCUwaMc5*cs%{$+Ar^ zuC=s&lDkv*K80K9g>=Hr=|oxOkR0yXv(hq-;T2Rm`#(kU&Fs`el(EV<-fUL|8>xy# zKhQ>R#-gNA1pBLT6lCxZGAi8BESOL1Wha^N`aR}s;Pz)$NQ^0=LOr-fiavPXTB7VU zYnjCm{pD3ivlUSdZLy@SeXZCg$8TGnMAz$k{=4>?v=`{ETbUZ;&y^I^CQ zcJ;#;lwnCbr&svcN3$gDrLF$))nkq0`F?)|A1VG5do`whRG5I3o`A_mEki7W!Ig72 z*k`Lo(RTTd;6^AO&8h}wjRk^%ok@@#E!N<%|LeqrZ8FXxUinDk*OW)M9Ob!!chtyf z3(rR-Nl1r?nd4B#yz+%JnEcFonc*|cvfkJ@_Q=15h?$uQNLb_}FyvR8{t) z?0$P)REDhq5)&VvL>O|1UtIWkY)w(1V-d=y@|c*Xvp=5>UsN!xBvMsVtMWg8VdmSw z%l9#MeXKPw&@5K#%uMV}FB^VG+d$@ny;-mM_C1!B(c({^h%+B}5z<*nNS1CkB9H#> z@9(5NXj`*iFQ zLVo+Z=d908b_eZ}QV_h{+?B4%aT?qg6*3E>N8M|uYuQwB%h;2iVVjN6&!TO!{U5=1 z;0!b@WRyKQNK}@08BoyFjPt(O>(Qsbckf<{SQznAFct%`#{2sevHb0#R7Li<0}Y?J z)li754AnDUOxas5cfV#yRQ_*n*{ z?-m*>h-E)~VGkv~zT62^kdX=I)6nJX9ur&6h*4%^VM&a%8_o;!zB*kSKP&LMIYQXu z+S&d3rb0kKOFCovjv+UD3%t(>^SF+Ai%A$&TJ5w+M6vHY=aPBxxFVq><_b917XJN7YS7^QyJnUSe! z9J@w(0ZT9hgFGwHe4 zNv5?h=ewie==kxC-AIpEntI;XuXF}x{`cU@Zi=5Qge-_BcP*UPhVaw0H#auY7TLqi zExkr{+wO|L%|B$ykB>fG=iCE#JB4OM3)>i`ed$M;ANfg zqA7Qugu|n}7(6{a9dztu(uztV@tJUb-E{sMJe;qz{0)y+&r|Z?hoJYtPhpanu7^*a z;Ef9ThlXL}kc^Ft=w$e8lo)<-NY>&1i#P9oOwZk~)A{x+g{RwjzJ>m0`n`VYcn^$K zY?i$&O1q)%yjGR+JnH~N?lrYl>BmN~CFNJUIxW9yU(-K$v5*_VAj^{YQ2upyXlG!L z>)WXa_qeqzU&2YVK>wU*n?UJU)GtvJQkMkE;R`+KjI`*bfwPUC^%wj7f)je9MH;Su z(rojLK0j5$K)rRbATci7U}MyRGa}WgfZFChC=t=vDE8%(J^y^*^(D1bfcWDYyTsi1 z3_c4qYAa0Mv&*WB#rMVqR*YNmCjb)p0D)FAhxL>vvktU0`V~{}3EJ zOy&q}n`v;ba$nP=4iAR<@`ZE#I&PVXg9D4vZx>baVpncuWu<_$>E$3>k_xv;qtG)m z57}DFF5E)dp-mit`*+P+X0nwvvH#9AkOiLhn+=s2@V+a;>92O_rm|QBaE~#1`cvYMl`UhLi>4|@IOAO3%4FY19rkZtY1)k~J{D@J^ zH;=U#`=IT;o*VJ$#n$6_v3(oYp)*x1E`Kf3aK~xG7C+JL=3~|xziw)=7k?x9 zt-8(kS9(8GR6M$5vDC0JFfdq7HZW};H!yphm&fAyiHeePDZ_oBUFvF&==twzg`YRA z@MEZWyYm!c{N51y)Ajr}bk@CZSfdlJZg;cm$fqVJ+gqeuW~Z9^sEEX|mX?)uA&Rqk zsI4~S!YL;`6--Pr;Wm^*9es+s8;hP|6Ls&|1U7T1_x0s5`lj73PXGBR20doL!9 z-CqyxDlg0W=eUIv++^qC;u>p0xW7|ogDxe0JmX$kZpd9UCFQy#zt~ve4eKa5mzRS> z>C16t;AI(CS#9m3=hL+sbb%Lp-}vyyc^_woTSVFkadG#PI!@J)F!~=RZln^+!i~CR zMX%HP=;Px;e9^e&$VpRQjhg4bM}%z;lQy7rT_0axWeZ4dESs5{^7tHYf6SWfc{7K_ z3&SlrXbIlJv&35W< zIAEH5t*of%mLrk~^%k#)b?Y1kY(UU@x#dj3A!~#BFr2D`FF~0Np7me31W!E4U#fv7 z#|OjtBU{Ss=Z&L?nZ?8T?0_@-uSXM49Pa+Nv|u8=JyE-4zK8vhU_kWGkF*dfGe2z! zIY+jr2z-r3R}N@rq9^W;79Wxs9~GKGh80 z?FLwz4GxU1(?SembNXeE7Gnhm+Pvod*WNETf6<-~R6-*(k}chgLAgB~9C_>RJ7{)4 z(gc<6+Oc4!*yMir@O@1!oiKA36Tx|OHj;aOjHC6H;9FG>!~5Jolh%M{0YhwNWJS=^ z(+hHsgMr%s98sL%hKq}b_t{Cvp$Fz7+{?F`uQy;9ji{!`B8HIt2-~hd>E!nWnWOdP z7Qk_Z4#UlC@T@`=eJv*^SkB*jd)pJ3ZCK^?7BcD>67=KB@*ue+#uTBZrWK&(voa1&JKtsk~~47GIl{l zDd{(@cVV9MKQ@6@0~6Fv2)D--4jP&(7l9U}BZbZU(8wr?Bim2F#i_boNJIQ$x8ql> z<9k}+^!EXmXSr&rJkfk3)Uedm=pSde|9Hob4oTyG^xkpHIdDg)#l1fb3QxGw`5n)C zc^{1%w2La0J^DEG_2ohNW)&bU2f{dPMjg6up?Y44K7j12oMy$!pVSe~2b|wkRaJGF zH1P`N55MVDFXQ;!r^nL-S%v#9?afj&GqKSFtTgVUDP~YG5$Ki~R1*4CD8)0BikDgq zWQazaV~(rf`TqK3adNU8&+jxNvZ_gnF*F6QSg0;02EPd-(VMT%HuvBQ^R%)hTN?N^$jkyS?-@^aNnM|6eLWme z3szTz84G1UqK7eXrsuiP3%cr1Jt_N`n3&-bU5*;(d4^0ePgz%2{&XSxSGUws%;DHA zWXY6#t~g@+-!VziJ*&vS50sGFB>_z7+IrZeF)IK5zT;4pm6DBkZewX_Da@@B?9N8d zO+Q8IDY}M+20jh4uC6XgZHeZs6dQ}l3KPj?G8#EIcXyK4io-SbqitR)82K8N?v{<% z>PKY7)jmfKB60bh3QLC5HTLMELav9yN@e$nb1{R6q%MdnHn|M=O$wp1!E(bM5Cy!L zTW^wXz#{E4{lSk^1r_m1&PojJP`mpVBvfdzv6w24lcUE(nz#93HMJ^%>ts_2Sl-i=lwo6uH-P<)jBS(BxzwTq@sip|EhOoysKh=B@(_}z zD`bDCzT9!qNTibXmliG`Y4Gph<8z!6^85GOHaLUb#DO_k_P(VZHD;FYwy5X##OUyD z0k*s}SiCJ z3kwTV3D0_vNnT&LR0w_aqthhByWW{3KI3-spIJ^6WcU{bH zgX*PVLCm?>VFNRd_{|X$92%>Z_mStLbF8QlVRn^dIY*n5%g|DH?>eyLfxd9RJCq~i~GUfCHoUvnT#%X}zt5|ybY1_lx7 z>9pkJws9X8xUn4$u^*S*;Qi}0O*4X#tm=~MOh_kR|* zjztYYZ4H8+v5;n)C3Agsnf!h%mPXKJEz@fWhAnkaR!b_Wm#s)EJ8n7d0U>hajBGQL z`CH|KJeMgxrfFu1EnXha_bkUt#UUFjteyD%m_jd+HSaS-F~4Oe_PEoM?9tu^Kw!`n zK`2bI7!t%s?}2U_Fc>q3nVx+xD8)EzH`WtYe4MODi*S00;qQ!y#igN_yR>5`w3k)A zsWu-QFTRfrY~!sdc>Eu1T?=)kbKdXZ z=WQMy%mkJ;a)!G%Jrdtz)7`D`&-~gr-3tnbU_D)rt4sggx;9UfLWiMQr@sDvZ4lh@ z^70hj&qMG111!1l$LPj~<1W=oT*lEx}rtbS1Mu zvikw4Yri82`U0o}ce8vp;8l=(sHw(oQG+5+sl%gLi80ch9eVtaXCpwyGWlpPM$X{3 zD`V{b^WMDg-zd&cjyFN2fY0NA8l1XEM~_j{9U`LBO^rlfQkMv=7QDMf_Ll9hZfxu; zM3N&J$rDzB4rzUT3a93yM>h16AG8bm|7~(|$xf7^J}?!2ntO=22ixBx zT|7ZwwSpOP(#0E)>!E8het_kygP6Enz;yRfzBB4}#qfwY3-V?rUt{Z`{5M z%zoAyO=oHR-_~@pMIQ6A$88y}Ff^UI7!UuOB%E$$tnw@*9?M9&FdkneY}8 zwAv0bxD4!p0Ja=PWx7k!BseHe2I?CY@aOo$n_ z&QZ`e-ugG~+}Z^TIES*jV)FDL`#KhQQ_0VwrY|l7fNIC@;*s7!9D|q+x>QLJ-C>sL z^{^5n{V&PK51-UI9U*j=_v+*M$a)eh3vDID)Ro_8&s}zSZ02EVH+_4VTpac{rv~7yN#Y{0UQ#y ziT{4hc2dvX>m3|a5~4k7AVbyBkm;sD8&^sdnW}Y+0V4*?m2AQ{6MW-Jp{Wzh^k;yR zJ{Oklavy2`0$V7|FcejGGC1fkne*AcY?ATsA0J`)$N&m(X;o-qVR;8ss@14V!MWAr} zLm*fZvB9u`8oUc-hyh%hN5=5_C|Ez||F+Plm2T>^P8GXbynOl6u*QxADGcr{_bhw0 zo@Z*Q+r(PTeSHb%0qFH$T+Pv>(SsA9QS|lIajTJurd%r#Po0SL=CSRN6G(c&`YM?Tr`73J7^@V}ps=29yxuMm(GVEvua zog&hfCV7G7Q=7@p{d0^NL8 z-T26og9Jb?{{G5!(z!*7b0kTVJ|MQqt)3}1UKf6Q+t%K`BzmP#O&zEy@UU2@~GSpsTKp^ewK8ebEMi$1pZ=4T<`HNAEDmS5OSeYfu2 z+diYUo28ycU7LSBoYJ3&jT~^6+b)JR;Ag#dy+@lKE7Z& zx#|Cb3ansinw73b+X1!~ESgQ!13R>kTxh@|DChTB-YiiTAD65md}~627&(1ErGez+RSYrOwlU zwkWBqkH|f$;m{7#yv&&vk|i5ne{jhv#BX(RvbR1`s21+b>PofpMmEpZ!h#vxCken} z0?%&d4}Vz7Sa(BV=H=DOJbBCV*!cmI^XKQkKB0nVgLF+nH1J>Ix59_suR|w8tfZRJ z?%G3Ntn+l8F5Ypv<%t0nZiYJ&J8WDv4g7ZeU43KE+qgt${ot2X{386(w~3|ZM*}2d zaG*eEX=IefyF%}(Xw?&^Z+Q(WhRcj=kIe^enDs^7iJhj4G*v!_>$&nK&Bn973m}`z zz-@VJV@lQUd96ho0%Q8$`aKH-p=cMV!db=eo2ryBrvywEthl&yMp)EQ~j9jjf} zi<0BDGY10}GdLcLl(&HQ+8pURzCBsAdx6`D^L)N#*2`ft`#(KX>iI7|DAWFkq}Am1@B!RTxxVd@}YTP@=HbUok*clbEP*gi&z5lv0MRW zbZ1mlVks~Ez9SbVJ~b08T0hQL_5>qzqgr6nf)L0O9TO8~V??u=)OR0WuEt?p^+%S( z6KrO^4X4NMyv>Ji?8ZxzdCSlX35r|Kk2X1KpZ{iA+N*b%1|`X#G)i(_Ovz!o7Q8w# zfSZlLG9TJ(_@V~cjTA&t3qFmloCkpy2y=`)3p27UBYkkQxBmWG_v}aHk#n&0^_UcM zsNv_Quh%Clvp1;338{mq?>~PBX3Sir$Datncf?q~aJ7kuy%3E&;5pIS(d>*C6FshT zA^=Y4wLNngmoV1o`Rs6Wl2;A~l>9hQRgvrQ1k`Un(0M@a&4CgNhSqHu%qWYFaL%%# z?VD+Y%+|Y!0B`OPrfxrdk`kt?B|(wlj+Ep<_li~{Oxc@+sfhN{p|V*6K%R2bW?J{PfiBPxW8lES?r~sc<~^INpcb+tK08D#3r>)50Qv}n zNxJ~FsAprmtO|5*aN#_*XK3J(dvG{1g2*&QWJHH2u_`u^vkqoB<`Km3H#{m$)qvDfhgFMZ=ZhU2|(JKRl{8yfo(}K3dc{;y})(;5aj{?Gf55Q7L$+i9uS1X8$4xZj)pto(aJAcN-; zn8PdUpEUX{zcoa2xHcqlIl6vR;yfB3SuIZ&9qiV3eB8) z9}$Idj?u7Q<}hDAm%At+qPnbt6dBKr znaCDpPexTA&0_+Mo%n&Y;hmb7Bh$s_8wk1>$@`s|h|7tFZI5+}rAX;L z_R^krxJ4|!HzEUGA&8*!_OIVNd^tu$blK#wZZm3wVG@liIue4Nd5N{~d_v0m=>pDaZrBDtD6z6cs174S(on3!F3uH>%7Wvq;yw0dP zQq*LmJ$;Dbbf(qkuenov+#tzRcPo0jluXs1`w+wJY!DrXD=Ck~=4M$=RoS3BbGxG- z_Q!u%G&Svq?>P~>m*d;m*cjG6 zrwJuSsw`q2>p_4h$|85MtgNPLw_?7~$d{W;D!@}y!ksy9*-wMHI#FpBPjK_TImn-Y z1nH3^0!)19Y<*PqhONK#vuhEdsY_h|JnDYc*puCNnu+8wY0NRGG`-EmrSn^as9R(> zx61c;yLoQd8QNIs1BUqg#>PfdDq8hXy*)iSAwr?6rYBMYhtrDA%}10BFIPxF7!d{! z{>U{K@SVt?cUDNJYq9+EfY|NH4Tz@!c#Z-KgKu*+94S=AOI_6uo<6~*$yjYU-|j$` zIzHRWZ*m|541alMfYg#jkfD^Y;7e2!7DMnJkdXyHFx?ade!m{{%C@H!3a@vg@yVK?v~68`xqv8*|?1c(|uZ|;+X7}FkLZu;H(5hoX`)pS23BlFdyDhLN&GXU zaC&_MqlZDlrv_Xn`0b;sz^emBGinisK%W!Y?sp;^AM%l?V(FQ!zw{zuF=Rx*;9kb# zQn%TZLXFhb6jdlUX?m0_!#q85Zj$|C9T|CX1@9TRzuHfx?MRD_l*ISnUv2lptMeVK zxZwqIeY!G4-Tma>ZcIw0n!HG>%m7wC+~lcrTz9mK8Lr zk0P^mRUU|uOInV}7>y>24opw2jPgIoE)038p<2f$*=s0kbV(dq-N0ApauxnhV-vt!Qg_?S$-x( z^AOIq>gB;xpmpN^epx|i#bzv4o&}jB0`I&EVmj(s;=c_ztniWI_Wu6m<9sk7%jZ8ZpKQIaM?PV580S$sgU!j3S29Ym%4B^ z5-Z_UaB*?{S_(QzCjO@;2YT}rL>`ylJGW>j7NH=Ega`yw_`!>ShkG@*h&_OUbbXqA zy{Ax_H#XQfZ*yN(Rerjf8(90(qj3)tgViX={v0SUmja&UrQ%`6;JR}MCNYY%YoRQ* z$Icuw;>mTBeSzqcv5pQJieZD>Ex5gF?rDvXsNnT6e*eBK#b zwGqOA=e5ultg68h+6KcH1sRXRN67ln;$?0p3yd~h*g1~!?&BOljKCIDLi(UTF|!q5 z(LiE`W**U~ex~Bn??KP8MhE_b9*<-vXESJez?)AFN45OvsMqM4eU5Zm%2pm;!9?R+ z8Uwcu8Ga1jy2X;eCObK;-YG&Fl~Ykc2;?Ywh`6c}h9w~2DqwbCB;?6vXh!{%N2b%+ z2@dlR!1dT)g^*;C2H=X6Q_UnY+>xF<(!K6EhuBwq^a2#s7~Yn8nSfG{ll9=#__x%V zN~AD{BIU4yfeh!FwFaQ*&^d}T^neIb1z;L~?GzF&TBp`v)A6>P$lhwPip_=W6)-CO ziL=A^68Va+bvR2sLk1u}@er5`tOvtO#-M0pDVK#d|3AxO4|BwTxkV#AO=+%G$Pq&) zOjFfW2X0_s`m!*d7-D7?P@|%Az>m%F+waBdT+C+q-elUBO#B*;nOPzy0KPEdl00z*4a1O$RwbuB^bTm+I+4IG`EfR=&9}8`@pefs$gg_*Pf59kg3? zrmkTBlf?*#Hrot(m{5U?t^^$sRoPNUTRZslVC{S+r=ord7l=0RCms`w8`iS5pakVY z5*NZuB|e(*RML5$h|!Rj2qbPtSW0q2x)fN^y^aa3EcRWQ2$ZF~jQ!zDVMRiWs1Z zbs0_W;x4hCBDK&!jsQ-k%M@Cyav2o7c zh!T|ikihHn`HhEg_c^k>Et_MX7U1?`s#0i}Qsu_g>@lw>6Oq+8PE#V|J&+C|XmcLN zWK()-L|^|T;JH#Wt zMg^9LrGhd}W0I6(0E-KhMQ^|bei*SLPjs-XmkU5S28$m8->=)=iy$2qz(B~RWdSY- zmk3@|ADjUV@?^cm;icRhw$zN9XpfV1ERAKfo4|c)R+{1YU zvK@aOl#GE2Q@Ve%&p$%skeGBtjv8^=2b1CYskq!s>9Po@CEd{!cODuWL>TOzkj zCM-2FJ zQ|iv)%P_q<2PI;uAW0K#jSg~rGBB?Pz3+o^wTdI%ULMj{?fArXM+PP$Omv8jRPpjS zMs|n&2i)al=RY(KI5{&-W+2r9P{)kAT&sBov!xiNPJ6Z5s5<}}_zg~ujV(Z=HrRq1 zLS1s^qJUmyK;NFXwE>%7a z_iP6gS!MZ~jIzhYA+ZoFIjMMt#)*z~tF0e16C0{MNA&Jc(GJLF&IfJ-$mBNU7HLrY zFy2cq+1(eW%jAR5jm{TV`a_Pe_0+(Nv_k;=i6&=?#oi?VkM)k@)&g^1|DmY^Sx;;sJ4|4c#O>G+RO@Dc|7UN$U z^HWT?w63+j-tb7fHLM0;sz_W2&{B-rv?XG2Eyr}VPV23hF*KzvJ#M|y^@j~DNWcy~ z(*=r^73?rFZ1%Z_JPqfTQ%vNB1z?GLu=xXHAl}C49XXndN#>39sx$(WU5uPB>0rXz~;%| z;ff>Op?1dDpyA*%V<^TmY&9*Z%+occa2=j+_)i;u2jt*@hYu**diI6*;xv_mRn(gU6^E@xk^C z8M;PBEmkA52oOHwK>ikyZsdr8j$R2g8c2pbdTk~|t3R^=hW~3=qu>W7-!UkC@vs?U zmf}eC1_4mH5=xJI9ZfqeWqS0;Sg+5>b1Mb9+TD7WMvWB7tj@4a?P^&ep3u)e3GM&o zt&j_6wWCDIlEt!k-qHtV1X36HvIyCB?d-*_TE~n1)Yed9G-&m1ikTIgr5>$~1Mycy zJ|PKCo_{iy!4vO6cH!Iw4-yl*vwqk&V-EP^`_G@VyqV0&!VsV}_TBm-xukGC=~))b zFMhV3kCf|2q5uyWAf!rOLrVjDuam|$gT!zL@Bx9eqJ4CiWhu|>v@FJl`y)O5e6iAI zI${^=*JG6cHgjKGFolSuKr|5<8V1`27a27L)Rhanp&q>WD-DU=kBf)CdDAxQB|FrE!aj28bmwAV(Oa=EtrDO7x!O>Gz(614>)~wA&3#(yv0p|LjoPpM@~{+iBv>M`A#8 z6V=(1vvj>H)H_Wm!DyB;q!+{LqXv9SzuS6!-by1c06~V=fTxTg8c#Q8&XO@65)Jf; zI=sq2tzkD-p8OYVxP!0x*26O_K)E2kgr~@MnVZInONv4Q zuWd~u*L_B22mMWcp%BOKGsRS*P~!8i-Ly-)vdFq`1vg&(TZUz)b=c z$=`iA4svJXnzOl?kpcH7EBwc)#wt9%z56JIu&NVgfsV1MAJX>>`vX30D)DQg|GiyQ z=ziG$eRrt*|3#$yf8JvH|8)>TG3G*bcJRn9HE3vv)@o|rdT3nx24+d=N%#IjxuzTT zlHm*|!Z`HX!;l!%sjX7g8ZEyb8M$)L=nEnjhhv6KoyA|jnd+0o|lxDcf#(0 zC=hF6*N`#Qoceld6oLEK@dQh6)?nqr)&(s`>`|e`MjoGkf1~=rArEpd0#ORUn7$)Q zPJJJel|q%6d6sUE0x7gESZ#PrU4;VOuxt0fBf^FOtny~&SNygEbYIW6n;d2wr(tgx z1VOqXj*UKWDwFI$$Qc=e+ze|${Y^*%Rhq9G0|iK?IkIJh66aM{>mZ{kD7*f^XZ-oz zPniFzy$c(Zpx1%g6`db1DV9%!(h1J(nEQX*p923DoiB*Q!L9<1u^E>Eh$8THcXm;k zantpP-u84G5S)N-T53L?)3r+8G64q^Vr%d}kOly0*9M+45e-rR1L&jQJK>5m__1R7 zksAt-8)!Eh|3_Qz9nNL@#}8YHvMCwiV~0p&C1mdvT9gK&$V>^PWM(ESWtWvo+(rtK zoh>D@cLR}8cwX1{_dL%(&vPF~N8OFjxUTCw&-eSa-rMaqxWf)G3dh*r-xt#<&~JM` zJu8dqu=h_wgz(8*PY~)leGzTD*@^PPd}EdLP|hr+j@}(vE8Q*WRm(#&7fYN^KhF8j zS%4)}v@o`A$uD$nJ=E|ApLB@DUbORe!?}LFmdAUIb`ACQs-VB_ykwDUsOzoo@uNagqGhr7s9)!@ zm(NzNi&NE@!f?vpPw|`F&&m0+-$}!`Y`E+*eRWo#_raOqcW2O5;mco6+%*~}VmaZ#=O%wP< z2MP(gL4Bo50Tk})u}xXO4%_&qeRw+8A98z^>dq5^I|f{jg&*zCGqx6p2{~1#Np^{3 zrntPVSI3KJV;BVMv6Fsij1e${5cQI5-jhE0f_IMO7n$TacXGC@-=<-XppCeCFlotI z_p#{HDE0t3J3uu!)_bk*a~^8;rZGQ^$`Z`J49($XGu8VNEpV>Va33b&yJ1k=zI#;|T z5Bs^~4)$!}=q@-_vI8Z8IrY0ccPK#SGop3Y=j@{Qs53+9iDNSjzFd&pT1G|@dHJX- zroX%vL7AIG`lyv@CL|4PnoxWZj%R!Tvf2aqB&ab0u}5%15VDP|MELdIX3t@+pn%@| z;};;FfYK8_Ck>F_mS;Kl&I)YFQ)Ru$h$=Mrf`-&;?+or<+>`sB`_KBXW$!s)dmEfM z?1tILW#}~Eu&=oGLkxOm$v`F;0cc2B#t}{o%^!~_)FMC9 z%Mb9KxwYXHlaeCQa-2;|_ELwM?|jX6qy~JIh1_{$;dsbS@_VgrYxCDu7@pg5cHO>$xe6SByHB??+x1+=6(~>@U~tJu1Fs-yh&ogk{hqvlD;$Ip+RWOmS=kjg-y|ZSu5GiVxG~_ z(K-#rBZ3eujg!0J32Vhp^5N>Ozo&5nGU^jlG`S&77AN}7^tlRLAa}p2`S&~dj~uay z6eo*H%PFV)Vsl57@>62poOu=uxxWmf^EY=pYN~%Tgej}44v1)tABk} zn?iW-MNFO)6e<6HW3Qg)n5^LcuWaNbr_48={Qnv270=+KC0sCGW=zYJywxHcH>6*(Jhg-*($POsHZ=`OTxs%uTqW$!JxlF0d^x6|#p4VryVrCJUzu5xbIs_ujoluff+j`yu4*@-9;I9+QxT*x3Sc>n(1&TQsO zz#ed1OYfP$mB(($I}AN}f|BJ=^4AxeSWemlp9O2YtM?r>J?AivF7@;0GkP++l;7dG zj<0Z~m@%1xGaJw$r)OQ(&=JDYy)q}}@2)PE7(4iDg+Q<3I~h|%e|~wb!=isG&G;EX z6bTW|zPdWiTJ7EHwj=NFxyx`XxRQ|#ul%KV)-^P&vpjBd58AETv4uU{;qack^qR9G zbFj83n`1NO&{u@xAA(SIv9Wwg9!1%!-;@o`V=5%ld>G(a+P<)`K!kAsB%AOqPQuqB zoE$`iM3<8O*iJHWs{%Dqw!HtO?_X`k=N|pP+mQXKnf{3p`?v>c@4R_`G9W=KNK=M| zl~o$@Oya%TEG4l0>XetwR7B!w9Qkzm>Ie8aC5FZVZ-HB)zDhpZP55e@dPE(Usl^7f zU@Z@Ys9)@Fo+BsJ#e&b*H80+&;UgS@VA0R`H`rtnNiB-T*fH+nT-x)A^N>>@*k3}O z{-5lD^$q_d)pKwz#cR5OwImWWToH?*ds!ty2ew(f^!YyqmX-uY0f2!p05I7NXB^ou zsBIs;TRnJ-$kl17qyEQs*lRY9?vRkdB?WHn^XK_3ED5OsUHGRFS6jS#tgFk=JDZB) z=v$&C8fI*G-pc38=X#)M$W&lpD3WMsXgFO_UPs~PdXb}K^bD0p1h!zGJ+3PPMg3i` zi(|+e{{+^Kc(5E`82!0R>!`1%K=A3-!=tGrP0ftKX@ zZ`BPJutwM8{t8Nujd8Z~iFHP0h<4?@5Zys+?}HC>B;D=!jbpz(OC51N(MEa0w~mwY zS@%9ahg`oA*FAt-rKeIpWf#ur>gq<}VX$sLuKhlB{7R=p9furkJ< zOePNue(HGkGp{7V+6qFrQK`K9z>w{LNpyH3)HFf=C6;qpTGDfCd7b<7F}wxf z&>1PkH{P_qdoDP+oq{|rAwfV=vhb9%K;fq!*KlE1eN|f4(l_0C^~Fuqhz9UJa4i9# zP4&eG}&pk|9R+tec2;0LR`_ z#GqxCq3KT1Yd3jmrh57BM%P5s)NhVE#v%EK{yt5f3hTM}>d)RIwT$+&GA~4SHx4CQ z_b9NR>OGa)vf4zuFZD#)tRSmzkpeqy$`{Y7wU1ZFS2W4W%5+j5-gsqx_|LB)Mig41 zoJR~a8^3RFWGC-CvM`iS`Fk>KS(1IGKtc8A-6l)n%IAlSMvqRodIjy0K5(@sFQg04 zbtFy?j{cLDgO<*6Ke<|mUgh<1zt#AyIrM>_IwfDEFyUMJ4Z_n3W1B70u{9Y@!3z=L zYh-*BhAa#s%00qbX0D@kv^PS$zkg;H5)vX4qjd$PN%-6#qHR887##G}kvLzJ8}s$u zbi|_3$7rZ3JiEN@bx&Qx1CRA8*?$t;`-bSIx;&DGw%u2fkV((_Fyda$L`S_pR8*?{ z$2EaHbow!=y9<&YyjrMrZP@E=3;llVoBWox&z`QG$rIZT>6xTlXO(^~shjZ8qdIwL z%6N@Xot#sJn4QiUhMp}@&^A1>;K=ukkk|CZ$X^QG=7ZfiR=E}{6%F70K);9h1eIipy8Wali4f_%0kr!r5}{eldy zhGPxeC;~(&C(4`Ub?8q@?@|6mrgay9GYyt4v1ij~$V$Bs_Hp0wKsb8yAur#d(73;c zhDCT$F9#3^2ywJMv-hf5mZ>Nl8wuvshUz{mwh9=Xdq!SfhTB-ZCChs-UivFQSQJoe zuDO+4H#RoDWN*EZfyRX9o;vm1H5)3`mwOqu<38O+{cE6c_QnlGe8SdnwADB7sw`R$ z&t{c-OzDq3O!{qLXc*_b533cG8o@ef7;iJ`j*f{z5}ERvw~<;f&+(JY(!yiMY?SG4 z8U7o$Q16z-u8lC*CIy)43@;qDOk;J&CPzr3% zMw6ZUKF#P+DWZ8r5q>MqZWC!htlIbYoI8=9aSegIRf_PGu^6 z1NFS`%~)4zB4jMn^NjQZ<21YSxTh8KMz6QVkDpj}&lHGYwhPR-b~=D7taY<#a;Owu zqrbnZhUOpV<&}-c8k|4%V}|2hP6n57I1He3 z?aj$Q$0wAu72L;ZBw;nFRWj7otp=Na)?jG#tc?He&6J|VqcC4pZWMOD69m5VY~JwGbHLEn;$2gZ-Ad(x%ceA zZ=bh^x_T|`?oGA3wXCdF6!(n#{Y>SUOEa~!w5J%eS^-xF?mQEc2^@s4efzGc6|Fz{ zM6S1AvoXin`j*o+RC9;C(E)KzoWBv~`u-FO+OM=Jow@dQc1;o%OCw+Ma|-jU6H%LA zEYFG^@hc1sSna!$dM|pmBC?=B0-oxMW_p9b$gUdlhc5hNS;yqOzof4yr00tT6t_&= zdFn_*eK%;lM9of+ZOW%?+C=F&Z$>iT`GPqm7<<`&D~i22^VY|*Vs5@N?xLj-Z)5WG z>#~-favCw`j#;K}$!U3ujnV4<(XZr+^YShYR+O;m=m~nGbVSG>9>QSA5mV!Txtk@? z*-dIZ{KR*%zx?!*?io#AU*Ct@uOKInyjpGi61}!_1=YPlVlG zDGlrUYMEuJe7tWeDma&aw(6Zw&1C%f^+ytgaob}>GF8}DsY$$A`Q9Hl^V#o2TLp{L z-&4ny(WSI^ZZD}Vung|%?^fp%656Jc+O9T!eK6&Am%>g`G(P{9$;K$Rz;cX3`PA~_TK1c|)-*q@3iEfR z11{bXf+=Tr`pb2~9g5_yKHGcaY1>9!6$s5)la1TkLGc%rcL>KlOs%pZi4}#Jx3)HQ zjg5nF%>gUz|B9|OP|;&@7}66pKBnkT`eC!>2#B*gJ$-R1Ml<>82$7S5I�%yZjxK z(Hi1lzbRl9A_6G@WOQQxYf&L$D4@=|&EycP*iG%K^tcS5z~#8>$-yJ`4i00GP1b=c zbXdEhuKwQSC;O>Wr@~O~pF`t3)iWd(b_e1%rZX?tZ<|R0F^NLeXSG(?GNBIWhu(TG z^9voG8&o*=-oxb~(5o){3@K7afzuhPo1}~m*W8`x=bx^KgnfwFd(eyhw*H2^tM<}W zc;PMBc-*G)@@I{t%$QlvpNs|%dP0v5_HhkgEeSWHh1(7=uNw$go ziztgZ>mwI47vC)|I;QaWOp`QJ%=0&;tjkP4Y0Z3vc`il%L)_*M!rpJVpzTQSXx#c+ z^H&GAm_zsUUIkaR$(UYQBM1^s{u^Pu#RLf-8@@U#kps4hp63JDZ2DYQN9CEWDxf)F z=(KP*_Ing9dgt(lWrRQnWf)j{E~)zPr*A}fopn?tukX*?RDc&3FJ5eXrv=ak7oqdO zC)t(C=e~a8Vf@fB2pK<7-q*Jb7Ra0L-Y`miEg8W+zuW!Ja_9(h%9cA7Ekc0}GhdRbIkGpcT^@@>t(A`|-{$nq+Xi3s`X>h7lhvCHA%dWFAmEi0L|-*PWt+&7*g z8ULAoxp*aW&kR!JXgN4Iq^E+HoR*ZAga4^0%GW+H>G*7tEZcNo(~9>=!JXOh*n74E zNBkJcu=OBJAmv|V)}FkmvyL_NS1!_YdhLaxoe)I7MCdA^JH;KT1H^D2St2{(E!Bo2 z_2?~qYX{t=iO)cNXi|L_X*pqb`e5Upd#7v_-1rFUoA_T1VPxi(yT%%#8h{sG9nM?h zBx`fsNPbG%w~rR9NFA3;$l(Y`oZ5}^Sx>sWY{G_QRg`(RMP#;55gd3pfHB>}RL9S` zmS`w&*Au+Cfz(?I&Vx4wD>s%Tb2YDT<;@*GJvD#9dP{bJ9!k^m&>0 zS<~Jg0YN|eOY)I3lFO8_m=}Xh=+vLogWo(>H~hc&w>8~-dxo&iD+&jwsSO~V!0hDA z)ruM6h0>~xj|V;cPn}98LNQvew3iEwPJ(n6gUvw-nPN_jWsE6$_I?1qITZR`6(ovY zzy3hzw*kyv89tx80qx#y}L zRo<{_19&7Q!^k|P7NfCi*Dm0|()(`@V4lbt4iXTOsHN4fU6TXsNB9Pbh$`qZ!kgXe zUc~OYKi1sT^gl5xuPTG3B_T9fn(b|gejM_qglT)ptu22z4R!~pkr59!mgZe7*Q z2{;N`QG$&j{vu%)0eO>y<9hs`u8C9ji>x>oWzL|<+i$MK1aB+<>iX6iuL=zG-oXxJ|@)uYNM6df>{a|{GsZxsBv|6@241;7$Q$W9j|E4BrBVPjic zJx&l;h_ZX~k2At6sAX?248)jj_bruF`*}_N@vq5fn!)Fc0O>>%uWMq0-RB4tjRrF( z)qh&aT3uB5i>(}bVse6kqNJu%184yM{qVx|@jb`h)@7Sh@o9>#Un?7q`&sN z{X}=N?lI(1zu`n`Ww5|_q^Bn zxP5;~%$D;LDV5-XJmVjaVfvse7d%8?W%uBlklQkmq(kr<^SZ-x!TI;DpZz!&XPs2Q za6l~Kjo3nmf&X;(YXBA%e-||3``daC$lj7QDVDpTn)6oH<=+A6yS(abvbHMUS1T6- zB|T3(NDlb)Q;J>{9@pCX_Is$T;3QJUCQnGv-QZRhJtD%KIP`B)p6Ie6brg91Pwt8Z zyBw)xA)Ly4jDO)bHoONJ;;xfzg+L&PASU#F(bmIKF&By!#@-8O$@$0dsW;!E=p?3vXy#|Zm$ux)LSv^3p@^R=6lVqW*G``IEr6?G?U;#^a-kD~kG*RH?u{=fdrgLlI2Gge(|dH!%Y zIV$GMy~d!3vxjHdNJ4!NQ7YB^S~;$_RN*;uCtR|kF}gSS%{!dF1b<10;sJnR38Jr$ zPD~7eYxM$pc!GE#8AiS7s(TN87^42pHY!}mXF3YlWN723cMy}AN2354htxYz7;9UE z0vive8And*7#l{lqHTJaD#l)eGO5bA}rN@ zaP-UDX}{#Nh~k3-s`ZT4MCWJh7=Ik*@*|Qnjoq>!DF?6vfHvXFt%5RhEwh){7&T%U z^?$lfcaV@lMFn*>nblT=3xPR0-c9K`*`RwXCck;a`}H?dH+zj6!MB5^<5b>%N0XDBBp2is1i zMEit0A%iEfd9nYX&81(H+%~qDfW&LOPD#lYD!+=1=#Ns; z(#4h=$*U^)K|)`FWH_3^L;*2cG{cu-g+oTQgsmI8gPIXnO}l`D4(D0ahoK7BCOp^O zM)DkWzT!D~VeP701JUWh4!ZoJVRw*&XV#lmSMKzClmh0eNv#QpFM<4nx z;bBm~LqPf(X?a@KNCQ+x<+zch<@m(JNQC^i=%i=Y-R-~0lfd|pMRF_NAp%YaPeL<~ z=9pG+2ed3N;qA(Cqpj}qzlRovZ;4R7qDd=b|@o>EaB8kH>H8*keLULbvU*f(xe1j?p+mY z+qMwrSosf?E=5kI<3m>4NId!tvFz}b|Aah2ky+>|Hz&dth2>fT3g>& z<0I2D!@r4+jWrhvpr^hIruI4L7+HCJyU-@4mWYPokn z4umk8)(aiS-=QK6l9(scw6cmL3 zXsA#o1oq7xT8f(dgKlSc_cIfAECG<3e6#Unvt#h9iGYR?0mmWoYs#s=IJXSiGJ3!4 z&G@*u5b$Tji4snH&b{V{US-0o?jjVt*fXLloW#b6=xK<(b`!skfKnFX2V85+FbwWS zOzdt5HJL$~BZqP;+WBw3+GGAKb($N4!FhS^0iC^EfuYz;*j9X}$@eG4yiA!>M><4l| z?>jDy)&-rdS$L+pp~vFMZzwwjknPL`q6ox11_7J~_`)IO*Ff)rl17?K&Ei3g-^(QY zEl`q!uFj1_xy{N179PzAmyA_9#!`wtN92V9;3h!v#jPsF8OIC6?PqQtwEm!u z6X@tg{>=7{bdAi}om3Qf$`JJf$eBF1Fwg z7f*_%&hk;FXNWEq-u$LB%X-#Z*+b>{u9&=_e2ua_CO}&!;EaK@eLpus4=Mpxrn!OSA)-(Y? zSc&#>6lkQ#{H5o8C8!#DCKab*+S~^AH;%M4h!}oJF zmI4EN+YRevjUKSX<>e7{^IXD8Kr;?_Q3;7aaMpbZ^+ibiK`{-<;Ink8r6YsNmtFD; zQ_FYBaWk}V8GQU*$H>p+VET+^2B?fFGWgTnNt9~%vPhUdN8@b4whi*A_e5lz=kfLQ zVI`qcCx8aT<_lc3v#a@Wjmxv7_&SlZy7NELa)TBWbQ3{TVv4my?3}o`L0HRDr`OM(LE@O`+%@5(l+ zZ=JIX?K+*(b@9}JR8Fg4#ehkESQD)aE)^I^oqPM!$EcdL9?PEG3wBVx#_#S# zF{0;Eb49lw%EGAnBd&$AY&*`uH5_ydjD_r#&rA?HK+{OwxihEd*keWoW+9h-7>1!{ z7(#g&^ij_Rcem~tPhx_S^c>D|;ITy(;kbxRlzb!-IjZB88_NOxy3UgO_djQTm9Zcq z?qA@&mm&CQg07}C+YSy*PjT1G_O_p)HGsm zmcdQrFcOFyqD%0-3t*h42b$p2$0Bu~2TsmTjfEnsWKRf=10- z%GJu#d%2gk08iBdeklrMqAuOf^)RO-yu7k$T0$Pp%$T2$)PMeCkNBc7jjI=(Kl{ zsE~1fu~LDZoO~Fr+=DqxA%A~;EtMjI!pdvPgx)+oz;)ZH$gEvxl0{*v?Z}SXGOspK zm)&ch0&ExJBQGP3D$Rsb>%yw&==aQ{ebJ4n!j2Cg2cQ)bDz> zxZ&X6_9=$b>@w{>_LE*4hCl0}D=0syc+>}Z{TJ0)OTRjsRwFU8k0?EN>$2$OM*b#e zXMBE;le`-2PXLzaIkbkczeyXp(69h2!|<5vM|TTHe8gs#`3}+_Hh-wu4F)B>{g~Bt z!{wd%IEi2dCX9ZP=cWKe4)#r|a{i8BB|C-np$pea*Iub@uZK~~6@FDBuqNm>l{%p8 z0NXz5BaW6p^BUk)*h!+op-EAlWAfr`mCE}O*SKfl5xhaC40ILGF^?L?lial@HG9xn zBbn=96HVx)Vq5f<*c|rL&fFUnEL+4%01@+Lu^jl&Fx;$%Tz#m31fV0>=~Dsu3=y_H zy9L2D#v%j-+#D~|BaTf$mVmywhnoIa8rRX{(5u{&t!Gr8C&Q!^`m{wg#Z-T$gwtkTnJv#YNFeffTG)InkTwt z;mG@2`Stx=^T&@R$`XhU9;mxsXN3V9*a^0g6}^RxoFAM)*1abR^?=+AUd6l@XkR%n z+^LRl|F4M#q^MHaZ_j{9#=Z*;ETNaVraQ9kMprjf{Kre!KJ##L;-#3gA~^N{HIJ)Ruhje-RM;)JH89T2OyvHFZ2H$13&nr&bjRf-k$pX-F42m0tILy^=Vl{OA%Teql7O|~e+@3ZPTLCdzBRFM z=sku#m2mb6lE(N(KQ`RmG_i|*70wWZT1sP)esFx_A{iO?te)mki;vZVUBMzun{aoBqZSwgQdAEHl^8pS z2nuT#CK)0F955deTg?9pXN`eU{nI7uGOm`>SKr?A{&r)#jD2f0nzEh4_pj#lPELP* zC19MQ5MU}Ac-p00C@kMy=`mrlAhU(en^0{B+m$3R&Jg(x&07o6A0e&KD)&oj zZ~=7fzFE$N$dr6yb`c^Uxv=gk%+0o7Uv>}`*&R~d{oAv{%m$}wJgK}VIPVTkLG^>M zo)>3%(R|08do6p0(EXsHBXao_jWul_8;bykVA@rDZY((S6N~wiYeqBysE<#purmb5 z#KlnoO1<`mo-2Wl2D?k}Q%CSg4L!NX?D*-5(jd#`gdX|uH=nuvCncSMS}71DSnN$9 zv)wu43?`s;m&5IeNTR$vf^hmbe@SLH8{06bzg`}8{@cnesvA<=3}fh`;(rN=h}6z4 ztK;~Gc+d3&nL}9t9_^Oe_Yz$!ZcQIQe!%@Drm+#RLSMdoS-dJvQQIp*)=}nmfzm#)#`4Z)dTMGaoU?+Iy4nn4zm`K$k^K@;8rU3CIn!_c$Rqv*GcNz7_Zd!-{-SxJ*U*0<;ycfrJs+IWp%p}OG!z}JnzA3 zfg>lOa0NQUsc_iCVy8$WygSth_>uCHXxjI9w=-zN@udPa$Fb>WHv|CQ!VBRPwR1`^ zw3;lsQ~P4H3@%i2Bd?^=?}&E*hU4Pms>c=@9mpG%(*z}B%RV+J#V0oQ5{rh&ZGs+y z-kS5_E*dJRu^ElJ2}JLUb|It4`!-7!Y>u_CBj3SMczmYS=_rufyNF@DYzKF&*``ql#)`MUx~{`&;ff`KT5C4MgqG` zl)uWuDerP6e3_jI+q3(tV|`x8Np4y!hn`s9rL|xs{X-Q3OOop3aJ;78+EgSmqiQ$g zQ*y8xpcWX8Jp8j79xYP2bU%%9fD1^?mjIR%ecH0J1TQ5Ap%^J^EI%`!Ppe z-RJPtSabkTEc$EpRak|do?gu8-odwRp?7NCCgWQ`0$obBpJ$w?3$0Jk`H<)pZ{P8m zhD7AkDECkrT{v`!&DK~f#I2lmLkdXeOciw6%1Cqn<}iL6hEVL{nsAOVXI zza0Rj3s{I#PBE8U62UFszm}TJ9zTsh9aB-ZV-^_^X24$K;@IwPCu829*2Nl7cf#YA zW35?SGx8HAvV9394Y6GkZC%T3>zL-F*f}xBe~kxXVq@=M`c9I`0}ua6m4!=!KBY>- zDZLJb)z;>UI@-LtZ`YSy4ShjBJA9ibzg?RG+}V zar-d1>HrZninI31?qulv zl%^aTmS$$>Om9YSCb6hqMON}7`K$GaakaDf3T_RuOHjNHWu7q>R&0&${q8%utkUPo z6`1AI?sGdbaKLs_PNB3;tMkM}=jiaSjtr8`u8p?6odGgj^FU}D2+J%PffKm3A6eN$ z$7QGXIi3Lr zb?jW{KQw5G$g~!!s0lUfw6MP^!mr8C&u)O79~Q9)AcJEV|4{=~h}84!S9PblHq5wM zAKm4;sXz)ZxgI*t8hvQn)_ZXRbzn7b)(zpD!_e z8&bN0`q0Az-IWU(u?Yt4-Q4qcAM?&yNVR`)%5>`SiHr-0{L*hkAm2^fR=&QbaJy{p z666_KC*SgX(D?73SIjOqbQ!aY4ym(9dm(PkQ0&e>z$S_U%CwYCh5KaiY zvxi(Mtj(G=QaLA@7~wTe$1;4)av{a7`%oLn_kzpGH=V0dG1?jzO9 za{Vd!ypvPpn$AA?uMUQH6eq3LZ_m(D$^TyPK;u7B`p2s-3+gj50$C8D3<(b-bs z7rz6Ibe$31Gp2lw)%^b^paYjE?z|aGymcyo<#poV^@0JP>01LfVNXVW?o*bC-fA1X z*J_tkD|K0>@hEqW&y|luG2v0Y3Lg1y)(-oW<`rG&wXyVDD*bV4spYowm5SSZ-g{r) zJycrkZlLNdO={U!s_BvMBC#{?VQ+l@(fA)HBn=0gPVb$&>U?|Gxv+_3jj^`Bb_@&S zv^Bf5Lfth+Yp4hIN_;wzbcD8m!Qy9{Ne!dwl9CHo38kEl4|&br!t&ooHVT^W1#RkV zrj7q|{_~5{c2!R^NuflI&$i6y!QYD%53NPk+LFt&Dkyj+n;G|Rj@(cS(0{*8^Ua+F z2bzIryK>0s!C=GVeYr2g@U6=~>X= z@IRs?WeH~F)y8Z9V17Uo2xl+B{-W%CMOT|$L|zT|5UPFLQA!v*=&FVoqZ)8fauUI5 zM6mQh8JX<6s#>C7ax$6ZBw=V0tApda4pO^&8KM-o$@nZRcfrx9Wd<&2*Z(0cY#<6y5csGo8ZC-&5j*Jf?1OC)*StDdK)vl1$L98LrLd-f%_s{f13Wmk3@KJM^QV%_Sqtx#z;muUBTaj-+`78?71)mKl|}+ zrfgcMvdCxvrZhDFxE2m^ScvU`OJ7t#TcJ19LU{zuQ4!s5VBQNzlnen`@_uCAL^(`O zQud0v4>=*r#AZ+MUUXc2hPsX#n6>8e=7(H)jN`E=4jJutpo(Bt&kn<02$ zz~U!rSCLR>j0dpT_$T7m5Ne3zq7P7qUpy>plwVY(`EN#X77cbNC;KM%M$~NDdO`E# z(1H)X0}^H9M{WOSCPW;7Z8Va49w3YNi3Hf?O7uK?tP!+HCCXI?F@agX%xx$7c879ui(HBEXOD zkJ*lcPZ||K*iQW>#%v@idf3MW+zF-*sy&B~LFBBMH#~j(b}*JJi)<|0)na#mc~x$n z*w?xjo?l8Xvl9eyuBy;j_^zA*w1r&#>OKZeHxKNATPd2IJ=XuztgwMTua5i!^CP1L z>A|q*Ad6h_smlsJIdn@n%M*U^NApzR%a~t6RFmO5xkFTX7fjL193+O;zTh$JCDWuaZqb>u9>906IE zffFnorC%dZUjP*)0z82|Y_~OJYu(?Fmvdq#H8=iAMJqCG=pWo4qHZDSuFzHU+}+fK=B`kIT`ZwU5@ zL?xRFk1!Y6v|8HRhKrArl4$?u1BBzB&c}&RNy3%#ENA=>8KE2A3(UL7+4C1$pTV&k z=$dpOShsLzCQ%U)OQ%&&HT>@@!4tEGW`}b!YHTjaoH1%@qi!aKVB#6EJ2I)ci;NID zukj<&4JY@YFzT7LC>nxI9WC zlxuW6%6kBFeZbPb_+{xQm{~ViIYx=un!tu!2fg}6VBo7I;*8PYqd}%8QfDDm!+=fF z)qNX=1_lqj_a(hTPl*N|B_kzia=_8bYBwregr}KVS=l$<8UH^*BBG3gHiVcIFyd!< z#N&Aj-fqI$7XV!B+~gBV!i7R4X(HcNBTt8Oi-@zwJM|{(aFwwB_q%@^nCx>F@oxH; zr+%-Em$Z$`>slM*QNdLmKg3LyA?Gj1auk!PiNJXXUTyr(?oHsPU@k(PLJXQ96x*hz zrnY4()@E$nD!wP&bCk_qa$up>5<@OP#ef*nE#y=fJ48&4CDX3pKR^mt%(BDrH+49EScQbszCnVW;! zicU?H`m4{e4wW`>4-yk;hFjm7!jwv8%hbK{<15kAVRs{D5l~l|HXr+n5d&D#uvhe} zU7CsZRC=s%?fV`S`uT^V-1^;C#EE+FFXM>NjwnNe|-cqv{*!UVlrNOl2_V@`6zA?d@T1))nup2-X(nCv}&N zuY8OgTav+ni9t+jHO5PmD+SHNK?h%x(<#)(_@Q>hG7J?HhZ%zy6qo%o&SL;)W|3f! zeRQIM7+Imq0aX)c(ylwZpk)HqWC~OK*BVPno~Z3-Ui3wWcUv=xj9S%0?m>TY^TyEi zllGZ>d!Nd(%WBKbN?uW47q~0OHlyYEdy%o-s%Skg2p>)?MxW2o7FTTU)!;XZ5X_h2)Fc){&L(U%HD5U?y44 z8gMt!)z?30yE|S*X|Z#(RNZbPjPd)c#s&*>ZbKnlaHE(v^2(X*juyl)V_p1Wi3&Jhq-E&0MFM zR<8U&67l))!3;W|%$@VHX}}zEi%e-^XgRXESROJxMaSK%)EM&GA2V?>-=DIyjL4lU zF_X7t?Mfw6r}0G^JGd8j!;Rr!UjGodh&bMPms^_^S|mSBFDqMpcI90_qlZS6rH^7) z1WT}XkaSUED!7{FibkJJh!6SjK%g|DcIg_3N7X_W^5+Z)KX?}vpj^!CpMhfq;5p~o z2=>#*)ckES@|{Dknnw#wZy~8u;w|Hq9_P=2OCq;3L~#UsetWYtJNvN_=VN1hs}1hPNp(&4_p}l`dy_vH$mKMknYCZ}HQg`hopV9?tk4 z)qINbdK!~89=5w@eD_o$G}>#o_~X=R(0*g+;MrNn@{v4LWrv)2qxv%{8Xw;0&o1bZ zR;NKlrLlolLdB%h`dY}P!Jv;Zn~iB7>wjszXnIQW>&Gn#Brx#vzpYpt;3q>QhttKt z8K}~aY6?57;*T^rn%K0C>g(_5>gvjfRX%=iJI{4BrE!naY!IX8A#sq7Fd7&5?yBIr zIIc(dIzr4T;j1J>WN<9pEctsS^IDB?mg>Pq7C$0#6&7t|u_ej&SZvp%!N`^f+!|X% z8>(6zyJh8Smh?~Tf|f;6Oj45Lf#GP;4WQ!WYHTr=A)$(6%0t-lDg}`jqeLf#c`J8C z0yrvv!o^MuF?UasOfX>Sh5gm?&3^2E{$CbHP3T@1wiM_H9DkA=r^6)+G!Rktcc4tF z>p#xk!vJa3BHgcksA^BFS*Vmf6k`ts??0UUInZUZ+o<#9Bs*qkTq6z3S-!*|8m3N_~5^;bM4=@ z1+H<@{+!Z#R3gkTE<%Sr2dYMdY5Y_4GkUHTxSwrD6Pu6K`l->h=lyC`9vKdQ!pGMQ zNK^>$_*^lRe8k)-GAOJ{Hsd|ZIAI=gNTkO* z>?ws$YR1pP38?Q(e{ZH)j`75I-&tScV7##8-!Ow?CPc_M|Q^Y}U zcS5CMY_7bqnO;(p?RqgId#a*CbGae^C_4+f6MXaDBLBIHNX)Eh`VT*&>T02kq`MQN zt9d36uITd$5sV+D*KPqx1eAR8lVcmZT3}+m6^+>iDGIKVoy2yoixOa9yR*}%9Cl!= zeRF}%C#*I`-4J}bLQzH$VkMBWQ}BF+wIl(RpLwhFRGh`c$U(>*zXJ*0+L2$Zp|z9Y zf2YfngY2xf@7uTU;L>h|($g3b^pTGLCiHNmZ%;H=A;fH<*{9EB^wUt2=5+BTQbRiM z#rS0aSrF%_7= zDh0w`UR+$vS^C!+wKnP*T4Hk3U(<(GPN*2@{pK*NVRUQ^YCZb&R7f|gkz4jc!wGr$2%Rj0uxH2@VwtZhVC|u)d1bie6J@EL$m(p2N6)SQ&~*TU;i`r%r?yz zXWkO9$@#0Oa-f#Q`TY`R;C*r)%n2S|%5gDoev>(bnBl}Gx&=bx^5Kied)@RT>uqY< z!utQ!yf$LSObtxUA{jo^VKGaBa^u0$Se651u>iV>`p38Ld@?(cZzrk$h`v;fWf1TB&yw_ z4~MxKnsVo-6hl5kZGc>V-N>kdYJ181i;t4MQYIONc9YH@K{tcQpgOfn&qKZeWp_m> zY2b4I@SER;1{Q<_Rd6AD^Q4yHNxPd$>?l#dQ@Mn&70rsf^%CrnH-M~7AQZ%~ zqU(5DOgBHK*LwX=1_~sCT_GE{S+t&_wqUU-q7JUbHRL&XF@&vK5wn==`Irtcd5AMa zEoEZ?!X8kKDGu}KM)y34%I@}hGf1SG5JDm}#!XF0UJ;NpluagICaTiA4diaGH7|wC z&zrW*@^drj2<84q(c7DLlv2Z{#+C_|CPgA;g#gMkw7G>!b}4wAh{SL=MMXu>Pnk7j z&+^0w4az9CUM+Zl=oIZNEf0-rJwN_}hoG{F`JwK6Kj*wL4Lov}oi6Ssuy;ba3!zp$ z))=AVU;6%q6`JHDn9LT1FI#ZBlmQLn0=iH=K-$Z&rTXIB6mKf1=B3@h)}z=OaD zQQ%AW34Mvv|IrQk|J@J&Z6wGlYmAR2?DQ~Xg+W8Z;d|`zY?poJpK9SOb|!n{FpqHi z^GCU}lP*i&<*pCV@8e*R4m|*qzVwqJ6V1_^67!4YhrUR3CCe+GOl?w)4T8DI zV9@^y%gz0N@wpyAoN{ffu&3Y&{QraS{;4+e$~inWUvwfPBV({Tp=WPoL?(t`)8Gg3 TU)Qk*#7}x!#+rrdws-z7$R;I5 From 877d3bbd22b36f468e23509134d41bed861c6dcb Mon Sep 17 00:00:00 2001 From: WizzXfpv <40316777+WizzX-FPV@users.noreply.github.com> Date: Sun, 19 Feb 2023 21:12:26 +0100 Subject: [PATCH 054/130] Update Temperature sensors.md --- docs/Temperature sensors.md | 18 ++++++++++++++++++ 1 file changed, 18 insertions(+) diff --git a/docs/Temperature sensors.md b/docs/Temperature sensors.md index e46cac2905..71a17f0b74 100644 --- a/docs/Temperature sensors.md +++ b/docs/Temperature sensors.md @@ -11,6 +11,24 @@ Up to 8 can be connected to the flight controller. * Supply: 2.7 to 5.5V * Temperature range: -55 to +125°C +On the purple LM75 (CJMCU-75), address line pins on the bottom of the PCB need to be bridged either to ground or VCC (to define I2C address) +![image](assets/images/CJMCU-75_address.png) + +Pin definition: +| A2 | A1 | A0 |Address|INAV add| +|-----|-----|-----|-------|--------| +| GND | GND | GND | 0x48 | 0 | +| GND | GND | VCC | 0x49 | 1 | +| GND | VCC | GND | 0x4A | 2 | +| GND | VCC | VCC | 0x4B | 3 | +| VCC | GND | GND | 0x4C | 4 | +| VCC | GND | VCC | 0x4D | 5 | +| VCC | VCC | GND | 0x4E | 6 | +| VCC | VCC | VCC | 0x4F | 7 | + +If more than one sensor is used, each sensor must have different address. + + ## DS18B20 * Package: TO-92, SO-8, µSOP-8 From 2fa94c56108d821f1bfd46311f2046a12b5ddf93 Mon Sep 17 00:00:00 2001 From: WizzXfpv <40316777+WizzX-FPV@users.noreply.github.com> Date: Sun, 19 Feb 2023 21:12:55 +0100 Subject: [PATCH 055/130] Update Temperature sensors.md --- docs/Temperature sensors.md | 1 + 1 file changed, 1 insertion(+) diff --git a/docs/Temperature sensors.md b/docs/Temperature sensors.md index 71a17f0b74..384be48eb3 100644 --- a/docs/Temperature sensors.md +++ b/docs/Temperature sensors.md @@ -12,6 +12,7 @@ Up to 8 can be connected to the flight controller. * Temperature range: -55 to +125°C On the purple LM75 (CJMCU-75), address line pins on the bottom of the PCB need to be bridged either to ground or VCC (to define I2C address) + ![image](assets/images/CJMCU-75_address.png) Pin definition: From 5f0d902552c81cb06164484153bc305a822e7f3a Mon Sep 17 00:00:00 2001 From: mateksys Date: Tue, 21 Feb 2023 16:40:43 +0800 Subject: [PATCH 056/130] add icm42688p support in MATEKF405SE target --- src/main/target/MATEKF405SE/config.c | 6 ++---- src/main/target/MATEKF405SE/target.h | 6 ++++++ 2 files changed, 8 insertions(+), 4 deletions(-) diff --git a/src/main/target/MATEKF405SE/config.c b/src/main/target/MATEKF405SE/config.c index 55a5e67099..f82e5fa109 100644 --- a/src/main/target/MATEKF405SE/config.c +++ b/src/main/target/MATEKF405SE/config.c @@ -37,11 +37,9 @@ void targetConfiguration(void) pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2; #endif - serialConfigMutable()->portConfigs[1].functionMask = FUNCTION_MSP; - serialConfigMutable()->portConfigs[1].msp_baudrateIndex = BAUD_57600; + //serialConfigMutable()->portConfigs[1].functionMask = FUNCTION_MSP; + //serialConfigMutable()->portConfigs[1].msp_baudrateIndex = BAUD_57600; - //featureSet(FEATURE_PWM_OUTPUT_ENABLE); // enable PWM outputs by default - //mixerConfigMutable()->mixerMode = MIXER_FLYING_WING; // default mixer to flying wing mixerConfigMutable()->platformType = PLATFORM_AIRPLANE; // default mixer to Airplane serialConfigMutable()->portConfigs[7].functionMask = FUNCTION_TELEMETRY_SMARTPORT; diff --git a/src/main/target/MATEKF405SE/target.h b/src/main/target/MATEKF405SE/target.h index efce983f5d..4c0b4b8b39 100644 --- a/src/main/target/MATEKF405SE/target.h +++ b/src/main/target/MATEKF405SE/target.h @@ -42,6 +42,12 @@ #define MPU6000_CS_PIN PA4 #define MPU6000_SPI_BUS BUS_SPI1 +// ICM42688P +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW0_DEG_FLIP +#define ICM42605_CS_PIN PA4 +#define ICM42605_SPI_BUS BUS_SPI1 + // *************** I2C /Baro/Mag ********************* #define USE_I2C #define USE_I2C_DEVICE_1 From 6200bb85bdbcef8155bac9317cd2f34fd0224edb Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Tue, 21 Feb 2023 11:44:50 +0000 Subject: [PATCH 057/130] Update navigation_multicopter.c --- src/main/navigation/navigation_multicopter.c | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/src/main/navigation/navigation_multicopter.c b/src/main/navigation/navigation_multicopter.c index ae53d0961b..f3e2b833e5 100644 --- a/src/main/navigation/navigation_multicopter.c +++ b/src/main/navigation/navigation_multicopter.c @@ -725,10 +725,14 @@ bool isMulticopterLandingDetected(void) DEBUG_SET(DEBUG_LANDING, 4, 0); static timeMs_t landingDetectorStartedAt; + bool throttleIsBelowMidHover = rcCommand[THROTTLE] < (0.5 * (currentBatteryProfile->nav.mc.hover_throttle + getThrottleIdleValue())); + /* Basic condition to start looking for landing - * Prevent landing detection if WP mission allowed during Failsafe (except landing states) */ + * Detection active during Failsafe only if throttle below mid hover throttle + * and WP mission not active (except landing states). + * Also active in non autonomous flight modes but only when thottle low */ bool startCondition = (navGetCurrentStateFlags() & (NAV_CTL_LAND | NAV_CTL_EMERG)) - || (FLIGHT_MODE(FAILSAFE_MODE) && !FLIGHT_MODE(NAV_WP_MODE)) + || (FLIGHT_MODE(FAILSAFE_MODE) && !FLIGHT_MODE(NAV_WP_MODE) && throttleIsBelowMidHover) || (!navigationIsFlyingAutonomousMode() && throttleStickIsLow()); if (!startCondition || posControl.flags.resetLandingDetector) { From 2dc400c120545518d677cf9526562921678ef661 Mon Sep 17 00:00:00 2001 From: tiriad <42714516+tiriad@users.noreply.github.com> Date: Tue, 21 Feb 2023 15:53:56 +0100 Subject: [PATCH 058/130] Add AUTOLEVEL message and updated pitch trim --- src/main/io/osd.c | 3 +++ src/main/io/osd.h | 1 + 2 files changed, 4 insertions(+) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index c871de4401..87d1a77f32 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -4589,6 +4589,9 @@ textAttributes_t osdGetSystemMessage(char *buff, size_t buff_size, bool isCenter messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_AUTOTUNE_ACRO); } } + if (IS_RC_MODE_ACTIVE(BOXAUTOLEVEL) && (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE) || (navigationRequiresAngleMode() && !navigationIsControllingAltitude()))) { + messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_AUTOLEVEL); + } if (FLIGHT_MODE(HEADFREE_MODE)) { messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_HEADFREE); } diff --git a/src/main/io/osd.h b/src/main/io/osd.h index 9cb4eaabd8..1857f92538 100644 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -112,6 +112,7 @@ #define OSD_MSG_AUTOTRIM "(AUTOTRIM)" #define OSD_MSG_AUTOTUNE "(AUTOTUNE)" #define OSD_MSG_AUTOTUNE_ACRO "SWITCH TO ACRO" +#define OSD_MSG_AUTOLEVEL "(AUTOLEVEL)" #define OSD_MSG_HEADFREE "(HEADFREE)" #define OSD_MSG_NAV_SOARING "(SOARING)" #define OSD_MSG_UNABLE_ARM "UNABLE TO ARM" From 217bb2789150994644931fbd0da83147112ae727 Mon Sep 17 00:00:00 2001 From: HakSeung Wang Date: Wed, 22 Feb 2023 13:53:42 +0900 Subject: [PATCH 059/130] Update Windows 11 - VS Code - WSL2 - Hardware Debugging.md need to modify command. --- .../Windows 11 - VS Code - WSL2 - Hardware Debugging.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/development/Windows 11 - VS Code - WSL2 - Hardware Debugging.md b/docs/development/Windows 11 - VS Code - WSL2 - Hardware Debugging.md index 80b794e8dd..3a1738b7ea 100644 --- a/docs/development/Windows 11 - VS Code - WSL2 - Hardware Debugging.md +++ b/docs/development/Windows 11 - VS Code - WSL2 - Hardware Debugging.md @@ -84,7 +84,7 @@ sudo udevadm control --reload-rules - Just for info: `usbipd detach --busid ID_OF_DEVICE_FROM_FIRST_COMMAND` - will deattach USB device from WSL ### Back to WSL2 prompt - `lsusb` - should show you just attached USB device -- `st-info -probe` - should "see" ST-Link and MCU +- `st-info --probe` - should "see" ST-Link and MCU #### Leave Command Prompt and WSL Prompt minimized (for later usage) #### **NOTE:** Due to some USB reconnect issues, sometimes, is need to execute `usbipd wsl list` and `usbipd wsl attach...` commands again, to reconnect ST-Link to WSL From ef0360591b286cecf7ade56ffa50c74ad9bba871 Mon Sep 17 00:00:00 2001 From: Scavanger Date: Wed, 22 Feb 2023 14:31:55 -0300 Subject: [PATCH 060/130] Bugfix --- src/main/flight/servos.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c index 5f2194faba..e94ce21eb1 100755 --- a/src/main/flight/servos.c +++ b/src/main/flight/servos.c @@ -525,7 +525,7 @@ void processContinuousServoAutotrim(const float dT) isGPSHeadingValid() // TODO: proper flying detection ) { // Plane is flying straight and level: trim servos - for (int axis = FD_ROLL; axis <= FD_YAW; axis++) { + for (int axis = FD_ROLL; axis <= FD_PITCH; axis++) { // For each stabilized axis, add 5 units of I-term to all associated servo midpoints const float axisIterm = getAxisIterm(axis); if (fabsf(axisIterm) > SERVO_AUTOTRIM_UPDATE_SIZE) { @@ -542,7 +542,7 @@ void processContinuousServoAutotrim(const float dT) // Convert axis I-term to servo PWM and add to midpoint const float mixerRate = currentServoMixer[i].rate / 100.0f; const float servoRate = servoParams(target)->rate / 100.0f; - servoParamsMutable(target)->middle += ItermUpdate * mixerRate * servoRate; + servoParamsMutable(target)->middle += (int16_t)(ItermUpdate * mixerRate * servoRate); servoParamsMutable(target)->middle = constrain(servoParamsMutable(target)->middle, SERVO_AUTOTRIM_CENTER_MIN, SERVO_AUTOTRIM_CENTER_MAX); } } From f330bdd6218849ec24bdfa3887cd49cb69f5211a Mon Sep 17 00:00:00 2001 From: Scavanger Date: Thu, 23 Feb 2023 10:49:14 -0300 Subject: [PATCH 061/130] Bugfixes and prepare configurator integration --- src/main/cms/cms_menu_navigation.c | 1 - src/main/common/time.c | 10 +++ src/main/common/time.h | 1 - src/main/config/config_streamer.h | 4 + src/main/config/config_streamer_file.c | 36 +++++---- src/main/drivers/accgyro/accgyro_fake.c | 5 -- src/main/fc/cli.c | 6 +- src/main/fc/fc_core.c | 6 +- src/main/fc/fc_msp.c | 4 - src/main/fc/settings.yaml | 18 ++--- src/main/flight/failsafe.c | 5 -- src/main/flight/imu.c | 16 ++-- src/main/io/displayport_msp_bf_compat.c | 12 +-- src/main/navigation/navigation.c | 73 ++----------------- src/main/navigation/navigation.h | 2 +- src/main/navigation/navigation_fixedwing.c | 25 ++----- src/main/navigation/navigation_multicopter.c | 31 +++----- .../navigation/navigation_pos_estimator.c | 2 +- src/main/navigation/navigation_private.h | 7 +- src/main/programming/logic_condition.c | 13 +--- src/main/programming/logic_condition.h | 2 - src/main/sensors/acceleration.c | 5 -- src/main/target/IFLIGHT_BLITZ_F722/target.c | 2 +- src/main/target/MATEKF411TE/target.h | 4 - src/main/target/SITL/sim/realFlight.c | 2 +- src/main/target/SITL/sim/xplane.c | 59 +++++++-------- src/main/target/SITL/target.c | 61 +++++++++------- 27 files changed, 166 insertions(+), 246 deletions(-) diff --git a/src/main/cms/cms_menu_navigation.c b/src/main/cms/cms_menu_navigation.c index d89cb2c249..33978f0118 100644 --- a/src/main/cms/cms_menu_navigation.c +++ b/src/main/cms/cms_menu_navigation.c @@ -50,7 +50,6 @@ static const OSD_Entry cmsx_menuNavSettingsEntries[] = OSD_SETTING_ENTRY("MC MAX BANK ANGLE", SETTING_NAV_MC_BANK_ANGLE), OSD_SETTING_ENTRY("MID THR FOR AH", SETTING_NAV_USE_MIDTHR_FOR_ALTHOLD), OSD_SETTING_ENTRY("MC HOVER THR", SETTING_NAV_MC_HOVER_THR), - OSD_SETTING_ENTRY("LANDING DISARM", SETTING_NAV_DISARM_ON_LANDING), OSD_BACK_AND_END_ENTRY, }; diff --git a/src/main/common/time.c b/src/main/common/time.c index f1204c57f4..8214398d26 100644 --- a/src/main/common/time.c +++ b/src/main/common/time.c @@ -35,6 +35,10 @@ #include "fc/settings.h" +#ifdef SITL_BUILD +#include +#endif + // For the "modulo 4" arithmetic to work, we need a leap base year #define REFERENCE_YEAR 2000 // Offset (seconds) from the UNIX epoch (1970-01-01) to 2000-01-01 @@ -310,11 +314,16 @@ bool rtcHasTime(void) bool rtcGet(rtcTime_t *t) { +#ifdef SITL_BUILD + *t = (rtcTime_t)(time(NULL) * 1000); + return true; +#else if (!rtcHasTime()) { return false; } *t = started + millis(); return true; +#endif } bool rtcSet(rtcTime_t *t) @@ -323,6 +332,7 @@ bool rtcSet(rtcTime_t *t) return true; } + bool rtcGetDateTime(dateTime_t *dt) { rtcTime_t t; diff --git a/src/main/common/time.h b/src/main/common/time.h index 82f2986077..81bc4ceae5 100644 --- a/src/main/common/time.h +++ b/src/main/common/time.h @@ -51,7 +51,6 @@ typedef uint32_t timeUs_t; #define USECS_PER_SEC (1000 * 1000) #define HZ2US(hz) (1000000 / (hz)) -#define HZ2MS(hz) (1000 / (hz)) #define US2S(us) ((us) * 1e-6f) #define US2MS(us) ((us) * 1e-3f) #define MS2US(ms) ((ms) * 1000) diff --git a/src/main/config/config_streamer.h b/src/main/config/config_streamer.h index 87b688406f..33c0954874 100644 --- a/src/main/config/config_streamer.h +++ b/src/main/config/config_streamer.h @@ -57,3 +57,7 @@ int config_streamer_flush(config_streamer_t *c); int config_streamer_finish(config_streamer_t *c); int config_streamer_status(config_streamer_t *c); + +#if defined(CONFIG_IN_FILE) +bool configFileSetPath(char* path); +#endif diff --git a/src/main/config/config_streamer_file.c b/src/main/config/config_streamer_file.c index c3fdbba95c..379155c22e 100644 --- a/src/main/config/config_streamer_file.c +++ b/src/main/config/config_streamer_file.c @@ -16,6 +16,7 @@ */ #include +#include #include "platform.h" #include "drivers/system.h" #include "config/config_streamer.h" @@ -26,21 +27,32 @@ #include #include + #define FLASH_PAGE_SIZE (0x400) static FILE *eepromFd = NULL; - static bool streamerLocked = true; +static char eepromPath[260] = EEPROM_FILENAME; + +bool configFileSetPath(char* path) +{ + if(!path || strlen(path) > 260) { + return false; + } + + strcpy(eepromPath, path); + return true; +} void config_streamer_impl_unlock(void) { if (eepromFd != NULL) { - fprintf(stderr, "[EEPROM] Unable to load %s\n", EEPROM_FILENAME); + fprintf(stderr, "[EEPROM] Unable to load %s\n", eepromPath); return; } // open or create - eepromFd = fopen(EEPROM_FILENAME,"r+"); + eepromFd = fopen(eepromPath,"r+"); if (eepromFd != NULL) { // obtain file size: fseek(eepromFd , 0 , SEEK_END); @@ -49,16 +61,16 @@ void config_streamer_impl_unlock(void) size_t n = fread(eepromData, 1, sizeof(eepromData), eepromFd); if (n == size) { - printf("[EEPROM] Loaded '%s' (%ld of %ld bytes)\n", EEPROM_FILENAME, size, sizeof(eepromData)); + fprintf(stderr,"[EEPROM] Loaded '%s' (%ld of %ld bytes)\n", eepromPath, size, sizeof(eepromData)); streamerLocked = false; } else { - fprintf(stderr, "[EEPROM] Failed to load '%s'\n", EEPROM_FILENAME); + fprintf(stderr, "[EEPROM] Failed to load '%s'\n", eepromPath); } } else { - printf("[EEPROM] Created '%s', size = %ld\n", EEPROM_FILENAME, sizeof(eepromData)); + printf("[EEPROM] Created '%s', size = %ld\n", eepromPath, sizeof(eepromData)); streamerLocked = false; - if ((eepromFd = fopen(EEPROM_FILENAME, "w+")) == NULL) { - fprintf(stderr, "[EEPROM] Failed to create '%s'\n", EEPROM_FILENAME); + if ((eepromFd = fopen(eepromPath, "w+")) == NULL) { + fprintf(stderr, "[EEPROM] Failed to create '%s'\n", eepromPath); streamerLocked = true; } if (fwrite(eepromData, sizeof(eepromData), 1, eepromFd) != 1) { @@ -66,8 +78,6 @@ void config_streamer_impl_unlock(void) streamerLocked = true; } } - - } void config_streamer_impl_lock(void) @@ -78,7 +88,7 @@ void config_streamer_impl_lock(void) fwrite(eepromData, 1, sizeof(eepromData), eepromFd); fclose(eepromFd); eepromFd = NULL; - printf("[EEPROM] Saved '%s'\n", EEPROM_FILENAME); + fprintf(stderr, "[EEPROM] Saved '%s'\n", eepromPath); streamerLocked = false; } else { fprintf(stderr, "[EEPROM] Unlock error\n"); @@ -93,9 +103,9 @@ int config_streamer_impl_write_word(config_streamer_t *c, config_streamer_buffer if ((c->address >= (uintptr_t)eepromData) && (c->address < (uintptr_t)ARRAYEND(eepromData))) { *((uint32_t*)c->address) = *buffer; - printf("[EEPROM] Program word %p = %08x\n", (void*)c->address, *((uint32_t*)c->address)); + fprintf(stderr, "[EEPROM] Program word %p = %08x\n", (void*)c->address, *((uint32_t*)c->address)); } else { - printf("[EEPROM] Program word %p out of range!\n", (void*)c->address); + fprintf(stderr, "[EEPROM] Program word %p out of range!\n", (void*)c->address); } c->address += CONFIG_STREAMER_BUFFER_SIZE; diff --git a/src/main/drivers/accgyro/accgyro_fake.c b/src/main/drivers/accgyro/accgyro_fake.c index 92be492f74..1389fa5433 100644 --- a/src/main/drivers/accgyro/accgyro_fake.c +++ b/src/main/drivers/accgyro/accgyro_fake.c @@ -39,9 +39,6 @@ static pthread_mutex_t gyroMutex; static pthread_mutex_t accMutex; -#define LOCK(mutex) (pthread_mutex_lock(mutex)) -#define UNLOCK(mutex) (pthread_mutex_unlock(mutex)) - #define GYROLOCK (pthread_mutex_lock(&gyroMutex)) #define GYROUNLOCK (pthread_mutex_unlock(&gyroMutex)) #define ACCLOCK (pthread_mutex_lock(&accMutex)) @@ -65,8 +62,6 @@ static void fakeGyroInit(gyroDev_t *gyro) #if defined(SITL_BUILD) pthread_mutex_init(&gyroMutex, NULL); #endif - - //ENABLE_STATE(ACCELEROMETER_CALIBRATED); } void fakeGyroSet(int16_t x, int16_t y, int16_t z) diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index 297d6e6506..ec45474d9f 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -3417,7 +3417,11 @@ static void cliStatus(char *cmdline) cliPrint("OSD: "); #if defined(USE_OSD) displayPort_t *osdDisplayPort = osdGetDisplayPort(); - cliPrintf("%s [%u x %u]", osdDisplayPort->displayPortType, osdDisplayPort->cols, osdDisplayPort->rows); + if (osdDisplayPort) { + cliPrintf("%s [%u x %u]", osdDisplayPort->displayPortType, osdDisplayPort->cols, osdDisplayPort->rows); + } else { + cliPrintf("no OSD detected"); + } #else cliPrint("not used"); #endif diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index 37d2c94dc5..620ec5203b 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -839,7 +839,7 @@ void taskMainPidLoop(timeUs_t currentTimeUs) if (!ARMING_FLAG(ARMED)) { armTime = 0; - + processDelayedSave(); } @@ -867,6 +867,7 @@ void taskMainPidLoop(timeUs_t currentTimeUs) if (isRXDataNew) { updateWaypointsAndNavigationMode(); } + isRXDataNew = false; updatePositionEstimator(); @@ -929,9 +930,10 @@ void taskMainPidLoop(timeUs_t currentTimeUs) writeMotors(); } #endif + // Check if landed, FW and MR if (STATE(ALTITUDE_CONTROL)) { - updateLandingStatus(US2MS(currentTimeUs)); + updateLandingStatus(); } #ifdef USE_BLACKBOX diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 2c547b28b7..4946edc8e8 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -46,11 +46,7 @@ #include "drivers/compass/compass_msp.h" #include "drivers/barometer/barometer_msp.h" #include "drivers/pitotmeter/pitotmeter_msp.h" -#include "drivers/accgyro/accgyro_fake.h" -#include "drivers/barometer/barometer_fake.h" -#include "drivers/compass/compass_fake.h" #include "sensors/battery_sensor_fake.h" -#include "drivers/pitotmeter/pitotmeter_fake.h" #include "drivers/bus_i2c.h" #include "drivers/display.h" #include "drivers/flash.h" diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index c6a0ac6259..08c64e5088 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1393,22 +1393,22 @@ groups: type: imuConfig_t headers: ["flight/imu.h"] members: - - name: ahrs_dcm_kp + - name: imu_dcm_kp description: "Inertial Measurement Unit KP Gain for accelerometer measurements" default_value: 2000 field: dcm_kp_acc max: UINT16_MAX - - name: ahrs_dcm_ki + - name: imu_dcm_ki description: "Inertial Measurement Unit KI Gain for accelerometer measurements" default_value: 50 field: dcm_ki_acc max: UINT16_MAX - - name: ahrs_dcm_kp_mag + - name: imu_dcm_kp_mag description: "Inertial Measurement Unit KP Gain for compass measurements" default_value: 2000 field: dcm_kp_mag max: UINT16_MAX - - name: ahrs_dcm_ki_mag + - name: imu_dcm_ki_mag description: "Inertial Measurement Unit KI Gain for compass measurements" default_value: 50 field: dcm_ki_mag @@ -1418,24 +1418,24 @@ groups: default_value: 25 min: 0 max: 180 - - name: ahrs_acc_ignore_rate + - name: imu_acc_ignore_rate description: "Total gyro rotation rate threshold [deg/s] before scaling to consider accelerometer trustworthy" default_value: 15 field: acc_ignore_rate min: 0 max: 30 - - name: ahrs_acc_ignore_slope + - name: imu_acc_ignore_slope description: "Half-width of the interval to gradually reduce accelerometer weight. Centered at `imu_acc_ignore_rate` (exactly 50% weight)" default_value: 5 field: acc_ignore_slope min: 0 max: 10 - - name: ahrs_gps_yaw_windcomp + - name: imu_gps_yaw_windcomp description: "Wind compensation in heading estimation from gps groundcourse(fixed wing only)" default_value: ON field: gps_yaw_windcomp type: bool - - name: ahrs_inertia_comp_method + - name: imu_inertia_comp_method description: "Inertia force compensation method when gps is avaliable, VELNED use the accleration from gps, TURNRATE calculates accleration by turnrate multiplied by speed, ADAPTIVE choose best result from two in each ahrs loop" default_value: VELNED field: inertia_comp_method @@ -2563,7 +2563,7 @@ groups: max: 45 - name: nav_auto_disarm_delay description: "Delay before craft disarms when `nav_disarm_on_landing` is set (ms)" - default_value: 1000 + default_value: 2000 field: general.auto_disarm_delay min: 100 max: 10000 diff --git a/src/main/flight/failsafe.c b/src/main/flight/failsafe.c index ab48fba2c6..097e5c3a99 100644 --- a/src/main/flight/failsafe.c +++ b/src/main/flight/failsafe.c @@ -346,11 +346,6 @@ static failsafeProcedure_e failsafeChooseFailsafeProcedure(void) } } - // Inhibit Failsafe if emergency landing triggered manually - if (posControl.flags.manualEmergLandActive) { - return FAILSAFE_PROCEDURE_NONE; - } - // Craft is closer than minimum failsafe procedure distance (if set to non-zero) // GPS must also be working, and home position set if (failsafeConfig()->failsafe_min_distance > 0 && diff --git a/src/main/flight/imu.c b/src/main/flight/imu.c index 3b54df3a02..89467545f8 100644 --- a/src/main/flight/imu.c +++ b/src/main/flight/imu.c @@ -116,15 +116,15 @@ FASTRAM bool imuUpdated = false; PG_REGISTER_WITH_RESET_TEMPLATE(imuConfig_t, imuConfig, PG_IMU_CONFIG, 2); PG_RESET_TEMPLATE(imuConfig_t, imuConfig, - .dcm_kp_acc = SETTING_AHRS_DCM_KP_DEFAULT, // 0.20 * 10000 - .dcm_ki_acc = SETTING_AHRS_DCM_KI_DEFAULT, // 0.005 * 10000 - .dcm_kp_mag = SETTING_AHRS_DCM_KP_MAG_DEFAULT, // 0.20 * 10000 - .dcm_ki_mag = SETTING_AHRS_DCM_KI_MAG_DEFAULT, // 0.005 * 10000 + .dcm_kp_acc = SETTING_IMU_DCM_KP_DEFAULT, // 0.20 * 10000 + .dcm_ki_acc = SETTING_IMU_DCM_KI_DEFAULT, // 0.005 * 10000 + .dcm_kp_mag = SETTING_IMU_DCM_KP_MAG_DEFAULT, // 0.20 * 10000 + .dcm_ki_mag = SETTING_IMU_DCM_KI_MAG_DEFAULT, // 0.005 * 10000 .small_angle = SETTING_SMALL_ANGLE_DEFAULT, - .acc_ignore_rate = SETTING_AHRS_ACC_IGNORE_RATE_DEFAULT, - .acc_ignore_slope = SETTING_AHRS_ACC_IGNORE_SLOPE_DEFAULT, - .gps_yaw_windcomp = SETTING_AHRS_GPS_YAW_WINDCOMP_DEFAULT, - .inertia_comp_method = SETTING_AHRS_INERTIA_COMP_METHOD_DEFAULT + .acc_ignore_rate = SETTING_IMU_ACC_IGNORE_RATE_DEFAULT, + .acc_ignore_slope = SETTING_IMU_ACC_IGNORE_SLOPE_DEFAULT, + .gps_yaw_windcomp = 1, + .inertia_comp_method = COMPMETHOD_VELNED ); STATIC_UNIT_TESTED void imuComputeRotationMatrix(void) diff --git a/src/main/io/displayport_msp_bf_compat.c b/src/main/io/displayport_msp_bf_compat.c index b6b1fe9d81..29a85b6718 100644 --- a/src/main/io/displayport_msp_bf_compat.c +++ b/src/main/io/displayport_msp_bf_compat.c @@ -228,6 +228,12 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) case SYM_WIND_VERTICAL: return BF_SYM_WIND_VERTICAL; + case SYM_3D_KMH: + return BF_SYM_3D_KMH; + + case SYM_3D_MPH: + return BF_SYM_3D_MPH; + case SYM_3D_KT: return BF_SYM_3D_KT; @@ -236,12 +242,6 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) return BF_SYM_AIR; */ - case SYM_3D_KMH: - return BF_SYM_KPH; - - case SYM_3D_MPH: - return BF_SYM_MPH; - case SYM_RPM: return BF_SYM_RPM; diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index e164b33ab5..3b55a2414b 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -1774,13 +1774,9 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_WAYPOINT_FINISHED(navig static navigationFSMEvent_t navOnEnteringState_NAV_STATE_EMERGENCY_LANDING_INITIALIZE(navigationFSMState_t previousState) { + // TODO: UNUSED(previousState); - if ((posControl.flags.estPosStatus >= EST_USABLE)) { - resetPositionController(); - setDesiredPosition(&navGetCurrentActualPositionAndVelocity()->pos, 0, NAV_POS_UPDATE_XY); - } - // Emergency landing MAY use common altitude controller if vertical position is valid - initialize it // Make sure terrain following is not enabled resetAltitudeController(false); @@ -1792,14 +1788,6 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_EMERGENCY_LANDING_IN_PR { UNUSED(previousState); - // Reset target position if too far away for some reason, e.g. GPS recovered since start landing. - if (posControl.flags.estPosStatus >= EST_USABLE) { - float targetPosLimit = STATE(MULTIROTOR) ? 2000.0f : navConfig()->fw.loiter_radius * 2.0f; - if (calculateDistanceToDestination(&posControl.desiredState.pos) > targetPosLimit) { - setDesiredPosition(&navGetCurrentActualPositionAndVelocity()->pos, 0, NAV_POS_UPDATE_XY); - } - } - if (STATE(LANDING_DETECTED)) { return NAV_FSM_EVENT_SUCCESS; } @@ -2813,18 +2801,12 @@ void calculateFarAwayTarget(fpVector3_t * farAwayPos, int32_t bearing, int32_t d /*----------------------------------------------------------- * NAV land detector *-----------------------------------------------------------*/ -void updateLandingStatus(timeMs_t currentTimeMs) +void updateLandingStatus(void) { if (STATE(AIRPLANE) && !navConfig()->general.flags.disarm_on_landing) { return; // no point using this with a fixed wing if not set to disarm } - static timeMs_t lastUpdateTimeMs = 0; - if ((currentTimeMs - lastUpdateTimeMs) <= HZ2MS(100)) { // limit update to 100Hz - return; - } - lastUpdateTimeMs = currentTimeMs; - static bool landingDetectorIsActive; DEBUG_SET(DEBUG_LANDING, 0, landingDetectorIsActive); @@ -2849,7 +2831,7 @@ void updateLandingStatus(timeMs_t currentTimeMs) if (navConfig()->general.flags.disarm_on_landing) { ENABLE_ARMING_FLAG(ARMING_DISABLED_LANDING_DETECTED); disarm(DISARM_LANDING); - } else if (!navigationInAutomaticThrottleMode()) { + } else if (!navigationIsFlyingAutonomousMode()) { // for multirotor only - reactivate landing detector without disarm when throttle raised toward hover throttle landingDetectorIsActive = rxGetChannelValue(THROTTLE) < (0.5 * (currentBatteryProfile->nav.mc.hover_throttle + getThrottleIdleValue())); } @@ -3433,10 +3415,7 @@ bool isNavHoldPositionActive(void) return isLastMissionWaypoint() || NAV_Status.state == MW_NAV_STATE_HOLD_TIMED; } // RTH mode (spiral climb and Home positions but excluding RTH Trackback point positions) and POSHOLD mode - // Also hold position during emergency landing if position valid - return (FLIGHT_MODE(NAV_RTH_MODE) && !posControl.flags.rthTrackbackActive) || - FLIGHT_MODE(NAV_POSHOLD_MODE) || - navigationIsExecutingAnEmergencyLanding(); + return (FLIGHT_MODE(NAV_RTH_MODE) && !posControl.flags.rthTrackbackActive) || FLIGHT_MODE(NAV_POSHOLD_MODE); } float getActiveWaypointSpeed(void) @@ -3535,7 +3514,6 @@ void applyWaypointNavigationAndAltitudeHold(void) // If we are disarmed, abort forced RTH or Emergency Landing posControl.flags.forcedRTHActivated = false; posControl.flags.forcedEmergLandingActivated = false; - posControl.flags.manualEmergLandActive = false; // ensure WP missions always restart from first waypoint after disarm posControl.activeWaypointIndex = posControl.startWpIndex; // Reset RTH trackback @@ -3612,41 +3590,6 @@ static bool isWaypointMissionValid(void) return posControl.waypointListValid && (posControl.waypointCount > 0); } -static void checkManualEmergencyLandingControl(void) -{ - static timeMs_t timeout = 0; - static int8_t counter = 0; - static bool toggle; - timeMs_t currentTimeMs = millis(); - - if (timeout && currentTimeMs > timeout) { - timeout += 1000; - counter -= counter ? 1 : 0; - if (!counter) { - timeout = 0; - } - } - if (IS_RC_MODE_ACTIVE(BOXNAVPOSHOLD)) { - if (!timeout && toggle) { - timeout = currentTimeMs + 4000; - } - counter += toggle; - toggle = false; - } else { - toggle = true; - } - - // Emergency landing toggled ON or OFF after 5 cycles of Poshold mode @ 1Hz minimum rate - if (counter >= 5) { - counter = 0; - posControl.flags.manualEmergLandActive = !posControl.flags.manualEmergLandActive; - - if (!posControl.flags.manualEmergLandActive) { - navProcessFSMEvents(NAV_FSM_EVENT_SWITCH_TO_IDLE); - } - } -} - static navigationFSMEvent_t selectNavEventFromBoxModeInput(void) { static bool canActivateWaypoint = false; @@ -3672,12 +3615,8 @@ static navigationFSMEvent_t selectNavEventFromBoxModeInput(void) posControl.flags.rthTrackbackActive = isExecutingRTH; } - /* Emergency landing controlled manually by rapid switching of Poshold mode. - * Landing toggled ON or OFF for each Poshold activation sequence */ - checkManualEmergencyLandingControl(); - - /* Emergency landing triggered by failsafe Landing or manually initiated */ - if (posControl.flags.forcedEmergLandingActivated || posControl.flags.manualEmergLandActive) { + /* Emergency landing triggered by failsafe when Failsafe procedure set to Landing */ + if (posControl.flags.forcedEmergLandingActivated) { return NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING; } diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h index 84255421be..b55bc15a4d 100644 --- a/src/main/navigation/navigation.h +++ b/src/main/navigation/navigation.h @@ -606,7 +606,7 @@ const char * fixedWingLaunchStateMessage(void); float calculateAverageSpeed(void); -void updateLandingStatus(timeMs_t currentTimeMs); +void updateLandingStatus(void); const navigationPIDControllers_t* getNavigationPIDControllers(void); diff --git a/src/main/navigation/navigation_fixedwing.c b/src/main/navigation/navigation_fixedwing.c index 9160669365..99fccb1e10 100755 --- a/src/main/navigation/navigation_fixedwing.c +++ b/src/main/navigation/navigation_fixedwing.c @@ -711,7 +711,7 @@ bool isFixedWingLandingDetected(void) static int16_t fwLandSetPitchDatum; const float sensitivity = navConfig()->general.land_detect_sensitivity / 5.0f; - const timeMs_t currentTimeMs = millis(); + timeMs_t currentTimeMs = millis(); // Check horizontal and vertical velocities are low (cm/s) bool velCondition = fabsf(navGetCurrentActualPositionAndVelocity()->vel.z) < (50.0f * sensitivity) && @@ -736,12 +736,9 @@ bool isFixedWingLandingDetected(void) DEBUG_SET(DEBUG_LANDING, 6, isRollAxisStatic); DEBUG_SET(DEBUG_LANDING, 7, isPitchAxisStatic); if (isRollAxisStatic && isPitchAxisStatic) { - /* Probably landed, low horizontal and vertical velocities and no axis rotation in Roll and Pitch - * Conditions need to be held for fixed safety time + optional extra delay. - * Fixed time increased if velocities invalid to provide extra safety margin against false triggers */ - const uint16_t safetyTime = posControl.flags.estAltStatus == EST_NONE || posControl.flags.estVelStatus == EST_NONE ? 5000 : 1000; - timeMs_t safetyTimeDelay = safetyTime + navConfig()->general.auto_disarm_delay; - return currentTimeMs - fwLandingTimerStartAt > safetyTimeDelay; + // Probably landed, low horizontal and vertical velocities and no axis rotation in Roll and Pitch + timeMs_t safetyTimeDelay = 2000 + navConfig()->general.auto_disarm_delay; + return currentTimeMs - fwLandingTimerStartAt > safetyTimeDelay; // check conditions stable for 2s + optional extra delay } else { fixAxisCheck = false; } @@ -755,6 +752,8 @@ bool isFixedWingLandingDetected(void) *-----------------------------------------------------------*/ void applyFixedWingEmergencyLandingController(timeUs_t currentTimeUs) { + rcCommand[ROLL] = pidAngleToRcCommand(failsafeConfig()->failsafe_fw_roll_angle, pidProfile()->max_angle_inclination[FD_ROLL]); + rcCommand[YAW] = -pidRateToRcCommand(failsafeConfig()->failsafe_fw_yaw_rate, currentControlRateProfile->stabilized.rates[FD_YAW]); rcCommand[THROTTLE] = currentBatteryProfile->failsafe_throttle; if (posControl.flags.estAltStatus >= EST_USABLE) { @@ -766,18 +765,6 @@ void applyFixedWingEmergencyLandingController(timeUs_t currentTimeUs) } else { rcCommand[PITCH] = pidAngleToRcCommand(failsafeConfig()->failsafe_fw_pitch_angle, pidProfile()->max_angle_inclination[FD_PITCH]); } - - if (posControl.flags.estPosStatus >= EST_USABLE) { // Hold position if possible - applyFixedWingPositionController(currentTimeUs); - int16_t rollCorrection = constrain(posControl.rcAdjustment[ROLL], - -DEGREES_TO_DECIDEGREES(navConfig()->fw.max_bank_angle), - DEGREES_TO_DECIDEGREES(navConfig()->fw.max_bank_angle)); - rcCommand[ROLL] = pidAngleToRcCommand(rollCorrection, pidProfile()->max_angle_inclination[FD_ROLL]); - rcCommand[YAW] = 0; - } else { - rcCommand[ROLL] = pidAngleToRcCommand(failsafeConfig()->failsafe_fw_roll_angle, pidProfile()->max_angle_inclination[FD_ROLL]); - rcCommand[YAW] = -pidRateToRcCommand(failsafeConfig()->failsafe_fw_yaw_rate, currentControlRateProfile->stabilized.rates[FD_YAW]); - } } /*----------------------------------------------------------- diff --git a/src/main/navigation/navigation_multicopter.c b/src/main/navigation/navigation_multicopter.c index ae53d0961b..b40282961f 100644 --- a/src/main/navigation/navigation_multicopter.c +++ b/src/main/navigation/navigation_multicopter.c @@ -723,7 +723,7 @@ bool isMulticopterFlying(void) bool isMulticopterLandingDetected(void) { DEBUG_SET(DEBUG_LANDING, 4, 0); - static timeMs_t landingDetectorStartedAt; + static timeUs_t landingDetectorStartedAt; /* Basic condition to start looking for landing * Prevent landing detection if WP mission allowed during Failsafe (except landing states) */ @@ -747,7 +747,7 @@ bool isMulticopterLandingDetected(void) DEBUG_SET(DEBUG_LANDING, 3, gyroCondition); bool possibleLandingDetected = false; - const timeMs_t currentTimeMs = millis(); + const timeUs_t currentTimeUs = micros(); if (navGetCurrentStateFlags() & NAV_CTL_LAND) { // We have likely landed if throttle is 40 units below average descend throttle @@ -761,13 +761,13 @@ bool isMulticopterLandingDetected(void) if (!landingDetectorStartedAt) { landingThrSum = landingThrSamples = 0; - landingDetectorStartedAt = currentTimeMs; + landingDetectorStartedAt = currentTimeUs; } if (!landingThrSamples) { - if (currentTimeMs - landingDetectorStartedAt < S2MS(MC_LAND_THR_STABILISE_DELAY)) { // Wait for 1 second so throttle has stabilized. + if (currentTimeUs - landingDetectorStartedAt < (USECS_PER_SEC * MC_LAND_THR_STABILISE_DELAY)) { // Wait for 1 second so throttle has stabilized. return false; } else { - landingDetectorStartedAt = currentTimeMs; + landingDetectorStartedAt = currentTimeUs; } } landingThrSamples += 1; @@ -783,7 +783,7 @@ bool isMulticopterLandingDetected(void) if (landingDetectorStartedAt) { possibleLandingDetected = velCondition && gyroCondition; } else { - landingDetectorStartedAt = currentTimeMs; + landingDetectorStartedAt = currentTimeUs; return false; } } @@ -798,13 +798,10 @@ bool isMulticopterLandingDetected(void) DEBUG_SET(DEBUG_LANDING, 5, possibleLandingDetected); if (possibleLandingDetected) { - /* Conditions need to be held for fixed safety time + optional extra delay. - * Fixed time increased if Z velocity invalid to provide extra safety margin against false triggers */ - const uint16_t safetyTime = posControl.flags.estAltStatus == EST_NONE ? 5000 : 1000; - timeMs_t safetyTimeDelay = safetyTime + navConfig()->general.auto_disarm_delay; - return currentTimeMs - landingDetectorStartedAt > safetyTimeDelay; + timeUs_t safetyTimeDelay = MS2US(2000 + navConfig()->general.auto_disarm_delay); // check conditions stable for 2s + optional extra delay + return (currentTimeUs - landingDetectorStartedAt > safetyTimeDelay); } else { - landingDetectorStartedAt = currentTimeMs; + landingDetectorStartedAt = currentTimeUs; return false; } } @@ -817,6 +814,8 @@ static void applyMulticopterEmergencyLandingController(timeUs_t currentTimeUs) static timeUs_t previousTimePositionUpdate = 0; /* Attempt to stabilise */ + rcCommand[ROLL] = 0; + rcCommand[PITCH] = 0; rcCommand[YAW] = 0; if ((posControl.flags.estAltStatus < EST_USABLE)) { @@ -853,14 +852,6 @@ static void applyMulticopterEmergencyLandingController(timeUs_t currentTimeUs) // Update throttle controller rcCommand[THROTTLE] = posControl.rcAdjustment[THROTTLE]; - - // Hold position if possible - if ((posControl.flags.estPosStatus >= EST_USABLE)) { - applyMulticopterPositionController(currentTimeUs); - } else { - rcCommand[ROLL] = 0; - rcCommand[PITCH] = 0; - } } /*----------------------------------------------------------- diff --git a/src/main/navigation/navigation_pos_estimator.c b/src/main/navigation/navigation_pos_estimator.c index 57443ebffd..0d0ecfb91c 100755 --- a/src/main/navigation/navigation_pos_estimator.c +++ b/src/main/navigation/navigation_pos_estimator.c @@ -241,7 +241,7 @@ void onNewGPSData(void) /* Use VELNED provided by GPS if available, calculate from coordinates otherwise */ float gpsScaleLonDown = constrainf(cos_approx((ABS(gpsSol.llh.lat) / 10000000.0f) * 0.0174532925f), 0.01f, 1.0f); - if (positionEstimationConfig()->use_gps_velned && gpsSol.flags.validVelNE) { + if (!ARMING_FLAG(SIMULATOR_MODE_SITL) && positionEstimationConfig()->use_gps_velned && gpsSol.flags.validVelNE) { posEstimator.gps.vel.x = gpsSol.velNED[X]; posEstimator.gps.vel.y = gpsSol.velNED[Y]; } diff --git a/src/main/navigation/navigation_private.h b/src/main/navigation/navigation_private.h index 0598467d28..44fc1796fd 100644 --- a/src/main/navigation/navigation_private.h +++ b/src/main/navigation/navigation_private.h @@ -42,7 +42,7 @@ #define MC_LAND_CHECK_VEL_XY_MOVING 100.0f // cm/s #define MC_LAND_CHECK_VEL_Z_MOVING 100.0f // cm/s #define MC_LAND_THR_STABILISE_DELAY 1 // seconds -#define MC_LAND_DESCEND_THROTTLE 40 // RC pwm units (us) +#define MC_LAND_DESCEND_THROTTLE 40 // uS #define MC_LAND_SAFE_SURFACE 5.0f // cm #define NAV_RTH_TRACKBACK_POINTS 50 // max number RTH trackback points @@ -104,13 +104,14 @@ typedef struct navigationFlags_s { bool forcedRTHActivated; bool forcedEmergLandingActivated; + bool wpMissionPlannerActive; // Activation status of WP mission planner + /* Landing detector */ bool resetLandingDetector; - bool wpMissionPlannerActive; // Activation status of WP mission planner bool rthTrackbackActive; // Activation status of RTH trackback + bool wpTurnSmoothingActive; // Activation status WP turn smoothing - bool manualEmergLandActive; // Activation status of manual emergency landing } navigationFlags_t; typedef struct { diff --git a/src/main/programming/logic_condition.c b/src/main/programming/logic_condition.c index f07e487f9c..95e76eb774 100644 --- a/src/main/programming/logic_condition.c +++ b/src/main/programming/logic_condition.c @@ -811,16 +811,12 @@ static int logicConditionGetFlightModeOperandValue(int operand) { return (bool) FLIGHT_MODE(NAV_POSHOLD_MODE); break; - case LOGIC_CONDITION_OPERAND_FLIGHT_MODE_WAYPOINT_MISSION: - return (bool) FLIGHT_MODE(NAV_WP_MODE); - break; - case LOGIC_CONDITION_OPERAND_FLIGHT_MODE_COURSE_HOLD: - return ((bool) FLIGHT_MODE(NAV_COURSE_HOLD_MODE) && !(bool)FLIGHT_MODE(NAV_ALTHOLD_MODE)); + return (bool) FLIGHT_MODE(NAV_COURSE_HOLD_MODE); break; case LOGIC_CONDITION_OPERAND_FLIGHT_MODE_CRUISE: - return (bool) (FLIGHT_MODE(NAV_COURSE_HOLD_MODE) && FLIGHT_MODE(NAV_ALTHOLD_MODE)); + return (bool)(FLIGHT_MODE(NAV_COURSE_HOLD_MODE) && FLIGHT_MODE(NAV_ALTHOLD_MODE)); break; case LOGIC_CONDITION_OPERAND_FLIGHT_MODE_ALTHOLD: @@ -839,11 +835,6 @@ static int logicConditionGetFlightModeOperandValue(int operand) { return (bool) FLIGHT_MODE(AIRMODE_ACTIVE); break; - case LOGIC_CONDITION_OPERAND_FLIGHT_MODE_ACRO: - return (((bool) FLIGHT_MODE(ANGLE_MODE) || (bool) FLIGHT_MODE(HORIZON_MODE) || (bool) FLIGHT_MODE(MANUAL_MODE) || (bool) FLIGHT_MODE(NAV_RTH_MODE) || - (bool) FLIGHT_MODE(NAV_POSHOLD_MODE) || (bool) FLIGHT_MODE(NAV_COURSE_HOLD_MODE) || (bool) FLIGHT_MODE(NAV_WP_MODE)) == false); - break; - case LOGIC_CONDITION_OPERAND_FLIGHT_MODE_USER1: return IS_RC_MODE_ACTIVE(BOXUSER1); break; diff --git a/src/main/programming/logic_condition.h b/src/main/programming/logic_condition.h index 779dbb1b98..1aaae7da0a 100644 --- a/src/main/programming/logic_condition.h +++ b/src/main/programming/logic_condition.h @@ -152,8 +152,6 @@ typedef enum { LOGIC_CONDITION_OPERAND_FLIGHT_MODE_COURSE_HOLD, // 11 LOGIC_CONDITION_OPERAND_FLIGHT_MODE_USER3, // 12 LOGIC_CONDITION_OPERAND_FLIGHT_MODE_USER4, // 13 - LOGIC_CONDITION_OPERAND_FLIGHT_MODE_ACRO, // 14 - LOGIC_CONDITION_OPERAND_FLIGHT_MODE_WAYPOINT_MISSION, // 15 } logicFlightModeOperands_e; typedef enum { diff --git a/src/main/sensors/acceleration.c b/src/main/sensors/acceleration.c index ed125f36c3..6a63c6cb88 100644 --- a/src/main/sensors/acceleration.c +++ b/src/main/sensors/acceleration.c @@ -520,11 +520,6 @@ void accUpdate(void) if (!ARMING_FLAG(SIMULATOR_MODE_SITL)) { performAcclerationCalibration(); - - applyAccelerationZero(&accelerometerConfig()->accZero, &accelerometerConfig()->accGain); - applyAccelerationZero(&accelerometerConfig()->accZero, &accelerometerConfig()->accGain); - applyAccelerationZero(&accelerometerConfig()->accZero, &accelerometerConfig()->accGain); - applyAccelerationZero(&accelerometerConfig()->accZero, &accelerometerConfig()->accGain); applyAccelerationZero(&accelerometerConfig()->accZero, &accelerometerConfig()->accGain); } diff --git a/src/main/target/IFLIGHT_BLITZ_F722/target.c b/src/main/target/IFLIGHT_BLITZ_F722/target.c index 8bba266c36..0986053b6d 100644 --- a/src/main/target/IFLIGHT_BLITZ_F722/target.c +++ b/src/main/target/IFLIGHT_BLITZ_F722/target.c @@ -35,7 +35,7 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM2, CH4, PB11, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S8 DMA1_S6_CH3 - DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // WS2812B + DEF_TIM(TIM1, CH2N, PB0, TIM_USE_LED, 0, 0), // WS2812B DMA2_S6_CH0 }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/MATEKF411TE/target.h b/src/main/target/MATEKF411TE/target.h index 7ecb2d1cb6..a410a2c135 100644 --- a/src/main/target/MATEKF411TE/target.h +++ b/src/main/target/MATEKF411TE/target.h @@ -38,10 +38,6 @@ #define BMI270_CS_PIN PC13 #define IMU_BMI270_ALIGN CW270_DEG_FLIP -#define USE_IMU_ICM42605 -#define ICM42605_SPI_BUS BUS_SPI2 -#define ICM42605_CS_PIN PC13 -#define IMU_ICM42605_ALIGN CW180_DEG_FLIP #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI2 diff --git a/src/main/target/SITL/sim/realFlight.c b/src/main/target/SITL/sim/realFlight.c index 4289d87d25..b57193d32b 100644 --- a/src/main/target/SITL/sim/realFlight.c +++ b/src/main/target/SITL/sim/realFlight.c @@ -414,7 +414,7 @@ bool simRealFlightInit(char* ip, uint8_t* mapping, uint8_t mapCount, bool imu) // Wait until the connection is established, the interface has been initialised // and the first valid packet has been received to avoid problems with the startup calibration. while (!isInitalised) { - // ... + delay(250); } return true; diff --git a/src/main/target/SITL/sim/xplane.c b/src/main/target/SITL/sim/xplane.c index 70ecb3361f..bc54166e1d 100644 --- a/src/main/target/SITL/sim/xplane.c +++ b/src/main/target/SITL/sim/xplane.c @@ -184,11 +184,11 @@ static void* listenWorker(void* arg) recvLen = recvfrom(sockFd, buf, sizeof(buf), 0, (struct sockaddr*)&remoteAddr, &slen); if (recvLen < 0 && errno != EWOULDBLOCK) { - break; + continue; } if (strncmp((char*)buf, "RREF", 4) != 0) { - break; + continue; } for (int i = 5; i < recvLen; i += 8) { @@ -276,7 +276,6 @@ static void* listenWorker(void* arg) default: break; } - } if (hpath < 0) { @@ -328,7 +327,9 @@ static void* listenWorker(void* arg) fakeBattSensorSetVbat(16.8 * 100); if (!initalized) { - ENABLE_ARMING_FLAG(SIMULATOR_MODE_SITL); + ENABLE_ARMING_FLAG(SIMULATOR_MODE_SITL); + // Aircraft can wobble on the runway and prevents calibration of the accelerometer + ENABLE_STATE(ACCELEROMETER_CALIBRATED); initalized = true; } @@ -362,42 +363,42 @@ bool simXPlaneInit(char* ip, int port, uint8_t* mapping, uint8_t mapCount, bool return false; } - if (bind(sockFd, (struct sockaddr *) &addr, sizeof(addr)) < 0) { + if (setsockopt(sockFd, SOL_SOCKET, SO_SNDTIMEO, (struct timeval *) &tv,sizeof(struct timeval))) { return false; } + + bind(sockFd, (struct sockaddr *) &addr, sizeof(addr)); serverAddr.sin_family = AF_INET; serverAddr.sin_addr.s_addr = inet_addr(ip); serverAddr.sin_port = htons(port); - - registerDref(DREF_LATITUDE, "sim/flightmodel/position/latitude", 100); - registerDref(DREF_LONGITUDE, "sim/flightmodel/position/longitude", 100); - registerDref(DREF_ELEVATION, "sim/flightmodel/position/elevation", 100); - registerDref(DREF_LOCAL_VX, "sim/flightmodel/position/local_vx", 100); - registerDref(DREF_LOCAL_VY, "sim/flightmodel/position/local_vy", 100); - registerDref(DREF_LOCAL_VZ, "sim/flightmodel/position/local_vz", 100); - registerDref(DREF_GROUNDSPEED, "sim/flightmodel/position/groundspeed", 100); - registerDref(DREF_TRUE_AIRSPEED, "sim/flightmodel/position/true_airspeed", 100); - registerDref(DREF_POS_PHI, "sim/flightmodel/position/phi", 100); - registerDref(DREF_POS_THETA, "sim/flightmodel/position/theta", 100); - registerDref(DREF_POS_PSI, "sim/flightmodel/position/psi", 100); - registerDref(DREF_POS_HPATH, "sim/flightmodel/position/hpath", 100); - registerDref(DREF_FORCE_G_AXI1, "sim/flightmodel/forces/g_axil", 100); - registerDref(DREF_FORCE_G_SIDE, "sim/flightmodel/forces/g_side", 100); - registerDref(DREF_FORCE_G_NRML, "sim/flightmodel/forces/g_nrml", 100); - registerDref(DREF_POS_P, "sim/flightmodel/position/P", 100); - registerDref(DREF_POS_Q, "sim/flightmodel/position/Q", 100); - registerDref(DREF_POS_R, "sim/flightmodel/position/R", 100); - registerDref(DREF_POS_BARO_CURRENT_INHG, "sim/weather/barometer_current_inhg", 100); - + if (pthread_create(&listenThread, NULL, listenWorker, NULL) < 0) { return false; } - while(!initalized) { - // + while (!initalized) { + registerDref(DREF_LATITUDE, "sim/flightmodel/position/latitude", 100); + registerDref(DREF_LONGITUDE, "sim/flightmodel/position/longitude", 100); + registerDref(DREF_ELEVATION, "sim/flightmodel/position/elevation", 100); + registerDref(DREF_LOCAL_VX, "sim/flightmodel/position/local_vx", 100); + registerDref(DREF_LOCAL_VY, "sim/flightmodel/position/local_vy", 100); + registerDref(DREF_LOCAL_VZ, "sim/flightmodel/position/local_vz", 100); + registerDref(DREF_GROUNDSPEED, "sim/flightmodel/position/groundspeed", 100); + registerDref(DREF_TRUE_AIRSPEED, "sim/flightmodel/position/true_airspeed", 100); + registerDref(DREF_POS_PHI, "sim/flightmodel/position/phi", 100); + registerDref(DREF_POS_THETA, "sim/flightmodel/position/theta", 100); + registerDref(DREF_POS_PSI, "sim/flightmodel/position/psi", 100); + registerDref(DREF_POS_HPATH, "sim/flightmodel/position/hpath", 100); + registerDref(DREF_FORCE_G_AXI1, "sim/flightmodel/forces/g_axil", 100); + registerDref(DREF_FORCE_G_SIDE, "sim/flightmodel/forces/g_side", 100); + registerDref(DREF_FORCE_G_NRML, "sim/flightmodel/forces/g_nrml", 100); + registerDref(DREF_POS_P, "sim/flightmodel/position/P", 100); + registerDref(DREF_POS_Q, "sim/flightmodel/position/Q", 100); + registerDref(DREF_POS_R, "sim/flightmodel/position/R", 100); + registerDref(DREF_POS_BARO_CURRENT_INHG, "sim/weather/barometer_current_inhg", 100); + delay(250); } return true; - } \ No newline at end of file diff --git a/src/main/target/SITL/target.c b/src/main/target/SITL/target.c index 5c7a3f7b23..7717fc7cbc 100644 --- a/src/main/target/SITL/target.c +++ b/src/main/target/SITL/target.c @@ -44,6 +44,7 @@ #include "drivers/pwm_mapping.h" #include "drivers/timer.h" #include "drivers/serial.h" +#include "config/config_streamer.h" #include "target/SITL/sim/realFlight.h" #include "target/SITL/sim/xplane.h" @@ -66,46 +67,46 @@ static int simPort = 0; void systemInit(void) { - printf("INAV %d.%d.%d SITL\n", FC_VERSION_MAJOR, FC_VERSION_MINOR, FC_VERSION_PATCH_LEVEL); + fprintf(stderr, "INAV %d.%d.%d SITL\n", FC_VERSION_MAJOR, FC_VERSION_MINOR, FC_VERSION_PATCH_LEVEL); clock_gettime(CLOCK_MONOTONIC, &start_time); - printf("[SYSTEM] Init...\n"); + fprintf(stderr, "[SYSTEM] Init...\n"); if (pthread_mutex_init(&mainLoopLock, NULL) != 0) { - printf("[SYSTEM] Unable to create mainLoop lock.\n"); + fprintf(stderr, "[SYSTEM] Unable to create mainLoop lock.\n"); exit(1); } if (sitlSim != SITL_SIM_NONE) { - printf("[SIM] Waiting for connection...\n"); + fprintf(stderr, "[SIM] Waiting for connection...\n"); } switch (sitlSim) { case SITL_SIM_REALFLIGHT: if (mappingCount > RF_MAX_PWM_OUTS) { - printf("[SIM] Mapping error. RealFligt supports a maximum of %i PWM outputs.", RF_MAX_PWM_OUTS); + fprintf(stderr, "[SIM] Mapping error. RealFligt supports a maximum of %i PWM outputs.", RF_MAX_PWM_OUTS); sitlSim = SITL_SIM_NONE; break; } if (simRealFlightInit(simIp, pwmMapping, mappingCount, useImu)) { - printf("[SIM] Connection with RealFlight (%s) successfully established. \n", simIp); + fprintf(stderr, "[SIM] Connection with RealFlight successfully established.\n"); } else { - printf("[SIM] Connection with RealFlight (%s) NOT established. \n", simIp); + fprintf(stderr, "[SIM] Connection with RealFlight NOT established.\n"); } break; case SITL_SIM_XPLANE: if (mappingCount > XP_MAX_PWM_OUTS) { - printf("[SIM] Mapping error. RealFligt supports a maximum of %i PWM outputs.", XP_MAX_PWM_OUTS); + fprintf(stderr, "[SIM] Mapping error. RealFligt supports a maximum of %i PWM outputs.", XP_MAX_PWM_OUTS); sitlSim = SITL_SIM_NONE; break; } if (simXPlaneInit(simIp, simPort, pwmMapping, mappingCount, useImu)) { - printf("[SIM] Connection with XPlane successfully established. \n"); + fprintf(stderr, "[SIM] Connection with X-Plane successfully established.\n"); } else { - printf("[SIM] Connection with XPLane NOT established. \n"); + fprintf(stderr, "[SIM] Connection with X-PLane NOT established.\n"); } break; default: - printf("[SIM] No interface specified. Configurator only.\n"); + fprintf(stderr, "[SIM] No interface specified. Configurator only.\n"); break; } @@ -149,21 +150,22 @@ bool parseMapping(char* mapStr) void printCmdLineOptions(void) { - printf("Avaiable options:\n"); - printf("--sim=[rf|xp] Simulator interface: rf = RealFligt, xp = XPlane. Example: --sim=rf\n"); - printf("--simip=[ip] IP-Address oft the simulator host. If not specified localhost (127.0.0.1) is used."); - printf("--simport=[port] Port oft the simulator host."); - printf("--useimu Use IMU sensor data from the simulator instead of using attitude data from the simulator directly (experimental, not recommended)."); - printf("--chanmap=[mapstring] Channel mapping, Maps INAVs motor and servo PWM outputs to the virtual receiver output in the simulator.\n"); - printf(" The mapstring has the following format: M(otor)|S(servo)-,)... All numbers must have two digits\n"); - printf(" For example map motor 1 to virtal receiver output 1, servo 1 to output 2 and servo 2 to output 3:\n"); - printf(" --chanmap=M01-01,S01-02,S02-03\n"); + fprintf(stderr, "Avaiable options:\n"); + fprintf(stderr, "--path=[path] Path and filename of eeprom.bin. If not specified 'eeprom.bin' in program directory is used.\n"); + fprintf(stderr, "--sim=[rf|xp] Simulator interface: rf = RealFligt, xp = XPlane. Example: --sim=rf\n"); + fprintf(stderr, "--simip=[ip] IP-Address oft the simulator host. If not specified localhost (127.0.0.1) is used.\n"); + fprintf(stderr, "--simport=[port] Port oft the simulator host.\n"); + fprintf(stderr, "--useimu Use IMU sensor data from the simulator instead of using attitude data from the simulator directly (experimental, not recommended).\n"); + fprintf(stderr, "--chanmap=[mapstring] Channel mapping, Maps INAVs motor and servo PWM outputs to the virtual receiver output in the simulator.\n"); + fprintf(stderr, " The mapstring has the following format: M(otor)|S(servo)-,)... All numbers must have two digits\n"); + fprintf(stderr, " For example map motor 1 to virtal receiver output 1, servo 1 to output 2 and servo 2 to output 3:\n"); + fprintf(stderr, " --chanmap=M01-01,S01-02,S02-03\n"); } void parseArguments(int argc, char *argv[]) { int c; - while(1) { + while(true) { static struct option longOpt[] = { {"sim", optional_argument, 0, 's'}, {"useimu", optional_argument, 0, 'u'}, @@ -171,6 +173,7 @@ void parseArguments(int argc, char *argv[]) {"simip", optional_argument, 0, 'i'}, {"simport", optional_argument, 0, 'p'}, {"help", optional_argument, 0, 'h'}, + {"path", optional_argument, 0, 'e'}, {NULL, 0, NULL, 0} }; @@ -185,13 +188,13 @@ void parseArguments(int argc, char *argv[]) } else if (strcmp(optarg, "xp") == 0){ sitlSim = SITL_SIM_XPLANE; } else { - printf("[SIM] Unsupported simulator %s.\n", optarg); + fprintf(stderr, "[SIM] Unsupported simulator %s.\n", optarg); } break; case 'c': if (!parseMapping(optarg) && sitlSim != SITL_SIM_NONE) { - printf("[SIM] Invalid channel mapping string.\n"); + fprintf(stderr, "[SIM] Invalid channel mapping string.\n"); printCmdLineOptions(); exit(0); } @@ -205,7 +208,11 @@ void parseArguments(int argc, char *argv[]) case 'i': simIp = optarg; break; - + case 'e': + if (!configFileSetPath(optarg)){ + fprintf(stderr, "[EEPROM] Invalid path, using eeprom file in program directory\n."); + } + break; case 'h': printCmdLineOptions(); exit(0); @@ -271,18 +278,18 @@ void delay(timeMs_t ms) void systemReset(void) { - printf("[SYSTEM] Reset\n"); + fprintf(stderr, "[SYSTEM] Reset\n"); exit(0); } void systemResetToBootloader(void) { - printf("[SYSTEM] Reset to bootloader\n"); + fprintf(stderr, "[SYSTEM] Reset to bootloader\n"); exit(0); } void failureMode(failureMode_e mode) { - printf("[SYSTEM] Failure mode %d\n", mode); + fprintf(stderr, "[SYSTEM] Failure mode %d\n", mode); while (1); } From 351c4ece088eb0b9ff787b43de3f9c139c26eede Mon Sep 17 00:00:00 2001 From: Scavanger Date: Thu, 23 Feb 2023 11:11:46 -0300 Subject: [PATCH 062/130] Revert "Bugfixes and prepare configurator integration" This reverts commit f330bdd6218849ec24bdfa3887cd49cb69f5211a. --- src/main/cms/cms_menu_navigation.c | 1 + src/main/common/time.c | 10 --- src/main/common/time.h | 1 + src/main/config/config_streamer.h | 4 - src/main/config/config_streamer_file.c | 36 ++++----- src/main/drivers/accgyro/accgyro_fake.c | 5 ++ src/main/fc/cli.c | 6 +- src/main/fc/fc_core.c | 6 +- src/main/fc/fc_msp.c | 4 + src/main/fc/settings.yaml | 18 ++--- src/main/flight/failsafe.c | 5 ++ src/main/flight/imu.c | 16 ++-- src/main/io/displayport_msp_bf_compat.c | 12 +-- src/main/navigation/navigation.c | 73 +++++++++++++++++-- src/main/navigation/navigation.h | 2 +- src/main/navigation/navigation_fixedwing.c | 25 +++++-- src/main/navigation/navigation_multicopter.c | 31 +++++--- .../navigation/navigation_pos_estimator.c | 2 +- src/main/navigation/navigation_private.h | 7 +- src/main/programming/logic_condition.c | 13 +++- src/main/programming/logic_condition.h | 2 + src/main/sensors/acceleration.c | 5 ++ src/main/target/IFLIGHT_BLITZ_F722/target.c | 2 +- src/main/target/MATEKF411TE/target.h | 4 + src/main/target/SITL/sim/realFlight.c | 2 +- src/main/target/SITL/sim/xplane.c | 59 ++++++++------- src/main/target/SITL/target.c | 61 +++++++--------- 27 files changed, 246 insertions(+), 166 deletions(-) diff --git a/src/main/cms/cms_menu_navigation.c b/src/main/cms/cms_menu_navigation.c index 33978f0118..d89cb2c249 100644 --- a/src/main/cms/cms_menu_navigation.c +++ b/src/main/cms/cms_menu_navigation.c @@ -50,6 +50,7 @@ static const OSD_Entry cmsx_menuNavSettingsEntries[] = OSD_SETTING_ENTRY("MC MAX BANK ANGLE", SETTING_NAV_MC_BANK_ANGLE), OSD_SETTING_ENTRY("MID THR FOR AH", SETTING_NAV_USE_MIDTHR_FOR_ALTHOLD), OSD_SETTING_ENTRY("MC HOVER THR", SETTING_NAV_MC_HOVER_THR), + OSD_SETTING_ENTRY("LANDING DISARM", SETTING_NAV_DISARM_ON_LANDING), OSD_BACK_AND_END_ENTRY, }; diff --git a/src/main/common/time.c b/src/main/common/time.c index 8214398d26..f1204c57f4 100644 --- a/src/main/common/time.c +++ b/src/main/common/time.c @@ -35,10 +35,6 @@ #include "fc/settings.h" -#ifdef SITL_BUILD -#include -#endif - // For the "modulo 4" arithmetic to work, we need a leap base year #define REFERENCE_YEAR 2000 // Offset (seconds) from the UNIX epoch (1970-01-01) to 2000-01-01 @@ -314,16 +310,11 @@ bool rtcHasTime(void) bool rtcGet(rtcTime_t *t) { -#ifdef SITL_BUILD - *t = (rtcTime_t)(time(NULL) * 1000); - return true; -#else if (!rtcHasTime()) { return false; } *t = started + millis(); return true; -#endif } bool rtcSet(rtcTime_t *t) @@ -332,7 +323,6 @@ bool rtcSet(rtcTime_t *t) return true; } - bool rtcGetDateTime(dateTime_t *dt) { rtcTime_t t; diff --git a/src/main/common/time.h b/src/main/common/time.h index 81bc4ceae5..82f2986077 100644 --- a/src/main/common/time.h +++ b/src/main/common/time.h @@ -51,6 +51,7 @@ typedef uint32_t timeUs_t; #define USECS_PER_SEC (1000 * 1000) #define HZ2US(hz) (1000000 / (hz)) +#define HZ2MS(hz) (1000 / (hz)) #define US2S(us) ((us) * 1e-6f) #define US2MS(us) ((us) * 1e-3f) #define MS2US(ms) ((ms) * 1000) diff --git a/src/main/config/config_streamer.h b/src/main/config/config_streamer.h index 33c0954874..87b688406f 100644 --- a/src/main/config/config_streamer.h +++ b/src/main/config/config_streamer.h @@ -57,7 +57,3 @@ int config_streamer_flush(config_streamer_t *c); int config_streamer_finish(config_streamer_t *c); int config_streamer_status(config_streamer_t *c); - -#if defined(CONFIG_IN_FILE) -bool configFileSetPath(char* path); -#endif diff --git a/src/main/config/config_streamer_file.c b/src/main/config/config_streamer_file.c index 379155c22e..c3fdbba95c 100644 --- a/src/main/config/config_streamer_file.c +++ b/src/main/config/config_streamer_file.c @@ -16,7 +16,6 @@ */ #include -#include #include "platform.h" #include "drivers/system.h" #include "config/config_streamer.h" @@ -27,32 +26,21 @@ #include #include - #define FLASH_PAGE_SIZE (0x400) static FILE *eepromFd = NULL; -static bool streamerLocked = true; -static char eepromPath[260] = EEPROM_FILENAME; -bool configFileSetPath(char* path) -{ - if(!path || strlen(path) > 260) { - return false; - } - - strcpy(eepromPath, path); - return true; -} +static bool streamerLocked = true; void config_streamer_impl_unlock(void) { if (eepromFd != NULL) { - fprintf(stderr, "[EEPROM] Unable to load %s\n", eepromPath); + fprintf(stderr, "[EEPROM] Unable to load %s\n", EEPROM_FILENAME); return; } // open or create - eepromFd = fopen(eepromPath,"r+"); + eepromFd = fopen(EEPROM_FILENAME,"r+"); if (eepromFd != NULL) { // obtain file size: fseek(eepromFd , 0 , SEEK_END); @@ -61,16 +49,16 @@ void config_streamer_impl_unlock(void) size_t n = fread(eepromData, 1, sizeof(eepromData), eepromFd); if (n == size) { - fprintf(stderr,"[EEPROM] Loaded '%s' (%ld of %ld bytes)\n", eepromPath, size, sizeof(eepromData)); + printf("[EEPROM] Loaded '%s' (%ld of %ld bytes)\n", EEPROM_FILENAME, size, sizeof(eepromData)); streamerLocked = false; } else { - fprintf(stderr, "[EEPROM] Failed to load '%s'\n", eepromPath); + fprintf(stderr, "[EEPROM] Failed to load '%s'\n", EEPROM_FILENAME); } } else { - printf("[EEPROM] Created '%s', size = %ld\n", eepromPath, sizeof(eepromData)); + printf("[EEPROM] Created '%s', size = %ld\n", EEPROM_FILENAME, sizeof(eepromData)); streamerLocked = false; - if ((eepromFd = fopen(eepromPath, "w+")) == NULL) { - fprintf(stderr, "[EEPROM] Failed to create '%s'\n", eepromPath); + if ((eepromFd = fopen(EEPROM_FILENAME, "w+")) == NULL) { + fprintf(stderr, "[EEPROM] Failed to create '%s'\n", EEPROM_FILENAME); streamerLocked = true; } if (fwrite(eepromData, sizeof(eepromData), 1, eepromFd) != 1) { @@ -78,6 +66,8 @@ void config_streamer_impl_unlock(void) streamerLocked = true; } } + + } void config_streamer_impl_lock(void) @@ -88,7 +78,7 @@ void config_streamer_impl_lock(void) fwrite(eepromData, 1, sizeof(eepromData), eepromFd); fclose(eepromFd); eepromFd = NULL; - fprintf(stderr, "[EEPROM] Saved '%s'\n", eepromPath); + printf("[EEPROM] Saved '%s'\n", EEPROM_FILENAME); streamerLocked = false; } else { fprintf(stderr, "[EEPROM] Unlock error\n"); @@ -103,9 +93,9 @@ int config_streamer_impl_write_word(config_streamer_t *c, config_streamer_buffer if ((c->address >= (uintptr_t)eepromData) && (c->address < (uintptr_t)ARRAYEND(eepromData))) { *((uint32_t*)c->address) = *buffer; - fprintf(stderr, "[EEPROM] Program word %p = %08x\n", (void*)c->address, *((uint32_t*)c->address)); + printf("[EEPROM] Program word %p = %08x\n", (void*)c->address, *((uint32_t*)c->address)); } else { - fprintf(stderr, "[EEPROM] Program word %p out of range!\n", (void*)c->address); + printf("[EEPROM] Program word %p out of range!\n", (void*)c->address); } c->address += CONFIG_STREAMER_BUFFER_SIZE; diff --git a/src/main/drivers/accgyro/accgyro_fake.c b/src/main/drivers/accgyro/accgyro_fake.c index 1389fa5433..92be492f74 100644 --- a/src/main/drivers/accgyro/accgyro_fake.c +++ b/src/main/drivers/accgyro/accgyro_fake.c @@ -39,6 +39,9 @@ static pthread_mutex_t gyroMutex; static pthread_mutex_t accMutex; +#define LOCK(mutex) (pthread_mutex_lock(mutex)) +#define UNLOCK(mutex) (pthread_mutex_unlock(mutex)) + #define GYROLOCK (pthread_mutex_lock(&gyroMutex)) #define GYROUNLOCK (pthread_mutex_unlock(&gyroMutex)) #define ACCLOCK (pthread_mutex_lock(&accMutex)) @@ -62,6 +65,8 @@ static void fakeGyroInit(gyroDev_t *gyro) #if defined(SITL_BUILD) pthread_mutex_init(&gyroMutex, NULL); #endif + + //ENABLE_STATE(ACCELEROMETER_CALIBRATED); } void fakeGyroSet(int16_t x, int16_t y, int16_t z) diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index ec45474d9f..297d6e6506 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -3417,11 +3417,7 @@ static void cliStatus(char *cmdline) cliPrint("OSD: "); #if defined(USE_OSD) displayPort_t *osdDisplayPort = osdGetDisplayPort(); - if (osdDisplayPort) { - cliPrintf("%s [%u x %u]", osdDisplayPort->displayPortType, osdDisplayPort->cols, osdDisplayPort->rows); - } else { - cliPrintf("no OSD detected"); - } + cliPrintf("%s [%u x %u]", osdDisplayPort->displayPortType, osdDisplayPort->cols, osdDisplayPort->rows); #else cliPrint("not used"); #endif diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index 620ec5203b..37d2c94dc5 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -839,7 +839,7 @@ void taskMainPidLoop(timeUs_t currentTimeUs) if (!ARMING_FLAG(ARMED)) { armTime = 0; - + processDelayedSave(); } @@ -867,7 +867,6 @@ void taskMainPidLoop(timeUs_t currentTimeUs) if (isRXDataNew) { updateWaypointsAndNavigationMode(); } - isRXDataNew = false; updatePositionEstimator(); @@ -930,10 +929,9 @@ void taskMainPidLoop(timeUs_t currentTimeUs) writeMotors(); } #endif - // Check if landed, FW and MR if (STATE(ALTITUDE_CONTROL)) { - updateLandingStatus(); + updateLandingStatus(US2MS(currentTimeUs)); } #ifdef USE_BLACKBOX diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 4946edc8e8..2c547b28b7 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -46,7 +46,11 @@ #include "drivers/compass/compass_msp.h" #include "drivers/barometer/barometer_msp.h" #include "drivers/pitotmeter/pitotmeter_msp.h" +#include "drivers/accgyro/accgyro_fake.h" +#include "drivers/barometer/barometer_fake.h" +#include "drivers/compass/compass_fake.h" #include "sensors/battery_sensor_fake.h" +#include "drivers/pitotmeter/pitotmeter_fake.h" #include "drivers/bus_i2c.h" #include "drivers/display.h" #include "drivers/flash.h" diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 08c64e5088..c6a0ac6259 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1393,22 +1393,22 @@ groups: type: imuConfig_t headers: ["flight/imu.h"] members: - - name: imu_dcm_kp + - name: ahrs_dcm_kp description: "Inertial Measurement Unit KP Gain for accelerometer measurements" default_value: 2000 field: dcm_kp_acc max: UINT16_MAX - - name: imu_dcm_ki + - name: ahrs_dcm_ki description: "Inertial Measurement Unit KI Gain for accelerometer measurements" default_value: 50 field: dcm_ki_acc max: UINT16_MAX - - name: imu_dcm_kp_mag + - name: ahrs_dcm_kp_mag description: "Inertial Measurement Unit KP Gain for compass measurements" default_value: 2000 field: dcm_kp_mag max: UINT16_MAX - - name: imu_dcm_ki_mag + - name: ahrs_dcm_ki_mag description: "Inertial Measurement Unit KI Gain for compass measurements" default_value: 50 field: dcm_ki_mag @@ -1418,24 +1418,24 @@ groups: default_value: 25 min: 0 max: 180 - - name: imu_acc_ignore_rate + - name: ahrs_acc_ignore_rate description: "Total gyro rotation rate threshold [deg/s] before scaling to consider accelerometer trustworthy" default_value: 15 field: acc_ignore_rate min: 0 max: 30 - - name: imu_acc_ignore_slope + - name: ahrs_acc_ignore_slope description: "Half-width of the interval to gradually reduce accelerometer weight. Centered at `imu_acc_ignore_rate` (exactly 50% weight)" default_value: 5 field: acc_ignore_slope min: 0 max: 10 - - name: imu_gps_yaw_windcomp + - name: ahrs_gps_yaw_windcomp description: "Wind compensation in heading estimation from gps groundcourse(fixed wing only)" default_value: ON field: gps_yaw_windcomp type: bool - - name: imu_inertia_comp_method + - name: ahrs_inertia_comp_method description: "Inertia force compensation method when gps is avaliable, VELNED use the accleration from gps, TURNRATE calculates accleration by turnrate multiplied by speed, ADAPTIVE choose best result from two in each ahrs loop" default_value: VELNED field: inertia_comp_method @@ -2563,7 +2563,7 @@ groups: max: 45 - name: nav_auto_disarm_delay description: "Delay before craft disarms when `nav_disarm_on_landing` is set (ms)" - default_value: 2000 + default_value: 1000 field: general.auto_disarm_delay min: 100 max: 10000 diff --git a/src/main/flight/failsafe.c b/src/main/flight/failsafe.c index 097e5c3a99..ab48fba2c6 100644 --- a/src/main/flight/failsafe.c +++ b/src/main/flight/failsafe.c @@ -346,6 +346,11 @@ static failsafeProcedure_e failsafeChooseFailsafeProcedure(void) } } + // Inhibit Failsafe if emergency landing triggered manually + if (posControl.flags.manualEmergLandActive) { + return FAILSAFE_PROCEDURE_NONE; + } + // Craft is closer than minimum failsafe procedure distance (if set to non-zero) // GPS must also be working, and home position set if (failsafeConfig()->failsafe_min_distance > 0 && diff --git a/src/main/flight/imu.c b/src/main/flight/imu.c index 89467545f8..3b54df3a02 100644 --- a/src/main/flight/imu.c +++ b/src/main/flight/imu.c @@ -116,15 +116,15 @@ FASTRAM bool imuUpdated = false; PG_REGISTER_WITH_RESET_TEMPLATE(imuConfig_t, imuConfig, PG_IMU_CONFIG, 2); PG_RESET_TEMPLATE(imuConfig_t, imuConfig, - .dcm_kp_acc = SETTING_IMU_DCM_KP_DEFAULT, // 0.20 * 10000 - .dcm_ki_acc = SETTING_IMU_DCM_KI_DEFAULT, // 0.005 * 10000 - .dcm_kp_mag = SETTING_IMU_DCM_KP_MAG_DEFAULT, // 0.20 * 10000 - .dcm_ki_mag = SETTING_IMU_DCM_KI_MAG_DEFAULT, // 0.005 * 10000 + .dcm_kp_acc = SETTING_AHRS_DCM_KP_DEFAULT, // 0.20 * 10000 + .dcm_ki_acc = SETTING_AHRS_DCM_KI_DEFAULT, // 0.005 * 10000 + .dcm_kp_mag = SETTING_AHRS_DCM_KP_MAG_DEFAULT, // 0.20 * 10000 + .dcm_ki_mag = SETTING_AHRS_DCM_KI_MAG_DEFAULT, // 0.005 * 10000 .small_angle = SETTING_SMALL_ANGLE_DEFAULT, - .acc_ignore_rate = SETTING_IMU_ACC_IGNORE_RATE_DEFAULT, - .acc_ignore_slope = SETTING_IMU_ACC_IGNORE_SLOPE_DEFAULT, - .gps_yaw_windcomp = 1, - .inertia_comp_method = COMPMETHOD_VELNED + .acc_ignore_rate = SETTING_AHRS_ACC_IGNORE_RATE_DEFAULT, + .acc_ignore_slope = SETTING_AHRS_ACC_IGNORE_SLOPE_DEFAULT, + .gps_yaw_windcomp = SETTING_AHRS_GPS_YAW_WINDCOMP_DEFAULT, + .inertia_comp_method = SETTING_AHRS_INERTIA_COMP_METHOD_DEFAULT ); STATIC_UNIT_TESTED void imuComputeRotationMatrix(void) diff --git a/src/main/io/displayport_msp_bf_compat.c b/src/main/io/displayport_msp_bf_compat.c index 29a85b6718..b6b1fe9d81 100644 --- a/src/main/io/displayport_msp_bf_compat.c +++ b/src/main/io/displayport_msp_bf_compat.c @@ -228,12 +228,6 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) case SYM_WIND_VERTICAL: return BF_SYM_WIND_VERTICAL; - case SYM_3D_KMH: - return BF_SYM_3D_KMH; - - case SYM_3D_MPH: - return BF_SYM_3D_MPH; - case SYM_3D_KT: return BF_SYM_3D_KT; @@ -242,6 +236,12 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) return BF_SYM_AIR; */ + case SYM_3D_KMH: + return BF_SYM_KPH; + + case SYM_3D_MPH: + return BF_SYM_MPH; + case SYM_RPM: return BF_SYM_RPM; diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 3b55a2414b..e164b33ab5 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -1774,9 +1774,13 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_WAYPOINT_FINISHED(navig static navigationFSMEvent_t navOnEnteringState_NAV_STATE_EMERGENCY_LANDING_INITIALIZE(navigationFSMState_t previousState) { - // TODO: UNUSED(previousState); + if ((posControl.flags.estPosStatus >= EST_USABLE)) { + resetPositionController(); + setDesiredPosition(&navGetCurrentActualPositionAndVelocity()->pos, 0, NAV_POS_UPDATE_XY); + } + // Emergency landing MAY use common altitude controller if vertical position is valid - initialize it // Make sure terrain following is not enabled resetAltitudeController(false); @@ -1788,6 +1792,14 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_EMERGENCY_LANDING_IN_PR { UNUSED(previousState); + // Reset target position if too far away for some reason, e.g. GPS recovered since start landing. + if (posControl.flags.estPosStatus >= EST_USABLE) { + float targetPosLimit = STATE(MULTIROTOR) ? 2000.0f : navConfig()->fw.loiter_radius * 2.0f; + if (calculateDistanceToDestination(&posControl.desiredState.pos) > targetPosLimit) { + setDesiredPosition(&navGetCurrentActualPositionAndVelocity()->pos, 0, NAV_POS_UPDATE_XY); + } + } + if (STATE(LANDING_DETECTED)) { return NAV_FSM_EVENT_SUCCESS; } @@ -2801,12 +2813,18 @@ void calculateFarAwayTarget(fpVector3_t * farAwayPos, int32_t bearing, int32_t d /*----------------------------------------------------------- * NAV land detector *-----------------------------------------------------------*/ -void updateLandingStatus(void) +void updateLandingStatus(timeMs_t currentTimeMs) { if (STATE(AIRPLANE) && !navConfig()->general.flags.disarm_on_landing) { return; // no point using this with a fixed wing if not set to disarm } + static timeMs_t lastUpdateTimeMs = 0; + if ((currentTimeMs - lastUpdateTimeMs) <= HZ2MS(100)) { // limit update to 100Hz + return; + } + lastUpdateTimeMs = currentTimeMs; + static bool landingDetectorIsActive; DEBUG_SET(DEBUG_LANDING, 0, landingDetectorIsActive); @@ -2831,7 +2849,7 @@ void updateLandingStatus(void) if (navConfig()->general.flags.disarm_on_landing) { ENABLE_ARMING_FLAG(ARMING_DISABLED_LANDING_DETECTED); disarm(DISARM_LANDING); - } else if (!navigationIsFlyingAutonomousMode()) { + } else if (!navigationInAutomaticThrottleMode()) { // for multirotor only - reactivate landing detector without disarm when throttle raised toward hover throttle landingDetectorIsActive = rxGetChannelValue(THROTTLE) < (0.5 * (currentBatteryProfile->nav.mc.hover_throttle + getThrottleIdleValue())); } @@ -3415,7 +3433,10 @@ bool isNavHoldPositionActive(void) return isLastMissionWaypoint() || NAV_Status.state == MW_NAV_STATE_HOLD_TIMED; } // RTH mode (spiral climb and Home positions but excluding RTH Trackback point positions) and POSHOLD mode - return (FLIGHT_MODE(NAV_RTH_MODE) && !posControl.flags.rthTrackbackActive) || FLIGHT_MODE(NAV_POSHOLD_MODE); + // Also hold position during emergency landing if position valid + return (FLIGHT_MODE(NAV_RTH_MODE) && !posControl.flags.rthTrackbackActive) || + FLIGHT_MODE(NAV_POSHOLD_MODE) || + navigationIsExecutingAnEmergencyLanding(); } float getActiveWaypointSpeed(void) @@ -3514,6 +3535,7 @@ void applyWaypointNavigationAndAltitudeHold(void) // If we are disarmed, abort forced RTH or Emergency Landing posControl.flags.forcedRTHActivated = false; posControl.flags.forcedEmergLandingActivated = false; + posControl.flags.manualEmergLandActive = false; // ensure WP missions always restart from first waypoint after disarm posControl.activeWaypointIndex = posControl.startWpIndex; // Reset RTH trackback @@ -3590,6 +3612,41 @@ static bool isWaypointMissionValid(void) return posControl.waypointListValid && (posControl.waypointCount > 0); } +static void checkManualEmergencyLandingControl(void) +{ + static timeMs_t timeout = 0; + static int8_t counter = 0; + static bool toggle; + timeMs_t currentTimeMs = millis(); + + if (timeout && currentTimeMs > timeout) { + timeout += 1000; + counter -= counter ? 1 : 0; + if (!counter) { + timeout = 0; + } + } + if (IS_RC_MODE_ACTIVE(BOXNAVPOSHOLD)) { + if (!timeout && toggle) { + timeout = currentTimeMs + 4000; + } + counter += toggle; + toggle = false; + } else { + toggle = true; + } + + // Emergency landing toggled ON or OFF after 5 cycles of Poshold mode @ 1Hz minimum rate + if (counter >= 5) { + counter = 0; + posControl.flags.manualEmergLandActive = !posControl.flags.manualEmergLandActive; + + if (!posControl.flags.manualEmergLandActive) { + navProcessFSMEvents(NAV_FSM_EVENT_SWITCH_TO_IDLE); + } + } +} + static navigationFSMEvent_t selectNavEventFromBoxModeInput(void) { static bool canActivateWaypoint = false; @@ -3615,8 +3672,12 @@ static navigationFSMEvent_t selectNavEventFromBoxModeInput(void) posControl.flags.rthTrackbackActive = isExecutingRTH; } - /* Emergency landing triggered by failsafe when Failsafe procedure set to Landing */ - if (posControl.flags.forcedEmergLandingActivated) { + /* Emergency landing controlled manually by rapid switching of Poshold mode. + * Landing toggled ON or OFF for each Poshold activation sequence */ + checkManualEmergencyLandingControl(); + + /* Emergency landing triggered by failsafe Landing or manually initiated */ + if (posControl.flags.forcedEmergLandingActivated || posControl.flags.manualEmergLandActive) { return NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING; } diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h index b55bc15a4d..84255421be 100644 --- a/src/main/navigation/navigation.h +++ b/src/main/navigation/navigation.h @@ -606,7 +606,7 @@ const char * fixedWingLaunchStateMessage(void); float calculateAverageSpeed(void); -void updateLandingStatus(void); +void updateLandingStatus(timeMs_t currentTimeMs); const navigationPIDControllers_t* getNavigationPIDControllers(void); diff --git a/src/main/navigation/navigation_fixedwing.c b/src/main/navigation/navigation_fixedwing.c index 99fccb1e10..9160669365 100755 --- a/src/main/navigation/navigation_fixedwing.c +++ b/src/main/navigation/navigation_fixedwing.c @@ -711,7 +711,7 @@ bool isFixedWingLandingDetected(void) static int16_t fwLandSetPitchDatum; const float sensitivity = navConfig()->general.land_detect_sensitivity / 5.0f; - timeMs_t currentTimeMs = millis(); + const timeMs_t currentTimeMs = millis(); // Check horizontal and vertical velocities are low (cm/s) bool velCondition = fabsf(navGetCurrentActualPositionAndVelocity()->vel.z) < (50.0f * sensitivity) && @@ -736,9 +736,12 @@ bool isFixedWingLandingDetected(void) DEBUG_SET(DEBUG_LANDING, 6, isRollAxisStatic); DEBUG_SET(DEBUG_LANDING, 7, isPitchAxisStatic); if (isRollAxisStatic && isPitchAxisStatic) { - // Probably landed, low horizontal and vertical velocities and no axis rotation in Roll and Pitch - timeMs_t safetyTimeDelay = 2000 + navConfig()->general.auto_disarm_delay; - return currentTimeMs - fwLandingTimerStartAt > safetyTimeDelay; // check conditions stable for 2s + optional extra delay + /* Probably landed, low horizontal and vertical velocities and no axis rotation in Roll and Pitch + * Conditions need to be held for fixed safety time + optional extra delay. + * Fixed time increased if velocities invalid to provide extra safety margin against false triggers */ + const uint16_t safetyTime = posControl.flags.estAltStatus == EST_NONE || posControl.flags.estVelStatus == EST_NONE ? 5000 : 1000; + timeMs_t safetyTimeDelay = safetyTime + navConfig()->general.auto_disarm_delay; + return currentTimeMs - fwLandingTimerStartAt > safetyTimeDelay; } else { fixAxisCheck = false; } @@ -752,8 +755,6 @@ bool isFixedWingLandingDetected(void) *-----------------------------------------------------------*/ void applyFixedWingEmergencyLandingController(timeUs_t currentTimeUs) { - rcCommand[ROLL] = pidAngleToRcCommand(failsafeConfig()->failsafe_fw_roll_angle, pidProfile()->max_angle_inclination[FD_ROLL]); - rcCommand[YAW] = -pidRateToRcCommand(failsafeConfig()->failsafe_fw_yaw_rate, currentControlRateProfile->stabilized.rates[FD_YAW]); rcCommand[THROTTLE] = currentBatteryProfile->failsafe_throttle; if (posControl.flags.estAltStatus >= EST_USABLE) { @@ -765,6 +766,18 @@ void applyFixedWingEmergencyLandingController(timeUs_t currentTimeUs) } else { rcCommand[PITCH] = pidAngleToRcCommand(failsafeConfig()->failsafe_fw_pitch_angle, pidProfile()->max_angle_inclination[FD_PITCH]); } + + if (posControl.flags.estPosStatus >= EST_USABLE) { // Hold position if possible + applyFixedWingPositionController(currentTimeUs); + int16_t rollCorrection = constrain(posControl.rcAdjustment[ROLL], + -DEGREES_TO_DECIDEGREES(navConfig()->fw.max_bank_angle), + DEGREES_TO_DECIDEGREES(navConfig()->fw.max_bank_angle)); + rcCommand[ROLL] = pidAngleToRcCommand(rollCorrection, pidProfile()->max_angle_inclination[FD_ROLL]); + rcCommand[YAW] = 0; + } else { + rcCommand[ROLL] = pidAngleToRcCommand(failsafeConfig()->failsafe_fw_roll_angle, pidProfile()->max_angle_inclination[FD_ROLL]); + rcCommand[YAW] = -pidRateToRcCommand(failsafeConfig()->failsafe_fw_yaw_rate, currentControlRateProfile->stabilized.rates[FD_YAW]); + } } /*----------------------------------------------------------- diff --git a/src/main/navigation/navigation_multicopter.c b/src/main/navigation/navigation_multicopter.c index b40282961f..ae53d0961b 100644 --- a/src/main/navigation/navigation_multicopter.c +++ b/src/main/navigation/navigation_multicopter.c @@ -723,7 +723,7 @@ bool isMulticopterFlying(void) bool isMulticopterLandingDetected(void) { DEBUG_SET(DEBUG_LANDING, 4, 0); - static timeUs_t landingDetectorStartedAt; + static timeMs_t landingDetectorStartedAt; /* Basic condition to start looking for landing * Prevent landing detection if WP mission allowed during Failsafe (except landing states) */ @@ -747,7 +747,7 @@ bool isMulticopterLandingDetected(void) DEBUG_SET(DEBUG_LANDING, 3, gyroCondition); bool possibleLandingDetected = false; - const timeUs_t currentTimeUs = micros(); + const timeMs_t currentTimeMs = millis(); if (navGetCurrentStateFlags() & NAV_CTL_LAND) { // We have likely landed if throttle is 40 units below average descend throttle @@ -761,13 +761,13 @@ bool isMulticopterLandingDetected(void) if (!landingDetectorStartedAt) { landingThrSum = landingThrSamples = 0; - landingDetectorStartedAt = currentTimeUs; + landingDetectorStartedAt = currentTimeMs; } if (!landingThrSamples) { - if (currentTimeUs - landingDetectorStartedAt < (USECS_PER_SEC * MC_LAND_THR_STABILISE_DELAY)) { // Wait for 1 second so throttle has stabilized. + if (currentTimeMs - landingDetectorStartedAt < S2MS(MC_LAND_THR_STABILISE_DELAY)) { // Wait for 1 second so throttle has stabilized. return false; } else { - landingDetectorStartedAt = currentTimeUs; + landingDetectorStartedAt = currentTimeMs; } } landingThrSamples += 1; @@ -783,7 +783,7 @@ bool isMulticopterLandingDetected(void) if (landingDetectorStartedAt) { possibleLandingDetected = velCondition && gyroCondition; } else { - landingDetectorStartedAt = currentTimeUs; + landingDetectorStartedAt = currentTimeMs; return false; } } @@ -798,10 +798,13 @@ bool isMulticopterLandingDetected(void) DEBUG_SET(DEBUG_LANDING, 5, possibleLandingDetected); if (possibleLandingDetected) { - timeUs_t safetyTimeDelay = MS2US(2000 + navConfig()->general.auto_disarm_delay); // check conditions stable for 2s + optional extra delay - return (currentTimeUs - landingDetectorStartedAt > safetyTimeDelay); + /* Conditions need to be held for fixed safety time + optional extra delay. + * Fixed time increased if Z velocity invalid to provide extra safety margin against false triggers */ + const uint16_t safetyTime = posControl.flags.estAltStatus == EST_NONE ? 5000 : 1000; + timeMs_t safetyTimeDelay = safetyTime + navConfig()->general.auto_disarm_delay; + return currentTimeMs - landingDetectorStartedAt > safetyTimeDelay; } else { - landingDetectorStartedAt = currentTimeUs; + landingDetectorStartedAt = currentTimeMs; return false; } } @@ -814,8 +817,6 @@ static void applyMulticopterEmergencyLandingController(timeUs_t currentTimeUs) static timeUs_t previousTimePositionUpdate = 0; /* Attempt to stabilise */ - rcCommand[ROLL] = 0; - rcCommand[PITCH] = 0; rcCommand[YAW] = 0; if ((posControl.flags.estAltStatus < EST_USABLE)) { @@ -852,6 +853,14 @@ static void applyMulticopterEmergencyLandingController(timeUs_t currentTimeUs) // Update throttle controller rcCommand[THROTTLE] = posControl.rcAdjustment[THROTTLE]; + + // Hold position if possible + if ((posControl.flags.estPosStatus >= EST_USABLE)) { + applyMulticopterPositionController(currentTimeUs); + } else { + rcCommand[ROLL] = 0; + rcCommand[PITCH] = 0; + } } /*----------------------------------------------------------- diff --git a/src/main/navigation/navigation_pos_estimator.c b/src/main/navigation/navigation_pos_estimator.c index 0d0ecfb91c..57443ebffd 100755 --- a/src/main/navigation/navigation_pos_estimator.c +++ b/src/main/navigation/navigation_pos_estimator.c @@ -241,7 +241,7 @@ void onNewGPSData(void) /* Use VELNED provided by GPS if available, calculate from coordinates otherwise */ float gpsScaleLonDown = constrainf(cos_approx((ABS(gpsSol.llh.lat) / 10000000.0f) * 0.0174532925f), 0.01f, 1.0f); - if (!ARMING_FLAG(SIMULATOR_MODE_SITL) && positionEstimationConfig()->use_gps_velned && gpsSol.flags.validVelNE) { + if (positionEstimationConfig()->use_gps_velned && gpsSol.flags.validVelNE) { posEstimator.gps.vel.x = gpsSol.velNED[X]; posEstimator.gps.vel.y = gpsSol.velNED[Y]; } diff --git a/src/main/navigation/navigation_private.h b/src/main/navigation/navigation_private.h index 44fc1796fd..0598467d28 100644 --- a/src/main/navigation/navigation_private.h +++ b/src/main/navigation/navigation_private.h @@ -42,7 +42,7 @@ #define MC_LAND_CHECK_VEL_XY_MOVING 100.0f // cm/s #define MC_LAND_CHECK_VEL_Z_MOVING 100.0f // cm/s #define MC_LAND_THR_STABILISE_DELAY 1 // seconds -#define MC_LAND_DESCEND_THROTTLE 40 // uS +#define MC_LAND_DESCEND_THROTTLE 40 // RC pwm units (us) #define MC_LAND_SAFE_SURFACE 5.0f // cm #define NAV_RTH_TRACKBACK_POINTS 50 // max number RTH trackback points @@ -104,14 +104,13 @@ typedef struct navigationFlags_s { bool forcedRTHActivated; bool forcedEmergLandingActivated; - bool wpMissionPlannerActive; // Activation status of WP mission planner - /* Landing detector */ bool resetLandingDetector; + bool wpMissionPlannerActive; // Activation status of WP mission planner bool rthTrackbackActive; // Activation status of RTH trackback - bool wpTurnSmoothingActive; // Activation status WP turn smoothing + bool manualEmergLandActive; // Activation status of manual emergency landing } navigationFlags_t; typedef struct { diff --git a/src/main/programming/logic_condition.c b/src/main/programming/logic_condition.c index 95e76eb774..f07e487f9c 100644 --- a/src/main/programming/logic_condition.c +++ b/src/main/programming/logic_condition.c @@ -811,12 +811,16 @@ static int logicConditionGetFlightModeOperandValue(int operand) { return (bool) FLIGHT_MODE(NAV_POSHOLD_MODE); break; + case LOGIC_CONDITION_OPERAND_FLIGHT_MODE_WAYPOINT_MISSION: + return (bool) FLIGHT_MODE(NAV_WP_MODE); + break; + case LOGIC_CONDITION_OPERAND_FLIGHT_MODE_COURSE_HOLD: - return (bool) FLIGHT_MODE(NAV_COURSE_HOLD_MODE); + return ((bool) FLIGHT_MODE(NAV_COURSE_HOLD_MODE) && !(bool)FLIGHT_MODE(NAV_ALTHOLD_MODE)); break; case LOGIC_CONDITION_OPERAND_FLIGHT_MODE_CRUISE: - return (bool)(FLIGHT_MODE(NAV_COURSE_HOLD_MODE) && FLIGHT_MODE(NAV_ALTHOLD_MODE)); + return (bool) (FLIGHT_MODE(NAV_COURSE_HOLD_MODE) && FLIGHT_MODE(NAV_ALTHOLD_MODE)); break; case LOGIC_CONDITION_OPERAND_FLIGHT_MODE_ALTHOLD: @@ -835,6 +839,11 @@ static int logicConditionGetFlightModeOperandValue(int operand) { return (bool) FLIGHT_MODE(AIRMODE_ACTIVE); break; + case LOGIC_CONDITION_OPERAND_FLIGHT_MODE_ACRO: + return (((bool) FLIGHT_MODE(ANGLE_MODE) || (bool) FLIGHT_MODE(HORIZON_MODE) || (bool) FLIGHT_MODE(MANUAL_MODE) || (bool) FLIGHT_MODE(NAV_RTH_MODE) || + (bool) FLIGHT_MODE(NAV_POSHOLD_MODE) || (bool) FLIGHT_MODE(NAV_COURSE_HOLD_MODE) || (bool) FLIGHT_MODE(NAV_WP_MODE)) == false); + break; + case LOGIC_CONDITION_OPERAND_FLIGHT_MODE_USER1: return IS_RC_MODE_ACTIVE(BOXUSER1); break; diff --git a/src/main/programming/logic_condition.h b/src/main/programming/logic_condition.h index 1aaae7da0a..779dbb1b98 100644 --- a/src/main/programming/logic_condition.h +++ b/src/main/programming/logic_condition.h @@ -152,6 +152,8 @@ typedef enum { LOGIC_CONDITION_OPERAND_FLIGHT_MODE_COURSE_HOLD, // 11 LOGIC_CONDITION_OPERAND_FLIGHT_MODE_USER3, // 12 LOGIC_CONDITION_OPERAND_FLIGHT_MODE_USER4, // 13 + LOGIC_CONDITION_OPERAND_FLIGHT_MODE_ACRO, // 14 + LOGIC_CONDITION_OPERAND_FLIGHT_MODE_WAYPOINT_MISSION, // 15 } logicFlightModeOperands_e; typedef enum { diff --git a/src/main/sensors/acceleration.c b/src/main/sensors/acceleration.c index 6a63c6cb88..ed125f36c3 100644 --- a/src/main/sensors/acceleration.c +++ b/src/main/sensors/acceleration.c @@ -520,6 +520,11 @@ void accUpdate(void) if (!ARMING_FLAG(SIMULATOR_MODE_SITL)) { performAcclerationCalibration(); + + applyAccelerationZero(&accelerometerConfig()->accZero, &accelerometerConfig()->accGain); + applyAccelerationZero(&accelerometerConfig()->accZero, &accelerometerConfig()->accGain); + applyAccelerationZero(&accelerometerConfig()->accZero, &accelerometerConfig()->accGain); + applyAccelerationZero(&accelerometerConfig()->accZero, &accelerometerConfig()->accGain); applyAccelerationZero(&accelerometerConfig()->accZero, &accelerometerConfig()->accGain); } diff --git a/src/main/target/IFLIGHT_BLITZ_F722/target.c b/src/main/target/IFLIGHT_BLITZ_F722/target.c index 0986053b6d..8bba266c36 100644 --- a/src/main/target/IFLIGHT_BLITZ_F722/target.c +++ b/src/main/target/IFLIGHT_BLITZ_F722/target.c @@ -35,7 +35,7 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM2, CH4, PB11, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S8 DMA1_S6_CH3 - DEF_TIM(TIM1, CH2N, PB0, TIM_USE_LED, 0, 0), // WS2812B DMA2_S6_CH0 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // WS2812B }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/MATEKF411TE/target.h b/src/main/target/MATEKF411TE/target.h index a410a2c135..7ecb2d1cb6 100644 --- a/src/main/target/MATEKF411TE/target.h +++ b/src/main/target/MATEKF411TE/target.h @@ -38,6 +38,10 @@ #define BMI270_CS_PIN PC13 #define IMU_BMI270_ALIGN CW270_DEG_FLIP +#define USE_IMU_ICM42605 +#define ICM42605_SPI_BUS BUS_SPI2 +#define ICM42605_CS_PIN PC13 +#define IMU_ICM42605_ALIGN CW180_DEG_FLIP #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI2 diff --git a/src/main/target/SITL/sim/realFlight.c b/src/main/target/SITL/sim/realFlight.c index b57193d32b..4289d87d25 100644 --- a/src/main/target/SITL/sim/realFlight.c +++ b/src/main/target/SITL/sim/realFlight.c @@ -414,7 +414,7 @@ bool simRealFlightInit(char* ip, uint8_t* mapping, uint8_t mapCount, bool imu) // Wait until the connection is established, the interface has been initialised // and the first valid packet has been received to avoid problems with the startup calibration. while (!isInitalised) { - delay(250); + // ... } return true; diff --git a/src/main/target/SITL/sim/xplane.c b/src/main/target/SITL/sim/xplane.c index bc54166e1d..70ecb3361f 100644 --- a/src/main/target/SITL/sim/xplane.c +++ b/src/main/target/SITL/sim/xplane.c @@ -184,11 +184,11 @@ static void* listenWorker(void* arg) recvLen = recvfrom(sockFd, buf, sizeof(buf), 0, (struct sockaddr*)&remoteAddr, &slen); if (recvLen < 0 && errno != EWOULDBLOCK) { - continue; + break; } if (strncmp((char*)buf, "RREF", 4) != 0) { - continue; + break; } for (int i = 5; i < recvLen; i += 8) { @@ -276,6 +276,7 @@ static void* listenWorker(void* arg) default: break; } + } if (hpath < 0) { @@ -327,9 +328,7 @@ static void* listenWorker(void* arg) fakeBattSensorSetVbat(16.8 * 100); if (!initalized) { - ENABLE_ARMING_FLAG(SIMULATOR_MODE_SITL); - // Aircraft can wobble on the runway and prevents calibration of the accelerometer - ENABLE_STATE(ACCELEROMETER_CALIBRATED); + ENABLE_ARMING_FLAG(SIMULATOR_MODE_SITL); initalized = true; } @@ -363,42 +362,42 @@ bool simXPlaneInit(char* ip, int port, uint8_t* mapping, uint8_t mapCount, bool return false; } - if (setsockopt(sockFd, SOL_SOCKET, SO_SNDTIMEO, (struct timeval *) &tv,sizeof(struct timeval))) { + if (bind(sockFd, (struct sockaddr *) &addr, sizeof(addr)) < 0) { return false; } - - bind(sockFd, (struct sockaddr *) &addr, sizeof(addr)); serverAddr.sin_family = AF_INET; serverAddr.sin_addr.s_addr = inet_addr(ip); serverAddr.sin_port = htons(port); - + + registerDref(DREF_LATITUDE, "sim/flightmodel/position/latitude", 100); + registerDref(DREF_LONGITUDE, "sim/flightmodel/position/longitude", 100); + registerDref(DREF_ELEVATION, "sim/flightmodel/position/elevation", 100); + registerDref(DREF_LOCAL_VX, "sim/flightmodel/position/local_vx", 100); + registerDref(DREF_LOCAL_VY, "sim/flightmodel/position/local_vy", 100); + registerDref(DREF_LOCAL_VZ, "sim/flightmodel/position/local_vz", 100); + registerDref(DREF_GROUNDSPEED, "sim/flightmodel/position/groundspeed", 100); + registerDref(DREF_TRUE_AIRSPEED, "sim/flightmodel/position/true_airspeed", 100); + registerDref(DREF_POS_PHI, "sim/flightmodel/position/phi", 100); + registerDref(DREF_POS_THETA, "sim/flightmodel/position/theta", 100); + registerDref(DREF_POS_PSI, "sim/flightmodel/position/psi", 100); + registerDref(DREF_POS_HPATH, "sim/flightmodel/position/hpath", 100); + registerDref(DREF_FORCE_G_AXI1, "sim/flightmodel/forces/g_axil", 100); + registerDref(DREF_FORCE_G_SIDE, "sim/flightmodel/forces/g_side", 100); + registerDref(DREF_FORCE_G_NRML, "sim/flightmodel/forces/g_nrml", 100); + registerDref(DREF_POS_P, "sim/flightmodel/position/P", 100); + registerDref(DREF_POS_Q, "sim/flightmodel/position/Q", 100); + registerDref(DREF_POS_R, "sim/flightmodel/position/R", 100); + registerDref(DREF_POS_BARO_CURRENT_INHG, "sim/weather/barometer_current_inhg", 100); + if (pthread_create(&listenThread, NULL, listenWorker, NULL) < 0) { return false; } - while (!initalized) { - registerDref(DREF_LATITUDE, "sim/flightmodel/position/latitude", 100); - registerDref(DREF_LONGITUDE, "sim/flightmodel/position/longitude", 100); - registerDref(DREF_ELEVATION, "sim/flightmodel/position/elevation", 100); - registerDref(DREF_LOCAL_VX, "sim/flightmodel/position/local_vx", 100); - registerDref(DREF_LOCAL_VY, "sim/flightmodel/position/local_vy", 100); - registerDref(DREF_LOCAL_VZ, "sim/flightmodel/position/local_vz", 100); - registerDref(DREF_GROUNDSPEED, "sim/flightmodel/position/groundspeed", 100); - registerDref(DREF_TRUE_AIRSPEED, "sim/flightmodel/position/true_airspeed", 100); - registerDref(DREF_POS_PHI, "sim/flightmodel/position/phi", 100); - registerDref(DREF_POS_THETA, "sim/flightmodel/position/theta", 100); - registerDref(DREF_POS_PSI, "sim/flightmodel/position/psi", 100); - registerDref(DREF_POS_HPATH, "sim/flightmodel/position/hpath", 100); - registerDref(DREF_FORCE_G_AXI1, "sim/flightmodel/forces/g_axil", 100); - registerDref(DREF_FORCE_G_SIDE, "sim/flightmodel/forces/g_side", 100); - registerDref(DREF_FORCE_G_NRML, "sim/flightmodel/forces/g_nrml", 100); - registerDref(DREF_POS_P, "sim/flightmodel/position/P", 100); - registerDref(DREF_POS_Q, "sim/flightmodel/position/Q", 100); - registerDref(DREF_POS_R, "sim/flightmodel/position/R", 100); - registerDref(DREF_POS_BARO_CURRENT_INHG, "sim/weather/barometer_current_inhg", 100); - delay(250); + while(!initalized) { + // } return true; + } \ No newline at end of file diff --git a/src/main/target/SITL/target.c b/src/main/target/SITL/target.c index 7717fc7cbc..5c7a3f7b23 100644 --- a/src/main/target/SITL/target.c +++ b/src/main/target/SITL/target.c @@ -44,7 +44,6 @@ #include "drivers/pwm_mapping.h" #include "drivers/timer.h" #include "drivers/serial.h" -#include "config/config_streamer.h" #include "target/SITL/sim/realFlight.h" #include "target/SITL/sim/xplane.h" @@ -67,46 +66,46 @@ static int simPort = 0; void systemInit(void) { - fprintf(stderr, "INAV %d.%d.%d SITL\n", FC_VERSION_MAJOR, FC_VERSION_MINOR, FC_VERSION_PATCH_LEVEL); + printf("INAV %d.%d.%d SITL\n", FC_VERSION_MAJOR, FC_VERSION_MINOR, FC_VERSION_PATCH_LEVEL); clock_gettime(CLOCK_MONOTONIC, &start_time); - fprintf(stderr, "[SYSTEM] Init...\n"); + printf("[SYSTEM] Init...\n"); if (pthread_mutex_init(&mainLoopLock, NULL) != 0) { - fprintf(stderr, "[SYSTEM] Unable to create mainLoop lock.\n"); + printf("[SYSTEM] Unable to create mainLoop lock.\n"); exit(1); } if (sitlSim != SITL_SIM_NONE) { - fprintf(stderr, "[SIM] Waiting for connection...\n"); + printf("[SIM] Waiting for connection...\n"); } switch (sitlSim) { case SITL_SIM_REALFLIGHT: if (mappingCount > RF_MAX_PWM_OUTS) { - fprintf(stderr, "[SIM] Mapping error. RealFligt supports a maximum of %i PWM outputs.", RF_MAX_PWM_OUTS); + printf("[SIM] Mapping error. RealFligt supports a maximum of %i PWM outputs.", RF_MAX_PWM_OUTS); sitlSim = SITL_SIM_NONE; break; } if (simRealFlightInit(simIp, pwmMapping, mappingCount, useImu)) { - fprintf(stderr, "[SIM] Connection with RealFlight successfully established.\n"); + printf("[SIM] Connection with RealFlight (%s) successfully established. \n", simIp); } else { - fprintf(stderr, "[SIM] Connection with RealFlight NOT established.\n"); + printf("[SIM] Connection with RealFlight (%s) NOT established. \n", simIp); } break; case SITL_SIM_XPLANE: if (mappingCount > XP_MAX_PWM_OUTS) { - fprintf(stderr, "[SIM] Mapping error. RealFligt supports a maximum of %i PWM outputs.", XP_MAX_PWM_OUTS); + printf("[SIM] Mapping error. RealFligt supports a maximum of %i PWM outputs.", XP_MAX_PWM_OUTS); sitlSim = SITL_SIM_NONE; break; } if (simXPlaneInit(simIp, simPort, pwmMapping, mappingCount, useImu)) { - fprintf(stderr, "[SIM] Connection with X-Plane successfully established.\n"); + printf("[SIM] Connection with XPlane successfully established. \n"); } else { - fprintf(stderr, "[SIM] Connection with X-PLane NOT established.\n"); + printf("[SIM] Connection with XPLane NOT established. \n"); } break; default: - fprintf(stderr, "[SIM] No interface specified. Configurator only.\n"); + printf("[SIM] No interface specified. Configurator only.\n"); break; } @@ -150,22 +149,21 @@ bool parseMapping(char* mapStr) void printCmdLineOptions(void) { - fprintf(stderr, "Avaiable options:\n"); - fprintf(stderr, "--path=[path] Path and filename of eeprom.bin. If not specified 'eeprom.bin' in program directory is used.\n"); - fprintf(stderr, "--sim=[rf|xp] Simulator interface: rf = RealFligt, xp = XPlane. Example: --sim=rf\n"); - fprintf(stderr, "--simip=[ip] IP-Address oft the simulator host. If not specified localhost (127.0.0.1) is used.\n"); - fprintf(stderr, "--simport=[port] Port oft the simulator host.\n"); - fprintf(stderr, "--useimu Use IMU sensor data from the simulator instead of using attitude data from the simulator directly (experimental, not recommended).\n"); - fprintf(stderr, "--chanmap=[mapstring] Channel mapping, Maps INAVs motor and servo PWM outputs to the virtual receiver output in the simulator.\n"); - fprintf(stderr, " The mapstring has the following format: M(otor)|S(servo)-,)... All numbers must have two digits\n"); - fprintf(stderr, " For example map motor 1 to virtal receiver output 1, servo 1 to output 2 and servo 2 to output 3:\n"); - fprintf(stderr, " --chanmap=M01-01,S01-02,S02-03\n"); + printf("Avaiable options:\n"); + printf("--sim=[rf|xp] Simulator interface: rf = RealFligt, xp = XPlane. Example: --sim=rf\n"); + printf("--simip=[ip] IP-Address oft the simulator host. If not specified localhost (127.0.0.1) is used."); + printf("--simport=[port] Port oft the simulator host."); + printf("--useimu Use IMU sensor data from the simulator instead of using attitude data from the simulator directly (experimental, not recommended)."); + printf("--chanmap=[mapstring] Channel mapping, Maps INAVs motor and servo PWM outputs to the virtual receiver output in the simulator.\n"); + printf(" The mapstring has the following format: M(otor)|S(servo)-,)... All numbers must have two digits\n"); + printf(" For example map motor 1 to virtal receiver output 1, servo 1 to output 2 and servo 2 to output 3:\n"); + printf(" --chanmap=M01-01,S01-02,S02-03\n"); } void parseArguments(int argc, char *argv[]) { int c; - while(true) { + while(1) { static struct option longOpt[] = { {"sim", optional_argument, 0, 's'}, {"useimu", optional_argument, 0, 'u'}, @@ -173,7 +171,6 @@ void parseArguments(int argc, char *argv[]) {"simip", optional_argument, 0, 'i'}, {"simport", optional_argument, 0, 'p'}, {"help", optional_argument, 0, 'h'}, - {"path", optional_argument, 0, 'e'}, {NULL, 0, NULL, 0} }; @@ -188,13 +185,13 @@ void parseArguments(int argc, char *argv[]) } else if (strcmp(optarg, "xp") == 0){ sitlSim = SITL_SIM_XPLANE; } else { - fprintf(stderr, "[SIM] Unsupported simulator %s.\n", optarg); + printf("[SIM] Unsupported simulator %s.\n", optarg); } break; case 'c': if (!parseMapping(optarg) && sitlSim != SITL_SIM_NONE) { - fprintf(stderr, "[SIM] Invalid channel mapping string.\n"); + printf("[SIM] Invalid channel mapping string.\n"); printCmdLineOptions(); exit(0); } @@ -208,11 +205,7 @@ void parseArguments(int argc, char *argv[]) case 'i': simIp = optarg; break; - case 'e': - if (!configFileSetPath(optarg)){ - fprintf(stderr, "[EEPROM] Invalid path, using eeprom file in program directory\n."); - } - break; + case 'h': printCmdLineOptions(); exit(0); @@ -278,18 +271,18 @@ void delay(timeMs_t ms) void systemReset(void) { - fprintf(stderr, "[SYSTEM] Reset\n"); + printf("[SYSTEM] Reset\n"); exit(0); } void systemResetToBootloader(void) { - fprintf(stderr, "[SYSTEM] Reset to bootloader\n"); + printf("[SYSTEM] Reset to bootloader\n"); exit(0); } void failureMode(failureMode_e mode) { - fprintf(stderr, "[SYSTEM] Failure mode %d\n", mode); + printf("[SYSTEM] Failure mode %d\n", mode); while (1); } From aa999a6049c70811afd31d7ae2df9f10ca326f31 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Mon, 27 Feb 2023 12:39:59 +0000 Subject: [PATCH 063/130] Improved wind estimator - stale reading state --- src/main/io/osd.c | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 25e9bfd145..0cfb67321d 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -427,11 +427,12 @@ static void osdFormatWindSpeedStr(char *buff, int32_t ws, bool isValid) suffix = SYM_KMH; break; } + osdFormatCentiNumber(buff, centivalue, 0, 2, 0, 3); - if (!isValid) - { + + if (!isValid && ((millis() / 1000) % 4 < 2)) suffix = '*'; - } + buff[3] = suffix; buff[4] = '\0'; } From 45342f6e260766b42a1d7ab4337706d5d96951c7 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Mon, 27 Feb 2023 13:39:26 +0100 Subject: [PATCH 064/130] show pitot failure status on osd --- src/main/io/osd.c | 16 ++++++++++++---- 1 file changed, 12 insertions(+), 4 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index eed14a2764..bd2437f60e 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -2676,12 +2676,20 @@ static bool osdDrawSingleElement(uint8_t item) case OSD_AIR_SPEED: { #ifdef USE_PITOT - const float airspeed_estimate = getAirspeedEstimate(); buff[0] = SYM_AIR; - osdFormatVelocityStr(buff + 1, airspeed_estimate, false, false); - if ((osdConfig()->airspeed_alarm_min != 0 && airspeed_estimate < osdConfig()->airspeed_alarm_min) || - (osdConfig()->airspeed_alarm_max != 0 && airspeed_estimate > osdConfig()->airspeed_alarm_max)) { + if (pitotIsHealthy()) + { + const float airspeed_estimate = getAirspeedEstimate(); + osdFormatVelocityStr(buff + 1, airspeed_estimate, false, false); + if ((osdConfig()->airspeed_alarm_min != 0 && airspeed_estimate < osdConfig()->airspeed_alarm_min) || + (osdConfig()->airspeed_alarm_max != 0 && airspeed_estimate > osdConfig()->airspeed_alarm_max)) { + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + } + else + { + strcpy(buff + 1, " X!"); TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); } #else From 936a7fd3a25ee4791af45a8ce6b79b6474486fac Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Mon, 27 Feb 2023 18:03:17 +0100 Subject: [PATCH 065/130] use pitot values only if healty --- src/main/fc/fc_tasks.c | 5 ++++- src/main/flight/pid.c | 2 +- src/main/navigation/navigation_fixedwing.c | 4 +++- src/main/telemetry/ibus_shared.c | 2 +- src/main/telemetry/ltm.c | 2 +- src/main/telemetry/mavlink.c | 2 +- src/main/telemetry/smartport.c | 2 +- 7 files changed, 12 insertions(+), 7 deletions(-) diff --git a/src/main/fc/fc_tasks.c b/src/main/fc/fc_tasks.c index 0e0b8c5432..fc21bc61b4 100755 --- a/src/main/fc/fc_tasks.c +++ b/src/main/fc/fc_tasks.c @@ -200,7 +200,10 @@ void taskUpdatePitot(timeUs_t currentTimeUs) } pitotUpdate(); - updatePositionEstimator_PitotTopic(currentTimeUs); + + if ( pitotIsHealthy()) { + updatePositionEstimator_PitotTopic(currentTimeUs); + } } #endif diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index dd2a480412..115bf4570d 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -979,7 +979,7 @@ static void NOINLINE pidTurnAssistant(pidState_t *pidState, float bankAngleTarge // yaw_rate = tan(roll_angle) * Gravity / forward_vel #if defined(USE_PITOT) - float airspeedForCoordinatedTurn = sensors(SENSOR_PITOT) ? getAirspeedEstimate() : pidProfile()->fixedWingReferenceAirspeed; + float airspeedForCoordinatedTurn = sensors(SENSOR_PITOT) && pitotIsHealthy()? getAirspeedEstimate() : pidProfile()->fixedWingReferenceAirspeed; #else float airspeedForCoordinatedTurn = pidProfile()->fixedWingReferenceAirspeed; #endif diff --git a/src/main/navigation/navigation_fixedwing.c b/src/main/navigation/navigation_fixedwing.c index 9160669365..4ca3d2fc3d 100755 --- a/src/main/navigation/navigation_fixedwing.c +++ b/src/main/navigation/navigation_fixedwing.c @@ -679,7 +679,9 @@ bool isFixedWingFlying(void) { float airspeed = 0.0f; #ifdef USE_PITOT - airspeed = getAirspeedEstimate(); + if (sensors(SENSOR_PITOT) && pitotIsHealthy()) { + airspeed = getAirspeedEstimate(); + } #endif bool throttleCondition = getMotorCount() == 0 || rcCommand[THROTTLE] > currentBatteryProfile->nav.fw.cruise_throttle; bool velCondition = posControl.actualState.velXY > 250.0f || airspeed > 250.0f; diff --git a/src/main/telemetry/ibus_shared.c b/src/main/telemetry/ibus_shared.c index 1e598dd2a7..8e29337986 100644 --- a/src/main/telemetry/ibus_shared.c +++ b/src/main/telemetry/ibus_shared.c @@ -170,7 +170,7 @@ static uint8_t dispatchMeasurementRequest(ibusAddress_t address) { return sendIbusMeasurement2(address, (uint16_t) (attitude.values.roll * 10)); //in ddeg -> cdeg, 1ddeg = 10cdeg } else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_VSPEED) { //Speed cm/s #ifdef USE_PITOT - if (sensors(SENSOR_PITOT)) return sendIbusMeasurement2(address, (uint16_t)getAirspeedEstimate()); //int32_t + if (sensors(SENSOR_PITOT) && pitotIsHealthy()) return sendIbusMeasurement2(address, (uint16_t)getAirspeedEstimate()); //int32_t else #endif return sendIbusMeasurement2(address, 0); diff --git a/src/main/telemetry/ltm.c b/src/main/telemetry/ltm.c index 282c9be4fd..00e99a8047 100644 --- a/src/main/telemetry/ltm.c +++ b/src/main/telemetry/ltm.c @@ -189,7 +189,7 @@ void ltm_sframe(sbuf_t *dst) sbufWriteU16(dst, (uint16_t)constrain(getMAhDrawn(), 0, 0xFFFF)); // current mAh (65535 mAh max) sbufWriteU8(dst, (uint8_t)((getRSSI() * 254) / 1023)); // scaled RSSI (uchar) #if defined(USE_PITOT) - sbufWriteU8(dst, sensors(SENSOR_PITOT) ? getAirspeedEstimate() / 100.0f : 0); // in m/s + sbufWriteU8(dst, (sensors(SENSOR_PITOT) && pitotIsHealthy())? getAirspeedEstimate() / 100.0f : 0); // in m/s #else sbufWriteU8(dst, 0); #endif diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c index 58a96a92d4..86d4fa9111 100644 --- a/src/main/telemetry/mavlink.c +++ b/src/main/telemetry/mavlink.c @@ -644,7 +644,7 @@ void mavlinkSendHUDAndHeartbeat(void) #endif #if defined(USE_PITOT) - if (sensors(SENSOR_PITOT)) { + if (sensors(SENSOR_PITOT) && pitotIsHealthy()) { mavAirSpeed = getAirspeedEstimate() / 100.0f; } #endif diff --git a/src/main/telemetry/smartport.c b/src/main/telemetry/smartport.c index 1ea659864b..4e1b0efbae 100755 --- a/src/main/telemetry/smartport.c +++ b/src/main/telemetry/smartport.c @@ -550,7 +550,7 @@ void processSmartPortTelemetry(smartPortPayload_t *payload, volatile bool *clear break; case FSSP_DATAID_ASPD : #ifdef USE_PITOT - if (sensors(SENSOR_PITOT)) { + if (sensors(SENSOR_PITOT) && pitotIsHealthy()) { smartPortSendPackage(id, getAirspeedEstimate() * 0.194384449f); // cm/s to knots*1 *clearToSend = false; } From 78b2fade3e0bc6f2b65fdf38d276cb0873ea6444 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Niccol=C3=B2=20Maggioni?= Date: Mon, 27 Feb 2023 11:57:43 +0100 Subject: [PATCH 066/130] AXISFLYINGF7PRO target --- .../target/AXISFLYINGF7PRO/CMakeLists.txt | 1 + src/main/target/AXISFLYINGF7PRO/config.c | 30 +++ src/main/target/AXISFLYINGF7PRO/target.c | 40 ++++ src/main/target/AXISFLYINGF7PRO/target.h | 178 ++++++++++++++++++ 4 files changed, 249 insertions(+) create mode 100644 src/main/target/AXISFLYINGF7PRO/CMakeLists.txt create mode 100644 src/main/target/AXISFLYINGF7PRO/config.c create mode 100644 src/main/target/AXISFLYINGF7PRO/target.c create mode 100644 src/main/target/AXISFLYINGF7PRO/target.h diff --git a/src/main/target/AXISFLYINGF7PRO/CMakeLists.txt b/src/main/target/AXISFLYINGF7PRO/CMakeLists.txt new file mode 100644 index 0000000000..7bcf5c0b90 --- /dev/null +++ b/src/main/target/AXISFLYINGF7PRO/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f722xe(AXISFLYINGF7PRO) \ No newline at end of file diff --git a/src/main/target/AXISFLYINGF7PRO/config.c b/src/main/target/AXISFLYINGF7PRO/config.c new file mode 100644 index 0000000000..2a72196c0c --- /dev/null +++ b/src/main/target/AXISFLYINGF7PRO/config.c @@ -0,0 +1,30 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + +#include + +#include "platform.h" + +#include "fc/fc_msp_box.h" + +#include "io/piniobox.h" + +void targetConfiguration(void) +{ + pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; + pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2; +} diff --git a/src/main/target/AXISFLYINGF7PRO/target.c b/src/main/target/AXISFLYINGF7PRO/target.c new file mode 100644 index 0000000000..532e668b3a --- /dev/null +++ b/src/main/target/AXISFLYINGF7PRO/target.c @@ -0,0 +1,40 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + +#include +#include + +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S3 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S4 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S5 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6 + DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S7 + DEF_TIM(TIM2, CH4, PB11, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 1), // S7 + + DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED STRIP + DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM + DEF_TIM(TIM12, CH2, PB15, TIM_USE_ANY, 0, 0), // CAM CONTROL +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/AXISFLYINGF7PRO/target.h b/src/main/target/AXISFLYINGF7PRO/target.h new file mode 100644 index 0000000000..7128dc9cf7 --- /dev/null +++ b/src/main/target/AXISFLYINGF7PRO/target.h @@ -0,0 +1,178 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "AXISFLYINGF7PRO" +#define USBD_PRODUCT_STRING "AXISFLYINGF7PRO" + +#define USE_TARGET_CONFIG + +#define LED0 PC15 +#define BEEPER PC13 +#define BEEPER_INVERTED + +// *************** SPI ********************** +#define USE_SPI + +#define USE_SPI_DEVICE_1 +#define SPI1_NSS_PIN PA4 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define USE_SPI_DEVICE_2 +#define SPI2_NSS_PIN PB12 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PC3 + +#define USE_SPI_DEVICE_3 +#define SPI3_NSS_PIN PA15 +#define SPI3_SCK_PIN PB3 +#define SPI3_MISO_PIN PB4 +#define SPI3_MOSI_PIN PB5 + +// *************** SPI1 Gyro & ACC ********************** +#define USE_IMU_MPU6000 +#define IMU_MPU6000_ALIGN CW0_DEG +#define MPU6000_SPI_BUS BUS_SPI1 +#define MPU6000_CS_PIN SPI1_NSS_PIN +#define MPU6000_EXTI_PIN GYRO_INT_EXTI + +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW0_DEG +#define ICM42605_SPI_BUS BUS_SPI1 +#define ICM42605_CS_PIN SPI1_NSS_PIN +#define ICM42605_EXTI_PIN GYRO_INT_EXTI + +#define USE_IMU_BMI270 +#define IMU_BMI270_ALIGN CW0_DEG +#define BMI270_SPI_BUS BUS_SPI1 +#define BMI270_CS_PIN SPI1_NSS_PIN +#define BMI270_EXTI_PIN GYRO_INT_EXTI + +// *************** SPI2 OSD ***************// +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN SPI2_NSS_PIN + +// *************** SPI3 FLASH ***************// +#define USE_BLACKBOX +#define USE_FLASHFS + +#define USE_FLASH_M25P16 +#define M25P16_SPI_BUS BUS_SPI3 +#define M25P16_CS_PIN SPI3_NSS_PIN + +#define USE_FLASH_W25N01G +#define W25N01G_SPI_BUS BUS_SPI3 +#define W25N01G_CS_PIN SPI3_NSS_PIN + +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +// *************** UART ***************************** +#define USE_VCP + +#define USE_UART1 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 + +#define USE_UART2 +#define UART2_TX_PIN PA2 +#define UART2_RX_PIN PA3 + +#define USE_UART3 +#define UART3_TX_PIN PC10 +#define UART3_RX_PIN PC11 + +#define USE_UART4 +#define UART4_TX_PIN PA0 +#define UART4_RX_PIN PA1 + +#define USE_UART5 +#define UART5_TX_PIN PC12 +#define UART5_RX_PIN PD2 + +#define USE_UART6 +#define UART6_TX_PIN PC6 +#define UART6_RX_PIN PC7 + +#define SERIAL_PORT_COUNT 7 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS +#define SERIALRX_UART SERIAL_PORT_USART2 + +// *************** I2C/Baro/Mag/Pitot ******************** +#define USE_I2C +#define DEFAULT_I2C_BUS BUS_I2C1 + +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 + +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C1 +#define USE_BARO_BMP280 +#define USE_BARO_SPL06 +#define USE_BARO_DPS310 + +#define TEMPERATURE_I2C_BUS BUS_I2C1 +#define BNO055_I2C_BUS BUS_I2C1 + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C1 +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_IST8310 +#define USE_MAG_MAG3110 +#define USE_MAG_LIS3MDL + +#define PITOT_I2C_BUS BUS_I2C1 + +// *************** PINIO *************************** +#define USE_PINIO +#define USE_PINIOBOX +#define PINIO1_PIN PC0 +#define PINIO2_PIN PC14 + +// *************** ADC ***************************** +#define USE_ADC +#define ADC_INSTANCE ADC1 +#define ADC1_DMA_STREAM DMA2_Stream0 +#define ADC_CHANNEL_1_PIN PC2 +#define ADC_CHANNEL_2_PIN PC1 +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 + +// *************** LED2812 ************************ +#define USE_LED_STRIP +#define WS2811_PIN PA8 + +// *************** OTHERS ************************* +#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY | FEATURE_SOFTSERIAL | FEATURE_LED_STRIP) + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) + +#define MAX_PWM_OUTPUT_PORTS 4 +#define USE_DSHOT +#define USE_ESC_SENSOR From 18c1f07b728ddc435aa11ff9d95d19e5652f4a6e Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Thu, 2 Mar 2023 01:12:38 +0100 Subject: [PATCH 067/130] Add ICM42688 to Betafpv F722 #8841 --- src/main/target/BETAFPVF722/target.h | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/main/target/BETAFPVF722/target.h b/src/main/target/BETAFPVF722/target.h index 290f009b46..7110d21c9e 100755 --- a/src/main/target/BETAFPVF722/target.h +++ b/src/main/target/BETAFPVF722/target.h @@ -40,6 +40,11 @@ #define USE_IMU_MPU6000 #define IMU_MPU6000_ALIGN CW180_DEG +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW180_DEG +#define ICM42605_SPI_BUS BUS_SPI1 +#define ICM42605_CS_PIN PA4 + // *************** I2C/Baro/Mag ********************* #define USE_I2C From 5d5991467a143aa57ad0248252318438a9d5f50c Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Thu, 2 Mar 2023 12:19:10 +0100 Subject: [PATCH 068/130] SpeedyBee F405 Wing --- .../target/SPEEDYBEEF405WING/CMakeLists.txt | 1 + src/main/target/SPEEDYBEEF405WING/config.c | 38 ++++ .../target/SPEEDYBEEF405WING/resources.txt | 49 +++++ src/main/target/SPEEDYBEEF405WING/target.c | 43 +++++ src/main/target/SPEEDYBEEF405WING/target.h | 173 ++++++++++++++++++ 5 files changed, 304 insertions(+) create mode 100644 src/main/target/SPEEDYBEEF405WING/CMakeLists.txt create mode 100644 src/main/target/SPEEDYBEEF405WING/config.c create mode 100644 src/main/target/SPEEDYBEEF405WING/resources.txt create mode 100644 src/main/target/SPEEDYBEEF405WING/target.c create mode 100644 src/main/target/SPEEDYBEEF405WING/target.h diff --git a/src/main/target/SPEEDYBEEF405WING/CMakeLists.txt b/src/main/target/SPEEDYBEEF405WING/CMakeLists.txt new file mode 100644 index 0000000000..dcdde1675a --- /dev/null +++ b/src/main/target/SPEEDYBEEF405WING/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f405xg(SPEEDYBEEF405WING) diff --git a/src/main/target/SPEEDYBEEF405WING/config.c b/src/main/target/SPEEDYBEEF405WING/config.c new file mode 100644 index 0000000000..62f5216cbd --- /dev/null +++ b/src/main/target/SPEEDYBEEF405WING/config.c @@ -0,0 +1,38 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#include +#include + +#include "platform.h" + +#include "fc/fc_msp_box.h" +#include "io/serial.h" + +void targetConfiguration(void) +{ + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART1)].functionMask = FUNCTION_RX_SERIAL; + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART3)].functionMask = FUNCTION_GPS; + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART6)].functionMask = FUNCTION_MSP; +} diff --git a/src/main/target/SPEEDYBEEF405WING/resources.txt b/src/main/target/SPEEDYBEEF405WING/resources.txt new file mode 100644 index 0000000000..84d7c52a58 --- /dev/null +++ b/src/main/target/SPEEDYBEEF405WING/resources.txt @@ -0,0 +1,49 @@ +A00: FREE +A01: FREE +A02: FREE +A03: FREE +A04: MPU CS +A05: SPI1 SCK +A06: SPI1 MISO +A07: SPI1 MOSI +A08: FREE +A09: FREE +A10: SERIAL1 UART RX +A11: USB IN +A12: USB OUT +A13: LED2 OUT +A14: LED1 OUT +A15: FREE +B00: SERVO2 OUT +B01: SERVO3 OUT +B02: FREE +B03: SPI3 SCK +B04: SPI3 MISO +B05: SPI3 MOSI +B06: FREE +B07: MOTOR1 OUT +B08: I2C1 SCL +B09: I2C1 SDA +B10: FREE +B11: FREE +B12: OSD CS +B13: SPI2 SCK +B14: FREE +B15: FREE +C00: ADC CH1 +C01: ADC CH2 +C02: SPI2 MISO +C03: SPI2 MOSI +C04: FREE +C05: FREE +C06: SERIAL6 UART TX +C07: SERIAL6 UART RX +C08: SERVO4 OUT +C09: SERVO5 OUT +C10: FREE +C11: FREE +C12: SERIAL5 UART TX +C13: FREE +C14: SDCARD CS +C15: BEEPER OUT +D02: SERIAL5 UART RX \ No newline at end of file diff --git a/src/main/target/SPEEDYBEEF405WING/target.c b/src/main/target/SPEEDYBEEF405WING/target.c new file mode 100644 index 0000000000..4892321064 --- /dev/null +++ b/src/main/target/SPEEDYBEEF405WING/target.c @@ -0,0 +1,43 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + +#include +#include +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 1, 0), // S1 D(1,3,2) + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 1, 0), // S2 D(1,0,2) + + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0), // S3 D(1,7,5) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0), // S4 D(1,2,5) + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0), // S5 D(2,4,7) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0), // S6 D(2,7,7) + + DEF_TIM(TIM8, CH2N,PB14, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 1, 0), // S7 + DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 1, 0), // S8 + DEF_TIM(TIM2, CH4, PB11, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 1, 0), // S9 + DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 1, 0), // S10 + DEF_TIM(TIM12, CH2, PB15, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 1, 0), // S11 + + DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), //2812LED D(1,5,3) + +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/SPEEDYBEEF405WING/target.h b/src/main/target/SPEEDYBEEF405WING/target.h new file mode 100644 index 0000000000..483c1e4070 --- /dev/null +++ b/src/main/target/SPEEDYBEEF405WING/target.h @@ -0,0 +1,173 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "SP4W" +#define USBD_PRODUCT_STRING "SpeedyBee F405 Wing" + +// LEDs +#define LED0 PA14 //Blue +#define LED1 PA13 //Green + +// Beeper +#define BEEPER PC15 +#define BEEPER_INVERTED + +/* + * Buses + */ + +// SPI1 +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +// SPI2 +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PC2 +#define SPI2_MOSI_PIN PC3 + +// SPI3 +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PB3 +#define SPI3_MISO_PIN PB4 +#define SPI3_MOSI_PIN PB5 + +// Serial ports +#define USE_VCP + +#define USE_UART1 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 + +#define USE_UART2 +#define UART2_TX_PIN PA2 +#define UART2_RX_PIN PA3 + +#define USE_UART3 +#define UART3_TX_PIN PC10 +#define UART3_RX_PIN PC11 + +#define USE_UART4 +#define UART4_TX_PIN PA0 +#define UART4_RX_PIN PA1 + +#define USE_UART5 +#define UART5_TX_PIN PC12 +#define UART5_RX_PIN PD2 + +#define USE_UART6 +#define UART6_TX_PIN PC6 +#define UART6_RX_PIN PC7 + +#define SERIAL_PORT_COUNT 7 + +/* + * I2C + */ +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 + +/* + * Sensor drivers + */ + +// ICM42605/ICM42688P +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW270_DEG +#define ICM42605_CS_PIN PA4 +#define ICM42605_SPI_BUS BUS_SPI1 + +// Baro +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C1 +#define USE_BARO_BMP280 +#define USE_BARO_MS5611 +#define USE_BARO_BMP085 +#define USE_BARO_DPS310 +#define USE_BARO_SPL06 + +//Mag +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C1 +#define USE_MAG_AK8963 +#define USE_MAG_AK8975 +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_IST8310 +#define USE_MAG_MAG3110 +#define USE_MAG_LIS3MDL +#define USE_MAG_VCM5883 + +#define RANGEFINDER_I2C_BUS BUS_I2C1 +#define PITOT_I2C_BUS BUS_I2C1 +#define TEMPERATURE_I2C_BUS BUS_I2C1 + +// OSD +#define USE_MAX7456 +#define MAX7456_CS_PIN PB12 +#define MAX7456_SPI_BUS BUS_SPI2 + +// SD Card +#define USE_SDCARD +#define USE_SDCARD_SPI +#define SDCARD_SPI_BUS BUS_SPI3 +#define SDCARD_CS_PIN PC14 + +#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_CRSF +#define SERIALRX_UART SERIAL_PORT_USART1 + +// *************** ADC *************************** +#define USE_ADC +#define ADC_INSTANCE ADC1 +#define ADC1_DMA_STREAM DMA2_Stream0 +#define ADC_CHANNEL_1_PIN PC0 +#define ADC_CHANNEL_2_PIN PC1 +#define ADC_CHANNEL_3_PIN PC5 +#define ADC_CHANNEL_4_PIN PC4 +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +#define RSSI_ADC_CHANNEL ADC_CHN_4 +#define AIRSPEED_ADC_CHANNEL ADC_CHN_3 + +// *************** LED2812 ************************ +#define USE_LED_STRIP +#define WS2811_PIN PA8 + +// *************** OTHERS ************************* +#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY | FEATURE_BLACKBOX | FEATURE_AIRMODE) +#define CURRENT_METER_SCALE 195 + +#define USE_DSHOT +#define USE_ESC_SENSOR +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) + +#define MAX_PWM_OUTPUT_PORTS 11 \ No newline at end of file From 9f55615a91ba2267a431881ef51cd5aa449bcb78 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Thu, 2 Mar 2023 12:19:34 +0100 Subject: [PATCH 069/130] Drop not needed file --- .../target/SPEEDYBEEF405WING/resources.txt | 49 ------------------- 1 file changed, 49 deletions(-) delete mode 100644 src/main/target/SPEEDYBEEF405WING/resources.txt diff --git a/src/main/target/SPEEDYBEEF405WING/resources.txt b/src/main/target/SPEEDYBEEF405WING/resources.txt deleted file mode 100644 index 84d7c52a58..0000000000 --- a/src/main/target/SPEEDYBEEF405WING/resources.txt +++ /dev/null @@ -1,49 +0,0 @@ -A00: FREE -A01: FREE -A02: FREE -A03: FREE -A04: MPU CS -A05: SPI1 SCK -A06: SPI1 MISO -A07: SPI1 MOSI -A08: FREE -A09: FREE -A10: SERIAL1 UART RX -A11: USB IN -A12: USB OUT -A13: LED2 OUT -A14: LED1 OUT -A15: FREE -B00: SERVO2 OUT -B01: SERVO3 OUT -B02: FREE -B03: SPI3 SCK -B04: SPI3 MISO -B05: SPI3 MOSI -B06: FREE -B07: MOTOR1 OUT -B08: I2C1 SCL -B09: I2C1 SDA -B10: FREE -B11: FREE -B12: OSD CS -B13: SPI2 SCK -B14: FREE -B15: FREE -C00: ADC CH1 -C01: ADC CH2 -C02: SPI2 MISO -C03: SPI2 MOSI -C04: FREE -C05: FREE -C06: SERIAL6 UART TX -C07: SERIAL6 UART RX -C08: SERVO4 OUT -C09: SERVO5 OUT -C10: FREE -C11: FREE -C12: SERIAL5 UART TX -C13: FREE -C14: SDCARD CS -C15: BEEPER OUT -D02: SERIAL5 UART RX \ No newline at end of file From f71f2c3d4eff2ad44ded8d7eb6c3491507722c6a Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Thu, 2 Mar 2023 18:22:00 +0100 Subject: [PATCH 070/130] Add MSP_BATTERY_STATE MSP_BATTERY_STATE is used by DJI googles to display flight pack volatge in the native OSD. This should address #8840 --- src/main/fc/fc_msp.c | 19 +++++++++++++++++++ src/main/msp/msp_protocol.h | 3 ++- 2 files changed, 21 insertions(+), 1 deletion(-) diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index ee5c8f0397..d9c0ce5a37 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -1123,6 +1123,25 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF serializeSDCardSummaryReply(dst); break; +#if defined (USE_DJI_HD_OSD) || defined (USE_MSP_DISPLAYPORT) + case MSP_BATTERY_STATE: + // Battery characteristics + sbufWriteU8(dst, constrain(getBatteryCellCount(), 0, 255)); + sbufWriteU16(dst, currentBatteryProfile->capacity.value); + + // Battery state + sbufWriteU8(dst, constrain(getBatteryVoltage() / 10, 0, 255)); // in 0.1V steps + sbufWriteU16(dst, constrain(getMAhDrawn(), 0, 0xFFFF)); + sbufWriteU16(dst, constrain(getAmperage(), -0x8000, 0x7FFF)); + + // Battery alerts - used values match Betaflight's/DJI's + sbufWriteU8(dst, getBatteryState()); + + // Additional battery voltage field (in 0.01V steps) + sbufWriteU16(dst, getBatteryVoltage()); + break; +#endif + case MSP_OSD_CONFIG: #ifdef USE_OSD sbufWriteU8(dst, OSD_DRIVER_MAX7456); // OSD supported diff --git a/src/main/msp/msp_protocol.h b/src/main/msp/msp_protocol.h index 0f9d551eea..f94b04fe1e 100644 --- a/src/main/msp/msp_protocol.h +++ b/src/main/msp/msp_protocol.h @@ -209,7 +209,7 @@ #define MSP_SET_FILTER_CONFIG 93 #define MSP_PID_ADVANCED 94 -#define MSP_SET_PID_ADVANCED 95 +#define MSP_SET_PID_ADVANCED 95 #define MSP_SENSOR_CONFIG 96 #define MSP_SET_SENSOR_CONFIG 97 @@ -257,6 +257,7 @@ #define MSP_RC_DEADBAND 125 //out message deadbands for yaw alt pitch roll #define MSP_SENSOR_ALIGNMENT 126 //out message orientation of acc,gyro,mag #define MSP_LED_STRIP_MODECOLOR 127 //out message Get LED strip mode_color settings +#define MSP_BATTERY_STATE 130 // DJI googles fc battery info #define MSP_SET_RAW_RC 200 //in message 8 rc chan #define MSP_SET_RAW_GPS 201 //in message fix, numsat, lat, lon, alt, speed From e77b2f03e91dc80d73fd4c006a4b4465da3b5316 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Fri, 3 Mar 2023 10:29:46 +0100 Subject: [PATCH 071/130] Also add BMI270 Betaflight unified target for this FC also lists BMI270. This FC is probably a victmin of the chip shortages and was shipped with any imu they could get their hands on. --- src/main/target/BETAFPVF722/target.h | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/main/target/BETAFPVF722/target.h b/src/main/target/BETAFPVF722/target.h index 7110d21c9e..8384cb8f1d 100755 --- a/src/main/target/BETAFPVF722/target.h +++ b/src/main/target/BETAFPVF722/target.h @@ -45,6 +45,11 @@ #define ICM42605_SPI_BUS BUS_SPI1 #define ICM42605_CS_PIN PA4 +#define USE_IMU_BMI270 +#define IMU_BMI270_ALIGN CW180_DEG +#define BMI270_SPI_BUS BUS_SPI1 +#define BMI270_CS_PIN PA4 + // *************** I2C/Baro/Mag ********************* #define USE_I2C From 154ea341f4857beb64f14aa348a39f162c49b34b Mon Sep 17 00:00:00 2001 From: Scavanger Date: Sun, 5 Mar 2023 00:22:12 -0300 Subject: [PATCH 072/130] - Bugfixes - Add magnetometer and rnagefinder - Add joystick interface - Configuator integration - Update docs --- .github/workflows/ci.yml | 30 +++ CMakeLists.txt | 2 +- cmake/host-checks.cmake | 10 - docs/SITL/RealFlight.md | 8 +- docs/SITL/SITL.md | 76 ++++--- docs/SITL/X-Plane.md | 24 ++- src/main/CMakeLists.txt | 4 + src/main/common/time.c | 10 + src/main/config/config_streamer.h | 4 + src/main/config/config_streamer_file.c | 36 ++-- src/main/drivers/accgyro/accgyro_fake.c | 46 +--- .../drivers/rangefinder/rangefinder_virtual.c | 9 +- .../drivers/rangefinder/rangefinder_virtual.h | 2 + src/main/fc/cli.c | 6 +- src/main/fc/fc_core.c | 17 +- src/main/fc/fc_msp.c | 4 - src/main/fc/settings.yaml | 4 +- src/main/io/rangefinder.h | 4 +- src/main/io/rangefinder_fake.c | 86 ++++++++ .../navigation/navigation_pos_estimator.c | 2 +- src/main/rx/rx.c | 7 + src/main/rx/rx.h | 3 +- src/main/rx/sim.c | 71 +++++++ src/main/rx/sim.h | 23 ++ src/main/sensors/acceleration.c | 5 - src/main/sensors/rangefinder.c | 9 +- src/main/sensors/rangefinder.h | 1 + src/main/target/SITL/sim/realFlight.c | 96 +++++++-- src/main/target/SITL/sim/simHelper.c | 44 ++-- src/main/target/SITL/sim/simHelper.h | 10 +- src/main/target/SITL/sim/simple_soap_client.c | 16 +- src/main/target/SITL/sim/xplane.c | 199 ++++++++++++++---- src/main/target/SITL/target.c | 92 ++++---- src/main/target/SITL/target.h | 2 + 34 files changed, 706 insertions(+), 256 deletions(-) delete mode 100644 cmake/host-checks.cmake create mode 100644 src/main/io/rangefinder_fake.c create mode 100644 src/main/rx/sim.c create mode 100644 src/main/rx/sim.h diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index df2a2cc580..3f85a75ff4 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -43,6 +43,36 @@ jobs: name: ${{ env.BUILD_NAME }}.zip path: ./build/*.hex + build-SITL: + runs-on: ubuntu-latest + steps: + - uses: actions/checkout@v3 + - name: Install dependencies + run: sudo apt-get update && sudo apt-get -y install ninja-build + - name: Setup environment + env: + ACTIONS_ALLOW_UNSECURE_COMMANDS: true + run: | + # This is the hash of the commit for the PR + # when the action is triggered by PR, empty otherwise + COMMIT_ID=${{ github.event.pull_request.head.sha }} + # This is the hash of the commit when triggered by push + # but the hash of refs/pull//merge, which is different + # from the hash of the latest commit in the PR, that's + # why we try github.event.pull_request.head.sha first + COMMIT_ID=${COMMIT_ID:-${{ github.sha }}} + BUILD_SUFFIX=ci-$(date '+%Y%m%d')-$(git rev-parse --short ${COMMIT_ID}) + VERSION=$(grep project CMakeLists.txt|awk -F VERSION '{ gsub(/^[ \t]+|[ \t\)]+$/, "", $2); print $2 }') + echo "BUILD_SUFFIX=${BUILD_SUFFIX}" >> $GITHUB_ENV + echo "BUILD_NAME=inav-${VERSION}-${BUILD_SUFFIX}" >> $GITHUB_ENV + - name: Build SITL + run: mkdir -p build_SITL && cd build_SITL && cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -G Ninja .. && ninja + - name: Upload artifacts + uses: actions/upload-artifact@v2-preview + with: + name: ${{ env.BUILD_NAME }}_SITL.zip + path: ./build_SITL/*_SITL + test: needs: [build] runs-on: ubuntu-latest diff --git a/CMakeLists.txt b/CMakeLists.txt index 4ce4d50b9b..186ecc16e7 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -44,8 +44,8 @@ else() include("${CMAKE_CURRENT_SOURCE_DIR}/cmake/${TOOLCHAIN}.cmake") else() set(CMAKE_TOOLCHAIN_FILE "${CMAKE_CURRENT_SOURCE_DIR}/cmake/${TOOLCHAIN}.cmake") + include("${CMAKE_CURRENT_SOURCE_DIR}/cmake/${TOOLCHAIN}-checks.cmake") endif() - include("${CMAKE_CURRENT_SOURCE_DIR}/cmake/${TOOLCHAIN}-checks.cmake") endif() project(INAV VERSION 6.0.0) diff --git a/cmake/host-checks.cmake b/cmake/host-checks.cmake deleted file mode 100644 index 9e08e1b61a..0000000000 --- a/cmake/host-checks.cmake +++ /dev/null @@ -1,10 +0,0 @@ -set(gcc_host_req_ver 10) - -execute_process(COMMAND ${CMAKE_C_COMPILER} -dumpversion - OUTPUT_STRIP_TRAILING_WHITESPACE - OUTPUT_VARIABLE version) - - message("-- found GCC ${version}") -if (NOT gcc_host_req_ver STREQUAL version) - message(FATAL_ERROR "-- expecting GCC version ${gcc_host_req_ver}, but got version ${version} instead") -endif() diff --git a/docs/SITL/RealFlight.md b/docs/SITL/RealFlight.md index eecb0b0d7d..a30963af02 100644 --- a/docs/SITL/RealFlight.md +++ b/docs/SITL/RealFlight.md @@ -2,10 +2,14 @@ Supported are RealFlight 9.5S and RealFlight Evolution, NOT RealFlight-X. -RealFlight is very well suited to simulate the model flight specific aspects. Autolaunch and the mixers can be set in INAV. +RealFlight is very well suited to simulate the model flight specific aspects. Autolaunch and the mixers can be used. However, since the sceneries do not correspond to a real environment, the GPS data must be "faked". The position is always shown somewhere in southern Nevada ;). GPS data and flight modes work fine though, only for missions with waypoints it is of course not ideal. +## Joystick +In the settings, calibrate the joystick, set it up and assign the axes in the same order as in INAV. +Channel 1 (Aileron) in RealFlight is Cannel 1 (Aileron in INAV) and so on. + ## General settings Under Settings / Physics / Quality Switch on "RealFlight Link enabled". As a command line option for SITL, the port does not need to be specified, the port is fixed. @@ -17,4 +21,4 @@ In the model editor under "Electronis" all mixers should be deleted and the serv In the "Radio" tab also deactivate Expo and low rates: "Activadd when: Never". Configure the model in the same way as a real model would be set up in INAV including Mixer, Expo, etc. depending on the selected model in RealFlight. -Then adjust the channelmap (see command line option) accordingly. \ No newline at end of file +Then adjust the channelmap im the Configurator or via command line accordingly. \ No newline at end of file diff --git a/docs/SITL/SITL.md b/docs/SITL/SITL.md index f2fb492ac6..8b0fb4abad 100644 --- a/docs/SITL/SITL.md +++ b/docs/SITL/SITL.md @@ -3,7 +3,7 @@ ![INAV-SIM-OSD](assets/INAV-SIM-OSD.png) ## ATTENTION! -SITL is currently still under development, its use is still a bit cumbersome. +SITL is currently still under development. SITL (Software in the loop) allows to run INAV completely in software on the PC without using a flight controller and simulate complete FPV flights. For this, INAV is compiled with a normal PC compiler. @@ -13,46 +13,23 @@ Currently supported are - RealFlight https://www.realflight.com/ - X-Plane https://www.x-plane.com/ -INAV SITL communicates for sensor data and control directly with the corresponding simulator, see the documentation of the individual simulators and the command line options. - -## Command line -The following SITL specific command line options are available: - -If SITL is started without command line options, only the Configurator can be used. - -```--help``` Displays help for the command line options. - -```--sim=[sim]``` Select the simulator. xp = X-Plane, rf = RealFlight. Example: ```--sim=xp``` - -```--simip=[ip]``` IP address of the simulator, if you specify a simulator with "--sim" and omit this option localhost (127.0.0.1) will be used. Example: ```--simip=172.65.21.15``` - -```--simport=[port]``` Port number of the simulator, not necessary for all simulators. Example: ```--simport=4900``` - -```--useimu``` Use IMU sensor data from the simulator instead of using attitude data directly from the simulator. Not recommended, use only for debugging. - -```--chanmap=[chanmap]``` The channelmap to map the motor and servo outputs from INAV to the virtual receiver channel or control surfaces around simulator. -Syntax: (M(otor)|S(ervo)-),..., all numbers must have two digits. - -Example: -To assign motor1 to virtual receiver channel 1, servo 1 to channel 2, and servo2 to channel 3: -```--chanmap:M01-01,S01-02,S02-03``` -Please also read the documentation of the individual simulators. +INAV SITL communicates for sensor data and control directly with the corresponding simulator, see the documentation of the individual simulators and the Configurator or the command line options. ## Sensors The following sensors are emulated: - IMU (Gyro, Accelerometer) - GPS - Pitot -- barometer +- Magnetometer (Compass) +- Rangefinder +- Barometer - Battery (current and voltage), depending on simulator ![SITL-Fake-Sensors](assets/SITL-Fake-Sensors.png) -Magnetometer (compass) is not yet supported, therefore no support for copters. - Select "FAKE" as type for all mentioned, so that they receive the data from the simulator. -## Serial ports +## Serial ports+ UARTs are replaced by TCP starting with port 5760 ascending. UART 1 port 5760, UART2 6761, ... By default, UART1 and UART2 are available as MSP connections. To connect the Configurator to SITL: Select TCP and connect to ```127.0.0.1:5760``` (if SITL is running on the same machine). @@ -64,8 +41,17 @@ The assignment and status of user UART/TCP connections is displayed on the conso All other interfaces (I2C, SPI, etc.) are not emulated. ## Remote control -At the moment only direct input via UART/TCP is supported. +Joystick (via simulator) or serial receiver via USB/Serial interface are supported. + +### Joystick interface +Only 8 channels are supported. +Select "SIM (SITL)" as the receiver and set up a joystick in the simulator, details of which can be found in the documentation for the individual simulators. + +### Serial Receiver via USB Connect a serial receiver (e.g. SBUS) to the PC via a UART/USB adapter. Configure the receiver in the Configurator as usual. + +The Configurator offers a built-in option for forwarding the serial data to the SITL TCP port, if SITL is started manually the following option can be used: + The connection can then be established with a programme that forwards the serial data unaltered to TCP, e.g. with the Python script tcp_serial_redirect.py (https://github.com/Scavanger/TCP-Serial-Redirect) If necessary, please download the required runtime environment from https://www.python.org/. Please use the linked version, which has a smaller buffer, otherwise the control response is relatively slow. @@ -78,7 +64,7 @@ For this you need a FT232 module. With FT-Prog (https://ftdichip.com/utilities/) For SBUS, the command line arguments of the python script are: ```python tcp_serial_redirect.py --parity E --stopbits 2 -c 127.0.0.1:[INAV-UART-PORT] COMXX 100000``` -Note: Telemetry via return channel through the receiver is not supported by SITL. +Note: Telemetry via return channel through the receiver is not supported by SITL (yet). ## OSD For the OSD the program INAV-Sim-OSD is available: https://github.com/Scavanger/INAV-SIM-OSD. @@ -86,6 +72,33 @@ For this, activate MSP-Displayport on a UART/TCP port and connect to the corresp Note: INAV-Sim-OSD only works if the simulator is in window mode. +## Command line +The command line options are only necessary if the SITL executable is started by hand, e.g. when debugging. +For normal use, please use the SITL tab in the configurator. + +The following SITL specific command line options are available: + +If SITL is started without command line options, only the Configurator can be used. + +```--path``` Full path and file name to config file, if not present, eeprom.bin in the current directory is used. Example: ```C:\INAV_SITL\flying-wing.bin``` + +```--sim=[sim]``` Select the simulator. xp = X-Plane, rf = RealFlight. Example: ```--sim=xp``` + +```--simip=[ip]``` IP address of the simulator, if you specify a simulator with "--sim" and omit this option localhost (127.0.0.1) will be used. Example: ```--simip=172.65.21.15``` + +```--simport=[port]``` Port number of the simulator, not necessary for all simulators. Example: ```--simport=4900``` + +```--useimu``` Use IMU sensor data from the simulator instead of using attitude data directly from the simulator. Not recommended, use only for debugging. + +```--chanmap=[chanmap]``` The channelmap to map the motor and servo outputs from INAV to the virtual receiver channel or control surfaces around simulator. +Syntax: (M(otor)|S(ervo)-),..., all numbers must have two digits. +Example: +To assign motor1 to virtual receiver channel 1, servo 1 to channel 2, and servo2 to channel 3: +```--chanmap:M01-01,S01-02,S02-03``` +Please also read the documentation of the individual simulators. + +```--help``` Displays help for the command line options. + ## Running SITL It is recommended to start the tools in the following order: 1. Simulator, aircraft should be ready for take-off @@ -94,7 +107,6 @@ It is recommended to start the tools in the following order: 4. serial redirect for RC input ## Compile -GCC 10 is required, GCC 11 gives an error message (bug in GCC?!?). ### Linux: Almost like normal, ruby, cmake and make are also required. diff --git a/docs/SITL/X-Plane.md b/docs/SITL/X-Plane.md index a4c85ab086..baca0e0fee 100644 --- a/docs/SITL/X-Plane.md +++ b/docs/SITL/X-Plane.md @@ -2,14 +2,32 @@ Tested on X-Plane 11, 12 should(!) work but not tested. -X-Plane is not a model flight simulator, but is based on real world data and is therefore suitable -GPS missions with waypoints. +X-Plane is not a model flight simulator, but is based on real world data and is therefore suitable for GPS missions with waypoints. + +## Aircraft +It is recommended to use the "AR Wing" of the INAV HITL project: https://github.com/RomanLut/INAV-X-Plane-HITL ## General settings In Settings / Network select "Accept incoming connections". The port can be found under "UDP PORTS", "Port we receive on". If no connection is established, the port can be changed. You may want to incease the "Flight model per frame" value under "General" +## Joystick +In the settings, calibrate the joystick, set it up and assign the axes as follows: + +| INAV | X-Plane | +|------|---------| +| Roll | Roll | +| Pitch | Pitch | +| Throttle | Throttle | +| Yaw | Yaw | +| Channel 5 | Prop | +| Channel 6 | Mixture | +| Channel 7 | Collective | +| Channel 8 | Thrust vector | + +Reverse axis in X-Plane if necessary. + ## Channelmap: The assignment of the "virtual receiver" is fixed: 1 - Throttle @@ -17,6 +35,6 @@ The assignment of the "virtual receiver" is fixed: 3 - Pitch 4 - Yaw -The internal mixer (e.g. for wings only) cannot be deactivated without further ado, therefore always select "Aircraft with tail" in INAV. +The internal mixer (e.g. for flying wings) cannot be deactivated without further ado, therefore always select "Aircraft with tail" in INAV. For the standard Aircraft preset the channelmap is: ```--chanmap=M01-01,S01-03,S03-02,S04-04``` diff --git a/src/main/CMakeLists.txt b/src/main/CMakeLists.txt index 66e671502a..3c12be4a42 100644 --- a/src/main/CMakeLists.txt +++ b/src/main/CMakeLists.txt @@ -406,6 +406,9 @@ main_sources(COMMON_SRC rx/srxl2.h rx/sumd.c rx/sumd.h + rx/sim.c + rx/sim.h + scheduler/scheduler.c scheduler/scheduler.h @@ -467,6 +470,7 @@ main_sources(COMMON_SRC io/rangefinder.h io/rangefinder_msp.c io/rangefinder_benewake.c + io/rangefinder_fake.c io/opflow.h io/opflow_cxof.c io/opflow_msp.c diff --git a/src/main/common/time.c b/src/main/common/time.c index f1204c57f4..8214398d26 100644 --- a/src/main/common/time.c +++ b/src/main/common/time.c @@ -35,6 +35,10 @@ #include "fc/settings.h" +#ifdef SITL_BUILD +#include +#endif + // For the "modulo 4" arithmetic to work, we need a leap base year #define REFERENCE_YEAR 2000 // Offset (seconds) from the UNIX epoch (1970-01-01) to 2000-01-01 @@ -310,11 +314,16 @@ bool rtcHasTime(void) bool rtcGet(rtcTime_t *t) { +#ifdef SITL_BUILD + *t = (rtcTime_t)(time(NULL) * 1000); + return true; +#else if (!rtcHasTime()) { return false; } *t = started + millis(); return true; +#endif } bool rtcSet(rtcTime_t *t) @@ -323,6 +332,7 @@ bool rtcSet(rtcTime_t *t) return true; } + bool rtcGetDateTime(dateTime_t *dt) { rtcTime_t t; diff --git a/src/main/config/config_streamer.h b/src/main/config/config_streamer.h index 87b688406f..33c0954874 100644 --- a/src/main/config/config_streamer.h +++ b/src/main/config/config_streamer.h @@ -57,3 +57,7 @@ int config_streamer_flush(config_streamer_t *c); int config_streamer_finish(config_streamer_t *c); int config_streamer_status(config_streamer_t *c); + +#if defined(CONFIG_IN_FILE) +bool configFileSetPath(char* path); +#endif diff --git a/src/main/config/config_streamer_file.c b/src/main/config/config_streamer_file.c index c3fdbba95c..379155c22e 100644 --- a/src/main/config/config_streamer_file.c +++ b/src/main/config/config_streamer_file.c @@ -16,6 +16,7 @@ */ #include +#include #include "platform.h" #include "drivers/system.h" #include "config/config_streamer.h" @@ -26,21 +27,32 @@ #include #include + #define FLASH_PAGE_SIZE (0x400) static FILE *eepromFd = NULL; - static bool streamerLocked = true; +static char eepromPath[260] = EEPROM_FILENAME; + +bool configFileSetPath(char* path) +{ + if(!path || strlen(path) > 260) { + return false; + } + + strcpy(eepromPath, path); + return true; +} void config_streamer_impl_unlock(void) { if (eepromFd != NULL) { - fprintf(stderr, "[EEPROM] Unable to load %s\n", EEPROM_FILENAME); + fprintf(stderr, "[EEPROM] Unable to load %s\n", eepromPath); return; } // open or create - eepromFd = fopen(EEPROM_FILENAME,"r+"); + eepromFd = fopen(eepromPath,"r+"); if (eepromFd != NULL) { // obtain file size: fseek(eepromFd , 0 , SEEK_END); @@ -49,16 +61,16 @@ void config_streamer_impl_unlock(void) size_t n = fread(eepromData, 1, sizeof(eepromData), eepromFd); if (n == size) { - printf("[EEPROM] Loaded '%s' (%ld of %ld bytes)\n", EEPROM_FILENAME, size, sizeof(eepromData)); + fprintf(stderr,"[EEPROM] Loaded '%s' (%ld of %ld bytes)\n", eepromPath, size, sizeof(eepromData)); streamerLocked = false; } else { - fprintf(stderr, "[EEPROM] Failed to load '%s'\n", EEPROM_FILENAME); + fprintf(stderr, "[EEPROM] Failed to load '%s'\n", eepromPath); } } else { - printf("[EEPROM] Created '%s', size = %ld\n", EEPROM_FILENAME, sizeof(eepromData)); + printf("[EEPROM] Created '%s', size = %ld\n", eepromPath, sizeof(eepromData)); streamerLocked = false; - if ((eepromFd = fopen(EEPROM_FILENAME, "w+")) == NULL) { - fprintf(stderr, "[EEPROM] Failed to create '%s'\n", EEPROM_FILENAME); + if ((eepromFd = fopen(eepromPath, "w+")) == NULL) { + fprintf(stderr, "[EEPROM] Failed to create '%s'\n", eepromPath); streamerLocked = true; } if (fwrite(eepromData, sizeof(eepromData), 1, eepromFd) != 1) { @@ -66,8 +78,6 @@ void config_streamer_impl_unlock(void) streamerLocked = true; } } - - } void config_streamer_impl_lock(void) @@ -78,7 +88,7 @@ void config_streamer_impl_lock(void) fwrite(eepromData, 1, sizeof(eepromData), eepromFd); fclose(eepromFd); eepromFd = NULL; - printf("[EEPROM] Saved '%s'\n", EEPROM_FILENAME); + fprintf(stderr, "[EEPROM] Saved '%s'\n", eepromPath); streamerLocked = false; } else { fprintf(stderr, "[EEPROM] Unlock error\n"); @@ -93,9 +103,9 @@ int config_streamer_impl_write_word(config_streamer_t *c, config_streamer_buffer if ((c->address >= (uintptr_t)eepromData) && (c->address < (uintptr_t)ARRAYEND(eepromData))) { *((uint32_t*)c->address) = *buffer; - printf("[EEPROM] Program word %p = %08x\n", (void*)c->address, *((uint32_t*)c->address)); + fprintf(stderr, "[EEPROM] Program word %p = %08x\n", (void*)c->address, *((uint32_t*)c->address)); } else { - printf("[EEPROM] Program word %p out of range!\n", (void*)c->address); + fprintf(stderr, "[EEPROM] Program word %p out of range!\n", (void*)c->address); } c->address += CONFIG_STREAMER_BUFFER_SIZE; diff --git a/src/main/drivers/accgyro/accgyro_fake.c b/src/main/drivers/accgyro/accgyro_fake.c index 92be492f74..645ae4e77d 100644 --- a/src/main/drivers/accgyro/accgyro_fake.c +++ b/src/main/drivers/accgyro/accgyro_fake.c @@ -32,59 +32,25 @@ #ifdef USE_IMU_FAKE -#if defined(SITL_BUILD) - -#define VOLATILE volatile - -static pthread_mutex_t gyroMutex; -static pthread_mutex_t accMutex; - -#define LOCK(mutex) (pthread_mutex_lock(mutex)) -#define UNLOCK(mutex) (pthread_mutex_unlock(mutex)) - -#define GYROLOCK (pthread_mutex_lock(&gyroMutex)) -#define GYROUNLOCK (pthread_mutex_unlock(&gyroMutex)) -#define ACCLOCK (pthread_mutex_lock(&accMutex)) -#define ACCUNLOCK (pthread_mutex_unlock(&accMutex)) - -#else -#define VOLATILE -#define GYROLOCK -#define GYROUNLOCK -#define ACCLOCK -#define ACCUNLOCK - -#endif - -static VOLATILE int16_t fakeGyroADC[XYZ_AXIS_COUNT]; +static int16_t fakeGyroADC[XYZ_AXIS_COUNT]; static void fakeGyroInit(gyroDev_t *gyro) { UNUSED(gyro); - -#if defined(SITL_BUILD) - pthread_mutex_init(&gyroMutex, NULL); -#endif - - //ENABLE_STATE(ACCELEROMETER_CALIBRATED); } void fakeGyroSet(int16_t x, int16_t y, int16_t z) { - GYROLOCK; fakeGyroADC[X] = x; fakeGyroADC[Y] = y; fakeGyroADC[Z] = z; - GYROUNLOCK; } static bool fakeGyroRead(gyroDev_t *gyro) { - GYROLOCK; gyro->gyroADCRaw[X] = fakeGyroADC[X]; gyro->gyroADCRaw[Y] = fakeGyroADC[Y]; gyro->gyroADCRaw[Z] = fakeGyroADC[Z]; - GYROUNLOCK; return true; } @@ -112,33 +78,25 @@ bool fakeGyroDetect(gyroDev_t *gyro) return true; } -static VOLATILE int16_t fakeAccData[XYZ_AXIS_COUNT]; +static int16_t fakeAccData[XYZ_AXIS_COUNT]; static void fakeAccInit(accDev_t *acc) { -#if defined(SITL_BUILD) - pthread_mutex_init(&accMutex, NULL); -#endif - acc->acc_1G = 9806; } void fakeAccSet(int16_t x, int16_t y, int16_t z) { - ACCLOCK; fakeAccData[X] = x; fakeAccData[Y] = y; fakeAccData[Z] = z; - ACCUNLOCK; } static bool fakeAccRead(accDev_t *acc) { - ACCLOCK; acc->ADCRaw[X] = fakeAccData[X]; acc->ADCRaw[Y] = fakeAccData[Y]; acc->ADCRaw[Z] = fakeAccData[Z]; - ACCUNLOCK; return true; } diff --git a/src/main/drivers/rangefinder/rangefinder_virtual.c b/src/main/drivers/rangefinder/rangefinder_virtual.c index c3bf85b89b..c3b9bab6ec 100644 --- a/src/main/drivers/rangefinder/rangefinder_virtual.c +++ b/src/main/drivers/rangefinder/rangefinder_virtual.c @@ -58,18 +58,15 @@ static int32_t virtualRangefinderGetDistance(rangefinderDev_t * dev) return highLevelDeviceVTable->read(); } -#define VIRTUAL_MAX_RANGE_CM 250 -#define VIRTUAL_DETECTION_CONE_DECIDEGREES 900 - bool virtualRangefinderDetect(rangefinderDev_t * dev, const virtualRangefinderVTable_t * vtable) { if (vtable && vtable->detect()) { highLevelDeviceVTable = vtable; dev->delayMs = RANGEFINDER_VIRTUAL_TASK_PERIOD_MS; - dev->maxRangeCm = VIRTUAL_MAX_RANGE_CM; - dev->detectionConeDeciDegrees = VIRTUAL_DETECTION_CONE_DECIDEGREES; - dev->detectionConeExtendedDeciDegrees = VIRTUAL_DETECTION_CONE_DECIDEGREES; + dev->maxRangeCm = RANGEFINDER_VIRTUAL_MAX_RANGE_CM; + dev->detectionConeDeciDegrees = RANGEFINDER_VIRTUAL_DETECTION_CONE_DECIDEGREES; + dev->detectionConeExtendedDeciDegrees = RANGEFINDER_VIRTUAL_DETECTION_CONE_DECIDEGREES; dev->init = &virtualRangefinderInit; dev->update = &virtualRangefinderUpdate; diff --git a/src/main/drivers/rangefinder/rangefinder_virtual.h b/src/main/drivers/rangefinder/rangefinder_virtual.h index 4d327edaf5..35468d1d6f 100644 --- a/src/main/drivers/rangefinder/rangefinder_virtual.h +++ b/src/main/drivers/rangefinder/rangefinder_virtual.h @@ -26,6 +26,8 @@ #include "drivers/rangefinder/rangefinder.h" +#define RANGEFINDER_VIRTUAL_MAX_RANGE_CM 250 +#define RANGEFINDER_VIRTUAL_DETECTION_CONE_DECIDEGREES 900 #define RANGEFINDER_VIRTUAL_TASK_PERIOD_MS 30 typedef struct virtualRangefinderVTable_s { diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index 297d6e6506..ec45474d9f 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -3417,7 +3417,11 @@ static void cliStatus(char *cmdline) cliPrint("OSD: "); #if defined(USE_OSD) displayPort_t *osdDisplayPort = osdGetDisplayPort(); - cliPrintf("%s [%u x %u]", osdDisplayPort->displayPortType, osdDisplayPort->cols, osdDisplayPort->rows); + if (osdDisplayPort) { + cliPrintf("%s [%u x %u]", osdDisplayPort->displayPortType, osdDisplayPort->cols, osdDisplayPort->rows); + } else { + cliPrintf("no OSD detected"); + } #else cliPrint("not used"); #endif diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index 620ec5203b..9619a3cc49 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -161,11 +161,22 @@ bool areSensorsCalibrating(void) int16_t getAxisRcCommand(int16_t rawData, int16_t rate, int16_t deadband) { - int16_t stickDeflection; + int16_t stickDeflection = 0; - stickDeflection = constrain(rawData - PWM_RANGE_MIDDLE, -500, 500); +#if defined(SITL_BUILD) // Workaround due to strange bug in GCC > 10.2 https://gcc.gnu.org/bugzilla/show_bug.cgi?id=108914 + const int16_t value = rawData - PWM_RANGE_MIDDLE; + if (value < -500) { + stickDeflection = -500; + } else if (value > 500) { + stickDeflection = 500; + } else { + stickDeflection = value; + } +#else + stickDeflection = constrain(rawData - PWM_RANGE_MIDDLE, -500, 500); +#endif + stickDeflection = applyDeadbandRescaled(stickDeflection, deadband, -500, 500); - return rcLookup(stickDeflection, rate); } diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 2c547b28b7..4946edc8e8 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -46,11 +46,7 @@ #include "drivers/compass/compass_msp.h" #include "drivers/barometer/barometer_msp.h" #include "drivers/pitotmeter/pitotmeter_msp.h" -#include "drivers/accgyro/accgyro_fake.h" -#include "drivers/barometer/barometer_fake.h" -#include "drivers/compass/compass_fake.h" #include "sensors/battery_sensor_fake.h" -#include "drivers/pitotmeter/pitotmeter_fake.h" #include "drivers/bus_i2c.h" #include "drivers/display.h" #include "drivers/flash.h" diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 08c64e5088..c82a9cb8f1 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -7,7 +7,7 @@ tables: values: ["NONE", "AUTO", "MPU6000", "MPU6500", "MPU9250", "BMI160", "ICM20689", "BMI088", "ICM42605", "BMI270", "FAKE"] enum: accelerationSensor_e - name: rangefinder_hardware - values: ["NONE", "SRF10", "VL53L0X", "MSP", "BENEWAKE", "VL53L1X", "US42", "TOF10120_I2C"] + values: ["NONE", "SRF10", "VL53L0X", "MSP", "BENEWAKE", "VL53L1X", "US42", "TOF10120_I2C", "FAKE"] enum: rangefinderType_e - name: mag_hardware values: ["NONE", "AUTO", "HMC5883", "AK8975", "MAG3110", "AK8963", "IST8310", "QMC5883", "MPU9250", "IST8308", "LIS3MDL", "MSP", "RM3100", "VCM5883", "MLX90393", "FAKE"] @@ -22,7 +22,7 @@ tables: values: ["NONE", "AUTO", "MS4525", "ADC", "VIRTUAL", "FAKE", "MSP"] enum: pitotSensor_e - name: receiver_type - values: ["NONE", "SERIAL", "MSP"] + values: ["NONE", "SERIAL", "MSP", "SIM (SITL)"] enum: rxReceiverType_e - name: serial_rx values: ["SPEK1024", "SPEK2048", "SBUS", "SUMD", "IBUS", "JETIEXBUS", "CRSF", "FPORT", "SBUS_FAST", "FPORT2", "SRXL2", "GHST", "MAVLINK"] diff --git a/src/main/io/rangefinder.h b/src/main/io/rangefinder.h index 275a4afb6b..6768c7d75d 100644 --- a/src/main/io/rangefinder.h +++ b/src/main/io/rangefinder.h @@ -31,5 +31,7 @@ extern virtualRangefinderVTable_t rangefinderMSPVtable; extern virtualRangefinderVTable_t rangefinderBenewakeVtable; +extern virtualRangefinderVTable_t rangefinderFakeVtable; -void mspRangefinderReceiveNewData(uint8_t * bufferPtr); \ No newline at end of file +void mspRangefinderReceiveNewData(uint8_t * bufferPtr); +void fakeRangefindersSetData(int32_t data); \ No newline at end of file diff --git a/src/main/io/rangefinder_fake.c b/src/main/io/rangefinder_fake.c new file mode 100644 index 0000000000..5c174fa3d1 --- /dev/null +++ b/src/main/io/rangefinder_fake.c @@ -0,0 +1,86 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#include +#include +#include +#include + +#include "platform.h" + +#include "build/build_config.h" +#include "build/debug.h" + +#include "common/maths.h" + +#include "io/serial.h" + +#if defined(USE_RANGEFINDER_FAKE) +#include "drivers/rangefinder/rangefinder_virtual.h" +#include "drivers/time.h" +#include "io/rangefinder.h" + +static bool hasNewData = false; +static int32_t sensorData = RANGEFINDER_NO_NEW_DATA; + +static bool fakeRangefinderDetect(void) +{ + // Always detectable + return true; +} + +static void fakeRangefinderInit(void) +{ +} + +static void fakeRangefinderUpdate(void) +{ +} + +static int32_t fakeRangefinderGetDistance(void) +{ + if (hasNewData) { + hasNewData = false; + return (sensorData > 0) ? sensorData : RANGEFINDER_OUT_OF_RANGE; + } + else { + return RANGEFINDER_NO_NEW_DATA; + } +} + +void fakeRangefindersSetData(int32_t data) +{ + sensorData = data; + hasNewData = true; +} + +virtualRangefinderVTable_t rangefinderFakeVtable = { + .detect = fakeRangefinderDetect, + .init = fakeRangefinderInit, + .update = fakeRangefinderUpdate, + .read = fakeRangefinderGetDistance +}; + + +#endif \ No newline at end of file diff --git a/src/main/navigation/navigation_pos_estimator.c b/src/main/navigation/navigation_pos_estimator.c index 57443ebffd..0d0ecfb91c 100755 --- a/src/main/navigation/navigation_pos_estimator.c +++ b/src/main/navigation/navigation_pos_estimator.c @@ -241,7 +241,7 @@ void onNewGPSData(void) /* Use VELNED provided by GPS if available, calculate from coordinates otherwise */ float gpsScaleLonDown = constrainf(cos_approx((ABS(gpsSol.llh.lat) / 10000000.0f) * 0.0174532925f), 0.01f, 1.0f); - if (positionEstimationConfig()->use_gps_velned && gpsSol.flags.validVelNE) { + if (!ARMING_FLAG(SIMULATOR_MODE_SITL) && positionEstimationConfig()->use_gps_velned && gpsSol.flags.validVelNE) { posEstimator.gps.vel.x = gpsSol.velNED[X]; posEstimator.gps.vel.y = gpsSol.velNED[Y]; } diff --git a/src/main/rx/rx.c b/src/main/rx/rx.c index 7491d20e70..7bb232bc9f 100755 --- a/src/main/rx/rx.c +++ b/src/main/rx/rx.c @@ -63,6 +63,7 @@ #include "rx/sumd.h" #include "rx/ghst.h" #include "rx/mavlink.h" +#include "rx/sim.h" const char rcChannelLetters[] = "AERT"; @@ -310,6 +311,12 @@ void rxInit(void) break; #endif +#ifdef USE_RX_SIM + case RX_TYPE_SIM: + rxSimInit(rxConfig(), &rxRuntimeConfig); + break; +#endif + default: case RX_TYPE_NONE: rxConfigMutable()->receiverType = RX_TYPE_NONE; diff --git a/src/main/rx/rx.h b/src/main/rx/rx.h index 4880c4c4fe..4d4ce835d9 100644 --- a/src/main/rx/rx.h +++ b/src/main/rx/rx.h @@ -62,7 +62,8 @@ typedef enum { typedef enum { RX_TYPE_NONE = 0, RX_TYPE_SERIAL, - RX_TYPE_MSP + RX_TYPE_MSP, + RX_TYPE_SIM } rxReceiverType_e; typedef enum { diff --git a/src/main/rx/sim.c b/src/main/rx/sim.c new file mode 100644 index 0000000000..a2a336f612 --- /dev/null +++ b/src/main/rx/sim.c @@ -0,0 +1,71 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include +#include + +#include "platform.h" + +#ifdef USE_RX_SIM + +#include "build/build_config.h" + +#include "common/utils.h" + +#include "rx/rx.h" +#include "rx/sim.h" + +static uint16_t channels[MAX_SUPPORTED_RC_CHANNEL_COUNT]; +static bool hasNewData = false; + +static uint16_t rxSimReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfigPtr, uint8_t chan) +{ + UNUSED(rxRuntimeConfigPtr); + return channels[chan]; +} + +void rxSimSetChannelValue(uint16_t* values, uint8_t count) +{ + for (size_t i = 0; i < count; i++) { + channels[i] = values[i]; + } + + hasNewData = true; +} + +static uint8_t rxSimFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig) +{ + UNUSED(rxRuntimeConfig); + + if (!hasNewData) { + return RX_FRAME_PENDING; + } + + hasNewData = false; + return RX_FRAME_COMPLETE; +} + +void rxSimInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig) +{ + UNUSED(rxConfig); + + rxRuntimeConfig->channelCount = MAX_SUPPORTED_RC_CHANNEL_COUNT; + rxRuntimeConfig->rxSignalTimeout = DELAY_5_HZ; + rxRuntimeConfig->rcReadRawFn = rxSimReadRawRC; + rxRuntimeConfig->rcFrameStatusFn = rxSimFrameStatus; +} +#endif diff --git a/src/main/rx/sim.h b/src/main/rx/sim.h new file mode 100644 index 0000000000..88342acad7 --- /dev/null +++ b/src/main/rx/sim.h @@ -0,0 +1,23 @@ +/* + * This file is part of INAV. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + +#include "rx/rx.h" + +void rxSimSetChannelValue(uint16_t* values, uint8_t count); +void rxSimInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig); diff --git a/src/main/sensors/acceleration.c b/src/main/sensors/acceleration.c index ed125f36c3..6a63c6cb88 100644 --- a/src/main/sensors/acceleration.c +++ b/src/main/sensors/acceleration.c @@ -520,11 +520,6 @@ void accUpdate(void) if (!ARMING_FLAG(SIMULATOR_MODE_SITL)) { performAcclerationCalibration(); - - applyAccelerationZero(&accelerometerConfig()->accZero, &accelerometerConfig()->accGain); - applyAccelerationZero(&accelerometerConfig()->accZero, &accelerometerConfig()->accGain); - applyAccelerationZero(&accelerometerConfig()->accZero, &accelerometerConfig()->accGain); - applyAccelerationZero(&accelerometerConfig()->accZero, &accelerometerConfig()->accGain); applyAccelerationZero(&accelerometerConfig()->accZero, &accelerometerConfig()->accGain); } diff --git a/src/main/sensors/rangefinder.c b/src/main/sensors/rangefinder.c index ce3aadd0e9..a4af166cfe 100644 --- a/src/main/sensors/rangefinder.c +++ b/src/main/sensors/rangefinder.c @@ -141,7 +141,14 @@ static bool rangefinderDetect(rangefinderDev_t * dev, uint8_t rangefinderHardwar } #endif break; - + case RANGEFINDER_FAKE: +#if defined(USE_RANGEFINDER_FAKE) + if(virtualRangefinderDetect(dev, &rangefinderFakeVtable)) { + rangefinderHardware = RANGEFINDER_FAKE; + rescheduleTask(TASK_RANGEFINDER, TASK_PERIOD_MS(RANGEFINDER_VIRTUAL_TASK_PERIOD_MS)); + } +#endif + break; case RANGEFINDER_NONE: rangefinderHardware = RANGEFINDER_NONE; break; diff --git a/src/main/sensors/rangefinder.h b/src/main/sensors/rangefinder.h index e7ab9e8a61..a57253bd3f 100644 --- a/src/main/sensors/rangefinder.h +++ b/src/main/sensors/rangefinder.h @@ -30,6 +30,7 @@ typedef enum { RANGEFINDER_VL53L1X = 5, RANGEFINDER_US42 = 6, RANGEFINDER_TOF10102I2C = 7, + RANGEFINDER_FAKE = 8, } rangefinderType_e; typedef struct rangefinderConfig_s { diff --git a/src/main/target/SITL/sim/realFlight.c b/src/main/target/SITL/sim/realFlight.c index 4289d87d25..c2feacbf75 100644 --- a/src/main/target/SITL/sim/realFlight.c +++ b/src/main/target/SITL/sim/realFlight.c @@ -45,14 +45,19 @@ #include "sensors/acceleration.h" #include "sensors/barometer.h" #include "drivers/pitotmeter/pitotmeter_fake.h" +#include "drivers/compass/compass_fake.h" +#include "drivers/rangefinder/rangefinder_virtual.h" +#include "io/rangefinder.h" #include "common/utils.h" #include "common/maths.h" #include "flight/mixer.h" #include "flight/servos.h" #include "flight/imu.h" #include "io/gps.h" +#include "rx/sim.h" #define RF_PORT 18083 +#define RF_MAX_CHANNEL_COUNT 12 // RealFlight scenerys doesn't represent real landscapes, so fake some nice coords: Area 51 ;) #define FAKE_LAT 37.277127f #define FAKE_LON -115.799669f @@ -212,6 +217,33 @@ static char* getStringFromResponse(const char* response, const char* elementName return ret; } +static bool getChannelValues(const char* response, uint16_t* channelValues) +{ + if (!response) { + return false; + } + + const char* channelValueTag = ""; + char* pos = strstr(response, channelValueTag); + if (!pos){ + return false; + } + + pos += strlen(channelValueTag); + for (size_t i = 0; i < RF_MAX_CHANNEL_COUNT; i++) { + char* end = strstr(pos, " 0 && altitudeOverGround <= RANGEFINDER_VIRTUAL_MAX_RANGE_CM) { + fakeRangefindersSetData(altitudeOverGround); + } else { + fakeRangefindersSetData(-1); + } + + const int16_t roll_inav = (int16_t)round(rfValues.m_roll_DEG * 10); + const int16_t pitch_inav = (int16_t)round(-rfValues.m_inclination_DEG * 10); + const int16_t yaw_inav = course; if (!useImu) { - imuSetAttitudeRPY( - (int16_t)round(rfValues.m_roll_DEG * 10), - (int16_t)round(-rfValues.m_inclination_DEG * 10), - course - ); + imuSetAttitudeRPY(roll_inav, pitch_inav, yaw_inav); imuUpdateAttitude(micros()); } @@ -326,26 +368,38 @@ static void exchangeData(void) accY = 0; accZ = (int16_t)(GRAVITY_MSS * 1000.0f); } else { - accX = clampToInt16(rfValues.m_accelerationBodyAX_MPS2 * 1000); - accY = clampToInt16(-rfValues.m_accelerationBodyAY_MPS2 * 1000); - accZ = clampToInt16(-rfValues.m_accelerationBodyAZ_MPS2 * 1000); + accX = constrainToInt16(rfValues.m_accelerationBodyAX_MPS2 * 1000); + accY = constrainToInt16(-rfValues.m_accelerationBodyAY_MPS2 * 1000); + accZ = constrainToInt16(-rfValues.m_accelerationBodyAZ_MPS2 * 1000); } fakeAccSet(accX, accY, accZ); fakeGyroSet( - clampToInt16(rfValues.m_rollRate_DEGpSEC * (double)16.0), - clampToInt16(-rfValues.m_pitchRate_DEGpSEC * (double)16.0), - clampToInt16(rfValues.m_yawRate_DEGpSEC * (double)16.0) + constrainToInt16(rfValues.m_rollRate_DEGpSEC * (double)16.0), + constrainToInt16(-rfValues.m_pitchRate_DEGpSEC * (double)16.0), + constrainToInt16(rfValues.m_yawRate_DEGpSEC * (double)16.0) ); fakeBaroSet(altitudeToPressure(altitude), DEGREES_TO_CENTIDEGREES(21)); fakePitotSetAirspeed(rfValues.m_airspeed_MPS * 100); - // TODO fakeMag - fakeBattSensorSetVbat((uint16_t)round(rfValues.m_batteryVoltage_VOLTS * 100)); - fakeBattSensorSetAmperage((uint16_t)round(rfValues.m_batteryCurrentDraw_AMPS * 100)); + fakeBattSensorSetAmperage((uint16_t)round(rfValues.m_batteryCurrentDraw_AMPS * 100)); + + fpQuaternion_t quat; + fpVector3_t north; + north.x = 1.0f; + north.y = 0; + north.z = 0; + computeQuaternionFromRPY(&quat, roll_inav, pitch_inav, yaw_inav); + transformVectorEarthToBody(&north, &quat); + fakeMagSet( + constrainToInt16(north.x * 16000.0f), + constrainToInt16(north.y * 16000.0f), + constrainToInt16(north.z * 16000.0f) + ); + ENABLE_STATE(COMPASS_CALIBRATED); } static void* soapWorker(void* arg) @@ -357,14 +411,14 @@ static void* soapWorker(void* arg) startRequest("RestoreOriginalControllerDevice", "12"); endRequest(); startRequest("InjectUAVControllerInterface", "12"); - endRequest(); - + endRequest(); exchangeData(); ENABLE_ARMING_FLAG(SIMULATOR_MODE_SITL); + isInitalised = true; } - exchangeData(); + exchangeData(); unlockMainPID(); } @@ -414,7 +468,7 @@ bool simRealFlightInit(char* ip, uint8_t* mapping, uint8_t mapCount, bool imu) // Wait until the connection is established, the interface has been initialised // and the first valid packet has been received to avoid problems with the startup calibration. while (!isInitalised) { - // ... + delay(250); } return true; diff --git a/src/main/target/SITL/sim/simHelper.c b/src/main/target/SITL/sim/simHelper.c index 4f7fb57244..576060199a 100644 --- a/src/main/target/SITL/sim/simHelper.c +++ b/src/main/target/SITL/sim/simHelper.c @@ -26,22 +26,42 @@ #include #include +#include "common/quaternion.h" + #include "target/SITL/sim/simHelper.h" -inline double clampd(double value, double min, double max) +inline int16_t constrainToInt16(double value) { - if (value < min) { - value = min; - } - - if (value > max) { - value = max; - } - - return value; + return (int16_t)round(constrain(value, INT16_MIN, INT16_MAX)); } -inline int16_t clampToInt16(double value) +// Move to quaternion.h ? +void computeQuaternionFromRPY(fpQuaternion_t *quat, int16_t initialRoll, int16_t initialPitch, int16_t initialYaw) { - return (int16_t)round(clampd(value, INT16_MIN, INT16_MAX)); + if (initialRoll > 1800) initialRoll -= 3600; + if (initialPitch > 1800) initialPitch -= 3600; + if (initialYaw > 1800) initialYaw -= 3600; + + const float cosRoll = cos_approx(DECIDEGREES_TO_RADIANS(initialRoll) * 0.5f); + const float sinRoll = sin_approx(DECIDEGREES_TO_RADIANS(initialRoll) * 0.5f); + + const float cosPitch = cos_approx(DECIDEGREES_TO_RADIANS(initialPitch) * 0.5f); + const float sinPitch = sin_approx(DECIDEGREES_TO_RADIANS(initialPitch) * 0.5f); + + const float cosYaw = cos_approx(DECIDEGREES_TO_RADIANS(-initialYaw) * 0.5f); + const float sinYaw = sin_approx(DECIDEGREES_TO_RADIANS(-initialYaw) * 0.5f); + + quat->q0 = cosRoll * cosPitch * cosYaw + sinRoll * sinPitch * sinYaw; + quat->q1 = sinRoll * cosPitch * cosYaw - cosRoll * sinPitch * sinYaw; + quat->q2 = cosRoll * sinPitch * cosYaw + sinRoll * cosPitch * sinYaw; + quat->q3 = cosRoll * cosPitch * sinYaw - sinRoll * sinPitch * cosYaw; +} + +void transformVectorEarthToBody(fpVector3_t *v, const fpQuaternion_t *quat) +{ + // HACK: This is needed to correctly transform from NED (sensor frame) to NEU (navigation) + v->y = -v->y; + + // From earth frame to body frame + quaternionRotateVector(v, v, quat); } diff --git a/src/main/target/SITL/sim/simHelper.h b/src/main/target/SITL/sim/simHelper.h index 2a9b25e410..22eaf0ab2e 100644 --- a/src/main/target/SITL/sim/simHelper.h +++ b/src/main/target/SITL/sim/simHelper.h @@ -23,11 +23,15 @@ */ #include +#include "common/maths.h" +#include "common/quaternion.h" #define EARTH_RADIUS ((double)6378.137) -#define DEG2RAD(deg) (deg * (double)M_PIf / (double)180.0) #define PWM_TO_FLOAT_0_1(x) (((int)x - 1000) / 1000.0f) #define PWM_TO_FLOAT_MINUS_1_1(x) (((int)x - 1500) / 500.0f) +#define FLOAT_0_1_TO_PWM(x) ((uint16_t)(x * 1000.0f) + 1000.0f) +#define FLOAT_MINUS_1_1_TO_PWM(x) ((uint16_t)((x + 1.0f) / 2.0f * 1000.0f) + 1000.0f) -double clampd(double value, double min, double max); -int16_t clampToInt16(double value); +int16_t constrainToInt16(double value); +void transformVectorEarthToBody(fpVector3_t *v, const fpQuaternion_t *quat); +void computeQuaternionFromRPY(fpQuaternion_t *quat, int16_t initialRoll, int16_t initialPitch, int16_t initialYaw); \ No newline at end of file diff --git a/src/main/target/SITL/sim/simple_soap_client.c b/src/main/target/SITL/sim/simple_soap_client.c index b3763b2ab0..1dd173bcf2 100644 --- a/src/main/target/SITL/sim/simple_soap_client.c +++ b/src/main/target/SITL/sim/simple_soap_client.c @@ -47,7 +47,7 @@ bool soapClientConnect(soap_client_t *client, const char *address, int port) } int one = 1; - if (setsockopt(client->sockedFd, SOL_SOCKET, SO_REUSEADDR, &one,sizeof(one)) < 0) { + if (setsockopt(client->sockedFd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one)) < 0) { return false; } @@ -69,6 +69,8 @@ void soapClientClose(soap_client_t *client) { close(client->sockedFd); memset(client, 0, sizeof(soap_client_t)); + client->isConnected = false; + client->isInitalised = false; } void soapClientSendRequestVa(soap_client_t *client, const char* action, const char *fmt, va_list va) @@ -78,11 +80,15 @@ void soapClientSendRequestVa(soap_client_t *client, const char* action, const ch } char* requestBody; - vasprintf(&requestBody, fmt, va); - + if (vasprintf(&requestBody, fmt, va) < 0) { + return; + } + char* request; - asprintf(&request, "POST / HTTP/1.1\r\nsoapaction: %s\r\ncontent-length: %u\r\ncontent-type: text/xml;charset='UTF-8'\r\nConnection: Keep-Alive\r\n\r\n%s", - action, (unsigned)strlen(requestBody), requestBody); + if (asprintf(&request, "POST / HTTP/1.1\r\nsoapaction: %s\r\ncontent-length: %u\r\ncontent-type: text/xml;charset='UTF-8'\r\nConnection: Keep-Alive\r\n\r\n%s", + action, (unsigned)strlen(requestBody), requestBody) < 0) { + return; + } send(client->sockedFd, request, strlen(request), 0); } diff --git a/src/main/target/SITL/sim/xplane.c b/src/main/target/SITL/sim/xplane.c index 70ecb3361f..e1b10fcb50 100644 --- a/src/main/target/SITL/sim/xplane.c +++ b/src/main/target/SITL/sim/xplane.c @@ -45,14 +45,19 @@ #include "sensors/battery_sensor_fake.h" #include "sensors/acceleration.h" #include "drivers/pitotmeter/pitotmeter_fake.h" +#include "drivers/compass/compass_fake.h" +#include "drivers/rangefinder/rangefinder_virtual.h" +#include "io/rangefinder.h" #include "common/utils.h" #include "common/maths.h" #include "flight/mixer.h" #include "flight/servos.h" #include "flight/imu.h" #include "io/gps.h" +#include "rx/sim.h" #define XP_PORT 49000 +#define XPLANE_JOYSTICK_AXIS_COUNT 8 static uint8_t pwmMapping[XP_MAX_PWM_OUTS]; @@ -67,6 +72,7 @@ static bool useImu = false; static float lattitude = 0; static float longitude = 0; static float elevation = 0; +static float agl = 0; static float local_vx = 0; static float local_vy = 0; static float local_vz = 0; @@ -83,13 +89,27 @@ static float gyro_x = 0; static float gyro_y = 0; static float gyro_z = 0; static float barometer = 0; +static bool hasJoystick = false; +static float joystickRaw[XPLANE_JOYSTICK_AXIS_COUNT]; +enum +{ + RF_ASSIGNMENT_PITCH, + RF_ASSIGNMENT_ROLL, + RF_ASSIGNMENT_YAW, + RF_ASSIGNMENT_THROTLE, + RF_ASSIGNMENT_PROP, + RF_ASSIGNMENT_MIXTURE, + RF_ASSIGNMENT_COLLECTIVE, + RF_ASSIGNMENT_THRUST_VECTOR +}; typedef enum { DREF_LATITUDE, DREF_LONGITUDE, DREF_ELEVATION, + DREF_AGL, DREF_LOCAL_VX, DREF_LOCAL_VY, DREF_LOCAL_VZ, @@ -106,7 +126,16 @@ typedef enum DREF_POS_Q, DREF_POS_R, DREF_POS_BARO_CURRENT_INHG, - DREF_COUNT + DREF_COUNT, + DREF_HAS_JOYSTICK, + DREF_JOYSTICK_VALUES_ROll, + DREF_JOYSTICK_VALUES_PITCH, + DREF_JOYSTICK_VALUES_THROTTLE, + DREF_JOYSTICK_VALUES_YAW, + DREF_JOYSTICK_VALUES_PROP, + DREF_JOYSTICK_VALUES_MIXTURE, + DREF_JOYSTICK_VALUES_COLLECTIVE, + DREF_JOYSTICK_VALUES_THRUST_VECTOR, } dref_t; uint32_t xint2uint32 (uint8_t * buf) @@ -168,7 +197,7 @@ static void* listenWorker(void* arg) if (y > 2) { break; } - if (pwmMapping[i] & 0x80) { // Motor) + if (pwmMapping[i] & 0x80) { // Motor motorValue = PWM_TO_FLOAT_0_1(motor[pwmMapping[i] & 0x7f]); } else { yokeValues[y] = PWM_TO_FLOAT_MINUS_1_1(servo[pwmMapping[i]]); @@ -184,11 +213,11 @@ static void* listenWorker(void* arg) recvLen = recvfrom(sockFd, buf, sizeof(buf), 0, (struct sockaddr*)&remoteAddr, &slen); if (recvLen < 0 && errno != EWOULDBLOCK) { - break; + continue; } if (strncmp((char*)buf, "RREF", 4) != 0) { - break; + continue; } for (int i = 5; i < recvLen; i += 8) { @@ -208,6 +237,10 @@ static void* listenWorker(void* arg) case DREF_ELEVATION: elevation = value; break; + + case DREF_AGL: + agl = value; + break; case DREF_LOCAL_VX: local_vx = value; @@ -273,10 +306,45 @@ static void* listenWorker(void* arg) barometer = value; break; + case DREF_HAS_JOYSTICK: + hasJoystick = value >= 1 ? true : false; + break; + + case DREF_JOYSTICK_VALUES_ROll: + joystickRaw[0] = value; + break; + + case DREF_JOYSTICK_VALUES_PITCH: + joystickRaw[1] = value; + break; + + case DREF_JOYSTICK_VALUES_THROTTLE: + joystickRaw[2] = value; + break; + + case DREF_JOYSTICK_VALUES_YAW: + joystickRaw[3] = value; + break; + + case DREF_JOYSTICK_VALUES_PROP: + joystickRaw[4] = value; + break; + + case DREF_JOYSTICK_VALUES_MIXTURE: + joystickRaw[5] = value; + break; + + case DREF_JOYSTICK_VALUES_COLLECTIVE: + joystickRaw[6] = value; + break; + + case DREF_JOYSTICK_VALUES_THRUST_VECTOR: + joystickRaw[7] = value; + break; + default: break; } - } if (hpath < 0) { @@ -287,6 +355,20 @@ static void* listenWorker(void* arg) yaw += 3600; } + if (hasJoystick) { + uint16_t channelValues[XPLANE_JOYSTICK_AXIS_COUNT]; + channelValues[0] = FLOAT_MINUS_1_1_TO_PWM(joystickRaw[RF_ASSIGNMENT_ROLL]); + channelValues[1] = FLOAT_MINUS_1_1_TO_PWM(joystickRaw[RF_ASSIGNMENT_PITCH]); + channelValues[2] = FLOAT_0_1_TO_PWM(joystickRaw[RF_ASSIGNMENT_THROTLE]); + channelValues[3] = FLOAT_MINUS_1_1_TO_PWM(joystickRaw[RF_ASSIGNMENT_YAW]); + channelValues[4] = FLOAT_0_1_TO_PWM(joystickRaw[RF_ASSIGNMENT_PROP]); + channelValues[5] = FLOAT_0_1_TO_PWM(joystickRaw[RF_ASSIGNMENT_MIXTURE]); + channelValues[6] = FLOAT_0_1_TO_PWM(joystickRaw[RF_ASSIGNMENT_COLLECTIVE]); + channelValues[7] = FLOAT_0_1_TO_PWM(joystickRaw[RF_ASSIGNMENT_THRUST_VECTOR]); + + rxSimSetChannelValue(channelValues, XPLANE_JOYSTICK_AXIS_COUNT); + } + gpsFakeSet( GPS_FIX_3D, 16, @@ -300,26 +382,33 @@ static void* listenWorker(void* arg) 0, //(int16_t)round(-local_vy * 100), 0 ); + + const int32_t altitideOverGround = (int32_t)round(agl * 100); + if (altitideOverGround > 0 && altitideOverGround <= RANGEFINDER_VIRTUAL_MAX_RANGE_CM) { + fakeRangefindersSetData(altitideOverGround); + } else { + fakeRangefindersSetData(-1); + } + + const int16_t roll_inav = roll * 10; + const int16_t pitch_inav = -pitch * 10; + const int16_t yaw_inav = yaw * 10; if (!useImu) { - imuSetAttitudeRPY( - (int16_t)round(roll * 10), - (int16_t)round(-pitch * 10), - (int16_t)round(yaw * 10) - ); + imuSetAttitudeRPY(roll_inav, pitch_inav, yaw_inav); imuUpdateAttitude(micros()); } fakeAccSet( - clampToInt16(-accel_x * GRAVITY_MSS * 1000), - clampToInt16(accel_y * GRAVITY_MSS * 1000), - clampToInt16(accel_z * GRAVITY_MSS * 1000) + constrainToInt16(-accel_x * GRAVITY_MSS * 1000), + constrainToInt16(accel_y * GRAVITY_MSS * 1000), + constrainToInt16(accel_z * GRAVITY_MSS * 1000) ); fakeGyroSet( - clampToInt16(gyro_x * 16.0f), - clampToInt16(-gyro_y * 16.0f), - clampToInt16(-gyro_z * 16.0f) + constrainToInt16(gyro_x * 16.0f), + constrainToInt16(-gyro_y * 16.0f), + constrainToInt16(-gyro_z * 16.0f) ); fakeBaroSet((int32_t)round(barometer * 3386.39f), DEGREES_TO_CENTIDEGREES(21)); @@ -327,8 +416,24 @@ static void* listenWorker(void* arg) fakeBattSensorSetVbat(16.8 * 100); + fpQuaternion_t quat; + fpVector3_t north; + north.x = 1.0f; + north.y = 0; + north.z = 0; + computeQuaternionFromRPY(&quat, roll_inav, pitch_inav, yaw_inav); + transformVectorEarthToBody(&north, &quat); + fakeMagSet( + constrainToInt16(north.x * 16000.0f), + constrainToInt16(north.y * 16000.0f), + constrainToInt16(north.z * 16000.0f) + ); + ENABLE_STATE(COMPASS_CALIBRATED); + if (!initalized) { - ENABLE_ARMING_FLAG(SIMULATOR_MODE_SITL); + ENABLE_ARMING_FLAG(SIMULATOR_MODE_SITL); + // Aircraft can wobble on the runway and prevents calibration of the accelerometer + ENABLE_STATE(ACCELEROMETER_CALIBRATED); initalized = true; } @@ -362,42 +467,52 @@ bool simXPlaneInit(char* ip, int port, uint8_t* mapping, uint8_t mapCount, bool return false; } - if (bind(sockFd, (struct sockaddr *) &addr, sizeof(addr)) < 0) { + if (setsockopt(sockFd, SOL_SOCKET, SO_SNDTIMEO, (struct timeval *) &tv,sizeof(struct timeval))) { return false; } + + bind(sockFd, (struct sockaddr *) &addr, sizeof(addr)); serverAddr.sin_family = AF_INET; serverAddr.sin_addr.s_addr = inet_addr(ip); serverAddr.sin_port = htons(port); - - registerDref(DREF_LATITUDE, "sim/flightmodel/position/latitude", 100); - registerDref(DREF_LONGITUDE, "sim/flightmodel/position/longitude", 100); - registerDref(DREF_ELEVATION, "sim/flightmodel/position/elevation", 100); - registerDref(DREF_LOCAL_VX, "sim/flightmodel/position/local_vx", 100); - registerDref(DREF_LOCAL_VY, "sim/flightmodel/position/local_vy", 100); - registerDref(DREF_LOCAL_VZ, "sim/flightmodel/position/local_vz", 100); - registerDref(DREF_GROUNDSPEED, "sim/flightmodel/position/groundspeed", 100); - registerDref(DREF_TRUE_AIRSPEED, "sim/flightmodel/position/true_airspeed", 100); - registerDref(DREF_POS_PHI, "sim/flightmodel/position/phi", 100); - registerDref(DREF_POS_THETA, "sim/flightmodel/position/theta", 100); - registerDref(DREF_POS_PSI, "sim/flightmodel/position/psi", 100); - registerDref(DREF_POS_HPATH, "sim/flightmodel/position/hpath", 100); - registerDref(DREF_FORCE_G_AXI1, "sim/flightmodel/forces/g_axil", 100); - registerDref(DREF_FORCE_G_SIDE, "sim/flightmodel/forces/g_side", 100); - registerDref(DREF_FORCE_G_NRML, "sim/flightmodel/forces/g_nrml", 100); - registerDref(DREF_POS_P, "sim/flightmodel/position/P", 100); - registerDref(DREF_POS_Q, "sim/flightmodel/position/Q", 100); - registerDref(DREF_POS_R, "sim/flightmodel/position/R", 100); - registerDref(DREF_POS_BARO_CURRENT_INHG, "sim/weather/barometer_current_inhg", 100); - + if (pthread_create(&listenThread, NULL, listenWorker, NULL) < 0) { return false; } - while(!initalized) { - // + while (!initalized) { + registerDref(DREF_LATITUDE, "sim/flightmodel/position/latitude", 100); + registerDref(DREF_LONGITUDE, "sim/flightmodel/position/longitude", 100); + registerDref(DREF_ELEVATION, "sim/flightmodel/position/elevation", 100); + registerDref(DREF_AGL, "sim/flightmodel/position/y_agl", 100); + registerDref(DREF_LOCAL_VX, "sim/flightmodel/position/local_vx", 100); + registerDref(DREF_LOCAL_VY, "sim/flightmodel/position/local_vy", 100); + registerDref(DREF_LOCAL_VZ, "sim/flightmodel/position/local_vz", 100); + registerDref(DREF_GROUNDSPEED, "sim/flightmodel/position/groundspeed", 100); + registerDref(DREF_TRUE_AIRSPEED, "sim/flightmodel/position/true_airspeed", 100); + registerDref(DREF_POS_PHI, "sim/flightmodel/position/phi", 100); + registerDref(DREF_POS_THETA, "sim/flightmodel/position/theta", 100); + registerDref(DREF_POS_PSI, "sim/flightmodel/position/psi", 100); + registerDref(DREF_POS_HPATH, "sim/flightmodel/position/hpath", 100); + registerDref(DREF_FORCE_G_AXI1, "sim/flightmodel/forces/g_axil", 100); + registerDref(DREF_FORCE_G_SIDE, "sim/flightmodel/forces/g_side", 100); + registerDref(DREF_FORCE_G_NRML, "sim/flightmodel/forces/g_nrml", 100); + registerDref(DREF_POS_P, "sim/flightmodel/position/P", 100); + registerDref(DREF_POS_Q, "sim/flightmodel/position/Q", 100); + registerDref(DREF_POS_R, "sim/flightmodel/position/R", 100); + registerDref(DREF_POS_BARO_CURRENT_INHG, "sim/weather/barometer_current_inhg", 100); + registerDref(DREF_HAS_JOYSTICK, "sim/joystick/has_joystick", 100); + registerDref(DREF_JOYSTICK_VALUES_ROll, "sim/joystick/joy_mapped_axis_value[1]", 100); + registerDref(DREF_JOYSTICK_VALUES_PITCH, "sim/joystick/joy_mapped_axis_value[2]", 100); + registerDref(DREF_JOYSTICK_VALUES_THROTTLE, "sim/joystick/joy_mapped_axis_value[3]", 100); + registerDref(DREF_JOYSTICK_VALUES_YAW, "sim/joystick/joy_mapped_axis_value[4]", 100); + registerDref(DREF_JOYSTICK_VALUES_PROP, "sim/joystick/joy_mapped_axis_value[8]", 100); + registerDref(DREF_JOYSTICK_VALUES_MIXTURE, "sim/joystick/joy_mapped_axis_value[9]", 100); + registerDref(DREF_JOYSTICK_VALUES_COLLECTIVE, "sim/joystick/joy_mapped_axis_value[5]", 100); + registerDref(DREF_JOYSTICK_VALUES_THRUST_VECTOR, "sim/joystick/joy_mapped_axis_value[12]", 100); + delay(250); } return true; - } \ No newline at end of file diff --git a/src/main/target/SITL/target.c b/src/main/target/SITL/target.c index 5c7a3f7b23..aabe2f6d2c 100644 --- a/src/main/target/SITL/target.c +++ b/src/main/target/SITL/target.c @@ -33,6 +33,7 @@ #include #include #include +#include #include #include "target.h" @@ -44,6 +45,7 @@ #include "drivers/pwm_mapping.h" #include "drivers/timer.h" #include "drivers/serial.h" +#include "config/config_streamer.h" #include "target/SITL/sim/realFlight.h" #include "target/SITL/sim/xplane.h" @@ -66,46 +68,55 @@ static int simPort = 0; void systemInit(void) { - printf("INAV %d.%d.%d SITL\n", FC_VERSION_MAJOR, FC_VERSION_MINOR, FC_VERSION_PATCH_LEVEL); + fprintf(stderr, "INAV %d.%d.%d SITL\n", FC_VERSION_MAJOR, FC_VERSION_MINOR, FC_VERSION_PATCH_LEVEL); clock_gettime(CLOCK_MONOTONIC, &start_time); - printf("[SYSTEM] Init...\n"); + fprintf(stderr, "[SYSTEM] Init...\n"); + + pthread_attr_t thAttr; + int policy = 0; + + pthread_attr_init(&thAttr); + pthread_attr_getschedpolicy(&thAttr, &policy); + + pthread_setschedprio(pthread_self(), sched_get_priority_min(policy)); + pthread_attr_destroy(&thAttr); if (pthread_mutex_init(&mainLoopLock, NULL) != 0) { - printf("[SYSTEM] Unable to create mainLoop lock.\n"); + fprintf(stderr, "[SYSTEM] Unable to create mainLoop lock.\n"); exit(1); } if (sitlSim != SITL_SIM_NONE) { - printf("[SIM] Waiting for connection...\n"); + fprintf(stderr, "[SIM] Waiting for connection...\n"); } switch (sitlSim) { case SITL_SIM_REALFLIGHT: if (mappingCount > RF_MAX_PWM_OUTS) { - printf("[SIM] Mapping error. RealFligt supports a maximum of %i PWM outputs.", RF_MAX_PWM_OUTS); + fprintf(stderr, "[SIM] Mapping error. RealFligt supports a maximum of %i PWM outputs.", RF_MAX_PWM_OUTS); sitlSim = SITL_SIM_NONE; break; } if (simRealFlightInit(simIp, pwmMapping, mappingCount, useImu)) { - printf("[SIM] Connection with RealFlight (%s) successfully established. \n", simIp); + fprintf(stderr, "[SIM] Connection with RealFlight successfully established.\n"); } else { - printf("[SIM] Connection with RealFlight (%s) NOT established. \n", simIp); + fprintf(stderr, "[SIM] Connection with RealFlight NOT established.\n"); } break; case SITL_SIM_XPLANE: if (mappingCount > XP_MAX_PWM_OUTS) { - printf("[SIM] Mapping error. RealFligt supports a maximum of %i PWM outputs.", XP_MAX_PWM_OUTS); + fprintf(stderr, "[SIM] Mapping error. RealFligt supports a maximum of %i PWM outputs.", XP_MAX_PWM_OUTS); sitlSim = SITL_SIM_NONE; break; } if (simXPlaneInit(simIp, simPort, pwmMapping, mappingCount, useImu)) { - printf("[SIM] Connection with XPlane successfully established. \n"); + fprintf(stderr, "[SIM] Connection with X-Plane successfully established.\n"); } else { - printf("[SIM] Connection with XPLane NOT established. \n"); + fprintf(stderr, "[SIM] Connection with X-PLane NOT established.\n"); } break; default: - printf("[SIM] No interface specified. Configurator only.\n"); + fprintf(stderr, "[SIM] No interface specified. Configurator only.\n"); break; } @@ -149,21 +160,22 @@ bool parseMapping(char* mapStr) void printCmdLineOptions(void) { - printf("Avaiable options:\n"); - printf("--sim=[rf|xp] Simulator interface: rf = RealFligt, xp = XPlane. Example: --sim=rf\n"); - printf("--simip=[ip] IP-Address oft the simulator host. If not specified localhost (127.0.0.1) is used."); - printf("--simport=[port] Port oft the simulator host."); - printf("--useimu Use IMU sensor data from the simulator instead of using attitude data from the simulator directly (experimental, not recommended)."); - printf("--chanmap=[mapstring] Channel mapping, Maps INAVs motor and servo PWM outputs to the virtual receiver output in the simulator.\n"); - printf(" The mapstring has the following format: M(otor)|S(servo)-,)... All numbers must have two digits\n"); - printf(" For example map motor 1 to virtal receiver output 1, servo 1 to output 2 and servo 2 to output 3:\n"); - printf(" --chanmap=M01-01,S01-02,S02-03\n"); + fprintf(stderr, "Avaiable options:\n"); + fprintf(stderr, "--path=[path] Path and filename of eeprom.bin. If not specified 'eeprom.bin' in program directory is used.\n"); + fprintf(stderr, "--sim=[rf|xp] Simulator interface: rf = RealFligt, xp = XPlane. Example: --sim=rf\n"); + fprintf(stderr, "--simip=[ip] IP-Address oft the simulator host. If not specified localhost (127.0.0.1) is used.\n"); + fprintf(stderr, "--simport=[port] Port oft the simulator host.\n"); + fprintf(stderr, "--useimu Use IMU sensor data from the simulator instead of using attitude data from the simulator directly (experimental, not recommended).\n"); + fprintf(stderr, "--chanmap=[mapstring] Channel mapping. Maps INAVs motor and servo PWM outputs to the virtual receiver output in the simulator.\n"); + fprintf(stderr, " The mapstring has the following format: M(otor)|S(servo)-,... All numbers must have two digits\n"); + fprintf(stderr, " For example: Map motor 1 to virtal receiver output 1, servo 1 to output 2 and servo 2 to output 3:\n"); + fprintf(stderr, " --chanmap=M01-01,S01-02,S02-03\n"); } void parseArguments(int argc, char *argv[]) { int c; - while(1) { + while(true) { static struct option longOpt[] = { {"sim", optional_argument, 0, 's'}, {"useimu", optional_argument, 0, 'u'}, @@ -171,6 +183,7 @@ void parseArguments(int argc, char *argv[]) {"simip", optional_argument, 0, 'i'}, {"simport", optional_argument, 0, 'p'}, {"help", optional_argument, 0, 'h'}, + {"path", optional_argument, 0, 'e'}, {NULL, 0, NULL, 0} }; @@ -185,13 +198,13 @@ void parseArguments(int argc, char *argv[]) } else if (strcmp(optarg, "xp") == 0){ sitlSim = SITL_SIM_XPLANE; } else { - printf("[SIM] Unsupported simulator %s.\n", optarg); + fprintf(stderr, "[SIM] Unsupported simulator %s.\n", optarg); } break; case 'c': if (!parseMapping(optarg) && sitlSim != SITL_SIM_NONE) { - printf("[SIM] Invalid channel mapping string.\n"); + fprintf(stderr, "[SIM] Invalid channel mapping string.\n"); printCmdLineOptions(); exit(0); } @@ -205,7 +218,11 @@ void parseArguments(int argc, char *argv[]) case 'i': simIp = optarg; break; - + case 'e': + if (!configFileSetPath(optarg)){ + fprintf(stderr, "[EEPROM] Invalid path, using eeprom file in program directory\n."); + } + break; case 'h': printCmdLineOptions(); exit(0); @@ -230,17 +247,6 @@ void unlockMainPID(void) } // Replacements for system functions -void microsleep(uint32_t usec) { - struct timespec ts; - ts.tv_sec = 0; - ts.tv_nsec = usec*1000UL; - while (nanosleep(&ts, &ts) == -1 && errno == EINTR) ; -} - -void delayMicroseconds_real(uint32_t us) { - microsleep(us); -} - timeUs_t micros(void) { struct timespec now; clock_gettime(CLOCK_MONOTONIC, &now); @@ -259,31 +265,31 @@ uint32_t millis(void) { void delayMicroseconds(timeUs_t us) { - timeUs_t now = micros(); - while (micros() - now < us); + usleep(us); } void delay(timeMs_t ms) { - while (ms--) - delayMicroseconds(1000); + delayMicroseconds(ms * 1000UL); } void systemReset(void) { - printf("[SYSTEM] Reset\n"); + fprintf(stderr, "[SYSTEM] Reset\n"); exit(0); } void systemResetToBootloader(void) { - printf("[SYSTEM] Reset to bootloader\n"); + fprintf(stderr, "[SYSTEM] Reset to bootloader\n"); exit(0); } void failureMode(failureMode_e mode) { - printf("[SYSTEM] Failure mode %d\n", mode); - while (1); + fprintf(stderr, "[SYSTEM] Failure mode %d\n", mode); + while (true) { + delay(1000); + }; } // Even more dummys and stubs diff --git a/src/main/target/SITL/target.h b/src/main/target/SITL/target.h index e3d5e5003a..1e3012f76b 100644 --- a/src/main/target/SITL/target.h +++ b/src/main/target/SITL/target.h @@ -65,6 +65,8 @@ #define USE_FAKE_BARO #define USE_FAKE_MAG #define USE_GPS_FAKE +#define USE_RANGEFINDER_FAKE +#define USE_RX_SIM #undef USE_DASHBOARD #undef USE_TELEMETRY_LTM From 1307549e4130b97f3ce6b60106f35db4f1451969 Mon Sep 17 00:00:00 2001 From: Scavanger Date: Sun, 5 Mar 2023 01:31:15 -0300 Subject: [PATCH 073/130] WIndows Build for CI --- .github/workflows/ci.yml | 38 +++++++++++++++++++++++++++++++++++++- 1 file changed, 37 insertions(+), 1 deletion(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 3f85a75ff4..ed45dfc5bb 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -43,7 +43,7 @@ jobs: name: ${{ env.BUILD_NAME }}.zip path: ./build/*.hex - build-SITL: + build-SITL-Linux: runs-on: ubuntu-latest steps: - uses: actions/checkout@v3 @@ -73,6 +73,42 @@ jobs: name: ${{ env.BUILD_NAME }}_SITL.zip path: ./build_SITL/*_SITL + build-SITL-Windows: + runs-on: windows-latest + defaults: + run: + shell: C:\tools\cygwin\bin\bash.exe -o igncr '{0}' + steps: + - uses: actions/checkout@v3 + - name: Setup Cygwin + uses: egor-tensin/setup-cygwin@v4 + with: + packages: cmake ruby ninja gcc-g++ + - name: Setup environment + env: + ACTIONS_ALLOW_UNSECURE_COMMANDS: true + run: | + # This is the hash of the commit for the PR + # when the action is triggered by PR, empty otherwise + COMMIT_ID=${{ github.event.pull_request.head.sha }} + # This is the hash of the commit when triggered by push + # but the hash of refs/pull//merge, which is different + # from the hash of the latest commit in the PR, that's + # why we try github.event.pull_request.head.sha first + COMMIT_ID=${COMMIT_ID:-${{ github.sha }}} + BUILD_SUFFIX=ci-$(date '+%Y%m%d')-$(git rev-parse --short ${COMMIT_ID}) + VERSION=$(grep project CMakeLists.txt|awk -F VERSION '{ gsub(/^[ \t]+|[ \t\)]+$/, "", $2); print $2 }') + echo "BUILD_SUFFIX=${BUILD_SUFFIX}" >> $GITHUB_ENV + echo "BUILD_NAME=inav-${VERSION}-${BUILD_SUFFIX}" >> $GITHUB_ENV + - name: Build SITL + run: mkdir -p build_SITL && cd build_SITL && cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -G Ninja .. && ninja + - name: Upload artifacts + uses: actions/upload-artifact@v2-preview + with: + name: ${{ env.BUILD_NAME }}_SITL-WIN.zip + path: ./build_SITL/*.exe + + test: needs: [build] runs-on: ubuntu-latest From e1cbf965e4049532b7d3e56c7158dc2cd445140f Mon Sep 17 00:00:00 2001 From: Scavanger Date: Mon, 6 Mar 2023 09:02:31 -0300 Subject: [PATCH 074/130] X-Plane bugfix --- docs/SITL/X-Plane.md | 10 ++-- src/main/sensors/compass.c | 4 ++ src/main/target/SITL/sim/realFlight.c | 1 - src/main/target/SITL/sim/xplane.c | 67 ++++++++++++--------------- 4 files changed, 39 insertions(+), 43 deletions(-) diff --git a/docs/SITL/X-Plane.md b/docs/SITL/X-Plane.md index baca0e0fee..28f4679553 100644 --- a/docs/SITL/X-Plane.md +++ b/docs/SITL/X-Plane.md @@ -19,12 +19,12 @@ In the settings, calibrate the joystick, set it up and assign the axes as follow |------|---------| | Roll | Roll | | Pitch | Pitch | -| Throttle | Throttle | +| Throttle | Cowl Flap 1 | | Yaw | Yaw | -| Channel 5 | Prop | -| Channel 6 | Mixture | -| Channel 7 | Collective | -| Channel 8 | Thrust vector | +| Channel 5 | Cowl Flap 2 | +| Channel 6 | Cowl Flap 3 | +| Channel 7 | Cowl Flap 4 | +| Channel 8 | Cowl Flap 5 | Reverse axis in X-Plane if necessary. diff --git a/src/main/sensors/compass.c b/src/main/sensors/compass.c index 4e610ee00a..23d45ed787 100644 --- a/src/main/sensors/compass.c +++ b/src/main/sensors/compass.c @@ -367,6 +367,9 @@ void compassUpdate(timeUs_t currentTimeUs) static int16_t magPrev[XYZ_AXIS_COUNT]; static int magAxisDeviation[XYZ_AXIS_COUNT]; +#if defined(SITL_BUILD) + ENABLE_STATE(COMPASS_CALIBRATED); +#else // Check magZero if ( compassConfig()->magZero.raw[X] == 0 && compassConfig()->magZero.raw[Y] == 0 && compassConfig()->magZero.raw[Z] == 0 && @@ -377,6 +380,7 @@ void compassUpdate(timeUs_t currentTimeUs) else { ENABLE_STATE(COMPASS_CALIBRATED); } +#endif if (!mag.dev.read(&mag.dev)) { mag.magADC[X] = 0; diff --git a/src/main/target/SITL/sim/realFlight.c b/src/main/target/SITL/sim/realFlight.c index c2feacbf75..4c3f2fcfe9 100644 --- a/src/main/target/SITL/sim/realFlight.c +++ b/src/main/target/SITL/sim/realFlight.c @@ -399,7 +399,6 @@ static void exchangeData(void) constrainToInt16(north.y * 16000.0f), constrainToInt16(north.z * 16000.0f) ); - ENABLE_STATE(COMPASS_CALIBRATED); } static void* soapWorker(void* arg) diff --git a/src/main/target/SITL/sim/xplane.c b/src/main/target/SITL/sim/xplane.c index e1b10fcb50..33b849790e 100644 --- a/src/main/target/SITL/sim/xplane.c +++ b/src/main/target/SITL/sim/xplane.c @@ -92,18 +92,6 @@ static float barometer = 0; static bool hasJoystick = false; static float joystickRaw[XPLANE_JOYSTICK_AXIS_COUNT]; -enum -{ - RF_ASSIGNMENT_PITCH, - RF_ASSIGNMENT_ROLL, - RF_ASSIGNMENT_YAW, - RF_ASSIGNMENT_THROTLE, - RF_ASSIGNMENT_PROP, - RF_ASSIGNMENT_MIXTURE, - RF_ASSIGNMENT_COLLECTIVE, - RF_ASSIGNMENT_THRUST_VECTOR -}; - typedef enum { DREF_LATITUDE, @@ -132,10 +120,10 @@ typedef enum DREF_JOYSTICK_VALUES_PITCH, DREF_JOYSTICK_VALUES_THROTTLE, DREF_JOYSTICK_VALUES_YAW, - DREF_JOYSTICK_VALUES_PROP, - DREF_JOYSTICK_VALUES_MIXTURE, - DREF_JOYSTICK_VALUES_COLLECTIVE, - DREF_JOYSTICK_VALUES_THRUST_VECTOR, + DREF_JOYSTICK_VALUES_CH5, + DREF_JOYSTICK_VALUES_CH6, + DREF_JOYSTICK_VALUES_CH7, + DREF_JOYSTICK_VALUES_CH8, } dref_t; uint32_t xint2uint32 (uint8_t * buf) @@ -210,6 +198,11 @@ static void* listenWorker(void* arg) sendDref("sim/joystick/yoke_roll_ratio", yokeValues[0]); sendDref("sim/joystick/yoke_pitch_ratio", yokeValues[1]); sendDref("sim/joystick/yoke_heading_ratio", yokeValues[2]); + sendDref("sim/cockpit2/engine/actuators/cowl_flap_ratio[0]", 0); + sendDref("sim/cockpit2/engine/actuators/cowl_flap_ratio[1]", 0); + sendDref("sim/cockpit2/engine/actuators/cowl_flap_ratio[2]", 0); + sendDref("sim/cockpit2/engine/actuators/cowl_flap_ratio[3]", 0); + sendDref("sim/cockpit2/engine/actuators/cowl_flap_ratio[4]", 0); recvLen = recvfrom(sockFd, buf, sizeof(buf), 0, (struct sockaddr*)&remoteAddr, &slen); if (recvLen < 0 && errno != EWOULDBLOCK) { @@ -326,19 +319,19 @@ static void* listenWorker(void* arg) joystickRaw[3] = value; break; - case DREF_JOYSTICK_VALUES_PROP: + case DREF_JOYSTICK_VALUES_CH5: joystickRaw[4] = value; break; - case DREF_JOYSTICK_VALUES_MIXTURE: + case DREF_JOYSTICK_VALUES_CH6: joystickRaw[5] = value; break; - case DREF_JOYSTICK_VALUES_COLLECTIVE: + case DREF_JOYSTICK_VALUES_CH7: joystickRaw[6] = value; break; - case DREF_JOYSTICK_VALUES_THRUST_VECTOR: + case DREF_JOYSTICK_VALUES_CH8: joystickRaw[7] = value; break; @@ -357,14 +350,14 @@ static void* listenWorker(void* arg) if (hasJoystick) { uint16_t channelValues[XPLANE_JOYSTICK_AXIS_COUNT]; - channelValues[0] = FLOAT_MINUS_1_1_TO_PWM(joystickRaw[RF_ASSIGNMENT_ROLL]); - channelValues[1] = FLOAT_MINUS_1_1_TO_PWM(joystickRaw[RF_ASSIGNMENT_PITCH]); - channelValues[2] = FLOAT_0_1_TO_PWM(joystickRaw[RF_ASSIGNMENT_THROTLE]); - channelValues[3] = FLOAT_MINUS_1_1_TO_PWM(joystickRaw[RF_ASSIGNMENT_YAW]); - channelValues[4] = FLOAT_0_1_TO_PWM(joystickRaw[RF_ASSIGNMENT_PROP]); - channelValues[5] = FLOAT_0_1_TO_PWM(joystickRaw[RF_ASSIGNMENT_MIXTURE]); - channelValues[6] = FLOAT_0_1_TO_PWM(joystickRaw[RF_ASSIGNMENT_COLLECTIVE]); - channelValues[7] = FLOAT_0_1_TO_PWM(joystickRaw[RF_ASSIGNMENT_THRUST_VECTOR]); + channelValues[0] = FLOAT_MINUS_1_1_TO_PWM(joystickRaw[0]); + channelValues[1] = FLOAT_MINUS_1_1_TO_PWM(joystickRaw[1]); + channelValues[2] = FLOAT_0_1_TO_PWM(joystickRaw[2]); + channelValues[3] = FLOAT_MINUS_1_1_TO_PWM(joystickRaw[3]); + channelValues[4] = FLOAT_0_1_TO_PWM(joystickRaw[4]); + channelValues[5] = FLOAT_0_1_TO_PWM(joystickRaw[5]); + channelValues[6] = FLOAT_0_1_TO_PWM(joystickRaw[6]); + channelValues[7] = FLOAT_0_1_TO_PWM(joystickRaw[7]); rxSimSetChannelValue(channelValues, XPLANE_JOYSTICK_AXIS_COUNT); } @@ -428,7 +421,6 @@ static void* listenWorker(void* arg) constrainToInt16(north.y * 16000.0f), constrainToInt16(north.z * 16000.0f) ); - ENABLE_STATE(COMPASS_CALIBRATED); if (!initalized) { ENABLE_ARMING_FLAG(SIMULATOR_MODE_SITL); @@ -503,14 +495,15 @@ bool simXPlaneInit(char* ip, int port, uint8_t* mapping, uint8_t mapCount, bool registerDref(DREF_POS_R, "sim/flightmodel/position/R", 100); registerDref(DREF_POS_BARO_CURRENT_INHG, "sim/weather/barometer_current_inhg", 100); registerDref(DREF_HAS_JOYSTICK, "sim/joystick/has_joystick", 100); - registerDref(DREF_JOYSTICK_VALUES_ROll, "sim/joystick/joy_mapped_axis_value[1]", 100); - registerDref(DREF_JOYSTICK_VALUES_PITCH, "sim/joystick/joy_mapped_axis_value[2]", 100); - registerDref(DREF_JOYSTICK_VALUES_THROTTLE, "sim/joystick/joy_mapped_axis_value[3]", 100); - registerDref(DREF_JOYSTICK_VALUES_YAW, "sim/joystick/joy_mapped_axis_value[4]", 100); - registerDref(DREF_JOYSTICK_VALUES_PROP, "sim/joystick/joy_mapped_axis_value[8]", 100); - registerDref(DREF_JOYSTICK_VALUES_MIXTURE, "sim/joystick/joy_mapped_axis_value[9]", 100); - registerDref(DREF_JOYSTICK_VALUES_COLLECTIVE, "sim/joystick/joy_mapped_axis_value[5]", 100); - registerDref(DREF_JOYSTICK_VALUES_THRUST_VECTOR, "sim/joystick/joy_mapped_axis_value[12]", 100); + registerDref(DREF_JOYSTICK_VALUES_PITCH, "sim/joystick/joy_mapped_axis_value[1]", 100); + registerDref(DREF_JOYSTICK_VALUES_ROll, "sim/joystick/joy_mapped_axis_value[2]", 100); + registerDref(DREF_JOYSTICK_VALUES_YAW, "sim/joystick/joy_mapped_axis_value[3]", 100); + // Abusing cowl flaps for other channels + registerDref(DREF_JOYSTICK_VALUES_THROTTLE, "sim/joystick/joy_mapped_axis_value[57]", 100); + registerDref(DREF_JOYSTICK_VALUES_CH5, "sim/joystick/joy_mapped_axis_value[58]", 100); + registerDref(DREF_JOYSTICK_VALUES_CH6, "sim/joystick/joy_mapped_axis_value[59]", 100); + registerDref(DREF_JOYSTICK_VALUES_CH7, "sim/joystick/joy_mapped_axis_value[60]", 100); + registerDref(DREF_JOYSTICK_VALUES_CH8, "sim/joystick/joy_mapped_axis_value[61]", 100); delay(250); } From d90280eb029238fc980afe965bb1f4fc30fbc45a Mon Sep 17 00:00:00 2001 From: Scavanger Date: Mon, 6 Mar 2023 09:05:43 -0300 Subject: [PATCH 075/130] Rangefinder OSD Element Bugfix --- src/main/io/osd.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index eed14a2764..55030cd211 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1947,6 +1947,8 @@ static bool osdDrawSingleElement(uint8_t item) int32_t range = rangefinderGetLatestRawAltitude(); if (range < 0) { buff[0] = '-'; + buff[1] = '-'; + buff[2] = '-'; } else { osdFormatDistanceSymbol(buff, range, 1); } From 060973d4be6bdc463a0d1715ab6783eddfe24f8f Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 6 Mar 2023 20:31:27 +0100 Subject: [PATCH 076/130] Drop the moron threshold --- src/main/fc/settings.yaml | 5 ----- src/main/sensors/gyro.c | 5 ++--- src/main/sensors/gyro.h | 1 - src/main/sensors/sensors.h | 1 + 4 files changed, 3 insertions(+), 9 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index a089c01859..ded56fcc0e 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -232,11 +232,6 @@ groups: default_value: "PT1" field: gyro_anti_aliasing_lpf_type table: filter_type - - name: moron_threshold - description: "When powering up, gyro bias is calculated. If the model is shaking/moving during this initial calibration, offsets are calculated incorrectly, and could lead to poor flying performance. This threshold means how much average gyro reading could differ before re-calibration is triggered." - default_value: 32 - field: gyroMovementCalibrationThreshold - max: 128 - name: gyro_main_lpf_hz description: "Software based gyro main lowpass filter. Value is cutoff frequency (Hz)" default_value: 60 diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index d40676477b..7d29a50638 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -96,13 +96,12 @@ EXTENDED_FASTRAM secondaryDynamicGyroNotchState_t secondaryDynamicGyroNotchState #endif -PG_REGISTER_WITH_RESET_TEMPLATE(gyroConfig_t, gyroConfig, PG_GYRO_CONFIG, 5); +PG_REGISTER_WITH_RESET_TEMPLATE(gyroConfig_t, gyroConfig, PG_GYRO_CONFIG, 6); PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig, .gyro_lpf = SETTING_GYRO_HARDWARE_LPF_DEFAULT, .gyro_anti_aliasing_lpf_hz = SETTING_GYRO_ANTI_ALIASING_LPF_HZ_DEFAULT, .gyro_anti_aliasing_lpf_type = SETTING_GYRO_ANTI_ALIASING_LPF_TYPE_DEFAULT, - .gyroMovementCalibrationThreshold = SETTING_MORON_THRESHOLD_DEFAULT, .looptime = SETTING_LOOPTIME_DEFAULT, #ifdef USE_DUAL_GYRO .gyro_to_use = SETTING_GYRO_TO_USE_DEFAULT, @@ -325,7 +324,7 @@ void gyroStartCalibration(void) } #endif - zeroCalibrationStartV(&gyroCalibration[0], CALIBRATING_GYRO_TIME_MS, gyroConfig()->gyroMovementCalibrationThreshold, false); + zeroCalibrationStartV(&gyroCalibration[0], CALIBRATING_GYRO_TIME_MS, CALIBRATING_GYRO_MORON_THRESHOLD, false); } bool gyroIsCalibrationComplete(void) diff --git a/src/main/sensors/gyro.h b/src/main/sensors/gyro.h index f6a3f71b8f..ce0d9ca13c 100644 --- a/src/main/sensors/gyro.h +++ b/src/main/sensors/gyro.h @@ -62,7 +62,6 @@ extern gyro_t gyro; extern dynamicGyroNotchState_t dynamicGyroNotchState; typedef struct gyroConfig_s { - uint8_t gyroMovementCalibrationThreshold; // people keep forgetting that moving model while init results in wrong gyro offsets. and then they never reset gyro. so this is now on by default. uint16_t looptime; // imu loop time in us uint8_t gyro_lpf; // gyro LPF setting - values are driver specific, in case of invalid number, a reasonable default ~30-40HZ is chosen. uint16_t gyro_anti_aliasing_lpf_hz; diff --git a/src/main/sensors/sensors.h b/src/main/sensors/sensors.h index 1a6ab0b8b2..b9d067a59b 100644 --- a/src/main/sensors/sensors.h +++ b/src/main/sensors/sensors.h @@ -43,6 +43,7 @@ typedef union flightDynamicsTrims_u { #define CALIBRATING_PITOT_TIME_MS 2000 #define CALIBRATING_GYRO_TIME_MS 2000 #define CALIBRATING_ACC_TIME_MS 500 +#define CALIBRATING_GYRO_MORON_THRESHOLD 32 // These bits have to be aligned with sensorIndex_e typedef enum { From 2aaefd4df2adbb3377435dda5550ae021b849a7a Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 6 Mar 2023 20:31:44 +0100 Subject: [PATCH 077/130] Docs update --- docs/Settings.md | 10 ---------- 1 file changed, 10 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index fa30e623d8..b9239f7865 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -2602,16 +2602,6 @@ ID of mixer preset applied in a Configurator. **Do not modify manually**. Used o --- -### moron_threshold - -When powering up, gyro bias is calculated. If the model is shaking/moving during this initial calibration, offsets are calculated incorrectly, and could lead to poor flying performance. This threshold means how much average gyro reading could differ before re-calibration is triggered. - -| Default | Min | Max | -| --- | --- | --- | -| 32 | | 128 | - ---- - ### motor_direction_inverted Use if you need to inverse yaw motor direction. From 7e6f1040da122b8010b8f21b9ba9ea997c9011c1 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 6 Mar 2023 21:16:44 +0100 Subject: [PATCH 078/130] Fix compilation is OSD is disabled --- src/main/fc/config.c | 4 ++++ src/main/fc/fc_msp.c | 4 ++++ src/main/io/displayport_msp_bf_compat.c | 2 +- src/main/io/displayport_msp_bf_compat.h | 2 +- src/main/rx/crsf.c | 7 ++++--- 5 files changed, 14 insertions(+), 5 deletions(-) diff --git a/src/main/fc/config.c b/src/main/fc/config.c index 3c6a09c688..8fa8b1682b 100755 --- a/src/main/fc/config.c +++ b/src/main/fc/config.c @@ -340,7 +340,9 @@ void processSaveConfigAndNotify(void) writeEEPROM(); readEEPROM(); beeperConfirmationBeeps(1); +#ifdef USE_OSD osdShowEEPROMSavedNotification(); +#endif } void writeEEPROM(void) @@ -370,7 +372,9 @@ void ensureEEPROMContainsValidData(void) */ void saveConfigAndNotify(void) { +#ifdef USE_OSD osdStartedSaveProcess(); +#endif saveState = SAVESTATE_SAVEANDNOTIFY; } diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index ee5c8f0397..6a5d18a16d 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -3221,8 +3221,12 @@ static bool mspParameterGroupsCommand(sbuf_t *dst, sbuf_t *src) #ifdef USE_SIMULATOR bool isOSDTypeSupportedBySimulator(void) { +#ifdef USE_OSD displayPort_t *osdDisplayPort = osdGetDisplayPort(); return (osdDisplayPort && osdDisplayPort->cols == 30 && (osdDisplayPort->rows == 13 || osdDisplayPort->rows == 16)); +#else + return false; +#endif } void mspWriteSimulatorOSD(sbuf_t *dst) diff --git a/src/main/io/displayport_msp_bf_compat.c b/src/main/io/displayport_msp_bf_compat.c index b6b1fe9d81..8b9af671d5 100644 --- a/src/main/io/displayport_msp_bf_compat.c +++ b/src/main/io/displayport_msp_bf_compat.c @@ -17,7 +17,7 @@ #include "platform.h" -#ifdef USE_MSP_DISPLAYPORT +#if defined(USE_OSD) && defined(USE_MSP_DISPLAYPORT) #ifndef DISABLE_MSP_BF_COMPAT diff --git a/src/main/io/displayport_msp_bf_compat.h b/src/main/io/displayport_msp_bf_compat.h index b7fe270700..91f231d005 100644 --- a/src/main/io/displayport_msp_bf_compat.h +++ b/src/main/io/displayport_msp_bf_compat.h @@ -22,7 +22,7 @@ #include "platform.h" -#if defined(USE_MSP_DISPLAYPORT) && !defined(DISABLE_MSP_BF_COMPAT) +#if defined(USE_OSD) && defined(USE_MSP_DISPLAYPORT) && !defined(DISABLE_MSP_BF_COMPAT) #include "osd.h" uint8_t getBfCharacter(uint8_t ch, uint8_t page); #define isBfCompatibleVideoSystem(osdConfigPtr) (osdConfigPtr->video_system == VIDEO_SYSTEM_BFCOMPAT) diff --git a/src/main/rx/crsf.c b/src/main/rx/crsf.c index d8182533df..fb2f7ec386 100755 --- a/src/main/rx/crsf.c +++ b/src/main/rx/crsf.c @@ -242,6 +242,7 @@ STATIC_UNIT_TESTED uint8_t crsfFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig) rxLinkStatistics.uplinkTXPower = crsfTxPowerStatesmW[crsftxpowerindex]; rxLinkStatistics.activeAntenna = linkStats->activeAntenna; +#ifdef USE_OSD if (rxLinkStatistics.uplinkLQ > 0) { int16_t uplinkStrength; // RSSI dBm converted to % uplinkStrength = constrain((100 * sq((osdConfig()->rssi_dbm_max - osdConfig()->rssi_dbm_min)) - (100 * sq((osdConfig()->rssi_dbm_max - rxLinkStatistics.uplinkRSSI)))) / sq((osdConfig()->rssi_dbm_max - osdConfig()->rssi_dbm_min)),0,100); @@ -250,10 +251,10 @@ STATIC_UNIT_TESTED uint8_t crsfFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig) else if (rxLinkStatistics.uplinkRSSI < osdConfig()->rssi_dbm_min) uplinkStrength = 0; lqTrackerSet(rxRuntimeConfig->lqTracker, scaleRange(uplinkStrength, 0, 99, 0, RSSI_MAX_VALUE)); - } - else + } else { lqTrackerSet(rxRuntimeConfig->lqTracker, 0); - + } +#endif // This is not RC channels frame, update channel value but don't indicate frame completion return RX_FRAME_PENDING; } From 5c5bf3bffdc279ae98fd92088997933550d455c9 Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Mon, 6 Mar 2023 21:56:00 +0000 Subject: [PATCH 079/130] not even INAV should dereference NULL pointers --- src/main/fc/cli.c | 18 +++++++++++------- 1 file changed, 11 insertions(+), 7 deletions(-) diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index e1633983b0..9596b3d9e3 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -1690,7 +1690,7 @@ static void cliDelay(char* cmdLine) { cliPrintLine("CLI delay deactivated"); return; } - + ms = fastA2I(cmdLine); if (ms) { cliDelayMs = ms; @@ -1699,7 +1699,7 @@ static void cliDelay(char* cmdLine) { } else { cliShowParseError(); } - + } static void printServo(uint8_t dumpMask, const servoParam_t *servoParam, const servoParam_t *defaultServoParam) @@ -2288,7 +2288,7 @@ static void cliFlashInfo(char *cmdline) UNUSED(cmdline); const flashGeometry_t *layout = flashGetGeometry(); - + if (layout->totalSize == 0) { cliPrintLine("Flash not available"); return; @@ -2323,12 +2323,12 @@ static void cliFlashErase(char *cmdline) UNUSED(cmdline); const flashGeometry_t *layout = flashGetGeometry(); - + if (layout->totalSize == 0) { cliPrintLine("Flash not available"); return; } - + cliPrintLine("Erasing..."); flashfsEraseCompletely(); @@ -3414,8 +3414,12 @@ static void cliStatus(char *cmdline) cliPrint("OSD: "); #if defined(USE_OSD) displayPort_t *osdDisplayPort = osdGetDisplayPort(); - cliPrintf("%s [%u x %u]", osdDisplayPort->displayPortType, osdDisplayPort->cols, osdDisplayPort->rows); -#else + if (osdDisplayPort != NULL) { + cliPrintf("%s [%u x %u]", osdDisplayPort->displayPortType, osdDisplayPort->cols, osdDisplayPort->rows); + } else { + cliPrint("not enabled"); + } +#else cliPrint("not used"); #endif cliPrintLinefeed(); From ba55f70140245625c77961e2359060c685695e93 Mon Sep 17 00:00:00 2001 From: rmaia <9812730+rmaia3d@users.noreply.github.com> Date: Tue, 7 Mar 2023 18:14:10 -0300 Subject: [PATCH 080/130] Initial mods --- src/main/io/osd.c | 81 +++++++++++++++++++++++++++++++---------------- 1 file changed, 54 insertions(+), 27 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 12c9cc469a..2637e840c4 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -251,34 +251,41 @@ static void osdLeftAlignString(char *buff) */ static void osdFormatDistanceSymbol(char *buff, int32_t dist, uint8_t decimals) { + uint8_t digits = 3U; // Total number of digits (including decimal point) + uint8_t sym_index = 3U; // Position (index) at buffer of units symbol + if (isBfCompatibleVideoSystem(osdConfig())) { + // Add one digit so up no switch to scaled decimal occurs above 99 + digits = 4U; + sym_index = 4U; + } switch ((osd_unit_e)osdConfig()->units) { case OSD_UNIT_UK: FALLTHROUGH; case OSD_UNIT_IMPERIAL: - if (osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(dist), FEET_PER_MILE, decimals, 3, 3)) { - buff[3] = SYM_DIST_MI; + if (osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(dist), FEET_PER_MILE, decimals, 3, digits)) { + buff[sym_index] = SYM_DIST_MI; } else { - buff[3] = SYM_DIST_FT; + buff[sym_index] = SYM_DIST_FT; } - buff[4] = '\0'; + buff[sym_index + 1] = '\0'; break; case OSD_UNIT_METRIC_MPH: FALLTHROUGH; case OSD_UNIT_METRIC: - if (osdFormatCentiNumber(buff, dist, METERS_PER_KILOMETER, decimals, 3, 3)) { - buff[3] = SYM_DIST_KM; + if (osdFormatCentiNumber(buff, dist, METERS_PER_KILOMETER, decimals, 3, digits)) { + buff[sym_index] = SYM_DIST_KM; } else { - buff[3] = SYM_DIST_M; + buff[sym_index] = SYM_DIST_M; } - buff[4] = '\0'; + buff[sym_index + 1] = '\0'; break; case OSD_UNIT_GA: - if (osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(dist), FEET_PER_NAUTICALMILE, decimals, 3, 3)) { - buff[3] = SYM_DIST_NM; + if (osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(dist), FEET_PER_NAUTICALMILE, decimals, 3, digits)) { + buff[sym_index] = SYM_DIST_NM; } else { - buff[3] = SYM_DIST_FT; + buff[sym_index] = SYM_DIST_FT; } - buff[4] = '\0'; + buff[sym_index + 1] = '\0'; break; } } @@ -2772,6 +2779,14 @@ static bool osdDrawSingleElement(uint8_t item) bool moreThanAh = false; timeUs_t currentTimeUs = micros(); timeDelta_t efficiencyTimeDelta = cmpTimeUs(currentTimeUs, efficiencyUpdated); + // Check for BFCOMPAT mode + uint8_t digits = 3U; + bool bf_compat = false; + if (isBfCompatibleVideoSystem(osdConfig())) { + // Increase number of digits so values above 99 don't get scaled by osdFormatCentiNumber + digits = 4U; + bf_compat = true; + } if (STATE(GPS_FIX) && gpsSol.groundSpeed > 0) { if (efficiencyTimeDelta >= EFFICIENCY_UPDATE_INTERVAL) { value = pt1FilterApply4(&eFilterState, ((float)getAmperage() / gpsSol.groundSpeed) / 0.0036f, @@ -2787,47 +2802,59 @@ static bool osdDrawSingleElement(uint8_t item) case OSD_UNIT_UK: FALLTHROUGH; case OSD_UNIT_IMPERIAL: - moreThanAh = osdFormatCentiNumber(buff, value * METERS_PER_MILE / 10, 1000, 0, 2, 3); + moreThanAh = osdFormatCentiNumber(buff, value * METERS_PER_MILE / 10, 1000, 0, 2, digits); if (!moreThanAh) { tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_MI_0, SYM_MAH_MI_1); } else { tfp_sprintf(buff, "%s%c", buff, SYM_AH_MI); } if (!efficiencyValid) { - buff[0] = buff[1] = buff[2] = '-'; - buff[3] = SYM_MAH_MI_0; - buff[4] = SYM_MAH_MI_1; - buff[5] = '\0'; + if(bf_compat){ + buff[0] = buff[1] = buff[2] = buf[3] = '-'; + } else { + buff[0] = buff[1] = buff[2] = '-'; + } + buff[digits] = SYM_MAH_MI_0; + buff[digits + 1] = SYM_MAH_MI_1; + buff[digits + 2] = '\0'; } break; case OSD_UNIT_GA: - moreThanAh = osdFormatCentiNumber(buff, value * METERS_PER_NAUTICALMILE / 10, 1000, 0, 2, 3); + moreThanAh = osdFormatCentiNumber(buff, value * METERS_PER_NAUTICALMILE / 10, 1000, 0, 2, digits); if (!moreThanAh) { tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_NM_0, SYM_MAH_NM_1); } else { tfp_sprintf(buff, "%s%c", buff, SYM_AH_NM); } if (!efficiencyValid) { - buff[0] = buff[1] = buff[2] = '-'; - buff[3] = SYM_MAH_NM_0; - buff[4] = SYM_MAH_NM_1; - buff[5] = '\0'; + if(bf_compat){ + buff[0] = buff[1] = buff[2] = buf[3] = '-'; + } else { + buff[0] = buff[1] = buff[2] = '-'; + } + buff[digits] = SYM_MAH_NM_0; + buff[digits + 1] = SYM_MAH_NM_1; + buff[digits + 2] = '\0'; } break; case OSD_UNIT_METRIC_MPH: FALLTHROUGH; case OSD_UNIT_METRIC: - moreThanAh = osdFormatCentiNumber(buff, value * 100, 1000, 0, 2, 3); + moreThanAh = osdFormatCentiNumber(buff, value * 100, 1000, 0, 2, digits); if (!moreThanAh) { tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_KM_0, SYM_MAH_KM_1); } else { tfp_sprintf(buff, "%s%c", buff, SYM_AH_KM); } if (!efficiencyValid) { - buff[0] = buff[1] = buff[2] = '-'; - buff[3] = SYM_MAH_KM_0; - buff[4] = SYM_MAH_KM_1; - buff[5] = '\0'; + if(bf_compat){ + buff[0] = buff[1] = buff[2] = buf[3] = '-'; + } else { + buff[0] = buff[1] = buff[2] = '-'; + } + buff[digits] = SYM_MAH_KM_0; + buff[digits + 1] = SYM_MAH_KM_1; + buff[digits + 2] = '\0'; } break; } From cafa34d7f9204449a35608ca4e8f2a279bff9349 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Tue, 7 Mar 2023 21:26:50 +0000 Subject: [PATCH 081/130] Update navigation_multicopter.c --- src/main/navigation/navigation_multicopter.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/navigation/navigation_multicopter.c b/src/main/navigation/navigation_multicopter.c index ae53d0961b..d8f0f4903a 100644 --- a/src/main/navigation/navigation_multicopter.c +++ b/src/main/navigation/navigation_multicopter.c @@ -483,7 +483,7 @@ static void updatePositionVelocityController_MC(const float maxSpeed) * 2 - in WP mission when: slowDownForTurning is OFF, we do not fly towards na last waypoint and computed speed is < maxSpeed */ if ( - (navGetCurrentStateFlags() & NAV_AUTO_WP && + ((navGetCurrentStateFlags() & NAV_AUTO_WP || posControl.flags.rthTrackbackActive) && !isNavHoldPositionActive() && newVelTotal < maxSpeed && !navConfig()->mc.slowDownForTurning From 72946187931fdbc1d41b95f58ba60fa5353dc889 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Tue, 7 Mar 2023 22:02:59 +0000 Subject: [PATCH 082/130] Update rc_controls.c --- src/main/fc/rc_controls.c | 17 +++++++++-------- 1 file changed, 9 insertions(+), 8 deletions(-) diff --git a/src/main/fc/rc_controls.c b/src/main/fc/rc_controls.c index 8391f6bebf..67f9273d26 100644 --- a/src/main/fc/rc_controls.c +++ b/src/main/fc/rc_controls.c @@ -27,6 +27,8 @@ #include "blackbox/blackbox.h" +#include "cms/cms.h" + #include "common/axis.h" #include "common/maths.h" #include "common/utils.h" @@ -250,17 +252,16 @@ void processRcStickPositions(bool isThrottleLow) return; } - if (ARMING_FLAG(ARMED)) { - // actions during armed + /* Disable stick commands when armed, in CLI mode or CMS is active */ + bool disableStickCommands = ARMING_FLAG(ARMED) || cliMode; +#ifdef USE_CMS + disableStickCommands = disableStickCommands || cmsInMenu; +#endif + if (disableStickCommands) { return; } - // Disable stick commands when in CLI mode. Ideally, they should also be disabled when configurator is connected - if (cliMode) { - return; - } - - // actions during not armed and not in CLI + /* REMAINING SECTION HANDLES STICK COMANDS ONLY */ // GYRO calibration if (rcSticks == THR_LO + YAW_LO + PIT_LO + ROL_CE) { From b9e1de0d2147074fb6a76a85b1aff5a93c83fc0f Mon Sep 17 00:00:00 2001 From: rmaia <9812730+rmaia3d@users.noreply.github.com> Date: Wed, 8 Mar 2023 11:07:52 -0300 Subject: [PATCH 083/130] Fix typos and add HDOP --- src/main/io/osd.c | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 2637e840c4..88df95c1a3 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1827,7 +1827,11 @@ static bool osdDrawSingleElement(uint8_t item) buff[0] = SYM_HDP_L; buff[1] = SYM_HDP_R; int32_t centiHDOP = 100 * gpsSol.hdop / HDOP_SCALE; - osdFormatCentiNumber(&buff[2], centiHDOP, 0, 1, 0, 2); + uint8_t digits = 2U; + if (isBfCompatibleVideoSystem(osdConfig())) { + digits = 3U; + } + osdFormatCentiNumber(&buff[2], centiHDOP, 0, 1, 0, digits); break; } @@ -2810,7 +2814,7 @@ static bool osdDrawSingleElement(uint8_t item) } if (!efficiencyValid) { if(bf_compat){ - buff[0] = buff[1] = buff[2] = buf[3] = '-'; + buff[0] = buff[1] = buff[2] = buff[3] = '-'; } else { buff[0] = buff[1] = buff[2] = '-'; } @@ -2828,7 +2832,7 @@ static bool osdDrawSingleElement(uint8_t item) } if (!efficiencyValid) { if(bf_compat){ - buff[0] = buff[1] = buff[2] = buf[3] = '-'; + buff[0] = buff[1] = buff[2] = buff[3] = '-'; } else { buff[0] = buff[1] = buff[2] = '-'; } @@ -2848,7 +2852,7 @@ static bool osdDrawSingleElement(uint8_t item) } if (!efficiencyValid) { if(bf_compat){ - buff[0] = buff[1] = buff[2] = buf[3] = '-'; + buff[0] = buff[1] = buff[2] = buff[3] = '-'; } else { buff[0] = buff[1] = buff[2] = '-'; } From 05092fbd7b74577f6f83b680880a2ccf52a637e1 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Wed, 8 Mar 2023 17:24:51 +0000 Subject: [PATCH 084/130] Update navigation_multicopter.c --- src/main/navigation/navigation_multicopter.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/navigation/navigation_multicopter.c b/src/main/navigation/navigation_multicopter.c index d8f0f4903a..1645e24dd8 100644 --- a/src/main/navigation/navigation_multicopter.c +++ b/src/main/navigation/navigation_multicopter.c @@ -480,7 +480,7 @@ static void updatePositionVelocityController_MC(const float maxSpeed) /* * We override computed speed with max speed in following cases: * 1 - computed velocity is > maxSpeed - * 2 - in WP mission when: slowDownForTurning is OFF, we do not fly towards na last waypoint and computed speed is < maxSpeed + * 2 - in WP mission or RTH Trackback when: slowDownForTurning is OFF, not a hold waypoint and computed speed is < maxSpeed */ if ( ((navGetCurrentStateFlags() & NAV_AUTO_WP || posControl.flags.rthTrackbackActive) && From f4b7f574d144fdae2198ff1e2a2ac18d83c7e2e6 Mon Sep 17 00:00:00 2001 From: rmaia <9812730+rmaia3d@users.noreply.github.com> Date: Wed, 8 Mar 2023 16:33:14 -0300 Subject: [PATCH 085/130] Streamline code for mah/km display --- src/main/io/osd.c | 22 ++++------------------ 1 file changed, 4 insertions(+), 18 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 88df95c1a3..67eae722c4 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -2785,11 +2785,9 @@ static bool osdDrawSingleElement(uint8_t item) timeDelta_t efficiencyTimeDelta = cmpTimeUs(currentTimeUs, efficiencyUpdated); // Check for BFCOMPAT mode uint8_t digits = 3U; - bool bf_compat = false; if (isBfCompatibleVideoSystem(osdConfig())) { // Increase number of digits so values above 99 don't get scaled by osdFormatCentiNumber digits = 4U; - bf_compat = true; } if (STATE(GPS_FIX) && gpsSol.groundSpeed > 0) { if (efficiencyTimeDelta >= EFFICIENCY_UPDATE_INTERVAL) { @@ -2813,12 +2811,8 @@ static bool osdDrawSingleElement(uint8_t item) tfp_sprintf(buff, "%s%c", buff, SYM_AH_MI); } if (!efficiencyValid) { - if(bf_compat){ - buff[0] = buff[1] = buff[2] = buff[3] = '-'; - } else { - buff[0] = buff[1] = buff[2] = '-'; - } - buff[digits] = SYM_MAH_MI_0; + buff[0] = buff[1] = buff[2] = buff[3] = '-'; + buff[digits] = SYM_MAH_MI_0; // This will overwrite the "-" at buff[3] if not in BFCOMPAT mode buff[digits + 1] = SYM_MAH_MI_1; buff[digits + 2] = '\0'; } @@ -2831,11 +2825,7 @@ static bool osdDrawSingleElement(uint8_t item) tfp_sprintf(buff, "%s%c", buff, SYM_AH_NM); } if (!efficiencyValid) { - if(bf_compat){ - buff[0] = buff[1] = buff[2] = buff[3] = '-'; - } else { - buff[0] = buff[1] = buff[2] = '-'; - } + buff[0] = buff[1] = buff[2] = buff[3] = '-'; buff[digits] = SYM_MAH_NM_0; buff[digits + 1] = SYM_MAH_NM_1; buff[digits + 2] = '\0'; @@ -2851,11 +2841,7 @@ static bool osdDrawSingleElement(uint8_t item) tfp_sprintf(buff, "%s%c", buff, SYM_AH_KM); } if (!efficiencyValid) { - if(bf_compat){ - buff[0] = buff[1] = buff[2] = buff[3] = '-'; - } else { - buff[0] = buff[1] = buff[2] = '-'; - } + buff[0] = buff[1] = buff[2] = buff[3] = '-'; buff[digits] = SYM_MAH_KM_0; buff[digits + 1] = SYM_MAH_KM_1; buff[digits + 2] = '\0'; From d98beef065c8efb212c32411afa7dca4e4300eee Mon Sep 17 00:00:00 2001 From: rmaia <9812730+rmaia3d@users.noreply.github.com> Date: Thu, 9 Mar 2023 10:48:39 -0300 Subject: [PATCH 086/130] Add pre-processor checks for if BFCOMPAT mode is not supported --- src/main/io/osd.c | 105 ++++++++++++++++++++++++++++++++++++---------- 1 file changed, 83 insertions(+), 22 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 67eae722c4..340eab7984 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -253,11 +253,13 @@ static void osdFormatDistanceSymbol(char *buff, int32_t dist, uint8_t decimals) { uint8_t digits = 3U; // Total number of digits (including decimal point) uint8_t sym_index = 3U; // Position (index) at buffer of units symbol +#ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it and change the values if (isBfCompatibleVideoSystem(osdConfig())) { // Add one digit so up no switch to scaled decimal occurs above 99 digits = 4U; sym_index = 4U; } +#endif switch ((osd_unit_e)osdConfig()->units) { case OSD_UNIT_UK: FALLTHROUGH; @@ -678,12 +680,21 @@ static void osdFormatCoordinate(char *buff, char sym, int32_t val) int32_t decimalPart = abs(val % GPS_DEGREES_DIVIDER); STATIC_ASSERT(GPS_DEGREES_DIVIDER == 1e7, adjust_max_decimal_digits); int decimalDigits; - if (!isBfCompatibleVideoSystem(osdConfig())) { + bool bfcompat = false; // Assume BFCOMPAT mode is no enabled + +#ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it + if(isBfCompatibleVideoSystem(osdConfig())) { + bfcompat = true; + } +#endif + + if (!bfcompat) { decimalDigits = tfp_sprintf(buff + 1 + integerDigits, "%07d", (int)decimalPart); // Embbed the decimal separator buff[1 + integerDigits - 1] += SYM_ZERO_HALF_TRAILING_DOT - '0'; buff[1 + integerDigits] += SYM_ZERO_HALF_LEADING_DOT - '0'; } else { + // BFCOMPAT mode enabled decimalDigits = tfp_sprintf(buff + 1 + integerDigits, ".%06d", (int)decimalPart); } // Fill up to coordinateLength with zeros @@ -1553,15 +1564,29 @@ static bool osdDrawSingleElement(uint8_t item) break; } - case OSD_MAIN_BATT_VOLTAGE: - osdDisplayBatteryVoltage(elemPosX, elemPosY, getBatteryRawVoltage(), (isBfCompatibleVideoSystem(osdConfig()) ? 3 : 2) + osdConfig()->main_voltage_decimals, osdConfig()->main_voltage_decimals); + case OSD_MAIN_BATT_VOLTAGE: { + uint8_t base_digits = 2U; +#ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it + if(isBfCompatibleVideoSystem(osdConfig())) { + base_digits = 3U; // Add extra digit to account for decimal point taking an extra character space + } +#endif + osdDisplayBatteryVoltage(elemPosX, elemPosY, getBatteryRawVoltage(), base_digits + osdConfig()->main_voltage_decimals, osdConfig()->main_voltage_decimals); return true; + } - case OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE: - osdDisplayBatteryVoltage(elemPosX, elemPosY, getBatterySagCompensatedVoltage(), (isBfCompatibleVideoSystem(osdConfig()) ? 3 : 2) + osdConfig()->main_voltage_decimals, osdConfig()->main_voltage_decimals); + case OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE: { + uint8_t base_digits = 2U; +#ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it + if(isBfCompatibleVideoSystem(osdConfig())) { + base_digits = 3U; // Add extra digit to account for decimal point taking an extra character space + } +#endif + osdDisplayBatteryVoltage(elemPosX, elemPosY, getBatterySagCompensatedVoltage(), base_digits + osdConfig()->main_voltage_decimals, osdConfig()->main_voltage_decimals); return true; + } - case OSD_CURRENT_DRAW: + case OSD_CURRENT_DRAW: { osdFormatCentiNumber(buff, getAmperage(), 0, 2, 0, 3); buff[3] = SYM_AMP; buff[4] = '\0'; @@ -1571,27 +1596,38 @@ static bool osdDrawSingleElement(uint8_t item) TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); } break; + } case OSD_MAH_DRAWN: { + uint8_t mah_digits = osdConfig()->mAh_used_precision; // Initialize to config value + bool bfcompat = false; // Assume BFCOMPAT is off +#ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it if (isBfCompatibleVideoSystem(osdConfig())) { - //BFcompat is unable to work with scaled values and it only has mAh symbol to work with - tfp_sprintf(buff, "%4d", (int)getMAhDrawn()); - buff[4] = SYM_MAH; - buff[5] = '\0'; - } else { - if (osdFormatCentiNumber(buff, getMAhDrawn() * 100, 1000, 0, (osdConfig()->mAh_used_precision - 2), osdConfig()->mAh_used_precision)) { - // Shown in mAh - buff[osdConfig()->mAh_used_precision] = SYM_AH; - } else { - // Shown in Ah - buff[osdConfig()->mAh_used_precision] = SYM_MAH; - } - buff[(osdConfig()->mAh_used_precision + 1)] = '\0'; + bfcompat = true; } +#endif + + if (bfcompat) { + //BFcompat is unable to work with scaled values and it only has mAh symbol to work with + tfp_sprintf(buff, "%5d", (int)getMAhDrawn()); // Use 5 digits to allow 10Ah+ packs + buff[5] = SYM_MAH; + buff[6] = '\0'; + } else { + if (osdFormatCentiNumber(buff, getMAhDrawn() * 100, 1000, 0, (mah_digits - 2), mah_digits)) { + // Shown in Ah + buff[mah_digits] = SYM_AH; + } else { + // Shown in mAh + buff[mah_digits] = SYM_MAH; + } + buff[mah_digits + 1] = '\0'; + } + osdUpdateBatteryCapacityOrVoltageTextAttributes(&elemAttr); break; } + case OSD_WH_DRAWN: osdFormatCentiNumber(buff, getMWhDrawn() / 10, 0, 2, 0, 3); osdUpdateBatteryCapacityOrVoltageTextAttributes(&elemAttr); @@ -1828,9 +1864,11 @@ static bool osdDrawSingleElement(uint8_t item) buff[1] = SYM_HDP_R; int32_t centiHDOP = 100 * gpsSol.hdop / HDOP_SCALE; uint8_t digits = 2U; +#ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it and change the values if (isBfCompatibleVideoSystem(osdConfig())) { digits = 3U; } +#endif osdFormatCentiNumber(&buff[2], centiHDOP, 0, 1, 0, digits); break; } @@ -1862,11 +1900,16 @@ static bool osdDrawSingleElement(uint8_t item) { int32_t alt = osdGetAltitude(); +#ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it if (isBfCompatibleVideoSystem(osdConfig())) { osdSimpleAltitudeSymbol(buff, alt); } else { osdFormatAltitudeSymbol(buff, alt); } +#else + // BFCOMPAT mode not supported, directly call original altitude formatting function + osdFormatAltitudeSymbol(buff, alt); +#endif uint16_t alt_alarm = osdConfig()->alt_alarm; uint16_t neg_alt_alarm = osdConfig()->neg_alt_alarm; @@ -1881,11 +1924,16 @@ static bool osdDrawSingleElement(uint8_t item) case OSD_ALTITUDE_MSL: { int32_t alt = osdGetAltitudeMsl(); +#ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it if (isBfCompatibleVideoSystem(osdConfig())) { osdSimpleAltitudeSymbol(buff, alt); } else { osdFormatAltitudeSymbol(buff, alt); } +#else + // BFCOMPAT mode not supported, directly call original altitude formatting function + osdFormatAltitudeSymbol(buff, alt); +#endif break; } @@ -2727,13 +2775,25 @@ static bool osdDrawSingleElement(uint8_t item) case OSD_MAIN_BATT_CELL_VOLTAGE: { - osdDisplayBatteryVoltage(elemPosX, elemPosY, getBatteryRawAverageCellVoltage(), (isBfCompatibleVideoSystem(osdConfig()) ? 4 : 3), 2); + uint8_t base_digits = 3U; +#ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it + if(isBfCompatibleVideoSystem(osdConfig())) { + base_digits = 4U; // Add extra digit to account for decimal point taking an extra character space + } +#endif + osdDisplayBatteryVoltage(elemPosX, elemPosY, getBatteryRawAverageCellVoltage(), base_digits, 2); return true; } case OSD_MAIN_BATT_SAG_COMPENSATED_CELL_VOLTAGE: { - osdDisplayBatteryVoltage(elemPosX, elemPosY, getBatterySagCompensatedAverageCellVoltage(), (isBfCompatibleVideoSystem(osdConfig()) ? 4 : 3), 2); + uint8_t base_digits = 3U; +#ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it + if(isBfCompatibleVideoSystem(osdConfig())) { + base_digits = 4U; // Add extra digit to account for decimal point taking an extra character space + } +#endif + osdDisplayBatteryVoltage(elemPosX, elemPosY, getBatterySagCompensatedAverageCellVoltage(), base_digits, 2); return true; } @@ -2783,12 +2843,13 @@ static bool osdDrawSingleElement(uint8_t item) bool moreThanAh = false; timeUs_t currentTimeUs = micros(); timeDelta_t efficiencyTimeDelta = cmpTimeUs(currentTimeUs, efficiencyUpdated); - // Check for BFCOMPAT mode uint8_t digits = 3U; +#ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it and change the values if (isBfCompatibleVideoSystem(osdConfig())) { // Increase number of digits so values above 99 don't get scaled by osdFormatCentiNumber digits = 4U; } +#endif if (STATE(GPS_FIX) && gpsSol.groundSpeed > 0) { if (efficiencyTimeDelta >= EFFICIENCY_UPDATE_INTERVAL) { value = pt1FilterApply4(&eFilterState, ((float)getAmperage() / gpsSol.groundSpeed) / 0.0036f, From 5895e1e40dd32a969627047397b6acb12c264564 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sun, 12 Mar 2023 11:18:24 +0100 Subject: [PATCH 087/130] Drop D-term LPF2 as no longer used. First filter PT2 gives equivalent results. --- docs/Profiles.md | 2 -- src/main/blackbox/blackbox.c | 2 -- src/main/cms/cms_menu_imu.c | 1 - src/main/fc/settings.yaml | 10 ---------- src/main/flight/pid.c | 9 +-------- src/main/flight/pid.h | 3 --- 6 files changed, 1 insertion(+), 26 deletions(-) diff --git a/docs/Profiles.md b/docs/Profiles.md index 9495342996..925de755f8 100644 --- a/docs/Profiles.md +++ b/docs/Profiles.md @@ -86,8 +86,6 @@ set max_angle_inclination_rll = 300 set max_angle_inclination_pit = 300 set dterm_lpf_hz = 110 set dterm_lpf_type = PT2 -set dterm_lpf2_hz = 0 -set dterm_lpf2_type = PT1 set yaw_lpf_hz = 0 set fw_iterm_throw_limit = 165 set fw_loiter_direction = RIGHT diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index bcf47a3481..17687db57c 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -1881,8 +1881,6 @@ static bool blackboxWriteSysinfo(void) BLACKBOX_PRINT_HEADER_LINE("yaw_lpf_hz", "%d", pidProfile()->yaw_lpf_hz); BLACKBOX_PRINT_HEADER_LINE("dterm_lpf_hz", "%d", pidProfile()->dterm_lpf_hz); BLACKBOX_PRINT_HEADER_LINE("dterm_lpf_type", "%d", pidProfile()->dterm_lpf_type); - BLACKBOX_PRINT_HEADER_LINE("dterm_lpf2_hz", "%d", pidProfile()->dterm_lpf2_hz); - BLACKBOX_PRINT_HEADER_LINE("dterm_lpf2_type", "%d", pidProfile()->dterm_lpf2_type); BLACKBOX_PRINT_HEADER_LINE("deadband", "%d", rcControlsConfig()->deadband); BLACKBOX_PRINT_HEADER_LINE("yaw_deadband", "%d", rcControlsConfig()->yaw_deadband); BLACKBOX_PRINT_HEADER_LINE("gyro_lpf", "%d", gyroConfig()->gyro_lpf); diff --git a/src/main/cms/cms_menu_imu.c b/src/main/cms/cms_menu_imu.c index d51b3ef8a1..7612ec4418 100644 --- a/src/main/cms/cms_menu_imu.c +++ b/src/main/cms/cms_menu_imu.c @@ -401,7 +401,6 @@ static const OSD_Entry cmsx_menuFilterPerProfileEntries[] = OSD_SETTING_ENTRY("HARDWARE LPF", SETTING_GYRO_HARDWARE_LPF), OSD_SETTING_ENTRY("GYRO MAIN", SETTING_GYRO_MAIN_LPF_HZ), OSD_SETTING_ENTRY("DTERM LPF", SETTING_DTERM_LPF_HZ), - OSD_SETTING_ENTRY("DTERM LPF2", SETTING_DTERM_LPF2_HZ), #ifdef USE_DYNAMIC_FILTERS OSD_SETTING_ENTRY("MATRIX FILTER", SETTING_DYNAMIC_GYRO_NOTCH_ENABLED), OSD_SETTING_ENTRY("MATRIX MIN HZ", SETTING_DYNAMIC_GYRO_NOTCH_MIN_HZ), //dynamic_gyro_notch_min_hz diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 1c0613893e..c0df0e204c 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1806,16 +1806,6 @@ groups: default_value: "PT2" field: dterm_lpf_type table: filter_type_full - - name: dterm_lpf2_hz - description: "Cutoff frequency for stage 2 D-term low pass filter" - default_value: 0 - min: 0 - max: 500 - - name: dterm_lpf2_type - description: "Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`, `PT2`, `PT3`." - default_value: "PT1" - field: dterm_lpf2_type - table: filter_type_full - name: yaw_lpf_hz description: "Yaw P term low pass filter cutoff frequency. Should be disabled (set to `0`) on small multirotors (7 inches and below)" default_value: 0 diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index dd2a480412..e03cd5223a 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -89,7 +89,6 @@ typedef struct { rateLimitFilter_t axisAccelFilter; pt1Filter_t ptermLpfState; filter_t dtermLpfState; - filter_t dtermLpf2State; float stickPosition; @@ -160,7 +159,6 @@ static EXTENDED_FASTRAM uint8_t usedPidControllerType; typedef void (*pidControllerFnPtr)(pidState_t *pidState, flight_dynamics_index_t axis, float dT); static EXTENDED_FASTRAM pidControllerFnPtr pidControllerApplyFn; static EXTENDED_FASTRAM filterApplyFnPtr dTermLpfFilterApplyFn; -static EXTENDED_FASTRAM filterApplyFnPtr dTermLpf2FilterApplyFn; static EXTENDED_FASTRAM bool levelingEnabled = false; #define FIXED_WING_LEVEL_TRIM_MAX_ANGLE 10.0f // Max angle auto trimming can demand @@ -171,7 +169,7 @@ static EXTENDED_FASTRAM bool levelingEnabled = false; static EXTENDED_FASTRAM float fixedWingLevelTrim; static EXTENDED_FASTRAM pidController_t fixedWingLevelTrimController; -PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t, pidProfile, PG_PID_PROFILE, 5); +PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t, pidProfile, PG_PID_PROFILE, 6); PG_RESET_TEMPLATE(pidProfile_t, pidProfile, .bank_mc = { @@ -254,8 +252,6 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile, .dterm_lpf_type = SETTING_DTERM_LPF_TYPE_DEFAULT, .dterm_lpf_hz = SETTING_DTERM_LPF_HZ_DEFAULT, - .dterm_lpf2_type = SETTING_DTERM_LPF2_TYPE_DEFAULT, - .dterm_lpf2_hz = SETTING_DTERM_LPF2_HZ_DEFAULT, .yaw_lpf_hz = SETTING_YAW_LPF_HZ_DEFAULT, .itermWindupPointPercent = SETTING_ITERM_WINDUP_DEFAULT, @@ -322,7 +318,6 @@ bool pidInitFilters(void) for (int axis = 0; axis < 3; ++ axis) { initFilter(pidProfile()->dterm_lpf_type, &pidState[axis].dtermLpfState, pidProfile()->dterm_lpf_hz, refreshRate); - initFilter(pidProfile()->dterm_lpf2_type, &pidState[axis].dtermLpf2State, pidProfile()->dterm_lpf2_hz, refreshRate); } for (int i = 0; i < XYZ_AXIS_COUNT; i++) { @@ -728,7 +723,6 @@ static float dTermProcess(pidState_t *pidState, float currentRateTarget, float d float delta = pidState->previousRateGyro - pidState->gyroRate; delta = dTermLpfFilterApplyFn((filter_t *) &pidState->dtermLpfState, delta); - delta = dTermLpf2FilterApplyFn((filter_t *) &pidState->dtermLpf2State, delta); // Calculate derivative newDTerm = delta * (pidState->kD / dT) * applyDBoost(pidState, currentRateTarget, dT); @@ -1236,7 +1230,6 @@ void pidInit(void) } assignFilterApplyFn(pidProfile()->dterm_lpf_type, pidProfile()->dterm_lpf_hz, &dTermLpfFilterApplyFn); - assignFilterApplyFn(pidProfile()->dterm_lpf2_type, pidProfile()->dterm_lpf2_hz, &dTermLpf2FilterApplyFn); if (usedPidControllerType == PID_TYPE_PIFF) { pidControllerApplyFn = pidApplyFixedWingRateController; diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index 8a95dc5b32..e7d3981a07 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -108,9 +108,6 @@ typedef struct pidProfile_s { uint8_t dterm_lpf_type; // Dterm LPF type: PT1, BIQUAD uint16_t dterm_lpf_hz; - uint8_t dterm_lpf2_type; // Dterm LPF type: PT1, BIQUAD - uint16_t dterm_lpf2_hz; - uint8_t yaw_lpf_hz; uint8_t heading_hold_rate_limit; // Maximum rotation rate HEADING_HOLD mode can feed to yaw rate PID controller From 2452275d296e15b9e2e7cd67cb8e4c05399d8e4d Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sun, 12 Mar 2023 11:20:13 +0100 Subject: [PATCH 088/130] Update docs --- docs/Settings.md | 20 -------------------- 1 file changed, 20 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index 7cbba17cd8..3b83395afa 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -792,26 +792,6 @@ Sets the DShot beeper tone --- -### dterm_lpf2_hz - -Cutoff frequency for stage 2 D-term low pass filter - -| Default | Min | Max | -| --- | --- | --- | -| 0 | 0 | 500 | - ---- - -### dterm_lpf2_type - -Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`, `PT2`, `PT3`. - -| Default | Min | Max | -| --- | --- | --- | -| PT1 | | | - ---- - ### dterm_lpf_hz Dterm low pass filter cutoff frequency. Default setting is very conservative and small multirotors should use higher value between 80 and 100Hz. 80 seems like a gold spot for 7-inch builds while 100 should work best with 5-inch machines. If motors are getting too hot, lower the value From 1a058ac8d92f1ca989169a1bf335b5246d0b19a7 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sun, 12 Mar 2023 11:34:17 +0100 Subject: [PATCH 089/130] Enable USE_SERVO_SBUS on all targets --- src/main/target/common.h | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/main/target/common.h b/src/main/target/common.h index 2365be9671..53517f4ed3 100644 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -46,9 +46,7 @@ #define COMMON_DEFAULT_FEATURES (FEATURE_TX_PROF_SEL) -#if defined(STM32F4) || defined(STM32F7) #define USE_SERVO_SBUS -#endif #define USE_ADC_AVERAGING #define USE_64BIT_TIME From 692fe65cb8c80ee010cfec0eba8e56aee998bd6a Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sun, 12 Mar 2023 11:55:32 +0100 Subject: [PATCH 090/130] Allow scheduler to go down to 10us period --- src/main/target/common.h | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/src/main/target/common.h b/src/main/target/common.h index 2365be9671..b4cacecbb8 100644 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -60,11 +60,8 @@ #define USE_TELEMETRY_LTM #define USE_TELEMETRY_FRSKY -#if defined(STM_FAST_TARGET) +// This is the shortest period in microseconds that the scheduler will allow #define SCHEDULER_DELAY_LIMIT 10 -#else -#define SCHEDULER_DELAY_LIMIT 100 -#endif #if defined(MAG_I2C_BUS) || defined(VCM5883_I2C_BUS) #define USE_MAG_VCM5883 From e7c93203617825d2e8660eed76d9efcc131866fd Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sun, 12 Mar 2023 12:33:55 +0100 Subject: [PATCH 091/130] Drop FrSky D-series telemetry --- docs/Telemetry.md | 34 -- src/main/CMakeLists.txt | 2 - src/main/fc/cli.c | 1 - src/main/fc/fc_core.c | 2 +- src/main/fc/settings.yaml | 38 +- src/main/io/serial.c | 2 +- src/main/io/serial.h | 2 +- src/main/target/ALIENFLIGHTF4/config.c | 1 - src/main/target/ALIENFLIGHTNGF7/config.c | 1 - src/main/target/common.h | 1 - src/main/telemetry/frsky.c | 2 +- src/main/telemetry/frsky_d.c | 567 ----------------------- src/main/telemetry/frsky_d.h | 30 -- src/main/telemetry/telemetry.c | 18 +- src/main/telemetry/telemetry.h | 12 +- src/test/unit/target.h | 1 - 16 files changed, 9 insertions(+), 705 deletions(-) delete mode 100644 src/main/telemetry/frsky_d.c delete mode 100644 src/main/telemetry/frsky_d.h diff --git a/docs/Telemetry.md b/docs/Telemetry.md index b4c64ba1d2..996630e66f 100644 --- a/docs/Telemetry.md +++ b/docs/Telemetry.md @@ -125,40 +125,6 @@ The following sensors are transmitted To quickly and easily monitor these SmartPort sensors and flight modes, install [OpenTX Telemetry Widget](https://github.com/iNavFlight/OpenTX-Telemetry-Widget) to your Taranis Q X7, X9D, X9D+ or X9E transmitter. -## FrSky telemetry - -FrSky telemetry is for older FrSky transmitters and D-series receivers. For newer transmitters paired with X-series receivers see SmartPort (S.Port) telemetry above. - -FrSky telemetry is transmit only and just requires a single connection from the TX pin of a serial port to the RX pin on an FrSky telemetry receiver. - -FrSky telemetry signals are inverted. To connect a INAV capable board to an FrSKy receiver you have some options. - -1. A hardware inverter - Built in to some flight controllers. -2. Use software serial. -3. Use a flight controller that has software configurable hardware inversion (e.g. F3 or F7). - -For 1, just connect your inverter to a usart or software serial port. - -For 2 and 3 use the CLI command as follows: - -``` -set telemetry_inverted = OFF -``` - -### Precision setting for VFAS - -INAV can send VFAS (FrSky Ampere Sensor Voltage) in two ways: - -``` -set frsky_vfas_precision = 0 -``` -This is default setting which supports VFAS resolution of 0.2 volts and is supported on all FrSky hardware. - -``` -set frsky_vfas_precision = 1 -``` -This is new setting which supports VFAS resolution of 0.1 volts and is supported by OpenTX and er9x/ersky9x firmware (this method uses custom ID 0x39). - ### Notes diff --git a/src/main/CMakeLists.txt b/src/main/CMakeLists.txt index 317da760b6..c08634606e 100644 --- a/src/main/CMakeLists.txt +++ b/src/main/CMakeLists.txt @@ -551,8 +551,6 @@ main_sources(COMMON_SRC telemetry/srxl.h telemetry/frsky.c telemetry/frsky.h - telemetry/frsky_d.c - telemetry/frsky_d.h telemetry/ghst.c telemetry/ghst.h telemetry/hott.c diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index e1633983b0..658f379991 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -120,7 +120,6 @@ bool cliMode = false; #include "sensors/esc_sensor.h" #endif -#include "telemetry/frsky_d.h" #include "telemetry/telemetry.h" #include "build/debug.h" diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index b7fafafdd0..f8ef157372 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -489,7 +489,7 @@ bool emergencyArmingUpdate(bool armingSwitchIsOn) return counter >= EMERGENCY_ARMING_MIN_ARM_COUNT; } -#define TELEMETRY_FUNCTION_MASK (FUNCTION_TELEMETRY_FRSKY | FUNCTION_TELEMETRY_HOTT | FUNCTION_TELEMETRY_SMARTPORT | FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_MAVLINK | FUNCTION_TELEMETRY_IBUS) +#define TELEMETRY_FUNCTION_MASK (FUNCTION_TELEMETRY_HOTT | FUNCTION_TELEMETRY_SMARTPORT | FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_MAVLINK | FUNCTION_TELEMETRY_IBUS) void releaseSharedTelemetryPorts(void) { serialPort_t *sharedPort = findSharedSerialPort(TELEMETRY_FUNCTION_MASK, FUNCTION_MSP); diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 1c0613893e..e22e71fdf0 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -80,9 +80,6 @@ tables: - name: osd_alignment values: ["LEFT", "RIGHT"] enum: osd_alignment_e - - name: frsky_unit - values: ["METRIC", "IMPERIAL"] - enum: frskyUnit_e - name: ltm_rates values: ["NORMAL", "MEDIUM", "SLOW"] - name: i2c_speed @@ -2815,7 +2812,7 @@ groups: - name: PG_TELEMETRY_CONFIG type: telemetryConfig_t - headers: ["io/serial.h", "telemetry/telemetry.h", "telemetry/frsky_d.h", "telemetry/sim.h"] + headers: ["io/serial.h", "telemetry/telemetry.h", "telemetry/sim.h"] condition: USE_TELEMETRY members: - name: telemetry_switch @@ -2826,41 +2823,12 @@ groups: description: "Determines if the telemetry protocol default signal inversion is reversed. This should be OFF in most cases unless a custom or hacked RX is used." default_value: OFF type: bool - - name: frsky_default_latitude - description: "D-Series telemetry only: OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired." - default_value: 0 - field: gpsNoFixLatitude - min: -90 - max: 90 - - name: frsky_default_longitude - description: "D-Series telemetry only: OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired." - default_value: 0 - field: gpsNoFixLongitude - min: -180 - max: 180 - - name: frsky_coordinates_format - description: "D-Series telemetry only: FRSKY_FORMAT_DMS (default), FRSKY_FORMAT_NMEA" - default_value: 0 - field: frsky_coordinate_format - min: 0 - max: FRSKY_FORMAT_NMEA - type: uint8_t # TODO: This seems to use an enum, we should use table: - - name: frsky_unit - description: "Not used? [METRIC/IMPERIAL]" - default_value: "METRIC" - table: frsky_unit - type: uint8_t - - name: frsky_vfas_precision - description: "D-Series telemetry only: Set to 1 to send raw VBat value in 0.1V resolution for receivers that can handle it, or 0 (default) to use the standard method" - default_value: 0 - min: FRSKY_VFAS_PRECISION_LOW - max: FRSKY_VFAS_PRECISION_HIGH - name: frsky_pitch_roll - description: "S.Port and D-Series telemetry: Send pitch and roll degrees*10 instead of raw accelerometer data" + description: "S.Port telemetry: Send pitch and roll degrees*10 instead of raw accelerometer data" default_value: OFF type: bool - name: report_cell_voltage - description: "S.Port, D-Series, and IBUS telemetry: Send the average cell voltage if set to ON" + description: "S.Port and IBUS telemetry: Send the average cell voltage if set to ON" default_value: OFF type: bool - name: hott_alarm_sound_interval diff --git a/src/main/io/serial.c b/src/main/io/serial.c index 3ca560cf30..ffc85097b4 100644 --- a/src/main/io/serial.c +++ b/src/main/io/serial.c @@ -263,7 +263,7 @@ serialPort_t *findNextSharedSerialPort(uint32_t functionMask, serialPortFunction return NULL; } -#define ALL_TELEMETRY_FUNCTIONS_MASK (FUNCTION_TELEMETRY_FRSKY | FUNCTION_TELEMETRY_HOTT | FUNCTION_TELEMETRY_SMARTPORT | FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_MAVLINK | FUNCTION_TELEMETRY_IBUS) +#define ALL_TELEMETRY_FUNCTIONS_MASK (FUNCTION_TELEMETRY_HOTT | FUNCTION_TELEMETRY_SMARTPORT | FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_MAVLINK | FUNCTION_TELEMETRY_IBUS) #define ALL_FUNCTIONS_SHARABLE_WITH_MSP (FUNCTION_BLACKBOX | ALL_TELEMETRY_FUNCTIONS_MASK | FUNCTION_LOG) bool isSerialConfigValid(const serialConfig_t *serialConfigToCheck) diff --git a/src/main/io/serial.h b/src/main/io/serial.h index 4f727fd100..9cd0e7e1d7 100644 --- a/src/main/io/serial.h +++ b/src/main/io/serial.h @@ -33,7 +33,7 @@ typedef enum { FUNCTION_NONE = 0, FUNCTION_MSP = (1 << 0), // 1 FUNCTION_GPS = (1 << 1), // 2 - FUNCTION_TELEMETRY_FRSKY = (1 << 2), // 4 + FUNCTION_UNUSED_3 = (1 << 2), // 4 //Was FUNCTION_TELEMETRY_FRSKY FUNCTION_TELEMETRY_HOTT = (1 << 3), // 8 FUNCTION_TELEMETRY_LTM = (1 << 4), // 16 FUNCTION_TELEMETRY_SMARTPORT = (1 << 5), // 32 diff --git a/src/main/target/ALIENFLIGHTF4/config.c b/src/main/target/ALIENFLIGHTF4/config.c index aae496c07d..6c123d0bfb 100644 --- a/src/main/target/ALIENFLIGHTF4/config.c +++ b/src/main/target/ALIENFLIGHTF4/config.c @@ -73,7 +73,6 @@ void targetConfiguration(void) rxConfigMutable()->spektrum_sat_bind_autoreset = 1; } else { rxConfigMutable()->serialrx_provider = SERIALRX_SBUS; - serialConfigMutable()->portConfigs[3].functionMask = FUNCTION_TELEMETRY_FRSKY; featureConfigMutable()->enabledFeatures |= (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY); } diff --git a/src/main/target/ALIENFLIGHTNGF7/config.c b/src/main/target/ALIENFLIGHTNGF7/config.c index 0b56c008f5..28d0465eaf 100644 --- a/src/main/target/ALIENFLIGHTNGF7/config.c +++ b/src/main/target/ALIENFLIGHTNGF7/config.c @@ -75,7 +75,6 @@ void targetConfiguration(void) rxConfigMutable()->spektrum_sat_bind_autoreset = 1; } else { rxConfigMutable()->serialrx_provider = SERIALRX_SBUS; - serialConfigMutable()->portConfigs[3].functionMask = FUNCTION_TELEMETRY_FRSKY; featureConfigMutable()->enabledFeatures |= (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY); } diff --git a/src/main/target/common.h b/src/main/target/common.h index 2365be9671..f7ec27ccc0 100644 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -58,7 +58,6 @@ #define USE_GPS_PROTO_MSP #define USE_TELEMETRY #define USE_TELEMETRY_LTM -#define USE_TELEMETRY_FRSKY #if defined(STM_FAST_TARGET) #define SCHEDULER_DELAY_LIMIT 10 diff --git a/src/main/telemetry/frsky.c b/src/main/telemetry/frsky.c index 0896f412de..adb69cd793 100644 --- a/src/main/telemetry/frsky.c +++ b/src/main/telemetry/frsky.c @@ -8,7 +8,7 @@ #include "platform.h" -#if defined(USE_TELEMETRY) && (defined(USE_TELEMETRY_FRSKY) || defined(USE_TELEMETRY_SMARTPORT)) +#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_SMARTPORT) #include "common/maths.h" #include "fc/runtime_config.h" diff --git a/src/main/telemetry/frsky_d.c b/src/main/telemetry/frsky_d.c deleted file mode 100644 index 3ba09eba38..0000000000 --- a/src/main/telemetry/frsky_d.c +++ /dev/null @@ -1,567 +0,0 @@ -/* - * This file is part of Cleanflight. - * - * Cleanflight is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * Cleanflight is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with Cleanflight. If not, see . - */ - -/* - * Initial FrSky Telemetry implementation by silpstream @ rcgroups. - * Addition protocol work by airmamaf @ github. - */ -#include -#include -#include -#include - -#include "platform.h" - -#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_FRSKY) - -#include "common/maths.h" -#include "common/axis.h" - -#include "config/feature.h" - -#include "drivers/time.h" -#include "drivers/serial.h" - -#include "fc/rc_controls.h" -#include "fc/runtime_config.h" - -#include "fc/config.h" -#include "fc/rc_modes.h" - -#include "flight/mixer.h" -#include "flight/pid.h" -#include "flight/imu.h" - -#include "io/gps.h" -#include "io/serial.h" - -#include "navigation/navigation.h" - -#include "sensors/acceleration.h" -#include "sensors/barometer.h" -#include "sensors/battery.h" -#include "sensors/gyro.h" -#include "sensors/sensors.h" - -#include "telemetry/telemetry.h" -#include "telemetry/frsky_d.h" -#include "telemetry/frsky.h" - -static serialPort_t *frskyPort = NULL; -static serialPortConfig_t *portConfig; - -#define FRSKY_BAUDRATE 9600 -#define FRSKY_INITIAL_PORT_MODE MODE_TX - -static bool frskyTelemetryEnabled = false; -static portSharing_e frskyPortSharing; - -#define CYCLETIME 125 - -#define PROTOCOL_HEADER 0x5E -#define PROTOCOL_TAIL 0x5E - -// Data Ids (bp = before decimal point; af = after decimal point) -// Official data IDs -#define ID_GPS_ALTIDUTE_BP 0x01 -#define ID_GPS_ALTIDUTE_AP 0x09 -#define ID_TEMPRATURE1 0x02 -#define ID_RPM 0x03 -#define ID_FUEL_LEVEL 0x04 -#define ID_TEMPRATURE2 0x05 -#define ID_VOLT 0x06 -#define ID_ALTITUDE_BP 0x10 -#define ID_ALTITUDE_AP 0x21 -#define ID_GPS_SPEED_BP 0x11 -#define ID_GPS_SPEED_AP 0x19 -#define ID_LONGITUDE_BP 0x12 -#define ID_LONGITUDE_AP 0x1A -#define ID_E_W 0x22 -#define ID_LATITUDE_BP 0x13 -#define ID_LATITUDE_AP 0x1B -#define ID_N_S 0x23 -#define ID_COURSE_BP 0x14 -#define ID_COURSE_AP 0x1C -#define ID_DATE_MONTH 0x15 -#define ID_YEAR 0x16 -#define ID_HOUR_MINUTE 0x17 -#define ID_SECOND 0x18 -#define ID_ACC_X 0x24 -#define ID_ACC_Y 0x25 -#define ID_ACC_Z 0x26 -#define ID_VOLTAGE_AMP 0x39 -#define ID_VOLTAGE_AMP_BP 0x3A -#define ID_VOLTAGE_AMP_AP 0x3B -#define ID_CURRENT 0x28 -// User defined data IDs -#define ID_GYRO_X 0x40 -#define ID_GYRO_Y 0x41 -#define ID_GYRO_Z 0x42 -#define ID_HOME_DIST 0x07 -#define ID_PITCH 0x08 -#define ID_ROLL 0x20 - -#define ID_VERT_SPEED 0x30 //opentx vario - -#define GPS_BAD_QUALITY 300 -#define GPS_MAX_HDOP_VAL 9999 -#define DELAY_FOR_BARO_INITIALISATION (5 * 1000) //5s -#define BLADE_NUMBER_DIVIDER 5 // should set 12 blades in Taranis - -static uint32_t lastCycleTime = 0; -static uint8_t cycleNum = 0; -static void sendDataHead(uint8_t id) -{ - serialWrite(frskyPort, PROTOCOL_HEADER); - serialWrite(frskyPort, id); -} - -static void sendTelemetryTail(void) -{ - serialWrite(frskyPort, PROTOCOL_TAIL); -} - -static void serializeFrsky(uint8_t data) -{ - // take care of byte stuffing - if (data == 0x5e) { - serialWrite(frskyPort, 0x5d); - serialWrite(frskyPort, 0x3e); - } else if (data == 0x5d) { - serialWrite(frskyPort, 0x5d); - serialWrite(frskyPort, 0x3d); - } else - serialWrite(frskyPort, data); -} - -static void serialize16(int16_t a) -{ - uint8_t t; - t = a; - serializeFrsky(t); - t = a >> 8 & 0xff; - serializeFrsky(t); -} - -static void sendAccel(void) -{ - int i; - - for (i = 0; i < 3; i++) { - sendDataHead(ID_ACC_X + i); - serialize16(lrintf(acc.accADCf[i] * 1000)); - } -} - -static void sendBaro(void) -{ - const int32_t alt = getEstimatedActualPosition(Z); - sendDataHead(ID_ALTITUDE_BP); - serialize16(alt / 100); - sendDataHead(ID_ALTITUDE_AP); - serialize16(ABS(alt % 100)); -} - -#ifdef USE_GPS -static void sendGpsAltitude(void) -{ - uint16_t altitude = gpsSol.llh.alt / 100; // meters - //Send real GPS altitude only if it's reliable (there's a GPS fix) - if (!STATE(GPS_FIX)) { - altitude = 0; - } - sendDataHead(ID_GPS_ALTIDUTE_BP); - serialize16(altitude); - sendDataHead(ID_GPS_ALTIDUTE_AP); - serialize16(0); -} -#endif - -static void sendThrottleOrBatterySizeAsRpm(void) -{ - sendDataHead(ID_RPM); - if (ARMING_FLAG(ARMED)) { - uint16_t throttleForRPM = getThrottlePercent() / BLADE_NUMBER_DIVIDER; - serialize16(throttleForRPM); - } else { - serialize16((currentBatteryProfile->capacity.value / BLADE_NUMBER_DIVIDER)); - } - -} - -static void sendFlightModeAsTemperature1(void) -{ - sendDataHead(ID_TEMPRATURE1); - serialize16(frskyGetFlightMode()); -} - -#ifdef USE_GPS -static void sendSatalliteSignalQualityAsTemperature2(void) -{ - sendDataHead(ID_TEMPRATURE2); - serialize16(frskyGetGPSState()); -} - -static void sendSpeed(void) -{ - if (!STATE(GPS_FIX)) { - return; - } - //Speed should be sent in knots (GPS speed is in cm/s) - sendDataHead(ID_GPS_SPEED_BP); - //convert to knots: 1cm/s = 0.0194384449 knots - serialize16(gpsSol.groundSpeed * 1944 / 100000); - sendDataHead(ID_GPS_SPEED_AP); - serialize16((gpsSol.groundSpeed * 1944 / 100) % 100); -} - -static void sendHomeDistance(void) -{ - if (!STATE(GPS_FIX)) { - return; - } - sendDataHead(ID_HOME_DIST); - serialize16(GPS_distanceToHome); -} - -#endif - -static void sendTime(void) -{ - uint32_t seconds = millis() / 1000; - uint8_t minutes = (seconds / 60) % 60; - - // if we fly for more than an hour, something's wrong anyway - sendDataHead(ID_HOUR_MINUTE); - serialize16(minutes << 8); - sendDataHead(ID_SECOND); - serialize16(seconds % 60); -} - -// Frsky pdf: dddmm.mmmm -// .mmmm is returned in decimal fraction of minutes. -static void GPStoDDDMM_MMMM(int32_t mwiigps, gpsCoordinateDDDMMmmmm_t *result) -{ - int32_t absgps, deg, min; - absgps = ABS(mwiigps); - deg = absgps / GPS_DEGREES_DIVIDER; - absgps = (absgps - deg * GPS_DEGREES_DIVIDER) * 60; // absgps = Minutes left * 10^7 - min = absgps / GPS_DEGREES_DIVIDER; // minutes left - - result->dddmm = deg * ((FRSKY_FORMAT_DMS == telemetryConfig()->frsky_coordinate_format) ? (100) : (60)) + min; - - result->mmmm = (absgps - min * GPS_DEGREES_DIVIDER) / 1000; -} - -static void sendLatLong(int32_t coord[2]) -{ - gpsCoordinateDDDMMmmmm_t coordinate; - GPStoDDDMM_MMMM(coord[LAT], &coordinate); - sendDataHead(ID_LATITUDE_BP); - serialize16(coordinate.dddmm); - sendDataHead(ID_LATITUDE_AP); - serialize16(coordinate.mmmm); - sendDataHead(ID_N_S); - serialize16(coord[LAT] < 0 ? 'S' : 'N'); - - GPStoDDDMM_MMMM(coord[LON], &coordinate); - sendDataHead(ID_LONGITUDE_BP); - serialize16(coordinate.dddmm); - sendDataHead(ID_LONGITUDE_AP); - serialize16(coordinate.mmmm); - sendDataHead(ID_E_W); - serialize16(coord[LON] < 0 ? 'W' : 'E'); -} - -#ifdef USE_GPS -static void sendFakeLatLong(void) -{ - // Heading is only displayed on OpenTX if non-zero lat/long is also sent - int32_t coord[2] = {0,0}; - - coord[LAT] = (telemetryConfig()->gpsNoFixLatitude * GPS_DEGREES_DIVIDER); - coord[LON] = (telemetryConfig()->gpsNoFixLongitude * GPS_DEGREES_DIVIDER); - - sendLatLong(coord); -} -#endif - -static void sendFakeLatLongThatAllowsHeadingDisplay(void) -{ - // Heading is only displayed on OpenTX if non-zero lat/long is also sent - int32_t coord[2] = { - 1 * GPS_DEGREES_DIVIDER, - 1 * GPS_DEGREES_DIVIDER - }; - - sendLatLong(coord); -} - -#ifdef USE_GPS -static void sendGPSLatLong(void) -{ - static uint8_t gpsFixOccured = 0; - int32_t coord[2] = {0,0}; - - if (STATE(GPS_FIX) || gpsFixOccured == 1) { - // If we have ever had a fix, send the last known lat/long - gpsFixOccured = 1; - coord[LAT] = gpsSol.llh.lat; - coord[LON] = gpsSol.llh.lon; - sendLatLong(coord); - } else { - // otherwise send fake lat/long in order to display compass value - sendFakeLatLong(); - } -} -#endif - -/* - * Send vertical speed for opentx. ID_VERT_SPEED - * Unit is cm/s - */ -static void sendVario(void) -{ - sendDataHead(ID_VERT_SPEED); - serialize16((int16_t)lrintf(getEstimatedActualVelocity(Z))); -} - -/* - * Send voltage via ID_VOLT - * - * NOTE: This sends voltage divided by batteryCellCount. To get the real - * battery voltage, you need to multiply the value by batteryCellCount. - */ -static void sendVoltage(void) -{ - uint32_t cellVoltage; - uint16_t payload; - - /* - * Format for Voltage Data for single cells is like this: - * - * llll llll cccc hhhh - * l: Low voltage bits - * h: High voltage bits - * c: Cell number (starting at 0) - * - * The actual value sent for cell voltage has resolution of 0.002 volts - * Since vbat has resolution of 0.01 volts it has to be multiplied by 5 - */ - cellVoltage = ((uint32_t)getBatteryVoltage() * 10) / (getBatteryCellCount() * 2); - - // Cell number is at bit 9-12 (only uses vbat, so it can't send individual cell voltages, set cell number to 0) - payload = 0; - - // Lower voltage bits are at bit 0-8 - payload |= ((cellVoltage & 0x0ff) << 8); - - // Higher voltage bits are at bits 13-15 - payload |= ((cellVoltage & 0xf00) >> 8); - - sendDataHead(ID_VOLT); - serialize16(payload); -} - -/* - * Send voltage with ID_VOLTAGE_AMP - */ -static void sendVoltageAmp(void) -{ - uint16_t vbat = getBatteryVoltage(); - if (telemetryConfig()->frsky_vfas_precision == FRSKY_VFAS_PRECISION_HIGH) { - /* - * Use new ID 0x39 to send voltage directly in 0.1 volts resolution - */ - sendDataHead(ID_VOLTAGE_AMP); - serialize16(vbat / 10); - } else { - uint16_t voltage = (vbat * 11) / 21; - uint16_t vfasVoltage; - if (telemetryConfig()->report_cell_voltage) { - vfasVoltage = voltage / getBatteryCellCount(); - } else { - vfasVoltage = voltage; - } - sendDataHead(ID_VOLTAGE_AMP_BP); - serialize16(vfasVoltage / 100); - sendDataHead(ID_VOLTAGE_AMP_AP); - serialize16(((vfasVoltage % 100) + 5) / 10); - } -} - -static void sendAmperage(void) -{ - sendDataHead(ID_CURRENT); - serialize16((uint16_t)(getAmperage() / 10)); -} - -static void sendFuelLevel(void) -{ - if (telemetryConfig()->smartportFuelUnit == SMARTPORT_FUEL_UNIT_PERCENT) { - sendDataHead(ID_FUEL_LEVEL); - serialize16((uint16_t)calculateBatteryPercentage()); - } else if (isAmperageConfigured()) { - sendDataHead(ID_FUEL_LEVEL); - serialize16((uint16_t)telemetryConfig()->smartportFuelUnit == SMARTPORT_FUEL_UNIT_MAH ? getMAhDrawn() : getMWhDrawn()); - } -} - -static void sendHeading(void) -{ - sendDataHead(ID_COURSE_BP); - serialize16(DECIDEGREES_TO_DEGREES(attitude.values.yaw)); - sendDataHead(ID_COURSE_AP); - serialize16(0); -} - -static void sendPitch(void) -{ - sendDataHead(ID_PITCH); - serialize16(attitude.values.pitch); -} - -static void sendRoll(void) -{ - sendDataHead(ID_ROLL); - serialize16(attitude.values.roll); -} - -void initFrSkyTelemetry(void) -{ - portConfig = findSerialPortConfig(FUNCTION_TELEMETRY_FRSKY); - frskyPortSharing = determinePortSharing(portConfig, FUNCTION_TELEMETRY_FRSKY); -} - -void freeFrSkyTelemetryPort(void) -{ - closeSerialPort(frskyPort); - frskyPort = NULL; - frskyTelemetryEnabled = false; -} - -void configureFrSkyTelemetryPort(void) -{ - if (!portConfig) { - return; - } - - frskyPort = openSerialPort(portConfig->identifier, FUNCTION_TELEMETRY_FRSKY, NULL, NULL, FRSKY_BAUDRATE, FRSKY_INITIAL_PORT_MODE, telemetryConfig()->telemetry_inverted ? SERIAL_NOT_INVERTED : SERIAL_INVERTED); - if (!frskyPort) { - return; - } - - frskyTelemetryEnabled = true; -} - -bool hasEnoughTimeLapsedSinceLastTelemetryTransmission(uint32_t currentMillis) -{ - return currentMillis - lastCycleTime >= CYCLETIME; -} - -void checkFrSkyTelemetryState(void) -{ - if (portConfig && telemetryCheckRxPortShared(portConfig)) { - if (!frskyTelemetryEnabled && telemetrySharedPort != NULL) { - frskyPort = telemetrySharedPort; - frskyTelemetryEnabled = true; - } - } else { - bool newTelemetryEnabledValue = telemetryDetermineEnabledState(frskyPortSharing); - - if (newTelemetryEnabledValue == frskyTelemetryEnabled) { - return; - } - - if (newTelemetryEnabledValue) - configureFrSkyTelemetryPort(); - else - freeFrSkyTelemetryPort(); - } -} - -void handleFrSkyTelemetry(void) -{ - if (!frskyTelemetryEnabled) { - return; - } - - uint32_t now = millis(); - - if (!hasEnoughTimeLapsedSinceLastTelemetryTransmission(now)) { - return; - } - - lastCycleTime = now; - - cycleNum++; - - // Sent every 125ms - if (telemetryConfig()->frsky_pitch_roll) { - sendPitch(); - sendRoll(); - } else { - sendAccel(); - } - sendVario(); - sendTelemetryTail(); - - if ((cycleNum % 4) == 0) { // Sent every 500ms - if (lastCycleTime > DELAY_FOR_BARO_INITIALISATION) { //Allow 5s to boot correctly - sendBaro(); - } - sendHeading(); - sendTelemetryTail(); - } - - if ((cycleNum % 8) == 0) { // Sent every 1s - sendFlightModeAsTemperature1(); - sendThrottleOrBatterySizeAsRpm(); - - if (feature(FEATURE_VBAT)) { - sendVoltage(); - sendVoltageAmp(); - sendAmperage(); - sendFuelLevel(); - } - -#ifdef USE_GPS - if (sensors(SENSOR_GPS)) { - sendSpeed(); - sendHomeDistance(); - sendGpsAltitude(); - sendSatalliteSignalQualityAsTemperature2(); - sendGPSLatLong(); - } - else { - sendFakeLatLongThatAllowsHeadingDisplay(); - } -#else - sendFakeLatLongThatAllowsHeadingDisplay(); -#endif - - sendTelemetryTail(); - } - - if (cycleNum == 40) { //Frame 3: Sent every 5s - cycleNum = 0; - sendTime(); - sendTelemetryTail(); - } -} - -#endif diff --git a/src/main/telemetry/frsky_d.h b/src/main/telemetry/frsky_d.h deleted file mode 100644 index fe4846d011..0000000000 --- a/src/main/telemetry/frsky_d.h +++ /dev/null @@ -1,30 +0,0 @@ -/* - * This file is part of Cleanflight. - * - * Cleanflight is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * Cleanflight is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with Cleanflight. If not, see . - */ - -#pragma once - -typedef enum { - FRSKY_VFAS_PRECISION_LOW = 0, - FRSKY_VFAS_PRECISION_HIGH -} frskyVFasPrecision_e; - -void handleFrSkyTelemetry(void); -void checkFrSkyTelemetryState(void); - -void initFrSkyTelemetry(void); -void configureFrSkyTelemetryPort(void); -void freeFrSkyTelemetryPort(void); diff --git a/src/main/telemetry/telemetry.c b/src/main/telemetry/telemetry.c index 00a5f182ae..0ed26e250f 100644 --- a/src/main/telemetry/telemetry.c +++ b/src/main/telemetry/telemetry.c @@ -41,7 +41,6 @@ #include "rx/rx.h" #include "telemetry/telemetry.h" -#include "telemetry/frsky_d.h" #include "telemetry/hott.h" #include "telemetry/smartport.h" #include "telemetry/ltm.h" @@ -54,16 +53,11 @@ #include "telemetry/ghst.h" -PG_REGISTER_WITH_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig, PG_TELEMETRY_CONFIG, 5); +PG_REGISTER_WITH_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig, PG_TELEMETRY_CONFIG, 6); PG_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig, - .gpsNoFixLatitude = SETTING_FRSKY_DEFAULT_LATITUDE_DEFAULT, - .gpsNoFixLongitude = SETTING_FRSKY_DEFAULT_LONGITUDE_DEFAULT, .telemetry_switch = SETTING_TELEMETRY_SWITCH_DEFAULT, .telemetry_inverted = SETTING_TELEMETRY_INVERTED_DEFAULT, - .frsky_coordinate_format = SETTING_FRSKY_COORDINATES_FORMAT_DEFAULT, - .frsky_unit = SETTING_FRSKY_UNIT_DEFAULT, - .frsky_vfas_precision = SETTING_FRSKY_VFAS_PRECISION_DEFAULT, .frsky_pitch_roll = SETTING_FRSKY_PITCH_ROLL_DEFAULT, .report_cell_voltage = SETTING_REPORT_CELL_VOLTAGE_DEFAULT, .hottAlarmSoundInterval = SETTING_HOTT_ALARM_SOUND_INTERVAL_DEFAULT, @@ -97,9 +91,6 @@ PG_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig, void telemetryInit(void) { -#if defined(USE_TELEMETRY_FRSKY) - initFrSkyTelemetry(); -#endif #if defined(USE_TELEMETRY_HOTT) initHoTTTelemetry(); @@ -167,9 +158,6 @@ serialPort_t *telemetrySharedPort = NULL; void telemetryCheckState(void) { -#if defined(USE_TELEMETRY_FRSKY) - checkFrSkyTelemetryState(); -#endif #if defined(USE_TELEMETRY_HOTT) checkHoTTTelemetryState(); @@ -215,10 +203,6 @@ void telemetryProcess(timeUs_t currentTimeUs) { UNUSED(currentTimeUs); // since not used by all the telemetry protocols -#if defined(USE_TELEMETRY_FRSKY) - handleFrSkyTelemetry(); -#endif - #if defined(USE_TELEMETRY_HOTT) handleHoTTTelemetry(currentTimeUs); #endif diff --git a/src/main/telemetry/telemetry.h b/src/main/telemetry/telemetry.h index 51e79b89b5..e6146a0393 100644 --- a/src/main/telemetry/telemetry.h +++ b/src/main/telemetry/telemetry.h @@ -36,11 +36,6 @@ typedef enum { FRSKY_FORMAT_NMEA } frskyGpsCoordFormat_e; -typedef enum { - FRSKY_UNIT_METRICS = 0, - FRSKY_UNIT_IMPERIALS -} frskyUnit_e; - typedef enum { LTM_RATE_NORMAL, LTM_RATE_MEDIUM, @@ -54,13 +49,8 @@ typedef enum { } smartportFuelUnit_e; typedef struct telemetryConfig_s { - float gpsNoFixLatitude; - float gpsNoFixLongitude; uint8_t telemetry_switch; // Use aux channel to change serial output & baudrate( MSP / Telemetry ). It disables automatic switching to Telemetry when armed. uint8_t telemetry_inverted; // Flip the default inversion of the protocol - Same as serialrx_inverted in rx.c, but for telemetry. - frskyGpsCoordFormat_e frsky_coordinate_format; - frskyUnit_e frsky_unit; - uint8_t frsky_vfas_precision; uint8_t frsky_pitch_roll; uint8_t report_cell_voltage; uint8_t hottAlarmSoundInterval; @@ -93,7 +83,7 @@ typedef struct telemetryConfig_s { PG_DECLARE(telemetryConfig_t, telemetryConfig); -#define TELEMETRY_SHAREABLE_PORT_FUNCTIONS_MASK (FUNCTION_TELEMETRY_FRSKY | FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_IBUS) +#define TELEMETRY_SHAREABLE_PORT_FUNCTIONS_MASK (FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_IBUS) extern serialPort_t *telemetrySharedPort; void telemetryInit(void); diff --git a/src/test/unit/target.h b/src/test/unit/target.h index 4e50761db8..b95e1678c7 100755 --- a/src/test/unit/target.h +++ b/src/test/unit/target.h @@ -24,7 +24,6 @@ #define USE_GPS_PROTO_UBLOX #define USE_DASHBOARD #define USE_TELEMETRY -#define USE_TELEMETRY_FRSKY #define USE_TELEMETRY_HOTT #define USE_TELEMETRY_IBUS #define USE_TELEMETRY_SMARTPORT From 728f291b92e4d385c605baf8bdef5ef48c6821b2 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sun, 12 Mar 2023 12:34:15 +0100 Subject: [PATCH 092/130] Docs update --- docs/Settings.md | 54 ++---------------------------------------------- 1 file changed, 2 insertions(+), 52 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index 7cbba17cd8..c42ac76ecc 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -1082,39 +1082,9 @@ _// TODO_ --- -### frsky_coordinates_format - -D-Series telemetry only: FRSKY_FORMAT_DMS (default), FRSKY_FORMAT_NMEA - -| Default | Min | Max | -| --- | --- | --- | -| 0 | 0 | FRSKY_FORMAT_NMEA | - ---- - -### frsky_default_latitude - -D-Series telemetry only: OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired. - -| Default | Min | Max | -| --- | --- | --- | -| 0 | -90 | 90 | - ---- - -### frsky_default_longitude - -D-Series telemetry only: OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired. - -| Default | Min | Max | -| --- | --- | --- | -| 0 | -180 | 180 | - ---- - ### frsky_pitch_roll -S.Port and D-Series telemetry: Send pitch and roll degrees*10 instead of raw accelerometer data +S.Port telemetry: Send pitch and roll degrees*10 instead of raw accelerometer data | Default | Min | Max | | --- | --- | --- | @@ -1122,26 +1092,6 @@ S.Port and D-Series telemetry: Send pitch and roll degrees*10 instead of raw acc --- -### frsky_unit - -Not used? [METRIC/IMPERIAL] - -| Default | Min | Max | -| --- | --- | --- | -| METRIC | | | - ---- - -### frsky_vfas_precision - -D-Series telemetry only: Set to 1 to send raw VBat value in 0.1V resolution for receivers that can handle it, or 0 (default) to use the standard method - -| Default | Min | Max | -| --- | --- | --- | -| 0 | FRSKY_VFAS_PRECISION_LOW | FRSKY_VFAS_PRECISION_HIGH | - ---- - ### fw_autotune_max_rate_deflection The target percentage of maximum mixer output used for determining the rates in `AUTO` and `LIMIT`. @@ -5054,7 +5004,7 @@ Selection of receiver (RX) type. Additional configuration of a `serialrx_provide ### report_cell_voltage -S.Port, D-Series, and IBUS telemetry: Send the average cell voltage if set to ON +S.Port and IBUS telemetry: Send the average cell voltage if set to ON | Default | Min | Max | | --- | --- | --- | From 4f7d53da8c95025d96c7d739b53d133c9fd52995 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sun, 12 Mar 2023 12:47:10 +0100 Subject: [PATCH 093/130] Cleanup --- src/main/CMakeLists.txt | 2 - src/main/telemetry/frsky.c | 89 ---------------------------------- src/main/telemetry/frsky.h | 26 ---------- src/main/telemetry/smartport.c | 71 ++++++++++++++++++++++++++- 4 files changed, 70 insertions(+), 118 deletions(-) delete mode 100644 src/main/telemetry/frsky.c delete mode 100644 src/main/telemetry/frsky.h diff --git a/src/main/CMakeLists.txt b/src/main/CMakeLists.txt index c08634606e..36bd62bf0b 100644 --- a/src/main/CMakeLists.txt +++ b/src/main/CMakeLists.txt @@ -549,8 +549,6 @@ main_sources(COMMON_SRC telemetry/crsf.h telemetry/srxl.c telemetry/srxl.h - telemetry/frsky.c - telemetry/frsky.h telemetry/ghst.c telemetry/ghst.h telemetry/hott.c diff --git a/src/main/telemetry/frsky.c b/src/main/telemetry/frsky.c deleted file mode 100644 index adb69cd793..0000000000 --- a/src/main/telemetry/frsky.c +++ /dev/null @@ -1,89 +0,0 @@ -/* - * frsky.c - * Common functions for FrSky D-series and SmartPort telemetry - */ - -#include -#include - -#include "platform.h" - -#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_SMARTPORT) - -#include "common/maths.h" -#include "fc/runtime_config.h" -#include "fc/rc_modes.h" -#include "io/gps.h" -#include "telemetry/frsky.h" - -uint16_t frskyGetFlightMode(void) -{ - uint16_t tmpi = 0; - - // ones column - if (!isArmingDisabled()) - tmpi += 1; - else - tmpi += 2; - if (ARMING_FLAG(ARMED)) - tmpi += 4; - - // tens column - if (FLIGHT_MODE(ANGLE_MODE)) - tmpi += 10; - if (FLIGHT_MODE(HORIZON_MODE)) - tmpi += 20; - if (FLIGHT_MODE(MANUAL_MODE)) - tmpi += 40; - - // hundreds column - if (FLIGHT_MODE(HEADING_MODE)) - tmpi += 100; - if (FLIGHT_MODE(NAV_ALTHOLD_MODE)) - tmpi += 200; - if (FLIGHT_MODE(NAV_POSHOLD_MODE)) - tmpi += 400; - - // thousands column - if (FLIGHT_MODE(NAV_RTH_MODE)) - tmpi += 1000; - if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) // intentionally out of order and 'else-ifs' to prevent column overflow - tmpi += 8000; - else if (FLIGHT_MODE(NAV_WP_MODE)) - tmpi += 2000; - else if (FLIGHT_MODE(HEADFREE_MODE)) - tmpi += 4000; - - // ten thousands column - if (FLIGHT_MODE(FLAPERON)) - tmpi += 10000; - if (FLIGHT_MODE(FAILSAFE_MODE)) - tmpi += 40000; - else if (FLIGHT_MODE(AUTO_TUNE)) // intentionally reverse order and 'else-if' to prevent 16-bit overflow - tmpi += 20000; - - return tmpi; -} - -uint16_t frskyGetGPSState(void) -{ - uint16_t tmpi = 0; - - // ones and tens columns (# of satellites 0 - 99) - tmpi += constrain(gpsSol.numSat, 0, 99); - - // hundreds column (satellite accuracy HDOP: 0 = worst [HDOP > 5.5], 9 = best [HDOP <= 1.0]) - tmpi += (9 - constrain((gpsSol.hdop - 51) / 50, 0, 9)) * 100; - - // thousands column (GPS fix status) - if (STATE(GPS_FIX)) - tmpi += 1000; - if (STATE(GPS_FIX_HOME)) - tmpi += 2000; - if (ARMING_FLAG(ARMED) && IS_RC_MODE_ACTIVE(BOXHOMERESET) && !FLIGHT_MODE(NAV_RTH_MODE) && !FLIGHT_MODE(NAV_WP_MODE)) - tmpi += 4000; - - return tmpi; -} - -#endif diff --git a/src/main/telemetry/frsky.h b/src/main/telemetry/frsky.h deleted file mode 100644 index 9d0e71b482..0000000000 --- a/src/main/telemetry/frsky.h +++ /dev/null @@ -1,26 +0,0 @@ -/* - * This file is part of INAV. - * - * INAV is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * INAV is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with INAV. If not, see . - */ - -/* - * frsky.h - * Common functions for FrSky D-series and SmartPort telemetry - */ - -#pragma once - -uint16_t frskyGetFlightMode(void); -uint16_t frskyGetGPSState(void); diff --git a/src/main/telemetry/smartport.c b/src/main/telemetry/smartport.c index 1ea659864b..81d5f79309 100755 --- a/src/main/telemetry/smartport.c +++ b/src/main/telemetry/smartport.c @@ -59,7 +59,6 @@ FILE_COMPILE_FOR_SPEED #include "telemetry/telemetry.h" #include "telemetry/smartport.h" -#include "telemetry/frsky.h" #include "telemetry/msp_shared.h" // these data identifiers are obtained from https://github.com/opentx/opentx/blob/2.3/radio/src/telemetry/frsky.h @@ -162,6 +161,76 @@ static smartPortWriteFrameFn *smartPortWriteFrame; static bool smartPortMspReplyPending = false; #endif +static uint16_t frskyGetFlightMode(void) +{ + uint16_t tmpi = 0; + + // ones column + if (!isArmingDisabled()) + tmpi += 1; + else + tmpi += 2; + if (ARMING_FLAG(ARMED)) + tmpi += 4; + + // tens column + if (FLIGHT_MODE(ANGLE_MODE)) + tmpi += 10; + if (FLIGHT_MODE(HORIZON_MODE)) + tmpi += 20; + if (FLIGHT_MODE(MANUAL_MODE)) + tmpi += 40; + + // hundreds column + if (FLIGHT_MODE(HEADING_MODE)) + tmpi += 100; + if (FLIGHT_MODE(NAV_ALTHOLD_MODE)) + tmpi += 200; + if (FLIGHT_MODE(NAV_POSHOLD_MODE)) + tmpi += 400; + + // thousands column + if (FLIGHT_MODE(NAV_RTH_MODE)) + tmpi += 1000; + if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) // intentionally out of order and 'else-ifs' to prevent column overflow + tmpi += 8000; + else if (FLIGHT_MODE(NAV_WP_MODE)) + tmpi += 2000; + else if (FLIGHT_MODE(HEADFREE_MODE)) + tmpi += 4000; + + // ten thousands column + if (FLIGHT_MODE(FLAPERON)) + tmpi += 10000; + if (FLIGHT_MODE(FAILSAFE_MODE)) + tmpi += 40000; + else if (FLIGHT_MODE(AUTO_TUNE)) // intentionally reverse order and 'else-if' to prevent 16-bit overflow + tmpi += 20000; + + return tmpi; +} + +static uint16_t frskyGetGPSState(void) +{ + uint16_t tmpi = 0; + + // ones and tens columns (# of satellites 0 - 99) + tmpi += constrain(gpsSol.numSat, 0, 99); + + // hundreds column (satellite accuracy HDOP: 0 = worst [HDOP > 5.5], 9 = best [HDOP <= 1.0]) + tmpi += (9 - constrain((gpsSol.hdop - 51) / 50, 0, 9)) * 100; + + // thousands column (GPS fix status) + if (STATE(GPS_FIX)) + tmpi += 1000; + if (STATE(GPS_FIX_HOME)) + tmpi += 2000; + if (ARMING_FLAG(ARMED) && IS_RC_MODE_ACTIVE(BOXHOMERESET) && !FLIGHT_MODE(NAV_RTH_MODE) && !FLIGHT_MODE(NAV_WP_MODE)) + tmpi += 4000; + + return tmpi; +} + smartPortPayload_t *smartPortDataReceive(uint16_t c, bool *clearToSend, smartPortCheckQueueEmptyFn *checkQueueEmpty, bool useChecksum) { static uint8_t rxBuffer[sizeof(smartPortPayload_t)]; From 5c6b68292c0eb8e0205cabc101acfe261905a61d Mon Sep 17 00:00:00 2001 From: rmaia <9812730+rmaia3d@users.noreply.github.com> Date: Sun, 12 Mar 2023 11:23:24 -0300 Subject: [PATCH 094/130] Fix distance field and add total trip distance --- src/main/io/osd.c | 57 +++++++++++++++++++++++++++++++++++++++++++++-- 1 file changed, 55 insertions(+), 2 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 340eab7984..3ed8a0e575 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -244,6 +244,38 @@ static void osdLeftAlignString(char *buff) for (sp = ch; sp < len; sp++) buff[sp] = ' '; } +/* + * This is a simplified distance conversion code that does not use any scaling + * but is fully compatible with the DJI G2 MSP Displayport OSD implementation. + * (Based on osdSimpleAltitudeSymbol() implementation) + */ +void osdSimpleDistanceSymbol(char *buff, int32_t dist) { + + int32_t convertedDistance; + char suffix; + + switch ((osd_unit_e)osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_GA: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + convertedDistance = CENTIMETERS_TO_FEET(dist); + suffix = SYM_ALT_FT; + break; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + convertedDistance = CENTIMETERS_TO_METERS(dist); + suffix = SYM_ALT_M; // Intentionally use the altitude symbol, as the distance symbol is not defined in BFCOMPAT mode + break; + } + + tfp_sprintf(buff, "%5d", (int) convertedDistance); // 5 digits, allowing up to 99999 meters/feet, which should be plenty for 99.9% of use cases + buff[5] = suffix; + buff[6] = '\0'; +} + /** * Converts distance into a string based on the current unit system * prefixed by a a symbol to indicate the unit used. @@ -1774,7 +1806,19 @@ static bool osdDrawSingleElement(uint8_t item) case OSD_HOME_DIST: { buff[0] = SYM_HOME; - osdFormatDistanceSymbol(&buff[1], GPS_distanceToHome * 100, 0); + uint32_t distance_to_home_cm = GPS_distanceToHome * 100; + +#ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it + if (isBfCompatibleVideoSystem(osdConfig())) { + osdSimpleDistanceSymbol(&buff[1], distance_to_home_cm); + } else { + osdFormatDistanceSymbol(&buff[1], distance_to_home_cm, 0); + } +#else + // BFCOMPAT mode not supported, directly call original formatting function + osdFormatDistanceSymbol(&buff[1], distance_to_home_cm, 0); +#endif + uint16_t dist_alarm = osdConfig()->dist_alarm; if (dist_alarm > 0 && GPS_distanceToHome > dist_alarm) { TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); @@ -1784,7 +1828,16 @@ static bool osdDrawSingleElement(uint8_t item) case OSD_TRIP_DIST: buff[0] = SYM_TOTAL; - osdFormatDistanceSymbol(buff + 1, getTotalTravelDistance(), 0); +#ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it + if (isBfCompatibleVideoSystem(osdConfig())) { + osdSimpleDistanceSymbol(&buff[1], getTotalTravelDistance()); + } else { + osdFormatDistanceSymbol(buff + 1, getTotalTravelDistance(), 0); + } +#else + // BFCOMPAT mode not supported, directly call original formatting function + osdFormatDistanceSymbol(buff + 1, getTotalTravelDistance(), 0); +#endif break; case OSD_GROUND_COURSE: From c9a2c2c71895c2716af211fc2975ead6e9d73858 Mon Sep 17 00:00:00 2001 From: rmaia <9812730+rmaia3d@users.noreply.github.com> Date: Mon, 13 Mar 2023 09:54:30 -0300 Subject: [PATCH 095/130] Fix scaling of altitude and distance fields --- src/main/io/osd.c | 60 +++++++++++++++++++---------------------- src/main/io/osd_utils.c | 7 ++++- 2 files changed, 34 insertions(+), 33 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 3ed8a0e575..4651e38fcb 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -249,7 +249,7 @@ static void osdLeftAlignString(char *buff) * but is fully compatible with the DJI G2 MSP Displayport OSD implementation. * (Based on osdSimpleAltitudeSymbol() implementation) */ -void osdSimpleDistanceSymbol(char *buff, int32_t dist) { +/* void osdSimpleDistanceSymbol(char *buff, int32_t dist) { int32_t convertedDistance; char suffix; @@ -274,7 +274,7 @@ void osdSimpleDistanceSymbol(char *buff, int32_t dist) { tfp_sprintf(buff, "%5d", (int) convertedDistance); // 5 digits, allowing up to 99999 meters/feet, which should be plenty for 99.9% of use cases buff[5] = suffix; buff[6] = '\0'; -} +} */ /** * Converts distance into a string based on the current unit system @@ -285,21 +285,34 @@ static void osdFormatDistanceSymbol(char *buff, int32_t dist, uint8_t decimals) { uint8_t digits = 3U; // Total number of digits (including decimal point) uint8_t sym_index = 3U; // Position (index) at buffer of units symbol + uint8_t symbol_m = SYM_DIST_M; + uint8_t symbol_km = SYM_DIST_KM; + uint8_t symbol_ft = SYM_DIST_FT; + uint8_t symbol_mi = SYM_DIST_MI; + uint8_t symbol_nm = SYM_DIST_NM; + #ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it and change the values if (isBfCompatibleVideoSystem(osdConfig())) { // Add one digit so up no switch to scaled decimal occurs above 99 digits = 4U; sym_index = 4U; + // Use altitude symbols on purpose, as it seems distance symbols are not defined in BFCOMPAT mode + symbol_m = SYM_ALT_M; + symbol_km = SYM_ALT_KM; + symbol_ft = SYM_ALT_FT; + symbol_mi = SYM_MI; + symbol_nm = SYM_MI; } #endif + switch ((osd_unit_e)osdConfig()->units) { case OSD_UNIT_UK: FALLTHROUGH; case OSD_UNIT_IMPERIAL: if (osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(dist), FEET_PER_MILE, decimals, 3, digits)) { - buff[sym_index] = SYM_DIST_MI; + buff[sym_index] = symbol_mi; } else { - buff[sym_index] = SYM_DIST_FT; + buff[sym_index] = symbol_ft; } buff[sym_index + 1] = '\0'; break; @@ -307,17 +320,17 @@ static void osdFormatDistanceSymbol(char *buff, int32_t dist, uint8_t decimals) FALLTHROUGH; case OSD_UNIT_METRIC: if (osdFormatCentiNumber(buff, dist, METERS_PER_KILOMETER, decimals, 3, digits)) { - buff[sym_index] = SYM_DIST_KM; + buff[sym_index] = symbol_km; } else { - buff[sym_index] = SYM_DIST_M; + buff[sym_index] = symbol_m; } buff[sym_index + 1] = '\0'; break; case OSD_UNIT_GA: if (osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(dist), FEET_PER_NAUTICALMILE, decimals, 3, digits)) { - buff[sym_index] = SYM_DIST_NM; + buff[sym_index] = symbol_nm; } else { - buff[sym_index] = SYM_DIST_FT; + buff[sym_index] = symbol_ft; } buff[sym_index + 1] = '\0'; break; @@ -483,7 +496,7 @@ static void osdFormatWindSpeedStr(char *buff, int32_t ws, bool isValid) * This is a simplified altitude conversion code that does not use any scaling * but is fully compatible with the DJI G2 MSP Displayport OSD implementation. */ -void osdSimpleAltitudeSymbol(char *buff, int32_t alt) { +/* void osdSimpleAltitudeSymbol(char *buff, int32_t alt) { int32_t convertedAltutude; char suffix; @@ -508,7 +521,7 @@ void osdSimpleAltitudeSymbol(char *buff, int32_t alt) { tfp_sprintf(buff, "%4d", (int) convertedAltutude); buff[4] = suffix; buff[5] = '\0'; -} +} */ /** * Converts altitude into a string based on the current unit system @@ -1807,17 +1820,7 @@ static bool osdDrawSingleElement(uint8_t item) { buff[0] = SYM_HOME; uint32_t distance_to_home_cm = GPS_distanceToHome * 100; - -#ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it - if (isBfCompatibleVideoSystem(osdConfig())) { - osdSimpleDistanceSymbol(&buff[1], distance_to_home_cm); - } else { - osdFormatDistanceSymbol(&buff[1], distance_to_home_cm, 0); - } -#else - // BFCOMPAT mode not supported, directly call original formatting function osdFormatDistanceSymbol(&buff[1], distance_to_home_cm, 0); -#endif uint16_t dist_alarm = osdConfig()->dist_alarm; if (dist_alarm > 0 && GPS_distanceToHome > dist_alarm) { @@ -1828,16 +1831,7 @@ static bool osdDrawSingleElement(uint8_t item) case OSD_TRIP_DIST: buff[0] = SYM_TOTAL; -#ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it - if (isBfCompatibleVideoSystem(osdConfig())) { - osdSimpleDistanceSymbol(&buff[1], getTotalTravelDistance()); - } else { - osdFormatDistanceSymbol(buff + 1, getTotalTravelDistance(), 0); - } -#else - // BFCOMPAT mode not supported, directly call original formatting function - osdFormatDistanceSymbol(buff + 1, getTotalTravelDistance(), 0); -#endif + osdFormatDistanceSymbol(buff + 1, getTotalTravelDistance(), 0); break; case OSD_GROUND_COURSE: @@ -1955,7 +1949,8 @@ static bool osdDrawSingleElement(uint8_t item) #ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it if (isBfCompatibleVideoSystem(osdConfig())) { - osdSimpleAltitudeSymbol(buff, alt); + // Use the same formatting function used for distance, which provides the proper scaling functionality + osdFormatDistanceSymbol(buff, alt, 0); } else { osdFormatAltitudeSymbol(buff, alt); } @@ -1979,7 +1974,8 @@ static bool osdDrawSingleElement(uint8_t item) int32_t alt = osdGetAltitudeMsl(); #ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it if (isBfCompatibleVideoSystem(osdConfig())) { - osdSimpleAltitudeSymbol(buff, alt); + // Use the same formatting function used for distance, which provides the proper scaling functionality + osdFormatDistanceSymbol(buff, alt, 0); } else { osdFormatAltitudeSymbol(buff, alt); } diff --git a/src/main/io/osd_utils.c b/src/main/io/osd_utils.c index 7e695276f4..12f94f6960 100644 --- a/src/main/io/osd_utils.c +++ b/src/main/io/osd_utils.c @@ -95,10 +95,15 @@ bool osdFormatCentiNumber(char *buff, int32_t centivalue, uint32_t scale, int ma // Keep number right aligned and correct length if(explicitDecimal && decimals == 0) { - if ((digits + 1) == length) { + uint8_t blank_spaces = ptr - buff; + int8_t rem_spaces = length - (digits + blank_spaces); + // Add any needed remaining leading spaces + while(rem_spaces > 0) + { *ptr = SYM_BLANK; ptr++; remaining--; + rem_spaces--; } } From e7a04fa26b31f9e85cea23f1c97ed697f6097fd5 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Tue, 14 Mar 2023 21:22:22 +0100 Subject: [PATCH 096/130] INAV 7 --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 04623c6774..3650dffc6b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -37,7 +37,7 @@ else() include("${CMAKE_CURRENT_SOURCE_DIR}/cmake/${TOOLCHAIN}-checks.cmake") endif() -project(INAV VERSION 6.0.0) +project(INAV VERSION 7.0.0) enable_language(ASM) From 2f42925ac305e80d568e81c96f705f9d33030e24 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Tue, 14 Mar 2023 21:23:45 +0100 Subject: [PATCH 097/130] INAV 6.1 --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 04623c6774..b61dc77876 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -37,7 +37,7 @@ else() include("${CMAKE_CURRENT_SOURCE_DIR}/cmake/${TOOLCHAIN}-checks.cmake") endif() -project(INAV VERSION 6.0.0) +project(INAV VERSION 6.1.0) enable_language(ASM) From 0641d90c1b94559d9283ab306e17e2fa361634de Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Thu, 16 Mar 2023 20:34:27 +0000 Subject: [PATCH 098/130] Show loiter instead of poshold in OSD for fixed wing --- src/main/io/osd.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index eed14a2764..ea8cb29ba8 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -2072,6 +2072,8 @@ static bool osdDrawSingleElement(uint8_t item) p = "TURT"; else if (FLIGHT_MODE(NAV_RTH_MODE)) p = isWaypointMissionRTHActive() ? "WRTH" : "RTH "; + else if (FLIGHT_MODE(NAV_POSHOLD_MODE) && STATE(AIRPLANE)) + p = "LOTR"; else if (FLIGHT_MODE(NAV_POSHOLD_MODE)) p = "HOLD"; else if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE) && FLIGHT_MODE(NAV_ALTHOLD_MODE)) From 4597bcefc11ec0b53d5d07be47a732dfd74f4d10 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 20 Mar 2023 19:22:15 +0100 Subject: [PATCH 099/130] Add SS on UART2 TX --- src/main/target/SPEEDYBEEF405WING/target.h | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/src/main/target/SPEEDYBEEF405WING/target.h b/src/main/target/SPEEDYBEEF405WING/target.h index 483c1e4070..ad58668268 100644 --- a/src/main/target/SPEEDYBEEF405WING/target.h +++ b/src/main/target/SPEEDYBEEF405WING/target.h @@ -78,7 +78,12 @@ #define UART6_TX_PIN PC6 #define UART6_RX_PIN PC7 -#define SERIAL_PORT_COUNT 7 +//Optional Softserial on UART2 TX Pin PA2 +#define USE_SOFTSERIAL1 +#define SOFTSERIAL_1_TX_PIN PA2 +#define SOFTSERIAL_1_RX_PIN PA2 + +#define SERIAL_PORT_COUNT 8 /* * I2C From dfb2415d6081ba876944d6975d507c3e549d41d4 Mon Sep 17 00:00:00 2001 From: HKR1987 <37500242+HKR1987@users.noreply.github.com> Date: Tue, 21 Mar 2023 17:13:19 +0100 Subject: [PATCH 100/130] Create target.h --- src/main/target/BLACKPILL_F411_OSD/target.h | 1 + 1 file changed, 1 insertion(+) create mode 100644 src/main/target/BLACKPILL_F411_OSD/target.h diff --git a/src/main/target/BLACKPILL_F411_OSD/target.h b/src/main/target/BLACKPILL_F411_OSD/target.h new file mode 100644 index 0000000000..8b13789179 --- /dev/null +++ b/src/main/target/BLACKPILL_F411_OSD/target.h @@ -0,0 +1 @@ + From 257b53fb46f3f8116ddaef8de419db2e5e7e7386 Mon Sep 17 00:00:00 2001 From: HKR1987 <37500242+HKR1987@users.noreply.github.com> Date: Tue, 21 Mar 2023 17:13:42 +0100 Subject: [PATCH 101/130] Create target.c --- src/main/target/BLACKPILL_F411_OSD/target.c | 1 + 1 file changed, 1 insertion(+) create mode 100644 src/main/target/BLACKPILL_F411_OSD/target.c diff --git a/src/main/target/BLACKPILL_F411_OSD/target.c b/src/main/target/BLACKPILL_F411_OSD/target.c new file mode 100644 index 0000000000..8b13789179 --- /dev/null +++ b/src/main/target/BLACKPILL_F411_OSD/target.c @@ -0,0 +1 @@ + From 9f8b5aafefdb34319ad5e24125213283e83bfa13 Mon Sep 17 00:00:00 2001 From: HKR1987 Date: Tue, 21 Mar 2023 17:32:34 +0100 Subject: [PATCH 102/130] Change target name --- src/main/target/{BLACKPILL_F411_OSD => BLACKPILL_F411}/target.c | 0 src/main/target/{BLACKPILL_F411_OSD => BLACKPILL_F411}/target.h | 0 2 files changed, 0 insertions(+), 0 deletions(-) rename src/main/target/{BLACKPILL_F411_OSD => BLACKPILL_F411}/target.c (100%) rename src/main/target/{BLACKPILL_F411_OSD => BLACKPILL_F411}/target.h (100%) diff --git a/src/main/target/BLACKPILL_F411_OSD/target.c b/src/main/target/BLACKPILL_F411/target.c similarity index 100% rename from src/main/target/BLACKPILL_F411_OSD/target.c rename to src/main/target/BLACKPILL_F411/target.c diff --git a/src/main/target/BLACKPILL_F411_OSD/target.h b/src/main/target/BLACKPILL_F411/target.h similarity index 100% rename from src/main/target/BLACKPILL_F411_OSD/target.h rename to src/main/target/BLACKPILL_F411/target.h From d67122b0ab6d8b5eedabc1fbc2d755126666d864 Mon Sep 17 00:00:00 2001 From: HKR1987 Date: Tue, 21 Mar 2023 17:49:16 +0100 Subject: [PATCH 103/130] Add configs to Blackpill --- src/main/target/BLACKPILL_F411/CMakeLists.txt | 2 + src/main/target/BLACKPILL_F411/config.c | 28 ++++ src/main/target/BLACKPILL_F411/target.c | 41 +++++ src/main/target/BLACKPILL_F411/target.h | 153 ++++++++++++++++++ 4 files changed, 224 insertions(+) create mode 100644 src/main/target/BLACKPILL_F411/CMakeLists.txt create mode 100644 src/main/target/BLACKPILL_F411/config.c diff --git a/src/main/target/BLACKPILL_F411/CMakeLists.txt b/src/main/target/BLACKPILL_F411/CMakeLists.txt new file mode 100644 index 0000000000..12987cf966 --- /dev/null +++ b/src/main/target/BLACKPILL_F411/CMakeLists.txt @@ -0,0 +1,2 @@ +target_stm32f411xe(BLACKPILL_F411_OSD HSE_MHZ 25) +target_stm32f411xe(BLACKPILL_F411_BLACKBOX HSE_MHZ 25) diff --git a/src/main/target/BLACKPILL_F411/config.c b/src/main/target/BLACKPILL_F411/config.c new file mode 100644 index 0000000000..07f6de4697 --- /dev/null +++ b/src/main/target/BLACKPILL_F411/config.c @@ -0,0 +1,28 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include +#include "platform.h" + +#include "fc/fc_msp_box.h" + +#include "io/piniobox.h" + +void targetConfiguration(void) +{ + pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; +} diff --git a/src/main/target/BLACKPILL_F411/target.c b/src/main/target/BLACKPILL_F411/target.c index 8b13789179..a7f6215215 100644 --- a/src/main/target/BLACKPILL_F411/target.c +++ b/src/main/target/BLACKPILL_F411/target.c @@ -1 +1,42 @@ +/* +* This file is part of Cleanflight. +* +* Cleanflight is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* Cleanflight is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with Cleanflight. If not, see . +*/ +#include +#include +#include "drivers/bus.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" +#include "drivers/pinio.h" + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 D(1,4,5) + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 D(1,5,5) + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S3 D(2,1,6) + DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S4 D(2,2,6) + DEF_TIM(TIM1, CH3, PA10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S5 D(2,6,6) + DEF_TIM(TIM4, CH3, PB8, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6 D(1,7,2) + + DEF_TIM(TIM5, CH3, PA2, TIM_USE_ANY, 0, 0), //TX2 pad - softserial_tx2 + + DEF_TIM(TIM11, CH1, PB9, TIM_USE_ANY, 0, 0), //ST1 pad -softserial_tx1 + + DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), //RX2 Pad -PPM + +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/BLACKPILL_F411/target.h b/src/main/target/BLACKPILL_F411/target.h index 8b13789179..ef672e855d 100644 --- a/src/main/target/BLACKPILL_F411/target.h +++ b/src/main/target/BLACKPILL_F411/target.h @@ -1 +1,154 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ +#pragma once + +#define TARGET_BOARD_IDENTIFIER "BLCKP" +#define USBD_PRODUCT_STRING "BLACKPILL_F411" + +#define LED0 PC13 +#define LED1 PC14 + +#define BEEPER PB2 +#define BEEPER_INVERTED + +// *************** SPI1 Gyro & ACC ********************** +#define USE_SPI +#define USE_SPI_DEVICE_1 + +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define USE_IMU_MPU6000 +#define IMU_MPU6000_ALIGN CW180_DEG +#define MPU6000_CS_PIN PA4 +#define MPU6000_SPI_BUS BUS_SPI1 + +// *************** SPI2 OSD ***************************** +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN PB12 + +// *************** UART ***************************** +#define USE_VCP +#define VBUS_SENSING_PIN PC15 +#define VBUS_SENSING_ENABLED + +#define USE_UART1 +#define UART1_TX_PIN PA15 +#define UART1_RX_PIN PB3 + +#define USE_UART2 +#define UART2_TX_PIN PA2 +#define UART2_RX_PIN PA3 + +#define USE_SOFTSERIAL1 +#define SOFTSERIAL_1_TX_PIN PB9 // ST1 pad +#define SOFTSERIAL_1_RX_PIN PB9 + + +#define USE_SOFTSERIAL2 +#define SOFTSERIAL_2_TX_PIN PA2 // TX2 pad +#define SOFTSERIAL_2_RX_PIN PA2 + +#define SERIAL_PORT_COUNT 5 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS +#define SERIALRX_UART SERIAL_PORT_USART2 + +// *************** I2C /Baro/Mag/Pitot ******************** +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB6 +#define I2C1_SDA PB7 + +#define DEFAULT_I2C_BUS BUS_I2C1 + +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C1 +#define USE_BARO_BMP280 +#define USE_BARO_MS5611 +#define USE_BARO_BMP085 +#define USE_BARO_DPS310 +#define USE_BARO_SPL06 + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C1 +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_IST8310 +#define USE_MAG_IST8308 +#define USE_MAG_MAG3110 +#define USE_MAG_LIS3MDL +#define USE_MAG_AK8975 + +#define PITOT_I2C_BUS BUS_I2C1 +#define TEMPERATURE_I2C_BUS BUS_I2C1 + +#define USE_RANGEFINDER +#define USE_RANGEFINDER_MSP +#define RANGEFINDER_I2C_BUS BUS_I2C1 + +// *************** ADC ***************************** +#define USE_ADC +#define ADC_INSTANCE ADC1 +#define ADC1_DMA_STREAM DMA2_Stream0 + +#define ADC_CHANNEL_1_PIN PB0 +#define ADC_CHANNEL_2_PIN PB1 +#define ADC_CHANNEL_3_PIN PA0 +#define ADC_CHANNEL_4_PIN PA1 + +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +#define RSSI_ADC_CHANNEL ADC_CHN_3 +#define AIRSPEED_ADC_CHANNEL ADC_CHN_4 + +// *************** LED2812 ************************ +#define USE_LED_STRIP +#define WS2811_PIN PB10 + +// *************** PINIO *************************** +#define USE_PINIO +#define USE_PINIOBOX +#define PINIO1_PIN PA13 // Camera switcher + +// *************** OTHERS ************************* +#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY | FEATURE_SOFTSERIAL ) + +#define CURRENT_METER_SCALE 423 + +#define USE_SPEKTRUM_BIND +#define BIND_PIN PA3 // RX2 + +#define USE_DSHOT +#define USE_ESC_SENSOR +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) + +#define MAX_PWM_OUTPUT_PORTS 6 From c70426087ba4058bf18bb8e0c1786cc5e70b7141 Mon Sep 17 00:00:00 2001 From: HKR1987 Date: Tue, 21 Mar 2023 17:52:27 +0100 Subject: [PATCH 104/130] Add 25Mhz HSE value --- src/main/target/system_stm32f4xx.c | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/main/target/system_stm32f4xx.c b/src/main/target/system_stm32f4xx.c index a836d1cd70..c4a9609b92 100644 --- a/src/main/target/system_stm32f4xx.c +++ b/src/main/target/system_stm32f4xx.c @@ -372,7 +372,9 @@ uint32_t hse_value = HSE_VALUE; /************************* PLL Parameters *************************************/ #if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F469_479xx) || defined (STM32F446xx) || defined (STM32F410xx) || defined (STM32F411xE) - #if HSE_VALUE == 24000000 + #if HSE_VALUE == 25000000 + #define PLL_M 25 + #elif HSE_VALUE == 24000000 #define PLL_M 24 #elif HSE_VALUE == 16000000 #define PLL_M 16 From 115418000e90ca270e9a09190bbeece95bdcf0b6 Mon Sep 17 00:00:00 2001 From: HKR1987 Date: Tue, 21 Mar 2023 18:09:10 +0100 Subject: [PATCH 105/130] add option OSD or FLASH for Blackpill --- src/main/target/BLACKPILL_F411/target.h | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/src/main/target/BLACKPILL_F411/target.h b/src/main/target/BLACKPILL_F411/target.h index ef672e855d..30bd76ee4c 100644 --- a/src/main/target/BLACKPILL_F411/target.h +++ b/src/main/target/BLACKPILL_F411/target.h @@ -39,15 +39,23 @@ #define MPU6000_CS_PIN PA4 #define MPU6000_SPI_BUS BUS_SPI1 -// *************** SPI2 OSD ***************************** +// *************** SPI2 OSD OR FLASH***************************** #define USE_SPI_DEVICE_2 #define SPI2_SCK_PIN PB13 #define SPI2_MISO_PIN PB14 #define SPI2_MOSI_PIN PB15 +#ifdef BLACKPILL_F411_BLACKBOX +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define M25P16_CS_PIN PB12 +#define M25P16_SPI_BUS BUS_SPI2 +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT +#else #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI2 #define MAX7456_CS_PIN PB12 +#endif // *************** UART ***************************** #define USE_VCP From 27f610cfeb9f2a958b2b91e0f7ad15fab5965caa Mon Sep 17 00:00:00 2001 From: HKR1987 Date: Tue, 21 Mar 2023 18:13:49 +0100 Subject: [PATCH 106/130] Add MPU6500 and MPU9250 for Blackpill --- src/main/target/BLACKPILL_F411/target.h | 12 +++++++++++- 1 file changed, 11 insertions(+), 1 deletion(-) diff --git a/src/main/target/BLACKPILL_F411/target.h b/src/main/target/BLACKPILL_F411/target.h index 30bd76ee4c..f425de423e 100644 --- a/src/main/target/BLACKPILL_F411/target.h +++ b/src/main/target/BLACKPILL_F411/target.h @@ -35,10 +35,20 @@ #define SPI1_MOSI_PIN PA7 #define USE_IMU_MPU6000 -#define IMU_MPU6000_ALIGN CW180_DEG +#define IMU_MPU6000_ALIGN CW0_DEG #define MPU6000_CS_PIN PA4 #define MPU6000_SPI_BUS BUS_SPI1 +#define USE_IMU_MPU9250 +#define IMU_MPU9250_ALIGN CW0_DEG +#define MPU9250_CS_PIN PA4 +#define MPU9250_SPI_BUS BUS_SPI1 + +#define USE_IMU_MPU6500 +#define IMU_MPU6500_ALIGN CW0_DEG +#define MPU6500_CS_PIN PA4 +#define MPU6500_SPI_BUS BUS_SPI1 + // *************** SPI2 OSD OR FLASH***************************** #define USE_SPI_DEVICE_2 #define SPI2_SCK_PIN PB13 From ede97745ee6e86310d66ae632ea6edcff86d2173 Mon Sep 17 00:00:00 2001 From: HKR1987 <37500242+HKR1987@users.noreply.github.com> Date: Tue, 21 Mar 2023 20:13:29 +0100 Subject: [PATCH 107/130] Update system_stm32f4xx.c --- src/main/target/system_stm32f4xx.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/system_stm32f4xx.c b/src/main/target/system_stm32f4xx.c index c4a9609b92..8e59fa1fac 100644 --- a/src/main/target/system_stm32f4xx.c +++ b/src/main/target/system_stm32f4xx.c @@ -373,7 +373,7 @@ uint32_t hse_value = HSE_VALUE; /************************* PLL Parameters *************************************/ #if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F469_479xx) || defined (STM32F446xx) || defined (STM32F410xx) || defined (STM32F411xE) #if HSE_VALUE == 25000000 - #define PLL_M 25 + #define PLL_M 25 #elif HSE_VALUE == 24000000 #define PLL_M 24 #elif HSE_VALUE == 16000000 From be886beedeb32f5f0f39e0628496e9801993d11e Mon Sep 17 00:00:00 2001 From: HKR1987 <37500242+HKR1987@users.noreply.github.com> Date: Tue, 21 Mar 2023 22:22:31 +0100 Subject: [PATCH 108/130] edit cmake - skip releases --- src/main/target/BLACKPILL_F411/CMakeLists.txt | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/target/BLACKPILL_F411/CMakeLists.txt b/src/main/target/BLACKPILL_F411/CMakeLists.txt index 12987cf966..5df7377c77 100644 --- a/src/main/target/BLACKPILL_F411/CMakeLists.txt +++ b/src/main/target/BLACKPILL_F411/CMakeLists.txt @@ -1,2 +1,2 @@ -target_stm32f411xe(BLACKPILL_F411_OSD HSE_MHZ 25) -target_stm32f411xe(BLACKPILL_F411_BLACKBOX HSE_MHZ 25) +target_stm32f411xe(BLACKPILL_F411_OSD HSE_MHZ 25 SKIP_RELEASES) +target_stm32f411xe(BLACKPILL_F411_BLACKBOX HSE_MHZ 25 SKIP_RELEASES) From 3fc1467544dc79da61c5dfafa79e055e4127b266 Mon Sep 17 00:00:00 2001 From: HKR1987 <37500242+HKR1987@users.noreply.github.com> Date: Wed, 22 Mar 2023 10:19:55 +0100 Subject: [PATCH 109/130] Add files via upload --- docs/assets/images/Blackpill_F411.png | Bin 0 -> 1052068 bytes 1 file changed, 0 insertions(+), 0 deletions(-) create mode 100644 docs/assets/images/Blackpill_F411.png diff --git a/docs/assets/images/Blackpill_F411.png b/docs/assets/images/Blackpill_F411.png new file mode 100644 index 0000000000000000000000000000000000000000..c20f762562ae6c571d6f81b8fe083faad7e140ce GIT binary patch literal 1052068 zcmeFYcQ~7G`#-L=tLRcKDrixq_TH=2+C^0s z85u+CU$0AbajsZ0vWtS}>MBNWt+!^VZP+>{spfam(mqXlk)!Wu?=+>(TBy?HP|(nx zh8aC0zx@0m=Yt1fLt3Fjfjdoj$Im~%1nxYEe_4KU5G>|X>sO!Ppe4$^b06mWud(9` z9uCf;b)e_u`j3(O=Z3G(f1KmuGN-@V^8dMXlZQKW|w~ekWAzKW{mD>A!#T|5?)iuIB$XrT^OI|MH^$ zy3qf|kN*PF|AQS|T>pjl|Aij^f1*%M>B8{ewskSG%P(5!IdLAsl&_ZawU9GYmoC|0 zBT=2}y4Vx!N8et1QFGvw+YUZrMgO5&vRE4LYW8YWTx`<{zFD-s>AIWGwJ|5r)jNGB zp3;jxHCDDGR8?&&HL>n%15Dqx-}GjrJC7PU#L|1ZNynU4Dh%HBVOMnwtS+!jw`hlh z0Qakl6ccrd;%|I;S(gFlzDb+$_(STxwBrBW>DYfF^P$qERxX-v&mJtsYx8isCSQLx zGCk@%ylP@6##yIIE_Ikqa13^M8v359Ba-~mJsu@Is+te*AyWI^!_{!5K4yc7=r80V zsA80WO{I&y9Ux`0UhIUw-mFNgP~a%FL$cicV32w*(khez{yX3&_f(XuKK<()5-8- zr`npA%Xr$mftA%d2wxjOVTBS^vz}0PG|tg6!Iy#OOVFmG_#i}#*pqfp1p7f~+arSE ziWDzXk2JK=eMim;F_ddYs9b}p&+={&WcSk@lKYnj$!C?MounBk054yfxQ5=2L45yi zp8GRJJx?Ss;~%IvEc^9O+Hx|c$#Zj9AISUV%a?f3jW?nNtpLfdzm$ib$buYcrai-$ zF10%3ix8BrDKS2>9s|~$!Dc3AdA?R#W?lT59y~*G)BymHk=IILq8(UO7XRZmC9CKj ztXArZ&6k4B79`!R(d*JYMKArkYN>si8JkOM5VF|Pij1PJrCt?5EGo^RY%r<)mgQ59 z&w6WwpyM;UrspYcrL@U7tP1-u4f1!5=~J7;k~zqD<1^{pONultCErWp+-K^agLVAq zhyKauay=OT$>V<4YCcMeFYIKh%*|0*eBAFSQ_{|5dtAH-3=8Ux`cgC`O!s&x@X=lv zOQ`ZEn|aD(2S!3c@1^~ZwR8hN2RwEtYxxR{Vjr#aGLHir0RZ8frB#+z!RWf z)T9yEESN$i0G(1y*#$`r=jhX)gTcJ9}4@4pz(`|WHL z*xmZoRPl0z_IGe2B~+;iJFNdg~N7PHpv; zz-`eem&YY`M*}|grEpfh zin4f4y5`nUQ$u%!Ef?CI-+Q-}E1LaL+XbJVy3vjB2g1{%@!X%dQ=dJP%-q58NE1S7 zSj88TXQl-)o8h5}^S-x-JN%P{fEiQ*%pNx_ftp@H*1|LOLB=KZL1wJa5*Y>dy68*= z%f(EoTz1g`9UJoj*$iW}9pF%*o71;Xy}gjkrA4Fgf+I@FAD$N4=Woya!xypG`cnjo zVvJbX>VqNoR9$$l{z_!yPebkD_KZnj*Z7^AC~T%@>dNYnwj^m@kWdAY~cG zDi`Nm&4e%ALcyE{FBVAWXoL@qX7(K_-)!9INqHlgFgE{we#kI|nHm&2*m~kQAxMcL zyeR?YST^ZV8I3NCk@?}xmPS#4?3B6e=RBV*R zT-s1)S#qM8g!k`oI1^o!M0a|mxX9bm& z2IK$CH2gH0!yJO_02Jfn?+jBl^BwrCAR{p5`f--0oorhkB zER6(TY4dI+_EN6gY99Y58(mNTa7o&VUSW>S`+aw%gJ1;di{b%;+2412bEf>Ppyp{=|Iy?s;|e@Gk(FU)<^*kY=q`%Wj3)#C~wBM z5=?+75tisyiFP#`HdX|OUG%HV*$k`H2jLDM#|hO+%>|pg2_;WZri3@aq=m2i3Mhr` zLMUvTJY2n4KXURbC6y13*#gNeq8}US!+*U)(zl)wd&IN^pZw$3bM|cE-}$+3aG^ma z^=s+QM#~d+Ph#W-k~hW&%Q#43)_Ye3)N><_QSlmr=pGli!_@lqQHLgF)3T+wm2kszOJ~{{Js!{z(|X)L zcK05cIzg^$;^K1M%;{d-lTViKBBC8VkbJ|<&8WY&&YbcS^QW!)ANN*8X~Ja1oIVat>{W~y03WR_IEMEr<-wQId zEZ4_)w+4{Cw4GcfR$F`+?`z_DRBL71)Bz4?mCqIwT#2PTfXE7P9;(|XySlnMl+{o@ zX9{`u4+aF~{iMz)-~V;9EW$&0YxE2+cKnVsabv(`(00RMa5;^t&467jf|4{J9h%S< zVWSihKqEqF0TkCGPsa)rD0b@d6M#=IE2J)yL*$z?25WH?2O>;(_~OVl?Z7C^0h*%7 z;N$oT6uS&PAizIoLp9ZcCv{tKDd;7&DZMCkAZfmZqsyFTvdtCl4amAiAoHE6UZ?tb z)(iIi9q3|!PK?=_VU*AA$^o(Zrj1-x{>~qxM+IT8{&B6t{!TK|3`PwFuX}F&3Vs4!VoO{^-CwBft{p7n&t3ba?ORp) z;0EpULId~5{}c^DhF&z^%PThuxt2N+l+=tJ4Dv&d{~b~2gx+t}W?Ohl&eq}97`ZlY zyuH)xxuBXVY^(Z%dTXKLEQFzh@OC{$K6?k+WF!2ZSzu|L+4V<^H#%_&8ZBRncM#UF zE~#`ZyUHT3{x0^8;9WOfGcjiRhsUqBOvPf+22ZdwV}Fb-!qJrD_pM$xmY$cfT;3MWI24Yn< zPL0tB8^Z)C9@(L&@FrOv#z+DIbfySGlQxa0{3shbjy!|Uj=7K5D@Y23SVlpR9tm^o znnKiKeU<*GTkKB3+Zf!}&U}I(tWL+Y^Q?7k>0YX)T}t)m2l0H*?Iy(A$8X-6Hu1bS zoN{{3X*$MV&WOF^Ts{*XK{M6 zc*HCe7~G6>?+cnt!txh;%ms_S9(`C+TIwnDj}`HEk&I|KFS`39lY49HSEDl zZ=vA}P%s~}@{9bH`(gxH;Y&21j`+mbNz0xc&6W*>oSMRKZVH^GQJ`x@k?)m0kEI`T zTyC((3^2cLVr*caMCzt9+m8nlylt5EJ%r~3iC|e2-}G#y!xg&KSn|28r^o?_^@1db z&K+%z+}?LfKRxQ$F$~$J!{8mh-V-R_5fK|74g;MYwaSD8^(8^@=V=(n4}{e7Hael+ ziJwd2@B0qWHra%;+hf$vn4xN4j%5GPGG1Oo??!m=}E&!CdCaNrtxehvFOdUcxt2aU_ee246Z?O|6Oao zW+nHm*PLfmmN~xfQ34^I&HeLY(}z-N>N=PY0P#8KmqL*<%5$KSAN#lpTwq@AhI#Vw z^D|olPLs;YsJr^C$dVs4wBg{zVCnr!Q;|4UxTs<1tzEy+K=R(;Y8J#!P+Xw-DNbQAHO0G zWK1+?E`?RMVS~UEfP zWXk&BREe9`sq;vPe~3UqY{@m_JT_I=3YHy)nNBEJN0~hyIcxA0kin7ElZN3D6muMi zm)ov0oP`|dloVGelz;o|0TgKtk|{$kV0zYU&zQ!og&MFwYx&dvC}-5yuk4@QXGlO) zIYDPG(iUS|Yx9olJ{@S)Fk_69fv=U;dt9Tjwa}`8lccRml;G92zZ3IZ-=9HwBWVlg z#sB8W=j3S~q)LL)EWv+X?hmOk)?7helCPsz?0bxxm+FSP{K$Zfj9chhfN#P0YX;$P zAxdnkB#k32)#Nd!ukqOIz&rS_C9e_~44RyL8*BB8-N05(UvL5$zQj;S-yj%LuGt@9 zs80a5I`o}U5a3i&d=v5}V^_vN3BlRH()S^Z>^~mwjKE6=4-AE2p2vd3`dY!IHAQTa z`PzuPNSDys_*#(-(nIg(qIZW2O`#T_H4JrJlwcL@Z-G0;fs!tj>hUBD4-I|uIefT6 zSqs7hydDhRJ;{5fB4fh4UtLt}sSdL`WMg`CV)z0Pl;~!F}t8;H| zlqJ%qFOrmza!a57n*B~z4^2C}1PiUdQNoD*AJxK`D@n8GaARcU2<-ul1_YZX3z#jA zRR=$76h%TT7$Z>%!VK=L8I1=1DnHViMV%Sb5(n~q!ldp@b(Vn-UUdsenH3Dg%|QEw z6d7-a-!&MX9u?SAw~Pp{WQk0Gjq{iDcKwMuwMjKzxta}>XQEqO8!3SAp`M{z-VY~~ z6{P@yALj%a>7ro%2-!3F6!;ZVaE)5wOtDV&exik?4oAHey0ueV*SL0YaL^_XH7Ybd zm|32D@&J5gc^UrL*wo3^pW+7RZedBu^BW%`1Bojr8=1HCw~%uv{+B$>WgZ&F(O=XU z_Pt`;C2oq2d+-bmz$s#j6h02BSnOl15H^{?at&n)x+;LDEMMP|i6;IebP#C@U+^Z+ z1+Re+i@hNzepsUbzjPn(-+``-;-96P3XLYQ4hYDf}9b%~FW;hJH5*XH)|M`{ax2@!;uVlbmneyiE`+r>A- zl)U_!zCB*2rB+y6-;*iB$C(H=iybfFiTH%9_#12Os|`^Zi=R)uH}<1MR~s7-j?mtJ z{)~5{gqpeN>Ho)5_y5tcjHuY3>7|K3cW>N#>OUVwZT~y>i93DP)D(4loU)3zsFOk+K(XfVNUP>6a^V|b;g&)RKD z2;DQ5s>_{^D0x9*fp|c@X?ES2f_bA}lu!w5@|nLgtgYVaUcDR7_&XbL>wXHM2O?xT zZjQkb#P@>~{LgRQ^0+Br5g;Qxxpg_1HKA7r*;sf6Me%2B9oek4mWTt9cful0f9g91O$HeZS$|jPn;4u{D%+n99}SQBYeA@p&k~a(@RRH^J<9JQ?|Fb zKPD30v45qUq*0ux4=-z``Mt@H(|C~eniRb@wND#WMhkZJ12#uXyu0rCbzAw(aML5A z%U5N^E?zM)Rjx>)d*8?1?-Me<+uE(=B0nL8xfUAVGjHquEc#8W{#jo8H%}{`iW<0lco*-zw=&+HMZEVQDJe;o!bqGY>7>43e`G{AnbuBen1h_| z@f&bjKUP@y_WpqucbzX$6rOxq+25nNGka!VWc3tf9k|VhDOJ!8I9kt9v$M^_CUsF+ zzeV_bpR+`ZZ=fTR5s=zh_Xxg=P~?1LTH~089g3;SDgRLR;YHdCI>8A=So8%~Xd~GZ zNf`CB2io29UeuuyricX#|(UHT&SB>j5*LYXSQO+hFgfw zL7GlxppRbD8oy3PPk}xK{w}zvf8jf~rc9sFUK2(%mY)?UVhc>s&X(0Nn0)W<#PDkX z-LcbL2SJ>UoqDYfRIwL5$8Zg}Oikat?q+vzc(nX+vydlqj_!7~eN5Th3I$wDB0bQ3 zv@cImt*BA|p@4-OA}M1p;Ub~wXjW@S=)C5i1m`l<{F@|$kjRA+p1=5(UxTdbR#eSA z{h4wm?ueD!2>fiI!$Mn>`xm=0{Q7UJf#Z%z?`}Va@s( zSbr)zi3wG!@in^ssl$FU{>lCiF});`wNxnlz9pQL65eWI8a((laLb)B@2bTVbBlp- zz|kfz8e8#W3(>`1x&0noU;+{fvhs8bIPayH4;^!2NpekgwQ-jrLnlFY-T8mpt1S6E zIY4t1tjT<>mEFg-h}7pBddAGiF0YUx0j>enRciTTOEPNZU@O@d5QfiNeN|>Qe6`B{ zqGSwL`f;9JzKU01@$n}~3O^gxwcAt1+u#9!hPCJK9ih6%!zpgccLF~3J~K2-=u219 zQzRT3`V$JA9HtW6$k@=n%{DyHv3j@4&>*Ere@+YY^rda)IzhpPeaXonAZuuXHc!F# z@0u(oqdklV%hqXV55pTsBxkL{5 z34F}4_twC7(!q%^vlGlq$^!FboRWMg|Bj<^t)x07o~WfurYCXz`ip_#CkX{P!Q~jH zaN{QqFBvzKoNs>U{BET?yJc3jjQVgBr@~T}wwcB<=~mUB@3%867<~@q)L*I^R7{vV zU6tD3D9Wy%4t0C_I?y*^E-NI5&1af+csPEDy5_{jGK9G$;^^xyi^Wy*C$U%Vyt=~Z zgZ1ROvq>2n{X)`iENJ(L)q8`oIXQKtXuh_3dWYdIeM^Zr*r@0I_51mHb4YU-voEny zZFhnLAU{8-kSvLFepzU_tx{sb3L3Yp5+5 zp9dK_&ji?@2SQDn408LX&wt&l_n;SWE=>St?%CZ{T2**nFl0!1Y<}ofr$w}+!zzo# z#TqzQDZvVkE&G1z#7@mtb{L~k>odMkddWN7K>_%OBSD z^w8u7nFY@7qbIA(9@aL+xytdded-y(xyuw!iv3-& z@4G0UHFkVlh;<-zs{)->pP@N9`$L>;t@zA-d&@t*&v+A_4yrFX+v%&Imu7AY;k6nE_a-y_B#f)$fpgwMxThr)-D_>t{^QC1BeY-dlRMQtqGagaA(t z7o4baVdk&S+06DPHR4@dyk$nM7kVFUAPH~-5$9smzbcH}m{(-FCbXw2e9=W|@85TK z_fmUU^7}Y8?j*Z_jm8h-&SD$e9*&po&&?m@I}Oh6pV`GG-h*44Jj(O($t=Q+)1g_vC@9f5t7`@p(N01R+adxl zXQgA*-0^iXEI(BwO*_x8H%5q>87hWjwPjtVHY47>0pt`5xV-N%97OUB%HvDbE8o(v zLzT{Pj|c<5yIki1>_hiGi(H;$p6>SndX7bQ(j5*%BYMFej_;@!kFJSK-d9|KIn2i}RoxGC;mo3K6j7~5=fbE_SSzguova(4TGi28Hyn?%~9Q_L1V)aG`+mYV?? z?gUO0pN+jU=Du3GvELdE=(X@@eB`s%=LzcGY2RT=M?;n=>X?wh7Ht9z{XwM(JzjGl zs&M?d*Gy(5RyVI8H&+z~ysGkNxKTCcV%u8O=}7*$!w>C0wuB|XU>yBBKd64;Z?_ND zKe+zCNwi$1*+VIrGXag1lepa5qZQaaw^6&x~Es&`Sf|3_tP&3~OrN-j+JY z4Ygk}=?Ql*^WWc)S|(xL7`x}S(1=CcJpg!z3RSmvPce#xn%*@yKeW*>^> zP$A|I>MI#OgGo1IlxC;xPU@y5$dv%;dj~uT@ut#TNsiw|l(gQTn>-HMev#_6vBT}E z7&x>^`y@|vE2CL6`;5Ww-?Y-`^{Xu#j}Xl#6uU+wzO`pM70^wD0kO%&_mMt}SivN} zW6tQhTV>^(YVW#h#(_J@#XtHz+!K3nS`NB~O#<#N$%&Z9t?g>V)=WvF`4)_Ke>Xv| zN+n=%1+GbSEk7Bf#BTJ!pAAlJdms5jd;MZgkc!G#(!r&TxRXzgO*>$f;&(B z5{rSJ`4-2&PUV}t8t&;<@uhP(#V0&yiv3aLjW6nNtR(FK?~6z()ar&Wrw{ve>1)H$ z+cfddoxZ{eJ-5PNs>)X1ewWx*g61110anvXH}J^62(RM#b)tYQ9js>hAdXe1o!2e=W;_ z;^eCzAbXesJ~0kcE_8OnI7G%)s;+P11#@jZ;V>zZ$!&Z;i~mv3P2=pBDmiwE1p zV1$!&wSufN`!XbS6i;`_{W1OH4ztr{0U>HuZ=22Qc+MuPLA_;O;BXyE^Drzq2AkGK zmVtsb7{cfLs}Y@`uPpfnw1ipChMtT`pBm~6BNCxM?V0MPXdh$b=#(Bv8BqT*&D+H% z`zM~Ung+*t%uw?ymk`QCv73MWboJ;9dy8jeozUcJY9t}r!R?dpaiDxa>Bp4)NoS?h zpOBR4y&(3)-wFEGCWVchHLf4spfx)xt!gVv3rt9 z@JFb!#M9RDz=j*CTwj6{Y8w9Z7EdV-i*?%mTn|yJ|EZ#=0`B{HgVqp%5@TuCg)d91=JsJ73=!|)>~e?`V()$pu|O@>xF+wU%JAGTdb@)^7vE?fj!}0UUd~37tMwom;Xw)I8^c7R`Ij} z9(h#|wjaHZG%&bpF2I!PVvw5p=+7jd!DGX|{aYV+cr^tio`0|G&VIemlfELvotz~Q z_v=AbaHV?$E=40gp-V=hnL;nLXF0WI}DF-v$zjq+Ts1x zg7y)#i+hoD=RaE&Qmg$R&r~XDM0qwMZ{LSjNBt~LC;^&m@I5qp!OmXM(2{F(qlumy zcL}+MAs>CYjiYZP4hAC}YBN_;LRiG|6Z-MuslaMf$45BbKm^zyfs>_drskzcOHmi> zVuR@g@K`l6J|O=@iTOwXfghP4f!FY1mz|>&c2w%G%w@Dy!>WXvnXFa41Y5YG&E5R%D?Q&Op=R;xKr zF;n~pQ$y_-e@#)j>8PbxojYirBcR>DIl|p>)-W~lnRiU&jaBP}wAVWlqJISRZnzK( zD*JD8qeWk|ts)H^wzXbVvE!2}Qn^Y#q;*OL07Md+go5~Tr1y)~E8Xq3pNmWD@7mIm z<2`YG4oc1-qv|^o1f29nXWAck)8_|*0JIvf9Eoj8aZwa_N5AH(h8MxvRwbNwp(d+3 z&~)BlE}?-;o`g+k@>OJ5o&P;2$uX1#ol{R)LT7iL7;o=%AysYiI@)!EPEYu_Fo7e5 z5Aim~;$IARZVah+`2}-|QV3GOw4#M11jUU{ROsLC2ka!jM`n?9njA*15?2!V#}kXb zBsi^U$93%SK+(ZECHaj_p73c!|5C-TmLt<*9va!lX^j>40=N^B-x?-7=o8_wU@7o_ zl8~>H1vsH;QhTuE^+8H1wd4i4`p}5lgK&1v7A1psiwN7^Ty}~&^*l*ovM@nOn?A+z zu822Aj?v+&Fe%61_PI{1)mBBq0VzW)H8F2`kF*z}gL>@6rhZUPy<2dAoTcROej>qu zoCuTi$QGRGr{;%95KL~Jo~GS{6YEQ&N!a#;Q!s_!=qsPI4%?$$p#7sU)HCo%{-QM= zx4?N}+ytqrpi4g52xqyBwE|7d8hundh>l)5OejJftKOo3dv!&?vYRwsp9T4_coKo~m8-QG zcog1V-IXH#uHc{vInSd0#ip59b$1%Jn)>Ep-PZci!%rt$ud8Oq=vxB}R*_Mnwm#U! z^CY@W6^<*Ltx_Yp6fh1`YCP*b_g*(x(_Bg*Z9w_QRLniktHmsMcJ*KLv+-?`+vgE> zW9SbqpZIcc&O6dPfWXcsD!gE++B*dO2E6zt=$F0J8^f?tqn9Qvwch7NXR1hIQ^Im+drW*Le!>Jk z=_Pen{!NMuve@0EFZ({o=!fJRw(!bXpu9;)XAs=Ywx?w@NyS5kQ5yhLa!L`O~ z4EeZmrC=R*Zi3>dbos9 zkHh2$_D5S0n9>I$j=;MXwNyhB3h1EJkfWcH?A8s`^UidlyE@}&>Un8~QkC7SQ=iZB zc;r3tU}u?xSaz|*=SyKS?}l4N=Go@M6!(SQnBe%X*NAG+tI!$0YafqkuZ+JMCuGda zvPoU0IP5-@UswSDxCakE2!B2jY}Rb~E;~oteUiI(7so_r^qVK~xA(Cl!?4iOTU<&_ z?rAE&Gc4WB+WiZhZ=&2A$v+b$KoibN-S_^o_v`A`dSv!Pt;z6c3@#&87TiB~(o`Zs} zO}v3AY(`QKYBeKG6=F3nK(wl_$^oj>PeIzju9D*T_Z8N)6Z+(ymR9HN(HyLOUj8oM zK3n5`Y2-6%KANgSvEXQWuesI$q7(0EVY^W-KVLD z%DL78?O*|xggA`HLnUe4h5ZjuE%f8}*B?@d2C&(t8n&1cz2@`3I_L(*S!?3lnn&Ed z*RRhdjD+|mpRO`8ql7|;yfO!+2M&i>)X!gnrOIaESFoZ^Lp35$46_{VWoP;h=wAF;6d7i8ch&UT<6p>4av5aT%32Zb#c#Uu%mA;?_#8D~M?z5n=@hgc*Fs*W#|k>qJxm>_&KQTAJ}$ z$VAA?q1l&Vv&r$#-&i$!ziqx)*HDUAI@{0_jCSsCjVMSpoPDD;`eG(X{p7Pkg|4zP#a;H@eEw;Fcq=h(YQ4n@-*idRU%->Q*?e!E8miP%PL?mUZ5$ z6r+GI2O5jY@BkR2_w?CR1gGdCEigIOnM>&*v#eL1OGeNta8FQAycN$>)w{`e2)EPB z3rL8qd>9en2D>3SPpx2J)4ZPD$@tqIm4|1w5G+tIwYeA2QPK4!6o9T`c<11SP8B-5 z6*kC~a_XaS$pl}azT95A|*<< zVkY=e$J!eC^?gmyi|<)Bq`ou4X*k%FVVm-~5~Xc=uKcLs9pyOY>Db^dsj{|}Ni%-9 zM48FvYO5?c)3R@@eBI!I==N>o z9jklsNQ~U}!{~dyDPsrS_hakgt;jFYtY!LTkytrN11qaC5WDP~Vm9w?PVYele4Rnm z`Ce>@v!29T(_t7;sidSNE`m|fls)*^*5nm#+HWpM_Tn7h3_E~BjwYP~%EQ+{BRWz^ zBw^vDt|GzS|Kbd9)idT<>WmM$AOfKy!MvGo;@#zJTFCr2ONuPFdxLgcsl7YzI(2u) z-N#+J!EV6Sy&gD6%xc{0WGzpWAkiy9gNHkFKy!0*OZVBW$ts7XFH&Q^^EJDjUs!or zLDesQ_>hF;hIJW#{EVMf58TSDgQ;>*k@yV1J%eLeA1h0TuYHSP80IK>Rg@iEe;)U? z`zz;3ed0j`;8YpicyUf_$Qamzg`8<&e$~7?dIiYSh)vcKMEpv680q>NQ&u~+r0Su? zL{dlE8RXWzm@TTE8)+I(Tkmo<``p7!ZY=!33ZE zn$tpl@tyK_Dk&=iYmJ&IT8jc_&BW1>3`+S-cGog1MVR7qP&X*Tnkq`S^UqAGXu&a@nTIvOPtXCNF4C0d$lo%{@EcAbDU#W4G+p?A)UE>{8dZt0F z5Q(8(`+bxW21!(v(^jqZSuwc|7q-|m`Dw{I#c5i;eEWQ;ZAV3W00&=C1W}h%l7lw*V}oHt@MR5C!ZHK7B>um6ZG@#eMy% zv&z$YlFajaC+z!Fc;$(rB#`AR4^93c;{}ED?e8OxB0%DA(77ap`Nk5`AHmMM>MK$U z_yTKfA_o>;y{zlmkC8Q@GI>FTzu^-*!lErx+Ir1riX6%y5``7XNWv0$B9+w)Y49IN zYTA&$2d}d|erWh51c}6j6u4^@L<} z%2M%Hb$L!eBe8J$O~2Ag67w!maQnFnVZBLexyf%<+yV^`+9NpaZ_*8R^8%2(I55~T zL|T`eUgBau(4|RfG>3Yc)@@Mgrh|VjZl^!<(xvZuso8N=tQaeX-%=Jlvs@@^w~M*T zV$h7_jOKR@_x0p|3wn8{q#Onvo8Y!HVRlCgptuvXbM=>8%3C1Yti3Yid7n0NETiQQ!FHfGQF&~i?n5H@9)Qa zHPll8*90!Opl1B$%EH7$2q<9nJ(?qBvi1xaAMrX06}665VVXVy4i@rwq);cpw*6ht zYPv^x*V*BS9x6_QozJjH7tC!!4-ecZfQkog{p{Loe4HI}j>!5k@2^HiBI23~!X)0_ zJ3sDHsvnNp+}x~QW53WCK58Q%NG=Grps+s<%}J8EI6ZJ6k{U!XK6^+4=i}a8!Pj#jx?Wr5-eh5 zCS8g$s~@k-pT&%`ffs9>-P{tvV`duTISPaF2cMCEVA3RCXZf|$OLgD2aO3n@8%UZX zVVPj<5J~YC@SFCE&T6O{kVUQd_Avt?IXgyviCIfsQiq5zI+ zI9~jOOFLOk(5rR=H0qIEvXI_p^=NznRiKdOTzB4`Z}leO$m{uAmp$E^&wS}U15Wq4 zaCPtNr#|=G3H~UnCe4;qqp`J^Tt8c}(7s}HfLNHqz@XIZ0ngYa@LwAGoWhkXJ;U5~ zwpBnIXjrzTbMVt@KUD&(7fIa47>t@ZN{pe>=^POSi9dLUh+FK!Dva zHB3-1yV(&JCdS@*L}FFGyIyN?01O-f#Pv@Y?r{A4Sgf9V{VwACp_$VRE?;9%QPjCx zwh~TYV|h9#Q#flcYKxC9Ld678xr;&Ipql|BtxaTQDl&5FS9ucEugjl4)z_YaT-AEe zenanRzRdL``$E-WGckuY7J*3FUC+BO~R>cH5JK1FdxR}lN^acT5m z@bT59HJ8KCJnoic5Wr*%#5R4SYnzwN9vOVA7Ue9bt0rw9IMgZ{aLGH$_|nl9-d$24 zrq7vtAQtKh(<1tB-|4dlKH-m4rnohd+gu5 zP>%2$es>ctI+Ivoa)aTR$A{~UZ_y=NCE0b;y2ZmvQk3SfWplFtw;iL^0FfPLRud;z z=a*XZXZh1!9OIkxTU?`29*=L5Dcsg*ARO;>}%mDxgIwCS>*tZirX zc$OxZZENjh^$WxLpP5@Y$0LvJpMOz_pmY}2<&7@(WX9QmCut_5E?yZkw+{~1Go^qD zk%Y`U{t5j%nI@LOai^Hd=I(Gp6}O9fNs!HT>kv$6V0^Y|A(}kUH$p zD#ad<9q4^zk9CP&Pj{cx(t958WSlbbCBr=)1^5iY%CH&^MfXlOe0TLG%+yW{tiU4> zUMp}k!~%*~J(N3khW?v482A>ln&Sa2gHLG&HeWit6RyPGpC+Ld?V!pL!5FVBBt1tM z@Dslmshs-LuIsfB@7r%X~y|v_}kb|6T6d^)0NnZ4X-2d9) zu$eVv?}^O$@sb3MZGw*E@A)eff*jHgvyJ`%>_diE!x@Kojt{agO2cGmR7r{5RK%>g zXO^e#HT%kXh%nt{$hEDCN2esXp_)1%U1oV8)VQlkpZ}&abh z8h6zpYK~pXwVZt&fW@xt zZ+C%3{mrX>-CQAOFcB}%a=++JM=fW@ZrY#bKXrL+T|-={PJO(;#jmxT3Qg`VMPLI> zmOHUO+S^qMNvc_5RCfp`AgrDB-TeDourzMwoJJ4s0qD~@QJ z_F#}Z^~7@bU7RX2+Mz+UnHf&oBF*Rh9*3M}GB1;oDm#)b;DM@ozCg;utF?sN7Ioa4 zSG^9z=oxRL4{TV}GPD5)h(^yP(EboN6xGCR$u(#hl=nFhNB1;L?d>)qyrSUungp)`er9c5WVSoBf00U}mz-2(IN7EZ^&GlpI2$~6SHwF=<~&*{ ziJb8wi_Nb$wX$Ojoj$0tIwhji02MTQz^C;2`{bpgum<*b_xA_i9xyidPeT@*kdqRU zQd?@C6w~=551Eto>r~SWlPYce)eD8*cjr%DCwMzPE9_%RZF(qx>t`BHR7UsNZ?=GX z@fp|0-iLlIK`H8YDS}$`Cg>%iyd6c+4qDEa8 zvn`Ld|E7S{nK#`2`b9ZL#^k4|(WAcQ2#+mSrFFz}SGz-!}@`+P>< zXBQh6;S=>DJ}#MVjz1LAAfRT8!)lg`JOimc^cu5|%(J=^Efp+6s98yB<3xE%Oy;D( z1vsFipK)|xIrYcvyL;eO0;EqI%OF^nnQi=}qH%JHS5w(BxM>?DSW{A=?B1v@p@S!I$6CaNUK! z@RPI5whY`#GL$Av^u@^0$16k`GM)Z+kMg-+K1Q+pa2SYxlnVc*TG&V1Q|)h?S}V;3 z{<5kV4_DjGF{U`=*rmed6tT7_R*V&1&yNheL^VLyHeh)LZOdv1MH^K!qz+Ca5kF0srlFptzug zAVB`8T7GZPbvf%mC|N_02yOK33aWHI(Kg8ic^!~1Mj|!686%4;d77@KilX!_jr150)N7@lYxP_A0@*Crr z{9#Jiti;rnl3sJ%NhPjPvRw^{Q%7Y5)FPy-oy}O1Tr~d5~% zq8TD;iJaPAKfN$=6PkMpcpt@aE!*VEWfjl!`K_wK zVBD;5z7tOe3G`xzd`*tFX5BrpkuKwqf6%qpmmy=gbLp+~yR7h|X&*f^xLc|-cR0z+zZ?vNZTBfNcCKenkfQhX^mla+f zx4f309?Nmo4qFs+1_Fpp^QUP7>7O8ST_PvZGaa~FjwzHr<>JMy)k5hapwVnOfx(90Oi*Y!ysDaQ?)vLv_UD7A>@dkJvhu zmGV$4ce~q)Q+zr4dIqsNnc1M-cP2VkU!AIn9a*z==d}_j!8P>tra?|8gkA*xj@(&K z>f9~@2Y!T->(6p)(IUqWrQeWmQMdBAG$F5vJCaXZ>I9r0rtjnOc(hHA608Lr_c8L& zd!{XYj+^k+v(KEno(g&N2=?kehXh*A`A(|Q$UfO-se8FSMz(@tY~jYAI8=V!SE&mXgC-@ZA+-@zFe$;UbTaN!R8GhxxDI{K7!JlH%{A$ERH# zcBk4M(D!^Ln^9aT(yoe1lD29izCPNH(JYN?1J|b#=L~INCsV21)rbh={2Tk$asloZ zk{-zEpzSE{^KI&0tF?18>ytt3{%pHmw`=Vjf9xqP+qKDuDVRch2K$Z0m{pChpIP=EZCCN&CW+TRjFz5y z`2U-K4L;Vo5~MXBQflSh!<}}%p%?P#FP5rMOGS^1Cg##ry_?H{#b$q6V&Gd%_*q0K z<5iQ$lDun)p&WF|Fdl_~!=X2Ptz_gOkQ0q6-N=@EheqKx(MMO6{;<;|lU+p_=~`TR z(Q%C|%K9alny0PveP@0$Y85V;vGqScOa$jkZc+Rnp58L9$^U)-r$d2(NJ)!`G?J17 zL6DLLX^?KDd-N0)lMs&PjY^CA1$HTT)U)}y9@{kiqdaW8+}!wr({o7qa8uKPmeGMa$f z-YjWXMJT4v0et=AW&;UH!5p<29EpL&M!-lZIOmu#?a^+VDY>)pir=j_deJ7OUYyss zd5f83J#5iz>+FFy6W&Tt`_P4~rs7Yyq3bO|++!Pg|4h|(8*0o$?dBYB2WvCr1Mevq z3b-^6^16IfO;9`f1N{PrR$$-3xp5|CFq^??qBikxr97H1RU}N!vCfTWt~JACEq$T& z1P+=51;iVhB}&YR_@3ML$OizmuBsN%T{|(=^x7D!V;}t4L?)cgD7mFM|AZH>h#AgxJSb; zjCFL_v?gQU&RsqWb8FzqC6km*L@a{l2q(HiA0(b7n9^8KkHs=fnk}jl1pHG@M_Fmi z&4kPw4PE}66@Jm!!|rS-wyW&Ujbk)Dt9Ywo(Bc`REW|iz5!^3bPLjy^!Z;e#OC;K@ zXVs1nx{%fro~ODqZg)05fKNwez+LL;&<44w+(_6CT!H8nSRn`LP<@x7V+bAsT8og}1An0b5Lk(5xq`^t@Y=-6HJK`6Pe9ft8 zTtgwZ?UMmu`O#mW3*fGTTj^wJ9z`EHYZ=_ko`3fHQi7M$>nvHVdM}1sK-ph6U(~`= zj^xZycZ`2&K9o{2Ni%SRKWH=l?|GVZ$D1u)mA(V~VZo4q+Mwe%CNdeBKiEmBwv7HB zd;jWhv(susFF}Lnli6N9xTI|aZ^Av8jtZIEF%9MK$61o7rfXK^p#3LcDIJvL)myr@ zOSzg=R;9uI;vDwCqu@}BosI(Wl~FK8S9@#Dih`juIO{mw9%fv`dXzMVG+odCd&a&S zTaroa*1-Y691)-1S!uw}v=-_#zzJm`?#-y!2($Tx@bxDxN54Kb&;08}j_-SZ6Tr}U zjy1TvBi%YP9;-1pSY2YFeXo-YU%m23+j?FC@f{{xT$){?|F1vb(=X4LSlh;U(!;r8 zq_P@(+#9$LVj`Z;m_vfI@;SbZMCSeUnX@ERZ=^aNH)~w>$ru^mCk(K5;Aif0|4U_H zKc;AR(i;h&reKKVgKmnh|D^ge?Hgv+MO^uh*f?*;6wjma07X6%^;R>6Ifgh)sC_nL zI*hf8{1ZOWtCMc!ic*j5&68f{*=$oRY37Qrkoyjl(K@pj`Pv4w1i0wQSKV%MfX8iG zeQ%C67^5s}#=3Etw9&Z*sAK8%AV7teh%^ecAgWbj4%Q9SeJwz9*V(=ju-~8MyHXOS z(?l&`!k}ef_zLOi;AnD?tnYf*l?2C1H}(0IgnN0!%@OSO{VRi6#s2n)MqlxUzI}5d z=?ttN|M;NYlV9BVKE&hqxRbJaeVZ6W=3^8Y6; z`8$D}H~+4yp4-HdO24kF6CS*Q*CP6rj#3s~ZyKdgW2SfNUU0ppt70Y zH3j@^hTeKNp8cAf0F?W3_8F7nHWT(X^S_PqqUw7uMeS<=hPJgiON;p3PeU&omxy)f zt!FaX0d(xcLez?jz=5jvlk|y+xy)pnLHfdKPWChE`o0#c{0jLHxDQ$P_vo_P~KnO z*Tfh_@nukvs6B5{6@L_yP<(%+LxewRT>u^?7wfgQ^KIc{LP@{A6CG?F&}q#6q>Vuw zOsFXse*4RWRWgZlny(NQk(?}Zt!;vh|s_(G;q```{IVX$^_ zfd!P}QWrw{a{e^Tv5E{oNbyI|Z3Q|gi*5Hyn$t6z6&SH6QZ|%$#Xxj*^Z=taX={9# z*UK9SpP_Ma$|GQSIP(TyUS4@F=sB@ox>w^V$1 znI~>=qPbwmIP*JyQK5A?`hu*@-KG}hnU3k!>T@Mn$aoFQpkv(Y45>~d0> zvUm4lwQ&_o{B&*uF$-zZ9BDarJIy%bOYDx50%(Jy{IDOBMQX_gWTg2N-0-E%w2Cf%#}UmG12-88Do+o2?i$n z9xBF9+>#By72-~OZXc=XFW?Ej``B1#TR^|JkU6%mu6ax7<|yN}7)1XWbyT+N;V3$% z%SAvoets%u9#0a^IQzZSa$luU{Qxq=_MdL|bHwWYx7_N3JM6i&t_T~zr((M@~90s8tB$ zP`Oy>3M+G(E~NA^N!%thTjI2j&D(6C^gMK9@e^x4%X=7Tg!uP<-PFbFF?|s4;W}=M zz(ERgxTD^(_pB)ZG&azD`{(%&_mjZTRIXfv@G>2zQuFn1a3UF< zZsFNou+?c6E@p6@@I2uz*m+dsFwE{H^kC5dwNTNhkbg(=HI0Y3QwT1MD7VW$)vIe$coW~;yQG0Xye4z|M~>8*;97M3F|lwSIapqI(u4!bl?&x->R6xGZgBvwW(iN2F)Q~I;{x_<;T$@3 z#`#a2b`hq(*UM4wDKu=)*RN70GY|=%d2Pjuq&=Ht_`H~}s5Mw}+1dIPv~iE>)QhBd z9I!9)Tz2RPbA*o3kFn*L-Z3Ao^i?O2a(6}s9QZ!Gz$>=s#NHdLc@DZ^I(~O-Q^oHb zCd=UbMW_&j48|_L65)OCgW+2!aHn%|M})_u)XTkdS3ja16IBZkww;LJEX~JrG5_q* z6%@p;rvrBxo0%HD^fS zFJcE80)F(o3h3$z9wPIFiehUA+zURXSPFcwTb<775)0{SHT1YQy-xyY>b;pHz3GXH zKwlsm3)7wTn#^{qiZc`{9*nqL;+y37CbYer$?qxg=%fkG(ePGYKI_?u>~fa=V7tc6 zevF<^M{|==ktk2XGnvF>tw#6io67^wVYJIV60@Ru50{q-tUerFrQDNP;bt38Z@8)7 zepY|8FCFu?D@XmK3`G)-{=-~pu=;me~e8; z)aejs0k=SM?A&hjg72z}#wACX0uNXLD%r0X@84GjaqVr&=W1if$t0iZ=a?ev?ZR@ZG@;#=AD! z&mVH~kaR@?5a)%Nr5l|)Zc*tdiTzv9&TcQ^q8b3QZZ{DKeATf#!S*b>zGDPp5KHde zq!SexjQRAl`v6E}M9OY(u;e*94M(#7YHv5&rVSssj8vGS`p4@n2=UqeIv&?aeJ+eU z_yxy)A-{<0pLS8@`*q5Mm3l4GR&kW1Q~!eefs8&?v>j)$1}q5lftUBra<+6I>`qy- zJEMWTj!5w$)eL54_b(pH}LK)4J}}OBz7lP8e?V3_>;PZqq*W z#M}gWdM9BrZD2l9LBoy~N)kU3X>tNI`7j&E&6+QFEVHI)U-&h1%7FR3SM1GY5k$4M z#E|)EesPqTxxW!pE5;VSJ>!IkDrSnOI)W%K_O2Qg%6#Nosb?-Fh&q;~KH;sV4an~7 zcGsD6PJOFna~EGely1yH`t74~A=@Jj>w*&TJn2c@)If8asCmBlBv(C4A&q_cdoMxu zFDW8}f9Qw}t6r1f=y{Y5@p_W}^l!^kMdS|tc>g%^B zrkL$@$Q!uYY_j?Db<%GALMpN!X4F+>tu}m<(1di!sMNLH%tW1fBO1pFJ*X_Aj7t#0 zdP5bQzY1Q#c4*ZknlhbI-t|?X5mzq37K+ttTlkodp8QQ@4;;C4e8thCyK3AIxBd=^ zK=&)9d$%nE!Mh%=zsEiT;r;FG2cC!e8Cigwefco4*E>hB@oS(gH*3S^Dk?fh+VaCW9}t^C*s~%p7J?c7NQQr@v5l=MBDLjs!eqS=)tTWnv9fWj z#}JyBPnbPzd1L0kPK+M)Ht6eRZsk3*9R+&WsQ14QTzC)Kocsm^&|>BRh+Df6Q}bm9 zyt6lE;Cs;Zc;G2&pMOx&t(Aweoi<2#s#ukLf%J{{py{f8(W@>Iv_5hCff1s_9L)Z60s9B_Xr@THY~Ibw^m>-djqx z#EeSYj@Dk1p8wQY%)hv`-?1R+U!#^V6ifp(mz2N1jWh3_Sv1|wiDN7a%P}VmzTRrl zGjDCWmH!r;bpW3=dxVZA00o;4JMn?l7+SqoYG8Jg?)?7gkfVI$>6w?NpU+ty+V{7ePVY$2zntT#l%?Y|b&VSuW2d%iHo8EUCpa z(goV&WWO)cUcR)b6Lg)%zh~2T0`$oe_dZcw*K2$NrRUehOAQ zf4lEiECcO6;+s-sSM!NA0>t zR}AVj(^^e+dsV@5jIKE@^;9=bg@sGij{I7-l6bv&gxtD$+rvTdl(%QOQ%$)d$8LBD4nfDbgGpQc`j{SU_8Rz4e5Xk_G`}2g@3`cES!9$@& zM-pEsaoe1(zJjwww&546&KFvr)xN3av@I?93PkGZmzF-AD6>;5y_ar<#0sF>ENi+mx;a*bknLWnAl>nN_TW+3*dPLquqOO`6?2TyIs4)ngIug z44pH&+=+-)ez(hM(zrYAUG49<52=%!1;Ujgv^LA$ zhx}dK5qagu;O&#O^|Mj%ENjTZ!?wk%hK}T`31K*8i@ ze}afCzVx4RlJFec;dJ(U^eAK#3ckr3tSA2(KD$v~JHoZ2jNipT$msRGs8~ItL8a^I zE2vE8?y%VE5Ggp?%!PbSj|?X&R(i%Kf?kS)mWvoEM^YHs;957Xc>0&dd?(;)#J8O- zP8yX;pe=nqCePO>H5Ijt^G05OFbU zme89WG*K}udGlS~q;!8>?(&=1D$nip#UvspE$5_bWl{=H$t>{pB3%({U5Pp57w8(u zkQKP1J<^1HE6eTQ-`*pZwPsUCIpk-}7J0So{Os19{UIOGEY+$YbT&__ZD544=~dc! zZwgb2nG*tuFBehTGWe2B)JL_945<~wB>DeSyvJ!W>{vjdEsMSLa^-F1n z_#!N$Y0dj<5}{sWZAt}xnTBup829-YyYS!=RB+!CeoH)(c4U9l(00C)vVVd*a4TWrxLW#c^z~n- zb3e6PgbbK<7TGq{VCHUG*;+!01e^L?5XSwr#c$w|dAC}mjg}dud1)@QR+wuU>YTH^ zKV+B6*@3C)F!0qqe<_{qVpmV*+VQ^uv)+Aw&#ZHOR^t<=g>RqB!N zZ#pAa7G3icJ9d>NABU?7LoSq3) zZ7cSGY3DPJTS?!X@g7_Ww!6nMQF=7$oNLSq z=YKC@hDJlq1*0&@@Nzuq$0KFts@cIVu~XAx%BwQ<6Zs8|1wtQnIB;wM)==~^4dD&A z#1RC9g|%7^_6i^&qQ1{6NLS){+x!Rf0o{(C9k1OaKQ#0bcgm<)S;^Z3bc=dmx;GH* z7-j+ZP8Nsd7W(qJ%0?!<)?#j-;nE|MfL_WTm%Khvvg^Hpo+;aM^W}H5;Ol+@dN)q# z0MvINKWe0*4d1F5`KKi_TE6`S;;q{6PV&_nIf2Tql7lFV z1qw+f|5S#+JjRgbMBvP1Q+@u&HY|a%HcxXqe<>gV8YUfMsRYouY`=3XJEx; zoN?hc3WfCgKl2Vw8#<}C#N7PA>!hUp`1eCZ9ONe7xgEWAU1ec2w)mOZ6&ut^?l(b= zCv%nONPZmF34*m@zv{p&BRAb3m<*C9!oRxjJ()pgnuIv)Ba*Ni=A?y(VXQkJ@yR3) z1W32+;O-m?Zg0;lv#}vn5pfyMDhY2IwF|K97 ztO9#L)P2lTA`s=A!hN0ouO1)FU>Jyx>ptf6D1h;_TY~ldA5gU(4{fN5W;6@HM>W5lByyMh&-Yu_;>ZcA z$%c+RIFS2JIYPe>3&zRk-~g-X*_}fEa2S~~5_hJ_)V|5~TR~OTocYw(3{y)BlLFNl zA;BN6bLou!8J3i3C_hd6kuCkSrdzbWW<3DCmf7H?k41+1)-WwrV6zsgB7R+U=Q>$R%Hs`5lbjXUuHEZBTt#oAun{c)!AD++Qi{iAnhg8?&XrGx9|!Em&v%|xUI zVlr;!hxM7WxFa&vD^A1_Bsr(lx1>Gp`9^Bmlp2ak$~a==j+46iKJTXeVZFfQ>e9*P zUOw)-pXzI9Zg>yXAi}OVi^u${|0@349NTaCV^m1CEN4qnR_@exckaSMcFpokMn7uN zxfJ_V1k^Pb`_+O|+r4FBzyI(fE*g9KrW|U$#PD6nrZ#l?26H84 zdkNR92?qeyZk3RM@)U^9qX!uSB zC7UMX8O>>TBr{*ITBBA)B0P*eu9hx9;diD z&1PR@N$+^mPc3S`R9>Ot5UvD{kPji|X{_IdcW$3^pG1~`5KF<3s|2n90_;xM~ zj@RN3Sbi-K?@(RP9btW1Q-K)i?HRlUNm-*@puISU>jPtH^LeHoV^TtsXS?r8GnC)3 z<4_FWIXc;F@HV6{`qJ@cI5$LnrG>WxEdi1qEBp|ihcvv&YQF|_wVz^bXL@e_q15Nc zB5WI7y0JmC8s)Scflr5~5%-fSf#2pFAEN(eA@=DY_Zx!9{G|KCPdjDNE!+J29I7Bs zkP)Q^_N&6wQK-6kY{DDRDyM2r;LsAy^7o84j=syrie`?Gd&9fETEUB(83_0CF*r_T z_?P-KJ#!8#(CYY7ZDmItZ7@>sX!#z4AeS`p;)dZ<&B|`z+r-zqInbVwv0}a09O8uqdT~%)5jeh{Oh8 z#=bykU5Zr}_a=fFb_Hs7IqBBu`VZFu0{=Q)fH^38+yf-_3ms_1JqpM;uz)$1h~>1` zV?vq3fnTKzSGxB~Hg`?@1PM7mon%6`TD5GTx_{!cYLd9$5IF9qh3FcdQLcY+hFu31j=EiSGs>h~W15M`kRM|{C0?05j&x*IaD z^O+r<9K!$NS67nVs4ZGVkZv-Z8EzDVG4ouvU-y4`aoGg^Tc0YSyz_;K4_{nlJqp4l zRZW5GI`yk61lUDb}g?TXu+%DK^w6+e2mJ73mV z*^O&kG1Lvz1GO`qFNH$eX|LHC8sz0!-@f>k=QI?6*TBMpHC-^-Kw8w~wQt5LKTF3h zdE_6@;BnwzGabA7BP2rfyS+D4QsmhbJ$Z`TsJSGU+;B)zpz;N2U$OdJ|@O!h9ymI)b#5kyzlvH z-Lo88`l~R1(?sew>C1Yz@F#P_SW{z?`X&QTmdhs(g@wMm;-dD785$WEbmvMRRWT1O zO_{Zq&#aC#7;Q-}95EsuZfUcNl5Me=I>PC(@R`$lcimw=uv&?R-K_uX7|c@&8V#CRkmcek^A2<_*jDxpQ#l>; zRJR-{Rj%0F*4d~*@J+wuPUiD2nfOgrHp}*MJYAG)zN#nOjV0rgYI9dmwzrO)#aFbH zZtc3Q;K93beU3UQq~SC9wcB8kN_t*^V@eTpiw+# zO?@2}K%|J#exURFVRYdh5m=WFCpySjg6q}e#XXaJ1#=o?kS>SV@=F8P*5FDL-$e#E z2Iy3}>%DmLH6pK=44m5mba@c+{cTuiZDDBgHP2E+PN}A}%qj>I5nM=JZ9Ww%mz(Xb z4ibkePfEHNb4L&^5KfhqYTN@535+#8q<^Wn-LVaG{^M-uwyJdCjuqXr4|6-Sdx;|j z0-ukC@6w*tZl6!SOHk!&f4>4jN*icfuil~(s`e zq{52_v;N3LlCJo=gI*58r63xd5Vz7_U;797r8vHklE$kQ+w_jN3>Fz5zDUwrewI0W zS&*l(Hmnq~Ps$e3=ezs@RrS#)qqt@49*l&m6hl6>4wQdMF6) zQ1^DpoY0E@_%s+p_3a5yDB-2OonV@vC*I>L7Hp}i9<850e7K~FT_)py5joW6Dx3ZR z`mHiz6xklVJQTL;bhTQDWqBHG;re`0#u)Utk+q|TIPp!?5uzHWEZp01fid3|`P}@u z`9wjmDZ#1M^Y#S6N6@!T^qwIONe-6yjO8ti;0L#dVj z(5nYGt$u>%u#Sy6e?h@-^Rk+%*QKIfH#Ly9xyKwOG+Ufj4-^e$SDWL}Tzofc!}NW+ z5Q}HNJr_Gofh<3Rz;B+2qkHWJqBERXmxo_&Fr|oY=jXMX{Tt@>>4*x{w5K!!(=#A^ z8e+&l%_Z+;zlvj=of&=GSKdW18I`c-*nc&OO;<(r|a6U6KD9rFH8 zV-k@Wa=pu^mkqW9C={)X?xgy^ISCd>5klsmDl#xW_d{6>podp>>1f{Eb*zOy^a=q$ z;$0DZzZ~@XY}Mg^y7_LbEKCBR^m2+`ex(hl;Ix}4P=;H%I@UmTIN9ffrW+Pr_qDSI z?YM!zB?CI^S7vBHZ$tWqtg>R1Vqs%Ij%>z51KP~YjIUtA!>XJ2=W&*MUL&@pu8IqVEQ0$JLbC# zNvvY+M48gtfb_s;r;dRNHggN|HfJuN@9GT;NQ zdMnl4CM9VRTfL$^^zXgFp&NMn4Q=xIc2RxOh%f2g!n)HVV$Wa>;W2zr?Md!xxBq#V zfJ7QUBt&1)>1EU{dZhN^D*v^G){Dm?7i>+PnMy*J#&fgXvzCjLK`s&dDg!inZ@&DJ zwd(`T>?0gS%c_h9A18HdTfXxT!H61VMw~GP@v3mjFe9!W&B4H!!p52ls#(KQ=VRLM zGtCAwOqs~eeX8>A?imSm^UWqaD9a>ydyyistk>SjRP!TK^2Z8`*jFSb*W*Mu8V3Rn z7NFsaf7(AsK3JY*gP>Nx%CO^XS&KIlLqZY?S+BF&r;BK{ua=)?*WLF&PkXEK+oXl) zRA_jxtKzY=1?$=~r%KU+6}b-_W^ zK5Na%bK|$GW_lBCfl=^|Pr83uTffkgG>fqv(mMk zbZO3Bs^(c!HS80@mgPfjX!BEqMqEO9i!Vz0>cwZ&UjFWfK{NlJLWKaN>;2uvg~wnC zLbY&xLqrUZKRlXiW-l|4q24F}Obu%CzUfd;Z{Ggz(+gL@E2=E{Qa z%0X`__;ML;rW(Wl29Fn*b}n#nEJT;RbkuR91zuYago}lod@*lYni=aJ6dIMv?|Mnp z%0&p9Zr-mf+x-s}d?${0td2WU!JNJaDC!flo;zcC%_KynU4eE0DY$@38g$yv0XK^w zAKM62#v)0IWF5xp68sMr79ssLc==p6=pC?qs&e}e2o}jw!`m?TdNNe>nkfswU-*Mb zgGXP5Lfdw_2#}Ol!)_sL5MW>uCVd6=JH+k{WBnDbNrPkQ{w_k^yMnJ396UxI-cC*u zIZF%~A~@IwVo9)Uev_2{G@-jLx?cAMhhnN$0`s7gC|3-?OAqK9yG(P+y;fj68PM5Q zT^6L@nPK{@py=8ZTv^n(PzU{L1X{jl!{XyvE@j&aG5xpgh!vgHyuFT}F5{jfQ?qjX zM4fP5{DAjzNaV8ME2_Zrz;}_XE>p10Fgs+Np!X2SLu0T$OQ+GmWMzb}E0UyIa? z?#Q6fV~(E`%Qi#VV2OaxTqy{)Gbh1okwR@I{MY@*b?)3)3XJ-EH0e2ccXwA4s{H+W z24?enA#D=w$d*IYVqwD!*`)Ut(9>|>L&n|I9B{d3Gr|ou-+9m`w)!^u$l&g5R z)*5_25LoV{+EEW3V9pNi<}F z_uALu)|(aq46`Ad?CDs#^kE(2$)}4zz|L~N5(cUR-|pbT zk5(ZmpEqQF^z;xMUUUULsKLBUvU$ekQ1Tsko(EwgH`xdEHW5?N94gPIeu4(Hd{qJq z`&9%@*>i%@;u~emSb(N(pXCkB`HjvTBo9h7QKywDdlmtjx`Mk*>%*^v2( zH-HVG@v`^ghxIrm^r#o&`5N`AHZ925gL9K`aBGdVNjZJpfUwtrp=;`{g<5WkyofKc)`;4W0HV9KxrP-*OyioK^n%K3>!gTF4 zSU~YRINC(^wH#x+*S`K$X3~sZ-H7L4CH3OHatPi2kA$+WN=5vzM}>%nkIryemp3ja zPIcefgP*&o&U?J4DHm&e*D-$~hfY6P=0SgZ_@(5ZUd7(;mn}Yst*!LGGy@HPGHm*P z&ezzF;L!>BWVW7+6bsrN-Iy4*5E>T`%Qs*6PleW2!HE>uRc~Qd1GB1H=Vr4) zT?5-^X@b55F%RTGuXcvZngIh@moqO!N%?RA`W8RBaZqe|smJ+?2nuv4@FmUbwT%Dv zOaF^`W1G8Hx(S$pg3n4#%GW2c7%2QQ^>tI+9=Wbx|De5mRSjEB$ zOSFpKp|zg}-KDkO9~qyb?U>U>s~)mDw@(zkV=&eyUn*$PY0Am;U18qDJ8KDAZ7*bQ zg$?m0$RrV5Vs*UljxY4+Vj^tGAuK~)sop;WV4PfIN0)82`l-zoEd_IplH#L;^MnS2 zZCHXgf3r%!;m6P-j@!Lw4p(DjXUva9b3Tg({*(SZM29p>Jn@*UBSLsV zR=-g5PS}933G5eLTMoB8BzouVa(M57RMv9*PWy?)7-1zAj$9Q3$%9>>c;!C>;E7kb zMbybguaitH`kUCwn3u68GmiW9#s2Kx`$cZr&$$Jq;s;^HLT4XB zh~BvIrfRMNLVU_T`xbgTCk1$C7yyz(y&P6AFbC(*8$Bd{AJO?397)S^g^T3H3-Rl^ zR5ZqZ70P6L1m9+I5gP$EEy;faGaEon7X7vI4aAH-@=O%$_ou z1{cp_{U#7tiFqxP4OHQwu04SYi)ImjqB@D|oqUmCpeTP6XF>u8#=Ec&_3dV!rH~S{ z>LD?#>Lj3COMi_NZ8@mJq#ZJ8aKPcJD>d&ahdGt3oH?utbgFzde`jH&hM)&dT1 z*I<iakv1>K0$Va7|7!psh~<(>Jswy_rnd@tqLaFUddj3A^DWwcXHZWPB9uY3$9)A-|Aq27g7+YOlHY7%` z5*B3b_k5Oj(Q|X+gH|SDu5}V6Cp^V6&G7iXAOayWB}PG3|*wnr{1bt{lCRGtPi#~HtQR~35K=X=}tzfPFG*SGRyip(O}z( zMKxB>;1(w->m%xUVH}+U5hyV>f3C<*5lRjE^CkTJbl-Yg8YS2vulrVzVm5EzeK;rR z;D?~g-ecurN^M4m#In1(3};b6o@%1#^52?%J0;JZWI76m+jxqkCwVkTl4SBjcJEYM*vJEyKlTW{PHcJ%*2Cv^A2&&8GNu zY{mBZyUaPRD*|%Auv}_2TC)doVprWfW>)8-kzf+QA)Em??<9g%tZ;3tMSQ5lZvnPA znd@ID>J8@Br$l%zeNeF{BpW$YzFI!=~`#}`~cW9aNmguXg3931_lvs$1=x&n$WFjC4;s7pUXTV zxi_Vwk@V84#~vmTI(v9~xjMT>f4&uI_VF0&NtamYJ~fOo+~c_8#+D;T_fDk>secyjUUq1SD#1=nztov>Cdk|arC=tha6ca#Q)0Sx)91q z*xS+e%(Uz;c)g%F6}xWXK9uIA!u7$2mbNp50xQyt!<~l+Z^nX6sJGjd^sPrrjqgLL zz4~nmbF|UW$+gvQvDy{U*^!8I`{feiO8E(4xl*p*+EJFZ?j*MNeWS}|H~R)A4p=iu zMyoTT3*S2fW~G*W-B0W6S>zK6QJ?!a_cv3jpXTPay^`_$iY6Tr%Q~o`_Wm+9^AUd* z|1#g8iP>?sRxA^LOa`&s74aFybIL^iD#&fNWzYR-xLw$lND4W}jKQbP3qCM4x}_KZ>thQh2R} z_tffrv&v^hwU(h^mM68dLO36vmcX^e_C*}ZGx84Ii~m#w@;;7tmA+OPHM_NrSg)_S z=xHlZB8|=i5-Ux=rvm>#Y=1Req*e-)rSgGt+P_7C;z^98@n!+S9TU-Bcm1TF`HpMyZMg*I_(use>h?FlWDe3iE zU7IG;!U93>x3jM+(Z|`pBXYGDbPP&R-ZSEISRkCJ<2xmdcRTgP6#)x@m6~J_BJ+8X z>e8`ytsEzv50K`Ws~(yJVQ-syC{l&3`^X!kcgm7f>icRzx39I87Z-H{D?T&1%iI*m zt)Tk|ybs_`Zu4H<4X|}RU}bWbm>a}me>G_1NHCz-j2%o?9>XL}*uMh3)tj`t-!p() z-nEL1VBV8}jpVReB`@sPBo&G z$pN%Pc~fiCQ>Tm$gwFHvQuIf14c+F# zGH+{<{auoEZ++7&LVk32@07pWdCAuJS($zEr9&cVA!b3TFPB0x{rcx~8unBCar&?7 z&z_lqwUX80<`dpX6=BD~oX!)ru_E@^&Nt^l6v@^NP#!X7mf5AdA5wR7`9-8V*c_~o z=7T4}JInSm-Rm=<(D^HI_n9rJ%)efS~o<^DUtaQa_w2s!XX4P|n8WbrqvS`DmNK zAYR3D?p8m%g)0bf(*!vZ;&Hs1^DYPiNoj>tRPk#tUG2r5b~U256HbL%dD8nNn` z>J<7-nQdoeEA4uyp4W15(*A9P*-(!my)!U&H-2B%f9ANg^Rkzq#Pk{l8QhV+9B(Mp z?q3StZ$dJ0oox-x$Y%OI^vG z(qQOC?DwPK84<*X|H{wkEo|Rfvs0NrpX^=XRQJqDylWe}707&fNx2kw@baJ6ZbOmZ zYl8l|Xct5_$Me41OR$BbY8smy=x3!iP^h~mE56^_(U-R>Z4`%HOxy^^KilquBHJpu zRi!Wgv`u_C()mHOP*|b8rC)~V+M16lho=;K6LI1FzMAmkW%C&EZzs%b=kuKwF4pll zOUcCOQxS9Hhat?Kt-`M zGPzymXWMn(^UGG2A4k&c_0FHaN`Ek5G%8I5yjW+{Rf`0P-iLK5I>>2W4cw6IO@7Tz z-lEM66%9Pz)NMmD`$y?IV7|Ql-_c~6f8(}sUJ+_RPoh%`7%xt4PYy}ju}OyOhD8_c z`PmPNg=H<|-LJV=Xsz?ViB2>$0+*uKbXzzW<9pBGmIF{8$I zIV~u>M7+G4frhRs{T+7VZq}s#N7Xq6#uWx{zirZ>QJXYYW82u+Y-4Y1t8p6Jwry>k zG`4MXV>{pW@9*~9oQwCJGjpDqd432TK6kUq=AI@QXfI6P+q*W|gret$kJZ&R0r6l+ z;U!S@>+mDo`4-66=EHj(Ue(9Qh%SyBCuaAjR>&J>mi8HB26xTIxFfP=i+wom`D%Y) zdaxM&EU@G)y}%jIxB4J!EA%0f!@;>tcdhNS^CG9ss(-)Mg{%|0o6lF*gC6cN8n&_I zxefjn~XzVnp^C`hyg5v5%QQk@Y0_nt% z50mMk5NtK?F0g55WWfe-AC$Llk%Eb+1<*8zH@L3JwLe|4Lz09;-TAoxeOs2JdS}p$ z&#nJu*2qd#C$&xcTW#CT3(M8pip`*ARXe3k=Ur{v^S;H^Rh|5ZW)-AE(*D>|>HdDY zU^p6dJ|uqLK}DE+RI#8Fd%xkT-5>F)l$xgfmDzcdp2fd(6QNx&e@0z0#e&2S_5=&2 zzg+w)N+zkrLvYHDtA(bK5)>MXLd{oo4^nT2J`{(CbYDHY33wPZ7j0XiVh~|6QhB7A5rMnLNyN{ zAmVGYPCm}hBj{C{DfWBzRnJo6Y{Lm|QP4n&H1_Lo&-0+M^Iyr6J2Lmj^(U>0-dy?{ z4Mw{B(4$KZDQJt{UO?k7%^Q7|eK`JT`JQS=Y<^e!sr|Of-=Mb^-B>9HEyKVZ2~rk6 zWetSem&QHDhxD0OQraZSm+Kp(&JpI6f1MhAxeo|O_|V(NjFE7rj2*((K@`^6q>?!9 zAsI`zzaGbQPq6C1Dgbw%Wh^;xAhF}CT2K_8nh$Q3ZGRmRk(}|#@Y_QmQHf^)Xt)Q)F#aARc%Dp-63zkb=>#mYb}RZ8)v;TmZ0R+_r3G90yLeq>q|LOd$lMxCh zT<9ZsDbxckNRdUq>`aNbdq5pkP>(EB8j7P@^~5NG}~l*QK%kg@%h;a}o}6@bmZ z{+BxtV`)cR@4>U;FotFk_7x9@MiK3!qop__g;#|}C5^Tk$;{R><9`lPq}U9I)(GA2 zhx{*%ozY$vC{A1jPEjg@Ltq>FZ}-v8PFq_Q=O1Bv_}rd6*yCfX>m?RFIwlOKpEhwO znr;Q@AEI8>*v&GUd0$fh)Q?*wei3KfRjfZ;2#z)+B|rKZaC0^T^m>cS+xugsDq-c4 zE5Tjau9)qiMkuusv|0T9c4vu(pt6yaniL&}bSg7VqI_k!P)mmS$atvVMB3v~EyQ?V zN|e@skbLKg_4e?B*?7f}x~zT4e+*EE3b-|N8@@qr9khz_pn?pB{1Jf`J|NwD345mt zBCrcD;V?KWa+%CbP|6kca(o3j+yzcC~m=Z-ho_N=oxM0d+3Xj!XvRYJ=1f^;K7Ml~_B z)&+LASm7v+rpn3I@5>3y3tVn@UsAxRAN`hW8%Txx$fm7G9L}*z0j>eeb}@-5#yAWy zHy#cXrc<88(LbSHWm><68xSGFbM5ot;!@Y)G$!y6rcpvH#J}qMc4GlJm~j#I~z#hg!!iT8DSJWaq_K zmk#*-@k+pEa5D-l5CIYU?%84dAKyyu=}!Aq#}H#6ZTF07XVor|5jRNwy}0%A;Ys5W#%#q)!dq%ScszcHU81{lvJ<(fJs0M=SE4M&G=P`Uo)z-b`FJsc4v=-kJ#Rh&WD~NKDGoYR~R9WTrvk zZ;+VLv|82{gSZ0&fOB&NyGyDX{JT}faFVi4A}}{mN7YJzmZY-=nuOtDVfp3P#sP9% zXBw>T{wN6We4pgRz9PZC;f{h` z@Ad39%w>Bhfj#GN8wd^m1!nVssQ9Ex?(p&>lyJi#i4}sw^G|%0$Jc_i<`3w$EVFTm z#fJGp=I-}#S??P$_LInT3UQgbIHp1FLKAQ-J5YA?k zKNGYvDG{cQbH+){hG1c4^1Pp$$#^m~=F1sv%EMz&ER$8;K`+cxwk%)phXcgZepDgD zue`rrXsAIVky+s1by);!LiUpcetVm1uu^o^L&ht8Bf`wCIw(WEfkPU?VrC!YCNkSe zbK5Nz7v>g#ZCQ9(RaT&7H!DxMN5ZZ{GnJbU0F2 zdA4F4a4H=!7DAD|OvF&7{W`?pi7e zFXr!`BU9l&a+*SY0+WRddpuvr*7E#cW8AkBS)3yaYxAKJdNud{zo(>jwQ!I|p5gT^TGsXx)>~HrUXG11TmPb_g zbW^6PBUW!0MO-(#f<`eU9Yo-Nqx4%?gV_2Y7=<`1=T+@Hp3NWF4O8UIrWf1_ii#Ov zB$$GRAUp^DvNBC-$oet`1K_^A?fs61*}b2%{kJ|R-HOH6NW^>HbiZz*Vn%=T!0hP{ z>3sOO{boizY;Nif=c!jyMOTj_RU^J7GX;7>3MD5hB(L)X#JFcIahAMpm?f+OEzDTC zmk&-H4F?H_;NexCe*DhPUXzL^?~_BsG`@>cB}Ced8Ai8;6z`Qe=J&I-i>~gy#2~$5 zcJJ+WtxaUwwsVXW&)Wj)5(~Y~H2yoeuDAcxfx(bQNLl=o0gSv84W!AGPOAwTrE8dg zbgih8bXttPB+1N2*cP-%sZrMK(mTJZ*zyG9Gd@b0e2s&o}T&UEtVEbVue_6n zjjrVxkw)t^vIHqf&ou=ua5&+Re+}XCCO#C(>$hybbxPa8Gsk1T({uSs3WDFLC%1Y&D!WDm(GqFSwbD8J3eFK#b&3V0!Ekf_s=!B?aKAoJ4qjNzL5ix@T-#3!=NY z5ahdmX^U(|EwsD@gOluUlWzxS$aX)2?Tm)o#oM$ptUF3W8_!KW%gQS9XsvM<+g?)b zSCY7q=`6;pDm8~5=>n%0=^u0`oA#{&3pMwe_g)fR-<aNnjU7#CjM-6g41zXd|x^V=*Qh$tIQ9xNs(o?5dKL5x<54%UA;#zYT$s;Zb~F z`NlX@S#cv%5Eq`2h7EU65lnU&-dof`8%`)lsVuE?&*HtSD3M&2C@CxsAkw;o=~>j+ z73(H7_S5$orGUZ|_n_0gQcbo`*UbBzwz6UC6#9h(H(q|)JDCvrBAE|Cx6H@gE$#|N zupNU`nmcXe2<+#6G*A((430>!+o%{^vZR0DVEVq*Zsh>QAY_MwGRJZlX4BsmaDY5x z9mP=BX$|1_0se)w(R8Y=y1| zL}J&}AQm6LY{iFgEA~*F59McNZ6?mQ-M+b|&4w?l<@!vZ90hWlrQQV0cHRfly6)>q z(rIqb*H1*VcryS%%UyIKqc6{o)2x>cjk66;_+I7Z*Wj@K-Zo}~fUwbD3W~A*k&Hd1 z3ufS5?{a`r%u|Q<#sA@q=(X`0^vL-w(ZTDU=W#oXVKr4q8~cyn78(1pivi@f0m67- zw$j*oSHWjBjkc`b3Y^XpM?n%1Sv#CEfzS%Lcfapj2$7=3q}eo!J~>`^m(7&A+nupu zH@3aD%Tz>qDYMz%Kvtc)Zyl$9LHZgCoo@}uf&oF5Qv5STq&VF@*3XZ8_d^?`zMY>J zfen_(9pG!txPTOInaH3%5C*1>e#cQQO?pf*(%+*wpqE|$l>O$N?6h#dH2d1g+YFoA z`~{j@lmG+!APA*qYUCq9Y2M?I$gmbH(W%oXz;^a;c<7a6Y2gEx27{Q~u6dsOat#b|)I6R+r6Pqga`{by66o?lSQfEP` z#UeA0)0TsX$2`31Zr&iGxp@%K>g6n$RNH0SSXn+HoL&}+-fU9>q1T(tk3>=$S+&^cE)ClbI0ju&0l z;qUESVyH9Pl+vcZHq&aeN{S(B5#geUM~i4EELFF07^kehJ|I5Y2R1JxpH?F|8<;aT z!nP6S9jbg}ORI`+F8T3?WCIx*qz7+7=KCWyc|WN3Fp`{JukI?>TZh8^%stqDO!mV9 zpO;)^F_4@B-ywT6lWn0suX|T@(24^{jC(>+H6NZnXz|u*1l$C)D6bJTfR4BuL#roEbel z`~?XlSj7Ris@`VX!TWw=aFu28Mn3|^A;rG}Y+@O6n97sl#5s&}4Il~5T@oxL_NMLm z904WpDC!VSSzP=r^}Q0mdalWKUeKyPb)!Mb-T)ng+K{Hl)wzZR6V>I5{-Atg668+l ze{x)XVH3aKSIF36MMpCWpYDY$1rF%#?CFp7csdue*NaP1tFhi;850D`Gpq<{c#fuV z$m@9Sp}THh4(z=>pT+T`Q zuM7+i#Zi8NiJmyU8%tG^jo0;|tLqINN}hAOKdcKBH%zuVUOa^JzOdbpdEJN`Tt{5kg4%Nvb~|Akz*){A637QCZ<~7@4EQS`6dE zTKI8FLg_wAhw|bB;5d_t;#X10EZ;@HpUo`#+?5+51g-N~Yz$^mwRiVmIgRPDCV9PX z`?3i+Bmu(qA!$1NNx$e5gOUT!$kWS^pUg`5Jb*W}>iPkXgq+sow(G6|G4oeR;f@f!eVqbpe^8)wrr!tr;{9^fA?<>&gpx*PZV5{CNPX?=!2AM5`p2QPCDq zE;OU^#R+ra{PDHQ(VOge(5fypf^IHWR|kAsps7|JVUv}W-fhr$t&?k>sx%UjumL@oE8m z?(_f{+KB}1a>nYaY3OPJtY-Ie8t|xv;dj9ajA8p;`e*2R zH(&f*2E@8S6cbCGVr|b}}QJQ&{Is#ykh{ z+O@@c#_$CFAm&4(k}D3zH1+6vNr-J;#mJ{1tBGVQ)S>**Ouk=dEqhX2uMY;hjhzqt z&DZ;2qZgAbskVY&(!?LA@FLB0$29x`ho5jQ$z#+4N&wzt+b4VD9LNOC*3EfODk>v- z7Qfdf7#E!?8X#KH2HX+)ZSBh~=IXR6!_4YU1ae1-&TlA~jej@zTZJCtUkFG%7degZ zku51Vvb!h4X?{(4W`h4d-LqIMLm#ra;y|S_Gnv-qBP>3Q;W=;5m0@Bli^ApB+doaG zv1QL4<-NF^ii91~pIf_xu`*agkwNYK1V*=?!@nP#=Q*V_8#*@7d_J7l?ja8u!3GGY zU-ZoE6}A#4cyBmYo%~*8g4lndX#TB<8mcL9AG9b8=WECC{93W3fhn~u$W9PwLKahx z63o~uP3o(s$GD2%)&`&EI3Ldux3qdkzxC-0vl##fdb)QN1 zEwS;Pk+b<#HS+Ul;MZU@CzL8-oM```vl_JkKH5gXkBdnuIb$Eydi^Iq$#^Zz==uoo zu%V#rkEw1f7h5v6rQLu7{t`le`|;-oafnRAXmVD(E5fl%hgqC@j1Z6Qmo6oPiINIJ zkF|pDRbN1#rRb6rqQeaApH(DCCP)#Ed)j0?wTUKkoy}XV`VNe5BVjAd*J@)AmNEwJ zgpfWTEDJ9$?CB&WP%UNt*>od4&Gqyq5kLlTuno*i&&JMwNRnCBGAOCPDgH7N+@(BS zq#95GwPMzKa)-gJy%{2(MpbS$vJqx4tlAv*Z6ggQEx);0G$^9(qab@RtPc%_?>Q>B zmJ+Yt2vPQD;h~(O)Oa(B!Y`{VGOc#rC6%oA{fxeE%(0C3-w}xl^hAk778jqtg9H)2 z;stN=uWm4_@9Oc?@rAgf_IeD8;Ztkvq7%V|ax^j<8D~`PKv$UZou`(d2`ss&C*2laBoaaMT8J<$=vI1ad zgJD$rU6RAQV+h{uE8&sGv%o5V&UwPjAYtv_7^UGwv|jD?Vf$XW!y5!S=jwZNvLuaQ zcI0b{o`1=>RH)#hYjuX=VvEo23I`J8PUwZQT>EQlHD}ZcActOB3|e#fOE9fh%v`u# zPZj3&4bMO5BH7U;QDpdpgoLRsZ$A-3vM@EDm_@l%$f=O8Emsd-+@k)@MS9g^AlkoB z4rzMGvH66)mE42u#RhnklnHPRO<(4}_;kH*Q~D02bxEJ5=VK0dgk{ z0^lz)aHfNw4dWG*f;Q-j0ajExgqF(gAe%4{3c7g#DD$Nz@9c$7szI0o;bNo!GuocX80Z8Lq7sd5)~zsi2L@ zBWOwCX+ow+d~x`MZ*1N)UQ+!Ky;8Fgr(K1Hn&!4elu zl|Y1r8Y+upQP=A#xJX2&Lt1gLvsv{yQu=j%GmvfM$_T;egyMWKAt{rhllN8R@m1Yq z7!8G=lBGyKCb5vb?(>;!aeJ}8aL^six*o+LP?=<)qSdVE7Aq(RyOTrTU?~}}G08C) zTSVYUbzE#KTJV1?!Yo2x%i#Xw>T0xo5GHMK!x1VoTXbs$dpw0>E2stqt1Z}D|>@*lB(g%M>!CqElDTk0HywE zRBLR8grkx|QP4TgO#@`*UR{A|WhQ`cFiMmy;s+KUAGtT}qXDzo{nr&(s!c8PzkmGl z8K5WwU|-uU$_m^Ylj})iH9AT^84=g!QqjncNtUo4u;DcH=r7@?I;S>o$h$AKg93j9 zINLqf2|`(KNEjF=(U!Bs5tNO5%A#LfzjW<;)X@aDZFbm`)yQ7%K05v=!+TFfpOFm% z)9uga1x`0WqZ06-W=BeEu@E{ff$I+p~1oWc#%IeCH zB>?M!qfCH12Cqo&T+nsXM8|Ur*%NnhxQJoWM~e{@aVsi!6daf>&V|&l~d&B1RZM#}7=v(2q%r&A&ufuY~E;MQ<-0 zs3A-1u8tOp#jc`$yic3$S5MLtL(`&RH;aKtgj9L=d?M!VISWwfupC;_$ZmNdBe8pC zDe4>wg^ee4akxyUWHYJvi6vvthgbRi0K=CnZNu&>Z6l4Dj>6S9<5xcBx%?vbGnzP+ z6QVfP6YHx{XIb~uwsymoB`;$S!j!4nC>bVjVXDzA&zdDig&9i9I;+Nhqa|$}hM3{q zr1m@w=CxAviDM1t%$`g7<7mNB?i8oAmqDzHS3R?bX7t;4z zE*EZhJ7e7(nAJZns|=S&NckEb$BZ_t3rAhC^u0?HUU=VhGvaKco?-G2=o6I+hT+yi z5>1fDiq1&VwQETW`Az1lk|>UhIb02PgW#k7{m9sqSdu@N9 zl{g7vE@9zl!5kKue_7;9R;)`J)b{|I8OV?3XqBjvAGml4-h$L>E0vHE7CCr?uHP2O z029VSCt>Hw*g28vjqRmk%A#EJ@CYDll5imVajrqgUKVdL`boO zsM>pX(M>&sg#vCMAl#rZh7K(LmkYoBr7Afe0YswNY+*Ah`nDT4JjaKrV>_eMWwzt7 zTy04nkunR?_Ae;wufKV(2l=BV6zB+|uRngrz#w5@2zQ`w!h6PZp_G!6x?Eqe*_;Q{ z_jK1bFT?0rNcxlQDk?@waEAYk)|~yB_!9R?rE8eY|MAB3+q6A1@M9v=iu4klo&s^i zLDQ{lFo8a_Td3r(9frN5fS?r#J02|Sxo-Auq9eg<)GYx8fJ3jMq>@U|SCri$&MUhm zU{w!+`)OEiF7d2Lo(6-8V!-t{?`M`mk1*24(dk4Pe&u4xLgyfA+5O~uhH>)Jh50gX}5SH)roArkAGe(;W%z4`K2(O0x9vb-zKUJ1-r;c zO^yn-ODc1kac4Q=nW4PEwEo8brI`|?$9 zxIoC_PSlP-uEslF)DhQOKkO=_PCl>X+?OnLzxmt*8dX8Pvk5}st`rWL zRCcC|vDES=XT^?kE&y#;dS!fmQik(uyHQ2*d*N~aHqSWCO%+NQy{1;zq}go`9X_ym z(;iI{@SB~6dp@##c~O7qZC7(S-)M`^D{x#ivO#Qll4IEWkBIpfA?&2%ABrjlz1)OX zm3aO|k$1cZai}W`e}4-bf`I(jNXV}Sjo1XAX13x2kxrx!A%xU&qxjD_xiM&Pe--#T z9A?x6CVaopk9>LY2*+dlvSL{mLA`_*xxdNr_YtzS!#1HM{vtyt4mU?>rRux!c8P<> zc1GGPzLU(p2itaeEX{dZe*JT~gQT>KrpEeIgV*C6-{q|Y_G=V{XfU)>Ms#<~Kvn?D zMC*rB9_L9ZP?>JS0SepSe$u=nf!z>*kD&O^QD{b}m=&EN2~W&0SnW<}@OCDZ|@g|ynd&tA*^ zje+SlsA~2@(CH%RM0HZb&hvKIMexg^YaVxFzU`#7r`-+T+Ely4*GJb?7{ub@p`HVN zrR|w>m66r^?murmlV#^$Z_fBX^_@y7Pfau{x>6Zz8m&|Y?3#79<@eo9$VV40bFk@9LhHmLJ^K z4K4AvtBMR5r&whZY>+m?KSojkwY3At5Ds*QUd)mKzsaSplXTO*!QY(Vh)F~o_^Q=1 zN1D9XePHOQgOglKjbs!35HR_HLZAl=2h?k5#stIJ5c8OD?ejASZ>c(6eoi8o2oG^H zu#-Q$qH*JMj6|k2_P~8!VdU*{rIib=)-S?B^5ozZCnE)z6p4+x;>#pvoIS&1iDew{M~D)@%c zw|@-6XF;BuV@tj`P2zlPGO#;7D%wiwY=+xvTJfs=XUPJ%<}kSQPl)(Q(@+hDM6(ROw3uY&W9%ee zNNT<6fTpIB9%1%2SFw?=d9)%Om0Ra#=Lg>$AuYSpibab~sIT&*KNZoG{gMrd0};jn zP>LPzQjLWQlqxH%)fp#MdHpgzq32rF_NcHY%eWMHtGMkgf#HLOU(lyKJlL9Xfbv>? z+p%YdOYYTy1fD^8p3ib{0ltnGd8bR+sO?QaNSAMk%>2I1%tbM}kc#=$2#4EdVvpJe z$rcXi)Yeg-rQvziDQ@rUa5zA&9%NSmjyt8$o@ba5_k0BV;Y+tzogWgaI%CJuR2A52 z-96=gM2?VHbaawM#~8~B2)HiPze`s?RH;Se370D|p#aJBq!g5)y6oSIx?JMpa7qIb zh>J%(@;@1e@d%uaX%N`9eUk_v1!#W`CyLmoF#CfhD)D4D!%xt~&U03nY2#wO)?&{^ zZo9qZZm{*@Iz3ShN^u3|cj!Qy&&Tl%-1fvzCWwTo%XAzig}4^oLO;h-?F>k;)hsh+ zL577)%16z-xfEw)psrcYe=BZzNYF6X-Fzaw-YgrZ>w&PRrR_ceHXWT|IFbLmRQPv| zm=_Py{?CJpsitoBKO)p-yq%LQ!ptFaG^*PPCWL)xQM|!wvPey2N>v@Nw%a8Kn@N~2 z@M+=8sB3OFeHbez;TgYI(8vnNHZgu$%$HBqs@Tb3A^7fd!26T=&t6Bu3j$XQtr%g1 zXtNmiX5D2^v-dtJ$c@*~f(K1m`Gb>7itG|Em9~7oD)GPtSBCd|Bg=tj9t#XvW!TJXY##!j_t;EC5>tl0>oDX`scpIX{d zJ+bc85O>2c&t4MBLBf8FX~VDoym4PR#H-|}zKRaFZin>9UdT;L*2mtn_OwBic_Bq> z$6nUHtWkuxV5MbB8UbnH>dKdr7Lf!MUXs`Uh1WngZ-wj8y@1)Jotem_d@9KNk1D z$?ac0dq)|Ed|Cb{-{JhNYP!XRDDtBf5u{OKoH1=4%6FBTtvK&)F9dBDCvnB4l}cf; ze6O(E(If*~{VQjE8)qILlC+)BKudZQyL+NvD@wW_s`v(4*vbU?Q7yab4VI^|&__#6 z?|g@DKP7CXIG#G7Dydr!U!-SZKC))l_y7@0qKhmOe?ZpFlX8{vHI-SBK833yVi-KC zm5U+SESgYX3U@K0Uiyy*2-(q6PNId8vngY${ObGNQoAWCoAG^{xV4Zx(3F*msM5;L zgnk}AD0|&{TapWt1x8j7vL`zsrl;=xtiH(NjOR@I<|52mAY-70eS6Ey(>d?)WGV$b zdH$7!h%oUaZCHex%d`ZRzH^UT(-5w(*l2q*8Y%HxPj8l<%@kJ*?Eif!f;z`$*UYgi zmCzCbjij-guQfZA-|J@&yzJ1+L_fuEw}#)(2UO&*Ts~DYGn4IN2s$}6?3WNlmg|WI zh?)x|Z6_-F;(#Qo!GZ9-cr14Cti-X1PZ98gsd)pA_;vjcJFN8O+Wo^joTF;Bka}NS zIjx0@^tq+hAsT>*q__UQ?8F9i-~OKygB)VdFI|k$uYY0<-_am&8#Ru@ElE29maA(e6~rJ7Z#hbG$Kwd{FkuM`f-1o&i)4mJ`vGJ zZYohOb}X6DDzDFcL-aI{nK_YMZgw+ectjj0G%MMdxHxB%!lI!B6fSc8iC^|5M?De{ z^FIam=?9A%m@(k^=>By%`HBrPAq524D~Yn_kr(Mq8|?xhpg$Yy^JUM_68?Jdsx)?W#g=?jb6{Ou2ZS=Bwx!++HMWEKS4Qy7j46SU9A}bM2e*n9gWP%MA9G4@J=ZN;|3Vx>>mCbJ=B{&2+1T zS1IHlEUW5luD*I*ytALLSgZb@r2OxI#Br`?Xa6_c@EQiOavmffzt<{}7CC~8P3y&w zehM9}epjK@^erN2L;L-{W9;#Ki&&Y93x}(|T+!uJTa4T$o@(X&7he84u#1cuToVvM}wRuC@Q`w&a8xn-Heu zIXI`|>G^{jlWV_+|L*DdxvEUdK`Qy2V}H}BJTr}y08x~bK!i3^h&59{*-7S%45wk} zRonoNDxOJG4@pOQzt|3A5+obhwObP?xeStZbqXi5b6eeVQ_|M} z|B2#V*r}?cg?f_31{#WICwnj-Pw{wny^hK-h~z5et+e9yF3iMFN^wwJ22JR$vnx)= z*Z7#By;vaCn57j}(G~}VBSJ;7pZ#y_L84L5_W$P67^pJKTN+b9LOD+JwW1=Kb!+W7GbvQS0~T zj<**mC8hZvnc=3vWIg8oaW@^6zhZwGTqmz#9t9VD9p}rlMdTx6Dp-uCi%T4`W2XKb zj=J2dI6FJ@K|I2?&CQ2V!6$k?=PGlB@6vzCjk-XLGenJfEs<+lO`HVA#*5|4X-o2U z;R48yYkvih>yZ ziqX>Q9$jHMA&arMPT{E~j@vo@|EX(iU*7w$H~;A){~4y@P-+2|%ao!!0!~h3I^LIN zTCW4wcBgxo+cmInKHa(1Mbm7hy7TId#$<)EnSVHd?gaPic7V$FYqF->mXXV21bMyX z{PUmc>XH86mBjS-QslQ1A%V=Zw!UU%c+(mF{kxiv5EH9zh1&}@`{yS>+b zrs!Iay%fP?o1!eW$TgoFa8K2w{R}1P?@Q$`e8+9VqY&bh(qrJfg6il_88@rpb~9X4 zIIjrr-_Q4LtviBI=jYGtOAUi)&SwkoWrB%vYf2BHj*8eH7?7 z!Mf|PuBQ6fg4mZ7UOKw2?-x};Da}K-gCjtC#d-d$lqNhX9bZqI(^bYgo;eN6CJQBO{a0g*wVrRS8InR9K_?RfXih?#K2#Wcfwd zHM2!~K!^pG0Bt%0D=iK+UXB5vCkgv4LToM!<{2$a8atsYRj+OiX@~k}YxXp&q~4wB z4wtUC>67p;yCX4KS%pZkAApOW>=Ec+uDS12j&nOJ-M*iC4d!&P1#xeXuevwarc+JCGJReTXeQhfWc0|}lVtF#(oyPmtNodV z44f2aU=VheDom0}P*~<~1rKs1t+@UtnjmNN@b1s@*Y1A;ED~mrazXZjCdxH3kiy(! zTQOddj>e=-iahEk7e3;U#bjy8p7OB&CwPBBgLG)$aB0RBwiE?3B0hC9`#tzk_DmX5 zQ~zO0nu);CF3fK-?=R}5)J2$h@YHed3WB6@3KIK7{0umSJro@K&#^bQOB9iesC^x@ul!)3|2FSN9b*cjb_1ENJy5}r!+O0An!6? zt8sOiE_;D{1na1L$ZNTf#gqA0qQOvpl5wNVnBzHX7DFrvthIZBgzZQZWoc>IZ1R|; zcwhUCTK!#mGG_tPAeVeKov>oN;Sc>b*Ewq?9ocgk_G{C5aS}e9(WB#7C~q)!_=!xJ zOzD(1e)5n#HrErMbhSeqe$qQmu<>h_?TIjFIoKYM=A+9&OJ? zU*X%=n| z#dM?q7-4ninK4G0tLGcs;BMcqSH8dC?fm_2#7OcRy1YI&{CZmUT6&Rz&*T`ka?8$1 zN+l(h_<<4q`b` z%s=C7P4Xar`o;#GOA9l6m0E(fzzjL;h}blyvBrTP0Du44KR&OBX00E43kdDjzDPfj zbek^zb=`DUi_m#r=QXc(I3D|0{kZ z$t4jb31neBMIminb1NyLi(Nw=8lOo`N5JK+_XO(Va)Ial<}Y*X)%=9&sdNTn85YVC zaEqoQR#_#faFg6eHs=)8y27NiTKn?yvC5gGS|l*u==%(qdPzyQnUs{3hhFi-NuxA> zr96-EV}>%6WZLc$9B}7?5w46pnKWn2Y+l#uufDgY+P>-m>c~^r!U|rjQXiStvg@D3 z`dHEtyw_UtHwN5F);j3Sz-(Fz|EJhQ9(e!#iR%6)+iK8DLi9fc&7Lh&+0_Fiagw&D zVH%gqjrV?t&BSDfr@LkIoC@blFv(=24Y0~TkM9s(|K;Jb=`c5p(QKNOVPVzzWA8U1 zq|h%2wzKdi`p+58Y=M+Y`ZEtAUjlsflxG8lSP^qRWn4xF4u?unp)%^&-tZyoLUQBf z#K74=Z9!Ox5IfS4kCdfDQJQ-iRYmT7%X#>Ijqy+P?Hie%rlGuPwJ+6Uj%;G#G6_Nc zh7{jqhNgniM_t3%iQY|>gm*H&UwuUkvOA4v)DO~j7S++|$dvDmQ){sQ?De~=iqYyy zgcOx2WzxJvW(R9{>RaI!uUVW<&r1SaUPCxs{!V#P{HUMvX~YcjxnBpMTOvO;cmP#R z6}_u*CilVm7)ObWJ2%_$YoJXnRUjh14>CUY;hhq-^zu~@tBm_E7P-5w8}ZA83WxFS zq=DUi?)Ah?NkF8LN~!{gC1JxcRO-D z@X_Rx*?nvIV4#@zY-?wd0u?w>SP}ELA}SSitoEmA#Z?r!N?oJ&-6)h3)d9&}Bw$p< zagfpehIIar9Io2Dx7D-cU`vXC&+P6~3>W5?fXe~tcYm}feu501-*@)^U-iYgiDO_yb`sKsL@8Q{u(O7z!YA0%%_`^Re(&a>Fpn2%C6Mv>I__ z72hKqhxRMQXcmWN=wm0x>>IM)-0aGJ{)<2u4%T2QI;*JhjMi-Fq;X1W z>O{Nz{3xdQDw=^@(XblhF>@sqr9V3Q;ok{LAR2tU^2{gaE{jP}nU2G!&u{_6O>g@v zH9eKBW?XCnv9218&TRj#F_RN2l5Lw+S?rv`2HbVjaMg=(y12Dq0zHXqVdABE-N7Be zu0O_;u^!lwE;Y>S@SMr(!2<}a@=^;+HFOsVeb$@#Mp83$5yK6eZZZtAdfdTC0~yHd zyju^r*;jL^_;$)!mF#Od6Vwd9op>#JZ1bBOi0_aK@0eLGop=x~U8O2eV8-|0EK|gF zEy%Qdo8Bod(tdwD;d`FR=ffuM<4LtEw5Vw!J+3m5xc3npp2m$RtOL6~nmzhSDmr`cK&&d?i*e>fm(=mKlxOF=a)xU!P{y!Z!^@WH}{V^ZYCYpRsHPc zO!%MdUpa<81g-oVJns}XkmZK#|Kox|PD4cKAfEv@cwi`UG z5@Kn^aEFY`Hj|QXk?E3{61kjJF!;-4Qw@rI+`nmsB<(uNJq1Pbn99|Z1IR|os`X`2 z!KEa@6g>)K66_Ur_)^sru@>Q&uBqBN%@OQ-w=^?(%hiZAeaB@x6OHF_{2B4LtTEJ# zfnquY6Fg9O;?kQ9Jrn5H`{Q#HA0qc-va+HoKQh*vT{iB@b7ND&p;J+^Z?u6c_te1N+S|IZrq!a5ep~HmCxo^#o zuoVr3a-$!aC~!`SsqMk!yl5xRaBwihpXG%k&wm@AG(46QgdeCV&od@%g{MTZt%g=1 zC_9Z69RMX5FLK3dY5D@g3E>aFFXt23DnNQnz))%W&W}Na4!$@I`S}|;jE#m;604Le zvy@t61iN$xE4( zjNSvZvg*=W{Lq#ABrdE-y)?_v>DW6r8?+8W5S@E{{&RK}Uz?Yy5|HKLx$t3Ffktt4xE&wyb%RV)CaTuq`<8px;?I#3Z{M6TJ$o!r)dr6w~~w^!UVNd z$-l!XbzC5jfVoHXA)upEw&CA%Viqy#qN6yY^6B+~0-Z!6^^cZn<(Uj8v^3}ZIBy1JSy zQzw#uI(4?v>YQ{^% zRrE7Y+3BPMa=ZN$Tu?t}I#PEXZR~aX%_ao@v3|3FSC9c?c&VkZPrvdZX!64WiucnF z49DNCr$%xWzhM`dCnMv|pKl%YQQv={*02A;!=>SPKec(d@I!(0SjlWNnoq7qn2b-< z7+{+qHoJCP0hn%7ka${l9-(X8Z0vlkNcvwXa~{^@|1tFz0d0V7+HMt!yIUy*io09! z;_eWgF7eR%s(?{(FL2bf$+SyT|U$5ZfL(PHw%{j>yjBs zeZc4g-})pvl%WM@+$Z4;!~TTKWmf35Zuth2UMdR-4Gj(1bw2EK9cuhDd%H|r0KdJo z&jbY{_B8L7vUr_Jk5p;~Uvdku%}_Goi=5|RBGVuG80M${CA(}BtRtU$7p$Wwm%-0d zo;MryP|V$x0iTA%#6fDeHTVg4BsF+f29E+C@td}a|8tw?_0ck!UW?0gs z-lGUgZ7lJp$n?p=^>;hFk{1t>WE*{uS5i|)vwXE4RdlRe#kr!w3r>XGcU*m3or4~*4fN^+h7#VX z6fpI2t;_e_tt*JAsWsQdK}8I;O9-$c{{k!ylbD<`NdcVaPar55)(eO>Lg+j<^2=1dW zy(Y%L#8}KEUZ#Mq7;k(*PZeaM1{&$*`CA|3RDIV0JApB~8J^vd5+Q#2{o!2Nju=%F%*f&?p|gHEIeC zec=8VK(h8WdRdzlL4Z4FRmYl8ao!3=d=i%#71c8{>9KmeVe01Wf~6Z~e(!s+uJ@|y zA8oyAkkKH_L`aE)UPU?O&sjEf`9L3b`R)c?IPOq0pWF;Pw~V{2fU1=)uGNPh4Qt*S z^|sZX^4|3)CE)xDA28XZF8acniL_m$!vV^%?GU-vDEHYO&Zci_DDV@;e~|Fnoo zJ7+lPc5HVE>7$*K!Ca1$G!S&JFqvv83$tr_%l%zmPF(N%R}Wp6!+gL{wIDJn>!-#Q zP-$OtuO-C$MNy9dsld4X2R;4F13e?-t;7F3-B2ZE?1iHL`}tihoXocE#k6N`KE1RBfk1tN=Gs$iGv*qq_UYp~}tY(Re-4wq1 ziG9rp;)fvsQ2I#fxgwXq+%Ah{aNVtPlJgg?=84bm#fuL^diKA@{16p3AV;ivm%ZSG zZA{1;NM&SjC}zdxMvl5zFVIKQ{4tW-6O2sEuDSGO*aJr?(BpK?L^+KRbZ;0y>T`d5 z-IXKKlcPk_3)Mv9EfdWbhzMexQ3lCW9iH%LBvA&=#r3lo13s&lMV4}rWo>^3kdYAB zDrlwSymS#6VR)>BXq+;11R>MOkOZ#=9sSikj~=Z)H|)kd$~pD$`dVhoU+#9ljbhMm z2raA`f9Q|4Szlfn%|IM{RMf?nkh0elSjR^YF4Io^H&R0jQ%G;pB&b0mQG_?F4zg;$ zZQ5d88Z`Z_fx4(|;F#h7P{`DiW+)E!&M~KIgMj#D^QszVTVr@5gY?#|P3uV;g*-P% zpV)Qc%Sp2-cB)fmAY<>aQWEvCZwPX*`B!S|!6u7fEQBk3$<_hdYoHK}aj6wfaeEY` z617YMPu7%3J6#W%as?Wg^Lr+<9GLIuo&p2x!Amj4#)cel9b~TtEDmzN`gii@JPt{g zWAbNl9`B%=hgcVjQxBS&%@u%cqMDilL@ag2PRO2YUu-Q^iD9Yn_9hJc2|IXhOkv;` z0J7Ujb$=REj!sEUE&u-~s~f-A|Ib&P_&|;E{vlJgwz%$UdseFj<`?m|@#tp9{ViA@ z`&Jo_7KN$(*#TB-h2&)UEdMph${rJNonIX)W1uP34C^<0^@&P|%l@|3l$c><-X==9 zz0Kx5u^p7x(3NO{-B~R50XSdQ!=>-(XWQ|NjnxPCWfFQqpN)?%>D%R~x7}ia>2|EkBIy}xpu_Bj9J#1s6exh{W{}Ptlc;d>ifN8 z&FOuL+2)PErn)W6}GSSkp<~n~`9MH;L35kB*Rsd~%KO?$e`6VOd`7 zlXh!Br#{sazv)idcHrZH4Ogqx?L%KtW!tU%nEipFc77fvCRc`0&gAzw)$c48eT1G| zrp>zN4P?K)zGBlgCX>FHP|8V^%c{q`0eVwX2qUHs;+Fd-(Sv<;ObJHlQ*gR%_)Nua z&sK@xNvrVsNE%37NMrx`pvF!za=aJ!br1PeI&<(B=sS1US2FdT?gv7JP~pK|^Ef=7H^EC5@(~Ja@Yg7GA8sf36*Gi!=6GG`Y89g5$sN zxhh%Gwv#J-pZ9;aKKMlC|EblHoMshQ-rM&CRr>%B_v%bCCdjq2cD3cAMPWL#<;;(8 z5p<8jo?yxBm^t@R`N1XguCAX^bl;}^{Eo&*gUTX;q`65{b zx6t3XxzIm*(rKaAr8|+-MJ5`vt#f~ldi#vQ+(xPz}@4J52?JMpmMW28SLQfDs0>9AwbCF}`E6w?*Gk;Up>- z@IQ@LqqD&_Fu*a<0_zQOj_i&sU?~p47nje!$1DHVkO!FlBvugFi-QxorWG;%YW=U3 zy5>Bh&%mOb+^gCiZ*+#GG-@aU;v^sg$jiI6pkw}BXAk=IPC3P$T@i~8-^&^~A6Tt}!do{`s=Urz2W zyvxfk05l3iaVIYC_BiiY&a)OKk?Z!Be}g?mnVpYRBlzYrRpfcZ=YAJb{jXoC{qb(_ zzYptvIP&C>T&vrC*nQFAbin>Ej7J*_6tZYvnBF!sjzsA0c?s0HxhG*_KPH$`OwE zX3ce&x~Q*C4EeztJzqw@6kw)E+XcY_PR4hu4ZR(Fcij^eSF`?dKkAhcdsQE-aWhFeSY*k6;k8t)WE|0-Y&5^|P0oKxvk zRNO83AS7mslcAjk$2|x9OoXghEDz!I1FzKqlacu-IG6S7O5pB~g4NviYx6bRSjk_I zz7mE};1)(>HQrQP%NXiRGG!6ut=Cfhi;-hWCt4=0L^J+1A)7L>e!{YA8D@I)YiN=T z%ma1@6NS%4Q?k2yE_&72dtA#5+eGcNvlq+FabmKvh^8-TIZD-KzCxddi+;xL(M2d- zej|^TVPcn}*Gd0ZxL(o26+55Bo3b4pal4)ri9eFIK-DG+N2A|5p4^farWmr8<7fG^ z-}wir%*;_`^LYe0a-iesqS?7#)su?=OV&1V9n$j;;5cpbzR3%^d)fHY-|ZY>48sl# zDFR&z^MmfE1YkU_Ft=i$q7yD}koUjaTng@!taKKm9y{BgZK`FQE zCjaekiv%{2-`19q)A3ySn7YIp-Nb!CQPF_ROB)Q@!lbCCreoi@_&e2bBTE=CWVdu! zc>Hu=_HeoDwhwu`Q7#|vml?X~F3AU!+-NDQ`6do~i?z+U$d}7#XUmtD5)0r|(mEX) z2EkFQnxrx&)z%enx-drDX`-kgA|c(xl??A{{$;w07Hd8Y|D9~rIiT@kM>v-QmD8-4 zG_qg zlQ!A|ml~VaXe47)X@N^@T3AkQejgKj4B8u1^O6w;h}X|&$8^gqu=X&&Q(J2o|} z6n(qbmcDJ9p$^MuXXl0EQNZA2|0x>t{8Ch@Ffvy!dY0|R??Xw4b$^f=?{*$$s@dX4 z%62q2e7)|CI*qh7FS*z0TgFd0(+_Gm4rQSf zgOPck7ekS6JJ^7c9d3mP>oSfF>bIb3PIZ60eR)w+qy|$f#I_Hwt#+ut%bYXpIN4PS zWQDb~k`paGU`>LFdZ0$Th7O`BY+n51>2l+Iy`iyDl)#+zlLC6GK`TzUE>VK@U_lkA+FNYHp}J}34${vyE*Mt$`k=7#w&8!j4|xsLv4xO4oi*x*k&fZv;2FcF^?Dcg)BGU- zFAkgL8}${Bw--WK6_u-UCdjNZ6MCyc)~0_)y6k+n+O7%r3c61+j=E7M$cVk;nuG(` z6;$f|u~nzPRJQK#8glTga?41x1cr;G4w-`N4N?%VQBV0qZVEFl8=LY-5Rt;1f!{&N zhikQXmy~kl*4$~qjH@jaF^PqwUvsLHXuTd3+SxRxv;l;}6LypVo87^NiPl`5f6q#l zu#>2F>C^<{muN-X&%Q^?GLH?Bi(z4?_FpLyL}XEs3e#hVsjk^1AOwEM*joCLM&mDi zC3b`96#g7y%|+J<@Hh*2eik|X7~x~`si5w8pOfV}%LM0i&_v`ZCrF$&e&S2NLEHl? z=^@dR<-SVr>1et_Y{noK0#yPH8`y$l?cNRp-~mSXJyIHNA9&NgQG*@#N3|C+G=ZpH z&XJYZm&cJWtHJ{J9wk?Tl=Cm#(ae0KF2@MR?q{a)E>7zKaj%!#eVxVf!1(x9$#PNS zn%aE|Ho@4;WG=#uclOO_h2y0$z(xGHQ61I%PcW-1Qf>h z6ITAG=PS3Z;=+r6qG*R^w?uEZTraZL=ar8K3&mLSJg4j{-*?|`Rvc;lGyBOrwh;JV zM%bE;Qh-&do*7oMV?hRY0=E;}SW}Hd(u8mI#Du@d=rV&dahT?d zii3mGB7V%!xZ*dNE9t?33>$bN{ymnKjJiMInjGW??ZvBKdD6<99_POr(RQ%9KWja| zfc@K=lq8#F^?JO9TGo*i!lp6s9RD{@P%ivc?Ws6Cw|?NJcLr8!Qeu)xpcmdBOKFt7O%J7bF$EEco`15ctgD+Dw&3-|@6pfWAr|7I9ZK9h#bb)rJc9&QyCGJ#*RRN! z4h$oG6B6=aB)OV^=)dQU+XGO{RYYvBMjgMFB;HVLzTj$DoDi!>TCOV_`Cc| zSk8>Uy6XF{Le(4@$nW9C*4zKob)j>3a1?DF998=IsImH?m}O~@urGM^>7>=R9WvH_ zzUBd4Dy;++qez~wwcGEny4qqR2JLm}f5-$~4rZ`~_+C97Y)9>1A9UXxjZ7=dgS@>R zUmqTix90pHdtj@+yOz%q#$vnY+i_7s{ozcI&ZAx#Cwj_szU;SyX#D15dGq!1FpU~R z)H5#RkIT*%$_&AM-?#gt`o;0|0tRELOLG!0j=m@ghZpINpW2-TCT=do%BygkmJv+b zL7B#T!Vj_PPGAcwfy0%}IC?ENih);`reV;XZr5B`dBEvl;d6f`i1QJRnEr#m+jcyj z-FW%D0krGkIp+77?St(ShxEP}tskSF$Hqb~+P_!6xE!-d?0{IA{G`Rlz~z<;vQmfP zA~)9XBh4@Ivo-SSc{>9PHccF|h@Tyv>gnQcs=tTic-kzBDRB3xAZAmirkKNcx~Ga6 z_#tE(;XUbh?Ey@XN5oFWcZQ%U48Lsjie{+#Nn1Z)2_7?S&fqjf?f%7fyt__HUj|~n z(942-pvhD9la&e`YN=ZrS&tffDY%xtrv%#sO$IM`Egtbgp zh2ky;JLat+RXr&1&J583%Oi-jWmKm|!gRUXbWiA0fI0s@L2O?C0>4Yh(4HY~tPc+`}Jm+aDRr~6OPG7t~_GpA6Bj#a{3fS7CM1Qhg z+W}NYN-6><*Y#;tii);wUE0jBevBw&*Wv$QkR})Est6Gl=ZoaxlFtLi?bgKqv^kTiC0F!UdJ zEa0yqh1rk%i|&}@UJ4xwMNIpaIhu0$&_p>QI{NvN!1QXA>(0U9YOyeLtANP1?1o@+ ze4*MHnpj$KseHp`za^$iu{$?^k)Iz<$bmSo>zdxzxL}0j3FDLy+9JRtOOi9ln|C-d z&(v^nX5$(N>FK04D)GaZ;FHw~4AlWZJlYIdGtN=c(s8_q_q18EEG=gS&e0>2p15CQ z{%0I><;S^<@x|g~tb$0wz$Uu5&)cphYRwd^gVBaTH%Ivp z^DY0fpe7jSaE6lkc)~nb2f{q6Z*1BPFG|dGyyIt_n~k-6R?O_?Kx2o(H7 zM^lA*Buynhh?&g0gD~n1$g<{U_PGQYUNfh_4gkLtv(Z8iHGmh_NHQ0XV2yznJ+RP1 zFPWM8*5H1^M!SN#A++X40%KH8NsIlquL4BZ|BuRWwTT6GyqeUhnY;T3M?BT-?s4^P z8Vm4f%N&%E)!?I*5G+H0qX9_f?9gflaR9szDOc>5t?!>mTsL6s6qS#kSwXdGlb;==aLCn^Jk zE7bNxP6fU|=y2P_c|K;E-)8b44L7T3LIoyPURchK!-wscd~4*8qN{QDD*B!9rt*u* zNV6#mnMJMT(?qEPIPE4C$-bva#qQpodb25ZT%uoIFKf9h5A$FppRO<6fphF}mXiA= z5hDKPD>}0*=4|@eJB=Sh%|TU6aCXoIUlpEOg?tdra5|cz>Y-qDBHtWAWH3Ht_(>iO zvBjqvK$``iwlu<^*TU(GTSV~W%O_r!)Bb~?qHcIp=76AfZ==mYH7;e;*Y!?4PV#3Z zXNy4G+Q+GkmGuYrn8Y&S?|`89dURF&XUoI;4I&l+p%y$Zo zpY)64@5+5GLyW`iW&diNzg|gf&&KD9sa7-bBsb0h)4by6O-pm{O`aXvo*oeC0T`0s zts1(vm{tU8VQ5ZZTmAWim4y|J#sd06hh5t%Cy}L4>zgcaqkgkD^~17mX0vtq9p%2~ z)7smL8-=wWR8FO+wm>>YYh+(QvXbfgSMRaQBCWA!F2~VfK}ROQcPU4$2=8vxFw$^A z`T8eLB1h641LUm=Br<1JYl_{NmRm@hAY*v4Fk1C6aAuB|67kc4q06uWSRi%7oqy-` zZWd}p4^RoGaa6f~?YDepZvU_@p8&b3fs072H-A7NEVUPqozS zffk~pN+|gR;!n{#noR#XTElFmRxGqr=P z4VxxOd0!(Pu1E2s7PB?)nc&rY)9Z#Y^vK$Evovx2-;9D_f1_<%IauhN|3+8WV`K9E zY}B=l@TQxAh`JoGmrrax2v6oY@w<;}CFpSJxI%_#eS+CPbJM03_BeTn0&l>^yl0;h ztQuc#@m-&xgq3K7CgA5uNjKPRVcEgZ&!5RQ}n5RV0%`ZsJw;QK&v74xWbX7ICmlrGV(8u+^QEs~J|6~~Z6+VFF zyt@#n4UT4t9~CW+%NysOVcWN#AkVu@(C4dh;F8E4MCkQCH^^eTz+$6v>ToO(?H3#> zaR`j-yh4}m3mMa{&Z($5%Y1t-6#NP6Y)N570bJTCJN-p3D z<~ynK2hCJZsIm5^9&1=wg&FHKJLHcgcUNa;O*LE1Q3FcsgOKTaZ1`Lzs-_!An17q_ z)iJR^E;3kJ5t-UrkfClbh|x+Eq0={w%OwI5HpF}!zi&R+C0}5od6}7M*5x8w zU|y5d0^9L6*=$Q#OY%Pp&(C+KjW?Um3|#9c@o={b#%LVqWl>{#EgMYW2bq=;4SnxF zFnB$FVVVv%kDgmoaybOTo(rTXnXe38iXxZh`_ z>vjv2IWZu!wOltG+b*5P=GgRDH(lfN$9Ukpd$V)4M$mYM2L>0JGv?k4^Wg9(%5r*3 z!3~&PHhe3!#PD^yK}kvW`BjHrzd>w#9}nATzWuiMA@P|2(tJM-dmyFHzB754>cxMX z-M>sOL~IA$^Msoy@2hRWYwfO8km@2w>qfiJALWxrChMuLBBr7 z6&E&0mX(z~o>u%CorfuPB)wQ-{^=^=16E;WcaMb(i}4uZh)xsX6(zlpYjY>utWJ>79iX4pA2InOE9&~pq){0*VYhtIJr9Gvw9lGa;vv z;cB<;!JGmgwx-2XEN`y+)V+(}FO*;6;|w^|(mNU+FX(WPvuJg9i;ex*u#48CALHK8 zFvh`l+}WYwon*Gl832AA^+<13_j(x3&$hQhH^F!5=yLGd6F+dLvT1l1$FlVLV5YFY zUTVDOYf&KE@hA1tbM(_WhX)}4gNn;C?;7uPAD-v-;61#WC5X4LX5p-&2&{(;-7Ju%Kxnd9y@uI6PPM# zxt2gzuRq~dA`iExvVd5OqrHD!WzP^gG3ti0bbAckTi)7X8}H7RBxM5QHB;j3 z%IHW~*{J&9*^*y-8YBNW-Y-oA^q2Q%1X*NqJ~z5Qv^}`(bO{wtS{g4)dDmN!YcDI# zDkV0qgN9*y@}5!p-Vdhjcjj)6V_IgL)skdt{w_8i&M?Hmrtj1Fo%Ba|GKUb)pdYu& z^_ysZ@`6yYo0zL}Jivq*iYG4g@wjq3=(w_9zoMzDwcj`0b#a#(Ixt)gY+U#Dh`4H& zklA!hF3bQ)gFi{EC7iQ+-gcL_+^_5wq}oi8xux6p5j>6r33+bu&jhFAfeI}K6WS8M zZ%^w>f*%D=h&?YlkCGiBFSpZX1_9%3fWLQz9e36FX`rKGz{vlmf$MM?-dr|dJ^(`i zT4>oFt|0%WDAH?6aDO5Igz$6@fn*H#!oFV#93S#?JRX@UEWZYsIL*BuCV8^UVKL7W zseCu*foiG*w~CHMxW(R(2&)!X#+$Q?8WRwrLf_*>$s{tWnL1SnI?6E8);7a)Kf!j? z-v9z4Rj4TD+-DzAxqpHe6OQNg*?XW@(0;PgMiPhJc#VoXraIU*LRHa;j;coat#ZV4 zt&Sk91X^f#QslDW-ipe-S#)NpDXLx;x|w=@tTA(UnqE9!p6jw+Od&5=052^Qo)biB zV_7oF#KV9^m9QP(m|*-cltil{fy~e~w#;dZL`1lJQYQz`@%3m?08OA}&*C|&z185r z;Hp#vG^14ydf~UaA#1B`gIntP?9S<=r9eSI*sH4HSempnaf~?6))hRKYFi!H=Lj8k z9G|r|7@$BC2q>*=K@YNS ztGu$w-0ztn7uZ94BQxXQ)T2)%BQyhEKRz1Uy+xYqS0VbE@L*bAi}bb>XOsT;8%$X$ zn#9>k?6_YU$5A-twi{Z29=}_d!^-H66Qkij3oNNJu>ahV(L|^(TcQ-j0}Zf9g;W$i z!&;V#iXxsYym*PmBS}h21xKB7vMA2xJ-E?|ngiAa{DF}0%;hF#o0%6W_uWSz?X>2= zuU}!q2r>)qO3m7VLtu|F(SV6uc$9`FN|gA6>z>?DCr4gtb>BH{#T1m$KxfMc3jy;o zFOLo$FKbI485NVK{Y-nJn!)(}Olojjwu=tXJ2kZV_wnt_t%8D--?1qu95fLAZ?2Mq zs~#?zX4tcxtL>+!Sz!34?6(Yb_qKKS%BiZrJ9EV|k1MUfJK#Hn>*G~Y(Wg(*iAlZ& zCCcr$_!!DspC;~^Qhxlasqam?-=>w#tk;}Nrq!}FDk_Q0&7qAfNs04J_+_XkP7E9} z)@-VSi~ZdX?Jj$VTmI$SX1QaWq|{+|oqsb5!)%Tc=3>XO>M{n2+%=%A$A)hu{Be?PMiCi?{0LLNUj?(pe5tHpy} z4wrJNQ3WnFt!ld~S|U}9;J|5eDYx_RpkUz0FXt|u^Q~f;w@^0$o#maaY48it+w&C% zfR+nr%#ozBc0IlqxyR<%hy230o-pzA)iqH!Cy1+=|GwjO3D{DPp1m&xDjWGM-wN3u7PQEva*UMM+?GFs7klCwtikmfH`V2Pl+o#D3irw$4OD+!j4XB=HQb@ODi zOr18apY6^B!tn=?2EnkLiV=;tR&PR=q>iohPa`4Y-HZw6zso;^zw|Q<{I7g2dHi2Z zlYY2;kMY{~;8DlN!$ROnm;PfLY|@Tt19<74~W1vxx8dZtoeNFWjTRH9o& zLb&*Rr~sbQ$Hfqo-C{~-Y`<2Pn@~~$mq-Q)>py#gCv86GeBPf0mwvb}mOSt5zFUjD zTlZFbbxACh9h&3h_hM3;L{=R`Bb>m~Tb7~i_%QgXu|(?daUkb+YkpOkt>Fkj(LYdT zZV-ee$}SNo5Pv`;_KkdJe{hKkCuXoI4j!}koq9z@XI%2`{aL?doCdraRIb;PpGvqf zTKXGyk#OsTkrl7e-c1v`2+nA2z89@2B(;qT71-QEc3FTtT}GRbmmB;`Iy z!kTC|)AtfOdCUWb_3_vF*E^()hS$?!nC0I5jN(*yhDuu$Je*Dd$MD{~XJvK^ShmUf zAED|*AP98&FAHB|#{#S!>?u0_kHJ@BKUXqp?tZ1&@kR?f zB5DraM$HtQ_m51j{`2#D+;%aYdr_9w`18k@7yhyTyGT$yGY(+~2~ix6>H+7+%EaFy{}z@+HfmStH6b!jZ3VPw;7Uc({y* zeE=%jonaq*_pkHGX|g;|n`He|Uv=g(N?+hHTwK@?-s|G!jPKm7S%@KCi?q?fFyh_f zd10of@-`9H3MtTvV$F#2_klPg5#a{=XB&#D{tORLF)|bXT^b&cfDTxqNLu=a_jGM= zwHsFHUc6UpHOB9GIf4ZHXucZKF{6_*5~|hA$5L^s62bfv0P1wV?tpA(d)V{}WxBnq z?6_uXyF53$xTd(<@NKo}EwjLimi-QeWhbSZ!5bZXHeKzQq-{^?p7&!!MOk;m3Jvl7)M!%_^$dDvVTASd@Y8gwL?9krUe(U`e zcP_ejmCI8@dJH7@Eu1}&KtXJ~QNL`feO&sw_B5f*p52?a0JuNqqAJa|-u;$XHW#z5 z&9>5V9+#cZ%ENUt8U@I`ZHWo=f4kP6b97*`19GlTjpC=FlTIh{4xT0D0nMtbAby>3 zgC%9XvRZ`ec26{fD}fY-J=-fHk#|32zGLk0`s2ghNN4L6A#eVSC_{^r^oL}XQIqTW z8x@O;#8%2rn=z*m z?{K~jy**|!=;F$Rb(5{ibQ`{0{Z{Bt%D7d;qlu}cz zuYYg@A4gjHtaz60>OYUr*)D`^)bpJwDcCdY-te7Cum|6X47Y{WFN!+WVNRN>wu{*y z--DB4AD$LHPZCz!UhzgUE1@X8FgKgo?ZO~JC#siWv#fUP(rBW*V6MD$J=ant+syPh zIyfV_*;GyErvm@2mPQn*K-H|ej)kWeEL~jY%IEYyGIV#fcb)FXo&UTbdO%j$e5-Sp ztlckFf7UPZ@)v?tVRqf*_T$g(B>A-jIt5OpL)l8s0Ei+VOj2fF(>=j&VwmSz_sp%~ zl!(HLeDgYZ>7zB%`S=uOO>36&gzPS#tRynAP*A6*H~y7`kNu1xFMmYGeCcdLFg)^9 z$7W+1JirKg-aD>z2DV1L2VK?7m^GP`VU8yWdgUHAl7S%EU9bCJz|K!E0ZTgElj2~< zl|eFxgY1%ko2yw3{oR$Vs$%*I%LV4++I@gn$)BL&n@(#^LL>Y5n;+A>nx9)p`O7I2 z$<+#nH4_+9f;BQcFwxe$kVu=3f3J8vMYugqdN7;qVXJ5$mP#fXe38M8H+)Sy44JpH zzSt=+{?N|25K!TKjf^1@jCwlJp@+HoRX`1FaKF^MDC=u@5q*1QL z+MdY)rfFyt&z+eT*>|>GKJIEZEJ4Br@?Zb{oR@$2F_5d2I+)8(xM!cryQkKR zSZ!zDyz(ZF&u*e(Rei&F-+Sv}IBabavFPF&j^E7FGISRmc^amaM3!(9sv{q$s72Df zRF9+Ck%Kv`(QCSzgZFhBZoVGB-ELAFUdo9+B1=KRIKb-Fo%x&B0Mn12f8?UGr3&oY z5m0@vpm}|7T%ZQSmEQJm%4%PL&2QP%5Nfgxw62&Y@ptduuBF6;Rb>+K(a6Mmd+}L7 zY%e;NI-6B&toV0@+I=xck8cucWq{meg>tl&8v7{^GWX(^{}ivL;WD;}e}}0sB6}L~F*qpAMsS+`%xbo6wf=S-0wHY^86$tX4(Lo+5aI5*CyV%B%_`m&0$>}cx!S~mWNRo6h zFWBKt#V*`&WZw7hjr+nUgTKH6E&Z@NG7RQA&GV(E4l_Y?8|}6-=3}YkE*;oT8kTJy zfBIFppSK({GT}WUeSg(HC@HPzGELOm+vOY?q|PkMFfwnugk=Xo%?$f~NR0nrgvbJW z8w&{)~_kO`56&0Uv$qFxiRE3GYGc=y%`XD7Z7j=+d5y0rKFw9f4o{`RM z@-wlvkSxu-(D>8Y8i6R>?}mVqsAR_ym{kVgM z8?0Hl%uHP8ig$fz+IG*L=$8|@uwSKPf-I~{cT7(96LM|2dioia=i(>R+^yo|>qa-) zvGy3pOIqz%*H&*>do3Ixx!_58zAfYi_pJ2}U{$@FfY0NQ2cn>3WRws$rNm{>H4hi; zi_*{{Laea96S(*XYTkXLdAOcdu!m_s?ld3ChTe+*fUoHPU*&0OxfhyP?P*Ko7gX8I z-*&U;1%JJ?i3ccQ)HrqIRv*#d$k!g*we9d3^9pDA#rYp|^5kDMpya_$cY7Dq1}j@n z={O_6uHR}vGamO>mlWX@kt}3YvZ5BOw6p{-%n%TX8!3JCOanyI{C~J9Qtc*bP`Mi-M z<1>W42_&_SGQ2)IlssK#0u`S5)z_~si;ntQk~^=t;+fA;>S~(@A6@%mdc*Sg(d8xV zk24!P7vvEC;z@lY&hbU%D#*q78iDvx6R=2xwU3=++?b8eZ9>oMd>s7zY!r_dCSDEd z#T?1xLvZ}<9hJ=H-4i;CQ&jT41h_STMmnGl7D;=Y^gEd(o)Eb$h3 ziWqY$k+0BmG<$dFSYz!U7Px6jrarA4Z4IqoUjve+HQpY?!4~1FEqM%EBVD>#TPor( zpRXVx1?^yPP;EEN7iM@m)V6h8IKG~FocLnN^DDhZCLD39CJs4|GemP@uUP(Br{GSw z8W$pSU9k^#EpWFxrfJ3DMR7k-S7q2dsU4TM_3GG%ok_PXu#Yoxmn948(QP!edx{@O zkagxLoh%&%!JQZx#?A>;agsRStc*Ti1^| z9xiWO3#EwU7TIR%xc|nv?&$~%9UvtA-L3v-)Oe6nx|<;Kxrw7An`QEma2@uae^ddN zslsY4gA?Jta-5l-&A8)jP1tYGcgpEjq|7+86 z`U;0ekQ3@7Gz5cZkp~-GF*Ho*&pPO>y!m{z>y6jgY9X@uDLL-A5ac7>!=@la5=`tg z0f)k_o>NWPNTW&CasTYdlwg=@-FRapXSM?EFZJs~Yh>E-SW?{J4BOq^br$)m3@N0h z1!*v{hpyhhc9d9|)Duh8RlT9ShFQv*@#{0)pcYNFtjo57PcT!Xa`@*s!bnz^Ygl<> zKWuEk*V=UjMF4ao`U86`?&cF=Z;kpTv;N}c)g?Nn;U6(o6q^Hgzh&iWdYp~FH@-ov zlPO8W+ea9|L11z5zyl$3dhhCCsRjGv>D;b_dEq&g^~Dsa%>Er3F?-Q)Xek3Zg6__SJUVlI zsoIUj`0j^1<{z!17U4vJ;W->8bpek{R^<=Cqa=rT;6cllp2#!?;i$dd#wk$(o=5wm z;&dm9mbDv9iZP!N=x(j=k1I) zzBLLVUWP+aZ7G0GxujKY#?r-#-jY_W!_f=QkZESmk+Xw2$D}frcBQ3iE?!rn5ORu! zPI-^W?z5-#P=+{3+&s$?mMG9*U#UupqYI zuiS_vkWZj?n$robN1PZBAzzMC4dcf;8vcBMjkNT#@$sokToo2fVjvQ`G*|6zvGM^@ zRvEnV4{m^{Youjv(kjdW1bXXJzVQe;=7QIPvAEIxyI0y~VVOa%5-};NA4=6LoU-G) z`wToqBY7VWuFYES*1Q^(wo|i3gSQfNY-jD>{L!}b#|45N$N3Z*>Ac?B?=FJZUu^sd z*UChmhs$;t~i5;nN%G6g&u@P_}>kKync#Cd(*7xKtI+J}31HL{>%;(l$`*B|Fd z9k^q<3m^C&F~OWK?LDk*e=o)Tay<=&O+Xe#=oZK(=K$aJ>XIhl)v`8Cs+o)?fQ08r1xTL8cTKHEj7AD15yAM=EL8AI`zfr6HMw zf=&4>U%3{ULwuSI!}=4&`WX7|VF$dHoFs4`%kCIRC@= z@nd7%e9qvHtX!owiP2?-BOk8XtF%GdF>?Io^}lX+x$l_Dk>5U;Ys5umr-s9ROw&V@ zbk2fZPCb70W`%0(as;b3a!loIe+D6+xuk_c$}^8?vny$5EqBo;cEAZYDaZxXyLoG$MXV zd9(%T!`~N5P!~nznc^NH46#sB&~4Cs%P(2%a1FpLC>-}OydR|m_fo=m9JSsr9@z0!nSL{B7_0>J>MEo(=;iJtoTR~`lGHqB z5}Qh{{9i2-gE;$d97ws0u=l%u;w8E6&L`(iQa;z7iO#@ZJ-)E;nln;42QbB!f4aW^ z3wEND3grZN-FtcXk@%Hd`*`|9-yjdXSLZcM70@yf6=mx`4Z?*s{ zd$*$mf(kQ1h+J!SAHBWS+>exC8|3zxUU#$iZ@kaq(2-=ecGatU@2&uCv~2`|A&v%X zRj&y;3=~5h|L+VxkFtxridVYJuQ>AbBo+Ro_%lZcE~WUqY6RL^7p1AySHK&p7)7eH(YF}p_ju~geBf%&xf(02^y>hQ3ute1Tv`-5&R zWjP$@-Y5N=zXH9Bp%e_2r%BcLOeDW;%#-3|Bslr?z!=8dhW{T?XBib`xPE;V0YyTT z91x^SO1h=HJ0zsLYiN-W7?AFg?(P_IWa#dY?yjL3-pBK<|2dy$E%-3cJok0)Yw!JA z$4aC|B&y`SGJM@41Lb*ayO!2I7QDy#Ql%Z8IwLUAu9W%?dz*qXXh|P)X{uZ^-yqX^ z&0R4M&j;tN=`Yw%Q2jeTI_YW4lh&LaZ$1~HF`rC0C+E+2oDVMB)!#IJwBk`PI9T@_ z9?^$gS!NLQP>ym^*!RrzGk>lSGWJGWgW4v1dXd?7(X~?}VA8vyr~(9~rRiC0wdJON zBwWy_r%B0{+e41Nu=j5B$R&N$8`S2G{RH&r{>gu=U$>sA!~?ARES9s<4lwNqWN@hQ z=&0goowCseAzuGUySo-W<576$1Nx4Z7U@&05ZP8#?viybibIpgT+~so5{ig%L-=%z zN9NumiELbkM$aQDXU-~)pBH4@DqG~aUPr5m=?Ag(lO8fZ4HyUDQ}W+l!6|4q1h#zI zP$X9+fI;S&#qkAS?BwcC$07Wt-(Ed<1uf{Ai|3I#kZj@%1-Y6v#jjb$EI%B1f*ci_ z?W@fFqGFrfiyv@9{+ndAA{l%u3+R8>FXsR;U^0Cu-LW%OYtqoE3l%&VTIm6}s?6>$ zo1mKF1P;5L_Vb(uo`2m-53Cttoa7TkkgDs-LI{oY`!C;5a$ojHp^{#)(H(bO88Rn# zH`=%1Ys%-GCECAcgjtnuINclMig~L%ijh`p6Oz^%Y2y)a-k%o87lniN*f7ad!kML# zS7u?YCT$h+2tlCD|izMg(})Y2pW zRN(jv{Qfa$#>i(Vk_!hMJYdm=aH3NVd5Tr0B(jdlwXwRqaVs`c`B{@)&8XO3O^t++ zR{*iMSuh>L@^I@_(~5Uf*)a_-u4In73pS#&oob6hJsnQ3GTw?&e;p~s?$yf%#5hiO zmddihR@M3Sa)nv;6}7d`@bS6g`jh!EZAnV!3tjkA)oAn$c}t`|*84Dg=ud7i{eXtG zjGHS{Bgd&`KS((H>C*;v>5o#~Z(jwir8h!hoN2M=8rAYSE*T4-1~at_-HYoj1J2J{ zG9y(L>d2~S{E;dxE}`BwAB^cj-BAw8h||3{w|V*0a&V@HLi#VnnAI}yt>tS?$C};J z&8hojaW$-2X2HnYD04M;>m37@G<|>Zv02`9vEdfSXLDS7lzECK0d`i5V2-r?Qem6V zmW;~=k#HiqZ#se{S>{$bZ(f`r3!O9n1RL^OJ)_Qg*{HZ=#Q7`sgCAFZdV)-$PoaI} zrRdSRj3L?YSiupdF_{en-Y(!wuBU<_|H)AW_*xqJs=%0dU zypskKpUv+RX4(G1HGPGqDtc;B#*CqqH&GgDq+`s5^zjQ)A!Y|3MjG;I(A5*j(kH&D#_0IL9GUhXa6#a!8J#DqSLd%#}b2K?b&TKe{h*v#xQkJ}=T zss5p^Yv1X9YBTvwH@NMNcSk-QNMb(!GPM0e9D8hJ@BdEXu)M<;y@a(%LhMeQ3YB4; z4yEs+rMz!8lMz8ra$gx8bt|$!fvyBU#MG?I0P~c*l6tNuF{4ja>mK7jW2T{ly`k4C zDyj1yT+lX3DaVMQ`Z~#1zyzsEe)-Q>?gdzQIFEluvZ$^91P*3WAUiVCUifA6vvW6o z^I1RBlxCfKssc)$ZB>WXI=1ve-0uLRTcQ3L=F@S=TL`W5vFR(W&c8{A>^AD>ub|an zuVN!n6Wz{_p+!b)hlfp;beO~{`OYHu9QVBwkpQ{<({?m&l)%q6Pg)+1ZH-mLW98^I zV3Yh+yozx2nZgq$hoTuljEYXxV-CN29Hv=trX*`e`9(Ls%T;+E(6&qKd$Ag}M7&Z! zy7U`67Li{8n5kb?#=3u7z{eHN*{(7p`MN(&1AXj(KRz4>tjC6tjeD_NM@|NOR}i)< ziaY3q;b?D)>W?)UK{KFV?QJcFGIVVX79I9$=(1FB>=Z*VWWjIF+Qzoqh3L-*u6Bzo z`u8@yY;)P44|PMUps3`6$f#r+Vxcf>__2|1zxthYl%H?{Uq{_m# zPlT_J%XD$UuE8t13{;v4BrpY3s4*|0W#3ZCiSMDf)&moiNSUH zOd*A=hbKNculcj|LCrFN7%VcCkg!O{eT+zJ!JwfmLuX_??vZOmC?NRBSJ-a`Q9A#4(ciFhY337v1_WWeG^GA_({l)LWG+ok*aH=TgFGiB*m@;)@2BJr#HYg*)-i(J!EfI?(E&r z0?Tqep+0aGB<>zIEznp80Yh z>;r(pG6cFc_RQ_6j-<&H9mTJqcFhS-lEuyV3|-0#UZa;@_o^P;#vv%YFqtK{%cz; z-M%pu-Zy8N4e@Cw$2w@)&hpyM^yF0XN0b?@9tS+O!EX*W)mmsfZ}*tE_EvH7(QwGh zw_gZRFF0oc6z^uhzs+Sxjw5pK1Rg*bAyBpD|<->h++9DR#Wi&4>(VLAzaW65#tUdh{5-l3y!Db@~qbFEjmr3 zq$K29ufZ>Wo-M3e*(R~3&VN`>x3h8*cVx#@Wbd?Q)OdrBPm-7Xyh&;HS3T1py<^&h z|FY;p+38TL`~Ha}N|wbu2)P%B6IXFMG*BzdW#KD6T{+}MvQ`yLLJ5L=nPOb02=8as z+-kywNk{z>Ick3k^g->T;iN-|*Ac&eK~atTPeYPzK=HIn<>tQPJEHccY@HNB7$n>} z3rD@;Gd?7xhcUu~k(-5PRpmRebt%Wy> zj1}vf7L5vCgo%M;T=ZM_Y)lQbQ^+NK5i`Yl9G~H;_HD*&L(~0VNU91w3~!+m z(4khYtX`l!X18E?^LA`>S=M1{_Q$G%y47+AlhjddUUI2?P(%l5mo<625o%Bzu?c^OD2RsZE8)Shm8vw6raiOL;l9mV3F`I z0=be|poNFie_WQXVrE(kTUtGZBpJem>^XACJ(M%R#L(3~kqkb!a zQdmy6`04iB^UpvoDh%?Qi0HN>V7Vgnswm5yxBDvwEb*ume^EL`y6Eu7p494OE-0S))n__qg<$9 zQLeG#2kV5za+ZhUayjF9x0a%tvXh*?Z9n-cE?GSs8GcsEtLhD66eg{U+)y-HWh@7^ zizDO7ovktk^WB$;w&KCFE{1V_F;4p*`UzAAixl3K5La4@Tgh;b?C4gBgt|GzR~OhH zW=zH{dsK%sIu@|(a`VmTo@WX@-U{0XwiHW7`*TUfSIUz&^iVsO^ph?V za!29RzW&`fCFYTS6mD>Y%FkgO$@k_9YU5Irv#3mKdF+0&JR0yw04zCxxgjeH8c%76 z)ksKQuftjH`r6{k8G{x`B^A@{A#faRWG5|-XPQHJCFoM4qG^u*yEfYOLq?dltHo*} zVRlyp0Gn3I&zQuJ(dDQrq&fGW&e~5Jt!nNd92k1KogLh6;RPSq`gJ}cnV*9^9)4J8 zP#(!Neem8N;_0w8g-sMW8X5Q?RE&1= zTtwN`WSQxafS&2$@ZO&S0ji9gQ$&bJd99(3mBOT&Y1M?1fT9T9f7||}8~+1gh{o!V zz-PKJ*~j8pRIyy%bL_m4YBHo;$)#f4ej5 z{eIq)Q;G>#@h6e-aB_C8ia!92SXQ@l0S{$e_W8BB$w?uv2&^)oNt>{pTOu~69EVMD z|NB#Ep+?kufqGap;*qhvV$P%OaL>z)R3WqGd08nx z1+G<$*&=-?%;w;y;(OMNUx8Von0w5%ZwGK=D&vu(qXpch!b;t^Rk|T(=F49;%LAwy z9lnC2zQg0f0sSH{4K%&!6-=+M5pw!A8I1VOo}fCy)5Z3C^#?e`IBf?oJkXf`$>Mnl zcV7gZCoII7#O(6M-!hsH$|~YE4t$EjqqHWrWh71%rp7&6yz-*7ojF}nPalRiD&ITH zR|xi>ZQPhBRkk8>{c0b^YqpLS;9oP9FWWAK#@UcpL1sk{_4An5Ta5*?o`28~lN*S( zUDx-UbNDwsSF;YAX6=$=>53X+24V^u&hp%{RE#_^gct1w%W*wapTtR*^bN@ssNBge ztg<&lvRvB}(2zo_X$hmq^J7zrQl>Hl*_M_HL!~37{ptABwf`PQIRxj^$5Ew`?QPUp z!d0*|6{TDxMa`Zm@Ft4@U3BN!A`IjR*gFvT6XILwD4ILd>_NE?zjwwd0>eM-UbJ^3 zKHw?H^1okxh=|3QxKj+O^xI36z8luI^)-#|lOT=U8tDRzL}3^=K60>6!?tqM%Agmx zj9I${^83Ak$*lU{HV2Y(YQMZIRLTepJAM!l_PW!Y)X*$d;0o<;E=JM-Tp<~g7u)FZkGZ9oEAvtwuBH(dA zpKKbxe|Q%KNp;tVvkO70E{+ zbpNo4m)HOlxATi|wy!4X`toirHJ9ZSDA3N2fn%4=7Qkoo9WJlDZa;5M# z7{F%UPOk+kYp;(5u)x2`!kbM_0>v=j833ilS!7FhUhWkqFue1X1ch`}-TlS#mPLOW zSm_kILYh{P_j%dBfVq6KG?(yA4@UdVl3e@Ayc*)yM5iCog8kG9Yu3XBd2J+Fky7ec z@AEBdU-92uK%K4^oJU#chC0hCh~yea@R-HGD29YbX?^Zw5r`D*6a;#@60tNA0JUlI zWi8(vU)uRFWhe6h+<{Y|ZU9^oN-W~l!2~3ggd?{SE{6KD_k_>OF-+Al8 zI)&?8T8Je>gwWMu_?H30`FcGAeY$}B`SwUUYaT#xeKwpM=@Dd^Vah{b)^G23mJ1qXD(kxCx2M35$VV|@%NXOO!dC`) zl;9YVhiCHB?h<%^sb{?UA|j(CCW~0Ex}Gt1&)D?%S&mpZv4RjcPBSn;)`si&;QqpYwmQ_SW|0GU29G&ieDz zD&XrpPhDqz4|R~-ag$*Hu2H}Z0|5(tJi?2cfYl%n)!en(s>?TFD4l8lRPZL9>6{)5 z=#(cX?>r|k^u3f_1jCF@&Rk>iTKkC<)UztzJ-hoN_|`iG^Vn{n_f;rcJFfWD(B&c) z-CsA&I>A-DfXQ6mE!M3bQpA`r0M=RI)k8K`s9gpS)FA^{;`iuy* zO4`}N+*dc^m6aYpMM$kI#+6pgx>j{uv?%N95-<7R*|T~+thy2-e|^Wp$6tj$J~+-7 z7jvyPI00!RYu}CDSRyW)1i1dQrpTYkJ4b(qw&#Ht#fuohvv7F&tB!!iscHTH37Ona zZ{oImB37)pu0PR|@JwNcovntEuTASac1P;^#GQAIl@w)_LZxbt+?kUhMD$7crM+$R#4|&X_-c72pY@c*HZSGzKb~VWA=U6KVuPeF-_R7HQ6-Bk_5P? zJSh?GMBdsWLSbRz{@e?89Hii#+&!^b=;Lj)z)|sCkP)!5yaqJF<4ucZAh_hbTaavX z4;YF5?zGeJ`Xk$~<~McfN^e3bFBDw=BXUk~zhm=o6M*m}ZZesA-G+oVnXa>z0K3fR z`Z3I!=2hfipXMvo34irjaO4}iHc2UGc0UVz5iMYV^$cPqphxS#p|FlE)JKYjnuB?b-pQ@4IJbvaSiPxIB^h(Bp z#0Z1WjJ)nTrB!OckYs%l(HQoB_41o*LAqT5J4nSQH2U zyV;W(GlBfG+q~j+wr{W6`cv7|`asmB$?sdYq@S;u%fJV4u~FTIi)Ci~7O+v=}PHq>zz-gKy~M0VvClC&87hob4~2AFzmyMbKL6I=o+oQSERT6ScY@Gnf}} z3a$3?0o~qTDKyIUBTM3;l9ccUG{Djwcl_m&?$9hU#$o(HeH%kf)rfK7_XZMZ4?~CCmsL^C4P444o~T z`D8aA6o5lo(Pi{_M(9hmyud?!;o!6I&NE*`e}t6@Mrh=ldm5V3)j&J2l0HIUrBdg6 z7IiFZ96r9yW8aLu`7oV$jEm!#NNW`59091=XmNE?S5<$FeqvtEA0Ow z7aKeO7%(Zpy9Crrkg`JWKLQnKCHgYXN;m7(K=9gVz^RRHI5vbVP@hDBV;(7##NT|6tjcoTo*UD3p@M9=`cU{ZO6F^cYv39E}_k9U-fJt>a{3P4 z;(xD7>wh?K${BHX;4LZ5eC-5S#EEs)(6RVACyC!TvwCGXlQ5*_lkmj-0N5u zr6O^vYn#ZeUkIe`4UMg^CHG(y$%WJNMISf$R?c@J2YY6b4J!F!L?JoCFC!` z-goTvL@2jhj{7O@n=gIuyKPt#DTpv~KC8a?%fFo)0QLRLNI{6aO#l5OD1?ZgzK)Dp z#~@g_(;&E1uFm~c-@vP!{Le&x+cr#Qe^9y|l8)UMjys+x&3&cW8U?z_j~CgJit%af0s_4RDcMxkPz3qXQ*B9hvra z8gNrDyREC@RU|d!by;QCq%!nZR8?o!o}~Qi82D(XkM;!#-!mY3-l7U48K8LJ?h4ep zHV4nP+t_3dPa&J{Rd&D)$`-H*->$21 zacM|o8u6cJw-l2>-E>V{Tu#d~bo*%&==%2^&KJOrC`O&Ydgbz@&kIn_ZJp-F?o3bD zPyv9Ci}u-hWG}%@I)p6PRY?TX6#avgzru8uSxfzK1#y-%d7=5uCu&kPM~yKZIpG*d z>KHPIW(1y(u8aqX2i!|6xqy~ zF|5fvLoa;iGQ6)>J7TK6;2+BMYu-p6%8!+3<3!C``(P4r=xy;`Z5xOPVJxif1f_HH zvql%zh;`D}uh}{bFg=e5v z1NR{={%jO~?{nd{Jm`d0<}cQD~L zkKfo(tC-y2SNmL@6u|HQ%{{O>@r>~$^>gCM@U_Fq@czPzMMpmIHjI1}U%+mna}N0Y zaU~PcdzcP7pGLT@EI2|ntGE}HB2{*!Ml3xP*HJeAS*Dw|3$ z@G&a(_d${llYM)^^X zxR)i_61+0vz(kqSIjWD^)SCxvlHzmYvLeok4JgX77QSj7&#Em?%5SC<1Wuk6(GR zQZ&rc5hQ79qW6|AH9v1SjwQt}sv-zjjG1YCUguK#h*_@Kmj?T49p#qm;So7oXzR!o zVU6(_{Q`DWL>A*bV^FEjo8<*Fa{6@x{gcBC=j^+teS>LoY#6MUw}6e~5L=%Mapa~p zK(`o932FnDX@rJOqUpd>({Z_^4+O~)uOAuov(QFW(!B>f7z$pq{Apm`dxI~bN`}RKrz)L{izoh z^8EfLyvH9IN=brpDChHKB)COL^$BoFHtqcuB(&ds8n(n*?sK`NqOLws{1mIH0mSK5 z4M5ZH*CZn+sX!fO^)wfOr=wIc`F|0QlY^N8gxf$8qI9uZf)aPpeMD%t0(w8%yn4Vf zq7f39%>>LgcAeb>hBoUP@df7B;2TQTDeemv#x9cw9#NSN!EzA|037#=;^OF&GBXg4 zB^8<=@q1OG#J&Cf)XQYDNlM!mO1^Qe^qTEs@y_Pl{4zDQB<}nR{V16idDX>uz10VRz$WwSi_RozPlU!~pl9i8i@eoU}GTt6Qw0o2!cNL@{_UF~V$ zIl^p^>D*ql+rJw7Q8w!kU)d6DHL7dkOq*X_DeO_Xk+nsj0bFNDTYA)F>rkiMn?wSQ z4w{(&qE})2H#5OdQ|$Sd@*9qIg_~JQV#8%_pviB}2Q|{GIUUk@+NYd&)E40i;8_5# zB<3$M{lq##O334|Mn;Wo24_81My024;nKMe1OGkl5kxXk{B-OZL-6jm{_V}DZKcft zkR*;Czm8Ibrh{#C*e=5aKe_PEA^iQ>M|@wWN`{HaghVy14|S-CL#E5_uSy44drsG* z#f!Aq0zVU$b#c@cyCwage>V-A`|_czSfj^Fxy zSg;c`u3TlYN#BwUZ}AycPvcOcH{F!$CMt>UDT ziW)r@%Fyo2Ht+=O`f=xNFQHJt%_O-VX_mQ>F^w+t>humBD0Z!_{RnxBd>tfGe+K(_ zp_B2T8{n79W+KMSD*V5x*M9Xa(Z94Z=d+IKS@a!6EH{P&r~3dCP<-UlHfB4ktdA#IqW*2oZTEPl;+dC@IBM0N~79Uq@0SA^Sxz8#hGJ(YMY1EaxMo3Mx@3~S+^p7P`?v0FGydaKWT@XmQ&D#@8%+>;99Q? zH1>Q%%5JxLKDiu@aOfD(TGzvt%^l1usC`XMy zE4<9N?k}du+nSdg+*&`AF*)2RrAO3%SiDeE+JX&-JPK83SJmcz@X4Rgu$9e_vx|nf zZyJqq9GyawTg=Sk8SIOzaIn@IY=bR!Z9mfsaA;TH&@ALsix_67iABPpWM(5IvOW3a z$ShkvGR2Q5`}4QRYqXrsmhpXoZlADFW|x58hu_R;2L#fo4z>AF@!bdow4{p>NdHBm z+Qg@dp5)esIj*fUnN7AP$?}pCE$=aU$Sd!q$yej&TJH<_zFl3bKl&0>wIhW3r|rKs z^sTUOxAHOns%)d^S?%RFd6joW-%u0t zPLVvEo!;s~nxg`Q>4jrix{tiJ2d_Bh)Y0zb6tYs^e!+C%>`7P10sQUZ0A5KgC+z?l#DVk-P#%8ne~kA=g{! zj{mqWD?^X>(lDS-v{;ISr2jhfpz-d=#uw(_35Z9A4hyhjy~VgaK+b{#d+DN35ddIX ze%1D}V*emR3P=ZUN!sxv&{A{ z?Z*+(IB7q*KL?l}6k%kg5x=rg+AephLV1Y`toGReS0wha2t{r%GnBOzPqrM!_Rq`n(3iRuv1JBtlWzgGog zNiq$zBE)n))Pm1#EB@(p?o7ta#`HaSqJpMFV6Seet78^TcI;##|JjGff6Z{^0YvRv4 zm`AK1h;o%|kCtF^yMU>aW$z;^g4K7PJYyRkKQ5;dht+U$J5TBY$@PA-SJdU)lv4#% z=v{?zHn4-`7 z$KT@0osqjtXeL;Vl7frm-;KXtu#$hL-exO?`x)TSvwqlrJwqu6>DLpd%KXHptkxZl z+L}knOHij}AECXJ8Doh=fB@m4;EH3xY{BM5!ci;__|TH}B>LQ<`xV*X#gcmGUX&BI zn;_g3M|t87OLG3y(#(8?bnd2(MlX2yCWIHfQn;fwT5F%YPbGo}7xfGKB7weM0~-Uk z16W7H!7Wgm6_xAmzfl=4nC>fg=7Y}^}vD~(AM9qo;3s5H=r6I!i5@{~7cL`A~N zU@Y{+uNp%)&&k~2tHe2__pI54R`Xfwg7X-8<*y^3cY(2aJkoLjeD?ib1rt$o_k_Hg zQAVqU3&&lO0j&hVJj5X?DRS=W<2&E&nbqq&$b>|lNRo=n@d0>7hv#WbTQ*$&xaxNl z7xY)@WOT6%c3j=NSP6<}T`%HFo~+6CV}Gx%-Uykb4?$y{;(95u{%g-=CB1LcYv+cq zdH*{Dz5ZZDPH`Id(74aHODdWhhILfBScUg^7*qr?Wwjl(rD{Sev%7I1T1qoak{udY zl!VbU3;$HbXE`sgYvI7W~h=0i0tlbzUUp}UZoFoMPf z&}`?-p2*!qf^dzJN3ZCSK``_|&(G?KfTdz;6L{dG{rUYVso7OUr$_p) zwY;VlMZ)<8W#0Y7g|q@ysLvPhL;rjBFo{1tM?uFL=f!d&tq^bXICL6h@A3MdN3bT> z>Hi>f(~h>X{|*J8HZl!w(5 zW}Hx8s%G)*#q+U_t0xB6Z6c;+haO4P9qP~7j8}}kaUj|u^D=tKtDV0jqTa{+9=oAJ zR|2n#G9O6Xj>pvT|4!msCUjkP^X$cYs!nDN{O&GvKY(=x;qNM<9T@CYd>@5 zqh)yq={^;z=B|$fCl&uTmOyz>jopFtn~`hK_XfVS9YGExP-F^;Z#9-0rcv`@2Hzoaz!a%xRph?^@)9E(%M z>#NkfyQHRf&Y@hwH^8xilI4n;! zCJ&K{T#u3IUFMhGuf7t#+leJ3Z$V__x#yfJ%F2FE{@<#e1j91$|IY*f9hA|7Y`whpVrVtn~Z%mkBhH(baE>kl!EyJuMFHkW?TUYGmBEt%@^ z-mc-RR~R+tWOpXLC$TQj@mZ>nmO9HXN9E+^KNL`ZRal5!(B>{sre3AMIc&8mBm@a2 z?9)A#+?DM*U`MrR_3`}o$qr&C-PC&{JQ%0VjNRfvc)+sN_hD+g`7pZ8xx3+NH9AbB z>(#O5YMwO;n{)SYN~?vkf_@VrZN)rs_VC=ZD#&qU&!c`I(=iK-+#xHxXh|nJq%88s z3%qbM&|7DP1N%={kya=3KK~O5mUBC3`O! zjM_@}6Rnu_PL`CZ@L)XfdwGxP7<|1D&Zx@bdGj4FP8JQsK9w{@G-p58xnTzt){z$D zu&D)p&?DIJZ5Dp+C!jG6de_iNUpnEKfR~tND>v{Mo zC#HCHgw*VwvTt4`qeN0Gq`!mR8ELN65L&L4LWLsBD(}z@y>B!>7`DrR?eB&V5Zm(G;SECRSKgzc63^e`mTXR9dB+Iu(Zf^_#+oyx^e&%)>2y#36b*x4QbZz+rtn9I&wLG@dy~4hx5BfD;UC&v2#@>AGVr!h+M8})JRyXI?pi3njii1E^Gs{ zgna%b(j`@$Ym(2Q;))-G8pc2xbj?#Qeh^~jQpbg@W&fHDH4KNxkjK1YZD%_SlEJUM zMgDm$g*Bg?v{tHr1k@cI7NWV5cRU&`x;!M(r}N2TxRMm&@q6rtbiug0_cjNry;O<& zXDXx^iDA9$3+wmGpF>qmxo7SkGauW(wmBe~2tLrC&&LrS>&fsi=`;wQPnw24A9_jT zO6q`T+TQydk#WirFTwjJ_D75peLk7Zmzv_}9s|cLr!qw?swYxjW|1!e4*~&S#D@v8 z5jp)X!TX!i^y&dJpSdL!%^QWqqEDbE+82M)xIfN%0}# zcdL45c&OtoCkVE-`>E0#&AHywC1a`?r9)P$X7Gra?dc%eM$dP084h`-Ei%us>c`&e zBGTmY9;OK&8|b2K&e00g|UbhndL}ivz(_e#VuNMXd~%3tg!fl&k-ocoR4Ojx$6-$ zMbmgs%;{2FYc)&KRgnBSV!a0vbTbQx zXMeUxN7`G0)|PIg`yPnGmz z_gBNxZT@K*_c3CdM{%fcs~v{KfFA&<*s8DFaRYIL{GLORc=uy{iTV`L`*f;k{{BdF zFQ6x&BPCdWEsBW!nRpo1xeK>HP>(3E2tFUu=>Rt*tEU5muXUV&+jykd>{#PT)*Wz5 zbpl*iCZ&tP#KrJvs+3|eXH{vz(=!sF%!WScgI-h_Yuoee_N%m_9WIQ;4s2df@@Kzy z{WFQ{Lo-Id{hExzfW4@Y$kF7v(|GE3uIskL^+lei^Mp}AOs#j_MwF)W%=tr?|ICRJ zhc&Q^_tXdg@DzNa-OcQOR;{x*G&?Y>@O{|K-Y~|)c?GR<%)n5YomnqhQjGPHnZMD0 zFNL3Y#|k>hXL?c6&YZ{@oRk@T*{UyTz;qg%Q7&yLn@Z{F&HW>2{r>r1i%2xylIEzc z`pj1x7MJ}A?2_s`qct2-4*bvZLUG_fOwxZUKbp{6YnLtwy)Z9TeHw$++jKpkgX*td z!xZc-GlkD9xUra+689L0c@X45!c7S$@*Il@i1#(A9m&O-e~QjoQ7{P zf`#D7qrW0# zN$^QFERPZl{yz31)RSdlyVN+!={Im0zDqM~c^2e#2)5I^wK-S#tjn=uFYijvK(TG@ z1*38u5?b|fp&-VdHHta_i*x~-l_KbJ&nryaSk-z5ArA(Kw}u`I{aOe zC@}nzkiXqF$H1qCN}(^`(yjpNf+Q#7eqx@klR($M*dIX2 zYfJvG7QxHSIsBxk;)HBt@;89!`u9vnPyg{-y3Wq8{rSuh`oJxGdm^5Yn3!8wDAiOl z?-wKFbd4)r{QLLVC8t>+>@az!iw2rQW$1n72aK_=29lX!lG|C)PIRW$jzQ~OR+Zi$#4{_*_6n6KoAQ+o*uT1^%=+oHO_&XozvH)Rc zjCC2l&k7`EE$HokEmwIN@_V8RSp#X0qKBxlxAqZg|$l*EcrjRa3Hc>e8JE4SQ(lr5Z zlpk+ja{uQQ2V}Y(itZwU7RMDg{Yd8f*h0`NRF1~W36Cd5u+iA2;I$*8!>WPFi$VnY zBr!3O9_U27nb+h+jtW(qol+jsZQk_Amng7Xu-UT}6IN=d7_PrSU2_>e&!KvpG$mZG z4NdXa#o-r}4^ICkXADh^H|%P^`Do>+ps|km&6_*hNs(gi#$Vy{u(- zDY3>6O*^gkBLVQ!;U_)+eH{X`fi%Ho$+!PJO#c+$*%vF*YGI^cdZfnyvljsNIXyTZ zSzo$4?qTmC+mCYOX4ANT!)RdtUISbGdj`3j@y$5R-c3QiANoP#h;XlLx{@<0HiW17N4c(^Y=F zfwdlL$TgYaetr74F?43DbgJx!3JT$FG->?HJl~?RNHo4!1(10Mc=H4^aqvm_Zqqam zvGswENsW1Z2J;8$OrKrLulk7MQ6_i3@*frs81y+&UnuBCQr$ zuo^zlYPh>6aymt1)7t>k=zZ5WsB z3@GNU4IZ6LOBAMZR(tOmo!X$DsT?(p@-#*zRgjG}UFF}=JCy;a5;iV{#}r$^O{Wfa z+nDkI&NEZuEaj266N5wL_O!3527dTOU$0|z38%5|*XB?0esqPTvZwLZ9A{hn8~pzJ zeLG#BWR?Ekgh(03k$fD);E&-ZEW@J%Tn9Fzd`^({@uc5!0L~cozMSh;8YZKRc27T z>_0+rd!fc3*8QHa1)eTkpen8c8@Bv~F{&k-L0B(ymEnj*{Yz_!0_g?xMaB@{l51yl znZnO9efjqF>LXUXD%oqM{_mlPFvz#vFA=cDWvUW|5&LO@GxHwPa(G5WbDJ7el3rg; zY=Dqdg&&kewOtXN96%La_lSPO-{i4_v{VY`-$rMyE*Y2qk`UMkmPWAq4$j)ryXy{^ z`}gSyYIO*Lv-F4;O`cDqPn?x^_sFaWEvOi!O^xU;yvtcKk(UJ<;%uo~WhIaC@bGh} zw`Uu?Nm{*q>KADf8y7qe`3h@|7ddJ+8*G9Q+IiV7?ssJ z03O3?iEn(QQ1zWw2scKXZ*>^{qC}vmA*2|fNfWDXyt4qrXgm%&{EeHWU2BjbG;%4b zf0OOjoylolxs#QcNCr|8US@5kSv}4hGGgLqGA8p}#d`K=Nax;b;jn(P4(O=id*e)< zbCp$~A zX_D0?az>1Q%`&7_KJdR@4I^o^JHp0>#^bM(VM0an7bs^BPxKl!?xE%O8zC>A$8-`HI%c#}mUYQ* zigOSa9A@U_=<_37XDPL;W~Vbd37MVZTeT~mwP$#VBZu_c%UWJ}WbxXCjM>=K+184U zo_jfJp433dZ+LZn5%)`FP94A44Co1d3+lES2VXxB)?n><+00UJ6C{Ne&gjcVP8%Zh z=F$-l$Hy5L2A5=^9@dFnx2atam8aJspQhpBx@U^nv^CBRw)CCuN*EZBgoTC8(8{$4 zx1h)aYRU7TVs&-caxMUk^$}RgN=5=6y_q>(5ibK#DePfPay@DJlwHR^_o_2B`(*Sx z)WZyAREBOkjE&K!KUIGcH4Ti9<6insDTaSH{O?!XzamuQL|N|tyaQ)`h&@irF+fy!4H;QjoAxxuy?YE?LFCW&xo~>u%MpjWxs~x>cVzsoP zNj}9Dn)YufBX3q!5&qCCY_v-oDxRTRvA;3I}oF^)M{qo_p*GS@rueuNRL4Z z?e=beT{pcOmmh|_RJ79{w50EvqiW>bL6#m*ma|)*N+s?WtFOa<-;ZRM5EgO>r{{zO%Xt3i>GLDIo zuD;i;z+AGMUaI%2^pT*XG>H>K0CgWOqCOeY5Xbh#RM?lIFQw{3tT<$;^w_5>REO^L zLVy$}xhsjofPES1l-vJ~&flzm|1A?CjH1v_Xjf_eL$joeqn=dRqs1r~a0M1X z_iH;)Z+d81halEr-+RK3WLq(ku(4WF<#=Cb?pZ2(r%Q7X(gV@aZ)($uc` z_(#avj1?ZUMEKA}$q3cX1*$c$e(Ap(B5U6un_c)GX;&vIpBQSIEscPd$h>^-HpL$LH}vPfc+lOpp$4Pb=*)` zzD;0*Pdoi->l_q$-0W#QD2d4iR2TDEsCjLmU-XDq6E_?mMJ_u{`ePAO;#0dlHNUbT zaInJ80pPaVo$s30yFV)hDX6MOlA#FZlf6igZ6S~uvi}w@MF)xI zh>`FWWfI{1Ry}&0=3tC7#4YPyG{oL+s8H2e#!#_j1v7F}A(ZaT)kVY!fkzaLyqPsE zcVeYPU0TaER<1ki@>LQZVS|Fqp$8)gvNEk@k?x%9L^hR!X`J9x*Wr4bu}B3 zy6u`_55YohigjF7FmFs7AA4JlVgQr{VO%OCq^2WSZ!*V_7v?7RY;rQ0WQKjsu@k!; zVs?BjK2*?z4<(`r;~`t%zytEi56emxdGtw;{E0N2H=HXP!D zFm`y7G7GO>P8}m9jcOuAJfNFcyg+YEQWi*`DzIv$5h6l}fI#<0D?~CoFpzS7m;xxK z8%ym}sl@QqbY6>sf%p7BxQ>-Vp}6n=>3QtEJw3p~{&N;v4pQY^$dz;}59~?X{=>AJx+L^VYLR`|6E>^sy`6^ z=Y~bdHLRW+%8JgQYzysx$W)&pGgJ~Q$7o2{@c>RgeqZ(TYJSOrc4ei3 zNn5Brzz92aoOtYc?VTq`?}TsrlxoCMA|c$*0R_2~Y!S?niigUBYg3|y?ZKRxMgVT> zImAr2X(kX?uy!N)$|b?H?Of8_5EIcv?sxVJQ}SGt=zyQiXG|Lk<&9>xJiSx zyq7t_iU8!`F(}a`KV;RjAspvn<*`vk*GNlezkia{!^3&R(P6||v%&T}QKoqIOXl{R z{CkfmEQ;A3S)*x<#sJ7r@`WDl7>5Jjap5YVz(`E+Cu|sIMKQ5Y!d;&~y#5>lKlV;8 zw;^6xbAqg77?P`*FwzRm2IGxhn+0&kD46<38Anff0;o$(%4IKPipF*9Cr#A1HhK#G z2(t1L=(M=9BYeDVuKxHbmKm8q03TK~W5VsPKB3R^(0!LYgOILJ48bjNTYt-`E{Z9Ih0}^^_CGAz9=3^l!9DLT@lC(txncTrR zOWV-7BP*0bqv2bn=mYRaH4|UTSstinlU+}qrS5Nsi&&3T8@R^ElA3IZKy&zrE^jiZ9Zllf5*zX1vm|&gXKZMEtmjoZs`p~j2wj?NHVoW1$Q2T}XG#<)Mxv${he)c=B>Nl2aj%C-#ODcPI-;TCd;>2T2AvaIxI1TC z-+wsE{=Z;8=^soO;Bk0!L4BZ|BkDUV4u*y{0Fo`8AgDjZW+J(vrSQ{85@TPRM{Tw7A|f4-i5Q zaC-TNU>^%U*kQtY;|Rew3+4K zfiB}QW;$7J6s~fUd53A1wn%e|Q}u8R?U(p6$?jikYFU_#mMHI+W&OH`$&nQF)Jb>m zC(7OYkn#BlrEwVlrp`)7|E7q}$OwTv$#ugfJ!8P^Xp<54`vKa~?q0TWR0jFP-sg?W zqMpErDyzTTHgcWTDJ!aI9Hjr(;xzn)y>Y^p>Q`!9^~2_0pJ0H3svQsEic5gBj3C)% zB#nkBeJb4cN7?VTLh_V_p?B*(xX=;DdZ1vnHNlFn(eph7kJ~aH^J+C<{v|QZu77~o zXQ!8~3wEMJ91!X>&OdL>ZD^6y0Lw)E9$U1pfG=x4K%XgasRammnh_3QsFQ9v%<>Lgw!J5sD+6xMkOZ+m-ACU(bl)6# zAQCoNpQ?vro_%Y2p0u&4sc}+J(T*6;kXDG!VmxdwuB;SQRmJA8UiodwEmm;4#F+x( z-)PWGPdYS%EkwtvWE%balqmBMeQhj3>~lYj(x|_+6EO1u^=WNl;-^O4d%?~PZ8~ix z@u{gPSlq3#CUZEYsk{7$l-8!R-EWQ6*?Aub!w_QoJy8wD#suWp31DErX1hCic5gy> z%+_4NXhc!J0^p=Nkv8VN)~PSZAJfI}K?}D0iTnqOr32&2BTPCUpENKvJCEMAtDC?$XZMS}$){)ALTWay7)2)Gb+Vc)I z8A&pNsk(8~J>fWvm8&B!B);L6$(9W{u?h@j ztEKMp`kLBWMeP-Y3@PI?YN`ptqkM1zcEUoF1I!;9TJ%U!a z8YEbF@JlN$A_d^2_y6ZxbcsZLi1w~Hds?}B3pow{+=dMmK|XJPgi}#3b2Ow|4gll+ zRV-RN4NT?Q8zd#lGV$8j+LLE!dKUt4O@_wJRt4{QFA`YrJP>I127~$+%-AaP^l0;q zMlLBD~Bes~Y?|X)~mm99@!R?(r z=4A?IV%)_Vr<%{U@Wv{Xv=T7 z8v{m;_&LMHFc+xH00-3U5TUXz#3CY+fZ-qwrDB1Qv`Z1hHU@9cCxG_qyjqUe3HBWv z8WUopd5LGSwEANYk@x*6dey=9fskRUR*Oyo$)0|LO!g29-abYPe5tK5RcmW%PSO#> zm6)e!L3uDXKJ?>U;Dy=wLO%k){|N>TO$b_PdDbnF#9%^ce1^6viiov*DAKQ>1(k09 zV<)G2PMN!!eKsBJvql?1P{5IMY5 z9K?wCD;BG*Py93)N!%!{?D(q${HuA*&N1~NYNb?WJ4``CXQahqjC?nzub5&o6>%wD zt;vQYbq;;w;7dJ&$w#jFw^QE}X-N8LCCVlf1|%QR-q(H#U8B>r9xQsMy_QnDew! zzdK%!@{HYHjRv@J@gzM5*xN-nJ<3lSPnBs^uQ`6)BqO&|HxXIcPaxm3!2dng(BX_k zMZd~c{Le{eM9!>l>#pp+5GFf%XbNKgYbPdz*j9VznW5TzQ@HJVD_pMFX3g)MpYL_S zNbVqwJpK1}X;`GYXWxfsr!Hi^He*y>?RxmiO3g6Nd4`^mQrvBbi4%m8`)+WG``&ok zQbnvYMUV3;(>?>~1>!DTzG5H52>_9h`$!F6NgktCONcbGB7|>ud;R#qKRm*b)6pT< zXdWh-mnw+Ex68DIT_I=Z z_1zy6v?54F_V>4zWC*+P7fKx@4YzHVY@_t;mE3^$f-Ec_c%UX7)Ucd;@%r8s**UwD z^sUuV&UpLo2u>3Y)>Mg;J97A^0U|A@Y~r@cdtrX5ysvqmrH@@MuMnqGYA@xlqzJ*) z!UKw4!NH-&zIr0k4_1Q*lnYaO5G}(K$+&<6AL{A|i2sSM zyJ`zO$+(Ysjoc0rSR~eWA99X37gFMgH_56M%k@+gRG$R7(*BJ`s(@gs~iQZ-HLjApZ5#CqJ z9#?Npwx&m$h%a0mWJnAWTK+p7bS1QUZ)P^RgvrheFTwnb;M(4v#C9~PBHKj2X9gVP#4SlX6kj28^r}c0zjah%=JEiHo@aEWl zffaL+A*o>tUdPRaj_ccsu*|^Zw{1S8w)%91L_t z*+0y3ZZyTosX`IR=j{QYHJ=f>$IGjq*Qdppa$SGBexM_Nx>)12+Xx2>h|vM2VbA&d zPa|JYx!_YYQ|_Ph&>%^rexa(giBb=TSp*A4weQ9$xXRx(rm-N+2-H8;3;i?)hOsA9e3sgwo zQ(D;>u3D;o0h1TsV^d?b`4;5YKVuZ7N-NkluVKrk6q5CF z52wNAS9q6@soaJ_KbGs8j4|++)b)r@ZGTm{}TxL4$I(Vo3 zF>zIwgx=b_LN7kYQr7M&@V*TpFA=HacflYD8JW(^eGQ9;)Y){i58}yvm=Vh1td}68 zQZVc?EhK}-rTg_sK7OB19n9NDWt+9YF?FfUgWTvGi(T*HqCoW0-b7^=Zeru5P4 zv`t8#*G_FDKjZRzD0AOgyt%KZTjhzuDNVl`Tdr+}O;=(01`foXU-u=xT`~J6{3}{u z$~$^^gmWuhIjXzAzO;_3k&gAl*$QT~*Hp;piSe2PgLL4ty&8xv0rg;x)++#ix3ji$1bLbTxD`!_fq^0y)=T-$79}(QWZ~O7Ok& zjN?BJ?Y%W(Er=>b_8C^~hZ5$usz^bi!bjTG-UtG|Z#FVX+)25))m~8pT_MDgayl*D z;^8Ka@-`ZssA(Lw-@k4sk8lfl$Qq#8wcXyiA1;O{>S=+JL;OW*XOp~CSLlo7c!RVQ zuz9M9MlP46yjv_#IM`;mnYH8_1b_4Mxb)cu={T>@uk+38I-wN$yf$OjoWR#vx~;?P zu}-u+y+*mXy{Wz=5}EBNpOY>$r(xFoJ7rxCho1WAfKRbKsP+GBsILPhR9azox(@-+ z@1RoqS?dJ#b78A^na)a|aDxGMKJ=L+ag)FViEyrY*D~BXE(iRfVX)+6HlO&qVm~e0 zqR>wJ(DDcQyj(9w%lrghTV^P=@PARV{lvk zyN(VF6zrw=d;{)OMM9Jzw*9?n=f)pVy?q-zu-|8dwh|O_)lLP@_d$0*=@xP%=7;QIo1%KMQYk>lGy zE8+Y29@^6@g0av&mGEzpVNf))2-C*2`z)PAky0$}?wHVzKeSQ=k4F9T=zMom%lFT< zVAZy*D@T%*-}V~0h!Jg?7mxl;k4wi;!qh-+MF(I=M9GCUA)(-Y7VH-$dSzC!AOXvz z-K$m*K_=0s`teS|F zF;gC1Cj9>DUlVhE40?c_g7agAL~5ydrW`gwY>DWnnSF25x!vz42lChZX)u*pu&0$S zjLVWFkV)&&9OG3YeI}hTTzfeq97pWmXrksL&3G`S7~{li3l_75U>s&(COdZ68x)LuSNmcd6mH zX3DL@D3lu?CL@q*T<^Lpz0YV_Tx_60?5+Ln~vhoL63hCx9@xZkl|!WiFFTLJc@b~Ytv>mh5hhtq8uevEd!2s?pg8X&#Lv@uo z`j|>Ixcx&54ifp1FoQ)M`XxgQr*zlTjap*?HCHG`YHhv?8lW;qtFJph@ zR^=);l^`V8npmK{N%oxv>rX4nr!q_SM4B~|iwY3d*x{yosu0WIY5m;#P}y&lS}2yx zGMmy?KFRfpO5ek9ay|{_3$M9E6v4&q6hxpf%<+OEtU~uSl!x&A+rv#kd0bP?`%v44c^}TC5QoE)|oOPt@ z=nAdSibfL;S2$GE)C}g5^b8hju+8DqY!*`=C1b>N;5(PFkn!+@9HW2ZkaN zsEep8qf~319B173)8nxdSlnfyq(t1&f$pGiwv2}6$c{qL534(AX|@vOc)iR@e?mcu zGsXNnhyAVW-phy0&M}L%UuG=f=kP#gzgwBM>y_zZ zD#qype}Ca?BCdB(8=3D0ij*n7e96qGm@B>`_3n3L^Pdqo2VFo%^usnqrgBeMcdy5; zWjggUDOub!vPN^ib+^^F+&%+aJ&cFaQPJ0h z9I@kXKxvVmF*NU$fXtk83;eqoR+FdkKI&fw$V44sK0tpeb{6!k8Kt!1@q4@0nM`wW zalxzmBjxq#&(4dtlWF;k=wC=#14Mppm>|77gJk{a}s>g2-e!P`^<0YwWT65N2n7WrHNIDnk7^uI9sJJ1CTBtj1NBUnAOq?68odz-B7C3Pyxix@VYUi8;?m}l(YWRiSW zfqC^#qeU+HT?$utaFi?<2&Fe@2Ab|ewOEpU_UgS! zo|{2I{8{&L{b3oqfaw)ew#>OYy5YR;cZf+xM@K3vB5kkPaf!824{5odDRzHI?vHbA zHkC|`R~#hNzWa4=nDWJv9J|~Y@(_n04B$t!UVtOzi^eb>-NhhH*}yR%G#aP&ZpRQD zU{wTtH$(~Zu4T4Wz@r>qseJ;pN@t|sjjrTn7y{`hx#kXC>uYie<@ua(0X`dmGK~(E zv+_?FNO2_}{|rk*_GrP|uYT)M*wQ$g=bUfojjQgFz3o36b$!s?UbZ<_9+OI$j<3*e zGG&gNsaLw%(N?S$6w68~yQXPzvN_hOD@_nAwzZBE4S&+fmggq^DEfa)w>0l)mAq*;b5rQAyJU1 zsNA4}j!vYy>o4qd&UyNtt)r+1Q9mmcu^xBV-TB`qxq8XR-IW!ssb)XHA7I&_vn{hj z#0DNL+r0T8Ul>w>hiz>E&M4tsi-z_ix_Z1|S4GD2t)?@q{-gX_7+AWl_{ zPSij;;xA5$aSoxX8WqIr0DSaM5BG4FqD9Cc2Tv+7Q{cBbDxSdx<8-?Q+@OmtWh zZjD}}?4l3Pf6@v78H6RO#WH);U><1i^t^gu8B8_FZ55Fd!Zo^cOOA)E4q;=KVZFB;)qxZ2&+24!;y?D3*dc<=2tlu~c&uNedJ0b> zUtu28T2#FcG|r{Y-BOe0Euo|(_sf`8`!PF)K2`N+$h*2T&8-R7}}-nSKnA}9RPiRwf|U=-^zx3*GNsTiOiQ+jmbWc>twL|8)~@Og10lf2t_UUBM^>OD{^EW<7dV9Bf<^Q*Y9moxbh2PFkBTo4!{# zBaN`FFDe7*@W#2~=MXvb{cgr)N@Dk~uZ}M_?mLs>4g-R(zXm zIV<%l$L_n1kP!0qhL#au2vSj?4pQgBTLt8dH;wVTg2W64VzFG@@oX&AsR2Jmq8Gu1 zPcPB#@AL3nxq~yANzA9V4%bl3BMl%!hoj^iovPPo`QB(5#gk2Os^s@)6(%_4$`?a< zn^#Zl{z#)9un#Rw=TeF+EVa(esX6X+G>|jL#(evuovvQ@T{>6>fe3tl#5f9M(X8A^ zc=9Ca%{l|F}vDNFjBR;`=S$ZdgyS7M?BH#2* ze)LO2*&$rh%r;H6BE2&gvhw;Ahr_6cyuYFnyXo2MH~!B`p=u; z#G>$Qr?|)IsoM$r3mOA&EIPGjc5`hUpBWA}=Pp}Z%v-LVEM8Ae=uY^3`NTl@zeXeU zjj|53-)r%t%}yGYEq&wHu{xXv*P>FI)YjP&Yc=HXb5w>KB+`OISCVMx;;fSL??nKm z41Gc}c*=BlZkeOh6maKabH(E}T0pPRKs@r~h7=BbKO+_tsh|5h8+Q*o{Gtl$I>Skbjb~myED8BJh&hJP&Jn=US z*MX|YI7gdV+t*Aps?4g(hAzlWYBksM+&s5%@x%w7=d@y!-p z{;_C?vfKZ@d2A3u9F=C<42vds3IFOkK=df^G7g=J)45y8JMVe$wnO9hy6uHQ=&!}w$2>8JPoTDE{bbS#^POH4}s1E%*)K`DU$hU>B>b`vFIrDn|DZqnhb^MjO?MsSW6vYS847M>_MtODIlcgT+T9cMc2VbKOTfwHmQ0#p9c7_M~ zV8MID{x(Pgpq}52KR{95@24Wz$6r^l)3YetfrrQ=cf0oAg%l!a`&@%A(Pr--f0inP zp6HmEUlls7N0q8~%XWg#S6Oe)N^B6Q3$o#0G|5pgD$yTX5dZC8s5yFw;LD->KO=W> zHQeF=4>BH?qd+JMZ7$Tp@NA`-3+lek?0%vDF+j-J#Khq5&-YDG>OrG)@e~eSI8w6p zQ7pi{q; z8Qv_mO@|aOvo==tufsz_i>A0+-SZ5lfB*hESnuq_e6&?i1BNZun(>mr=xOzz*C%0G zj{kxKG%Z%<($dmG`j0DlbD|0;aJs|^)VXtROO~n-i1{u*o;BaA-yfIkZ}e}=4|MuD zQtLKvuWQum=fwT-Nt{zL6q+5!%t{S%^Gr7rdWLp-a5I`umB6~~F$rmT5SfLd_0K!F zIA5%oE}yRnnDAgiPCr$ygED_DqXFyh_n*I##dK{)3)qC&VOckmbuAE#?^{Z0- zsj8ahw*+7D7Rl`|n;j=PS{iL6D1`joumYiW1VZawU$G)-z6?i5xJR8>7f=a)&`GZP zBkx(nAHC3zIT3pAbTtLuS6{;_dN-Q`423wK)$jV0YJnAF? z_8(WDv9YmfiVJC1>m;)tf`dJs&r~9OZUG=8kN`$ey7RYjzEhQSk4Foxhx~JcbsviC zuY#ScnT6o}>&Eo;v`Kd%Wcm?yu&7skJz9|d%j0d=Ob=Smm!b^+S~)>%vvf~HIlfIU zXwD&o$KswHrb0tYs{m|~)GpzPLKw(2N)QM>+&%)VT1B6&SoP#-p=Nl=>g>Cg*9$a2 z<>=ixt|4iS=6}IORH4ayKfG^QgaxkSpS9%U=~ z3$1oB_SloY_AyTWzIu?nBzPZ5Hiyio)N8hv`N3mMa3|YmqPCduS1$|qq<+KN^g}eb zT~dBhi|$a|hK{&Ys+P&D8CQ=^#$f3=kT6c8t{+sBDkF&*Tc(SRFa;r&-dcC(LzMSM z;V~=k)iv@oI9XtxB8$Qd@+%a0HSwX(siN53obzNB>2_IYGN7j!mNpSUDy>qyLcf)L zy*GKq=krFE6FBzPzAP<;)Q(hk3qi+fM$2R}&YjD&)bbSz$9RX~2-I?fmm0{G9BpuX zFS#>cug2~NxN*0Fx8-`)$M4Yr9ha7)?uYDwRu8}l0mA+HdAeDf5;|VuamuWb{i_Vv z&hX}kIW0&W62srGKz=LeXeq)t-!Yx`Rgs`gt&4aE#q)JHQVe4y`QbS@QvWQ?;BM7z zULd9>DRXAK0pn;1Q#1syT6ndI#bSipquCNHgo4cof=~V-^b~!Z@j$AlJC7QhbVa%j0U3mJoYp8d+~jtBUf8c3}!d9LFmG41(i!_ z)S5)<+-s>A_kKSD+02DmeuLU1S-$e$ttgA~d@_eHn={{2>qVz@KEptN~zZyFX<_@OET#D1K%A(_HE1a20q8B$Of~m>Xflf zH~1*k-AL>4Zb(E?=&xk;OT-sH9F`hHEuT)v!bVq=-M|L!x!>be)@%g7CRFAtngAAj z<6HB((}^E>p7Zn_#}jcqs^tB%xxmV z8?lYUs#N?qc0YwLB6X~|pTDD*#Tm33f~~&==%X5pb8=i(>WzN@K(31yQ&5(~XHyYJ`qXi=7xA{D)zH)z%y{FyMf^qAFXV z|7*q8XP|XxA9Wc#XB76p5D~4L%qnCzW_w>3?M{27>e$XhHn*Aznx%&tTmqZwuZ%_< zNFsfbNQurnldnrE8W3j_2qqQO!^VS{osW0sI|`K$QaGO%Q~(M4jcVPoS#KH76kow{ zPI_K^ml2YH0B&$6pVH1ZQaTIwo!R((xhW+&w+RDrD2Y^v=hfThEA!zUlDuH>5`Gwn z3`9uGtb2l}2A@o+)TIYcPkm1Q(0Ml;PZtQ~*7liMbMCOy~7^mNQZr>jWn zB+oBJi>aZ9FKQtw^X$MT;ypNuJbX1&z7@evSc`&PzMw!A7ti#0^d#`n{r%pkR-kzx z4x@Qo$P3d8Tg5}pWc7>4hrPO((cW$cWPA?%C)rg0o+v(mGKe4j=|m8gR2(D<()Fpb zJ;nEaekHgh96nA8G5j&EL)R1E4N0ZSQgkCQ@nx!Rw?8gvoTGOVw)wF+wu-A4<#y(S zM{5ceT|BCP#Mi90g_-kh$J1+vpbB_gYGPyFe5r5N=gFvA(IfHTKT1s4?$vO``Nzn< zBbm7e!G*4_!fkqt^LVZ*aGjg)p%>E~O5eMH_9wE%)|9V&c=qYXOR>N*SpquKwkRRQ z4uL$e(cDuRZ}%N>-Mx1HtY87HCoSG%Cu{d>21?guc;~a=lg-wgt@5O*!^4oO!;}z3 znt?x{HL*5pOqNHq;3T!KOT_3!Klouiuel+M3lkGkJI1RQtn!@+3~(a+%}K!7{)_fY z3_ET0Z5HRBEPGuBfh~6x-;3aeyz7U7Dv02nMU%nd{NM@eyN(k=_ua)k4#fg6KaE`m z&zZPc{uP4RSG#9lxxs&rTR49lZ$yXI(P~VZ4m?Nb8;i3(eDQU7e%Q}ChCn^nWH5yP+%38^O5`)g4IR{sq zyLG?LZL2h|vu1Ho#^oN~^R{X8n-Dcet_G|R5D5s>dyFt|A1Hjxfpr?4^}Iu=(d<~T zw|TDs?>xpnUrZG`A6~dktx==liVc+_mL~a}1U8Hg<}7mE{>E?#k!9!?*uI>suYH)^ zYe7NhyV(-M?yu`xnB?Yq&Ng&`JJ$<@7+poD8R5uL?RZ=TINlWf=s|PBo!RW7oZIdJ z(@uWg+p2ML+WTNz%bw0|J*9J@+Z2%wYbfG6u4V zRljwgd#BU{7U1F0q|udLoKn0~&&|ADLf+uOZaL?=vv=z!20o>xOP%c=H4%9@>l|V@ z*%bfW+;5b|8^^G?);t)t2=)1eFY{?NvsN=pV_s+iQ6gn8ut6T@K7ncSJOo#Q=6(Vt z;R8&KhH;oj?p*A}ae~_US%Ul0BBVE#u!U7km>qtPi%kcYrS`9V>Kj#gpn03Zqa({| zi)|iB%x&Swi|djKl^K8z;bkb|E|j$Fc|yv`vbUQ>YO2i_xKhl zx`l{z8IzP0aB?Dp4XOqavLc#lLojq&z77zn-?cOujpiM%Snal4A4>smi|D5Y`mlxT z2x(DFKi*@OUwj5mZZ&weIhj+3fEmwgtBrzlzEoKkc?v_H`zex8ps5laXt1WF%)GEq*F6$LXbuqdkU=_<~3%(A4G`@w} zvqhO}XHr|Bl-^R5MiXm?YzBnwT2>}H z`aTv8jf_ka`^8M*zUB>_=GczoCi~5)ly#iqW6#gXyy3ZAbt=6dKjMA$uLKKLJ6M&r zIXr!vS%pv6rdjhD^R~xw6g#b$Ging&>McCApJo- zHni3f1*JEOzc7ds`_uvd=D;R4Y~YSKYtwPvE*Rb58k_;P%5C&!@ykNKr9oLM^N~pH z+UZ=-b~q$${aLJs`1E5q0vxe*2b%}fY3X_apj}1rk6SyS5!NlDxnLd^S3BDm*Vg0) zS|vHcQ9gw7o;w}9=z!n{Xn}U}UYe`BeYvvbh~^)x0MD)V?qy^S6pbPYN=b>V{$tYYkzHg(MgZOdqw?xRm*#>Mh%ep2 zP#p{R%LwaA*q@x7huoedCrij}2zGIKUc!5{+ZB2=I5|4!aa-Q-BzFD7uqp$%P<^xxXfgo=kpy;bt!j4S z*@nMR$XT0~oV30ZWtBE5o7!wJ$P)v(3YYhk|BA8|op>0XmQRCSLN#>l6C0T4xlx_H z@4WI2zL9QtKK8=}jx-;4>-|wpzrD9aa$!cir378Ob)t7EMQT|E=G4iiUvq8nvd+)w5 zkp0l7+&E_;Jj*Bq%1I9-Ehp*=OEi6+4PooVerB7WKJbf1ia2>R^v;jcRUK#$xvyRd+rI@6Jo? z&KbcFV&rqdG`39`3!9k~sJRy_29@&7aYTf` zf-F3E0xZ%QGbeWqaKx-7&Ei-?le1u|;r;P5b3Lw}Vr-Gx-s-7XYZIUL)HALL}^NdM9Ho-=~*Jx~3H2FA~8{zjR5Dq`9{oi*Ye z$9IF=o8+jEzXhdsmbrYPU-)=ID6+9BQirHb@px@)d_<8GXi zQwEIQYm#LvL3iI>#?77)bFOL#?@$+l8w8uaEoFvZ>MvyR+Y{UI8ddf{7F)BvuB8Y2 zY3q{9*?K+GpV2v`;uMQF9DZnC3cuX6V2|q|Z?PbGqq>}HDD?v?j7?!&Q`JvvZrn_l zJ-Oz`^_ULo7n0h8#s^J$*3gurXVH{+hTf#6555{kf3FoY5he9w-JLI}V^HDG8AWTg zj|#r8$WEwWWbhhCDB^DKKa8a&+R`Z?yh!Ir+JdHsn_W~(?obNJh#3Q-W+|@LT817CYx# z`+e9-c!=GqR|_DacCA2QaI84;bS)4q!hI~<^yo~lPXeIblEe_dCj)&04Ia@ z)8ck;z#3!S+>zhl_%+aX=iDgx**Tac|CV zX}02RS`!fkrc*PFuCwxb z{qtvwuoh8Wb6rEXAGhRGbS@V!&bh*lS#Io-6U3xDOBjMTwKZKNBTtVJzd2d2T0guTMC^WBizl89Pv&e-0Wm+ATKJKp@1sL8zgg{tY2KbzF56&tyHOFwz>6tq-- zvQ^&2e|*Um=w>2@lyKf<|F&(3Obp)6O3H!wVUIc*D_iF`h>@BPc8mq&hT-^B&5xA` zlHmy^H>oC#D2NRl`IZCXXKOU>bdCY&j(3!50MbDPp_)hH4c2u2(O=SC7 z!X(ZY0_L-X3{L?Vywz{%cTPSnYlCs#k)I&Xkz-OJF1G=up!_8CbKKdyAx_S>XLM(H zs#MWk@Luf{0~$vN=65tNvNz^GgP)fL@TM11#%t zjn((D5SpvKA82kXi+iNr`SN(mua?K8VGw)h{vwqKIw!JZ0$RE`-7DwIDY|jN(4|h1 zsh(x(Jv8-Q)G6Bkwvtm;Lb*s`dvG#_eVEI5 zl6K%mY|{Auy{9t4z`t$KNnh62Qod+wFX(axzg}RfwqQXi(r(@7YpaB{WjGl?0=;y3 zC-lw9c^oGRh_nj;cT)=3#L%|9#NwWH!ZxY*+elHKhEH+2 zaMAT^try*>f8oqIPvm^uEbJQpz1MU>;_L@{$t@85%H(|+yCo0y%m@*G0qD3*B3|_V zDdN=Ab}hSyZr9nG!!mw1y{I=Di?rjhlT0B>8Ys#_?cU!&t3w9RT1mvXOfbRuc5tk* zpbRvA{NaVqBcj$FCGBJep>*lIlR9cgDm`4b!VyhWs2EA-&gbLOr*8~+0b%c?Sfe;;F%!R}U50 zR^{B}u$cSB-67Zg&DhcFT?$$Q^vd~3;rK{ew97@{ejfMB#*2h=PItp{OT`EHnkVo(b8BOc6JYwVo~p{b*Ng2JtvWVN6o2UBN!2_{J4zAPpz z56;{wrC8)tgDGjnyPNbj%sjwM8sL-mU^q3^vb$QYq;~@2kuSeAfOomhvo>~rd!mDE z*KGv2u1@uOj;w0Ii^n;@Bpk^%m*qEtrTva1>D|Pulx<}Owy%h$PYqFsOl3AfCeU|9 zuA#D9;o4CB?7flm^?^2rmyTp+W(|pF1wB&E_x+tj&WehKhFr8Mw>_KleW{-%r;|j#SI^}sBrFX)KvqPI{%D>sfTd;dk!f;I+2vHX)I#wrRT1z ze|5xA8})8Sk&vzyayK9vQd^nwTfwT#(U1Rc?`WNKqhM*{^Xeg)Q@mg@|GDsug#d=6GlHXD$BT9^`csY?AY-d#6S zY%iZhMjR zxNK%@Kjc#KxG&4=CN(rGRK{^NA;tqOH52|*x$ev>gc0Sxh)NXx*&FI0188{iI zL6vJ@SBa{f>9?!zF+YKGHG4kXl*U|=X{7P+GziVjX6JbaKiJN-b9jm4hGsX_c55y* z67xyp&EM3K5tGn<2OJ{&eCC0`OYr%A6wK;abY%9erO<2*CxW|?lJq8$ee)39pm)dVyXW;2uN{`YJ z0@<4`Y!H>%PEB>SKKS=H;^(<^J|!cbf*V?}X=qob`bzO?9lVh^DAulm*?% z&~`jNo+Rhg_G^UPa67jheUftBKD;?W&Q1K)<`lFfx)j#W5(J`cf^Dz%>#NGF(}ifZ zAovMOyoJ^jeEb4)VODE z=F+K#?Dm#V?=I9cL^s5wsR}c7g*gb%jH3M1v0R;+PDmoTVMYoXk)d;A!TKg-=R({k zkBpJFIxWe(9kG!O}XH+ zV2EcSE%cy;938$4)n-%pqsBmlZ#}w~E^r*2pnTLu9CCZ;a#9O1PiCd-pgL|p71$ch zj$Pby_bsvFHb;qR%;V7|D5AqQ`S`V?+m{|WX#;A zP&BI-rv4qJk?Jh%yS&(#RO=P&J0{MCw)3_hlOV|IY~Sr1n?LkQOdmv#hYx?hspsA} z5WyEOPDr;iX^jOfF7;^Zt$=4ng<;x$8|P{$nY0-=$@mvcS1 zM_O@L0RoP|-cJ-lyK+)?|6kL0J%zwP@+3X9RKw){=?H$~Cgd~vxu~}D18Rr`V6^6* z6N;@`zQBhoFhrjpC!|rx=g5q8_T+BA7V%eMG2YH%6z4$(7a=JgdPabijope!b3KaodR) zO6^yIfZd{NE~_i|M+yesO*{+*KImTsColw7nBgkf6N1(kIi3~1Mi%6TbUO1lRIY{{ zz?~uHZo`tH#L)x-V>_&oyi!f@WWi8h01kQvPFhEr>t)3k_Fi|* zcO=Ut2e%EIeR$?fZ@cIDMZVd5cHkxFFUti}wuFv^?_jbTQv3{3teccGQcL4yR5K!U z{A3GQyQ56&Ea$O23btM^!6@zgZ*GqeTUp1r1sl@76Ug=LIx@-j59jq)=rnLoy(b4p zZN|;91I^8`xccjkKibyiDwL_uR6`BdmF@s zv24ASlJhYpO7H*kJQO#orue|t)ynS6xBgVu{SLb38FDA=s_LQ^q#!+pJk`3q{jMGE z8te@hEQOZ#N@SH67RnXyiW1bO<0^`Fe|*c0?KVs!lT0#iJ7sHESfOIU3Qg!nXDcoO z{X?*Z)d*Y&600>`Ai7&kUzZleny~k+0F>b@q5vwH0+E;J8{$)uEN2c5&0`1lW{}O>ixS@R@$wK%` zU0?Y++~IBM2De_0Du6T{8uBf#Gs|)yC=glGuN1MKzU`^tM@=9Nq2z6^H=unnR33S< zklyJVPE>~Z2H%u=#pYeoR`!HMw!xR|F27C(uh?;#f@-#h$qdNKEtWUTgZEjWoMX-l zFR#lOB}&&T)o4p(>&qC{O;l<-7=A`|u;TH=y(8Wx82A}*q*EYuUlkeF7T4!$b1n6R zS=u|Tg+uF)yS*|7I-x#iiCnbJ65J08f^&bVX!dmYHOJ zB^z)5Z{~QufLU^*->$SGHGue;%1rCSKQkvUY?(&?`=ok65JWABvTecEu6SRV8o^A1 z{VeR}(j_>2N>f@fAIgvjBU^VLM+S9!q7R4#(&r4c9eb3l4afxPhmW~lx-eP1?4U=) zyijd8m%d4-7s;OhSR2}IgwMHkO5KkLdZC;W>#U*cpX?>~$pOAkeEtM@WOCND6QLt9 z$#=Y+J4NPq3bbSJYuTIcw1yUsR9`!riJN|;i@!0NB*lC|9p=1k_7vcaPl;v~6{(HA zYya7!I-NTPe|+L^aRIzE?0l5SKy8)pX+aABF*@TRMdy~ilac?thV7AzQ*sh|`w`!Z z_Enr`ZI@rY^{ggJ-H{U7pM@^+x4#JQwAnwI{-3MuEzieJ(to;Hb%ZH;pnA9bQ(mO2 z++G+ik2XCvSmP4`j>!&f(1i}^&*pV19GA&{Q5Z(`ly;!U#e}j?%uN~hQZO7XkNK-_ zCrKXtMO@ASYN3al4O5!BPsab*td>V@!MmlIRu?-HIUu!76LbV;bT-CC<@#v(Qbp%W z|C#xE{DLsLK-c@?wVF=#=~f$Q^LcmU9x51)URgX)B86Yb%Bj$WPYlIwGH z4vn5#7M#+wU6Sldp8RJXvo5~@w#98Z9u8DHed+gzyapQwDkRCSMJRD{jY}afcu3)| zcxF+07En#e&9CO`V-n};Qs}|SPt118tNZWNuF$&?Q1E3g1L)6?BM(n;Kh|98=oR`Q z-&BGMUxP0z7Mq8#4=FY)VJKmr0Mm~k&ZG5PJ6HbMDkz8g0Or-(!50Mu23pNFKx#12 zA6^bQOI30buf4Fhe`9imUV?SpCq+2F@O>y^Yrw(`I`MC2##W>okdIb<3mG@^iy7!+ z-drsGl9LxIr{Dv%c##|Sq?h2WrUkhwxvP5#eInK~g`E}a|DqDIK7SQehV{#uVU?%9 zu0P6+fal1UHS}|bS|iRUv(BJP0O1*RFBi+Fes@krH&v9Qis0r^KQiIb)>rf89o2Z$~YAI%kcIW*#-2H8~nMt6k*!3ssy0zrksrXQaqjtk0M^UY6&PF1^p;DE}MLBguoW8`#SS>t@~lg=0Ii!hnnRTOiTR*$jEN3Y zLmPV)@z`G`0)G!^6v)t^g>YF5r+!L|Y*Ckdle9uf^giN@3Eu5YZE$4UQL7pf zhC95T!TeygH9+O!Y2}08K&jAtlh=83J0dv#arB$;9p>Du6J{gxP34w-L68A?gO)7P zGciXxpvk1|c0A-;@TKA~VMIK?u(0qRoal&*zav2OklDE|FvlT=MQ`wfJ~6cQrOpUI zFPYqevtPL&hda~%dZg=%9Eg|VFQvR#s$OR2$KT!x&k8hal|a?TBu6SD&T&?=PK*^| zt`PZW7&P}}!-&(u>(8-!A?Jyri)JND=?9%qT8?~rbo{m%LTb65v06Jo;MSLg-X8F+ zj2t|Hq?lw^7JTt*FTMN*3eBLk8{Bu6knuw7y! zx+}#c<2hCRt0c9qge&{!Kyiy?@}2fTEQ>g; zZft98rU~E7maLH$o8~qboS)#HKz}oplcI?&lfni(syq+GobB+0EfC)_OA#DyM-=64 z7rvskZceGxc>+xlFbndnWjqc=rdY!Hlh!}yCBa*n=RccMw%_Lq%J?`DSKn83y#q&h zOtKFYALN2mA7#oefz=2NmS~97%H(j)Krw`E>a;Q`cRU%l2wz}9jj(+-GWD6|6 zvfrC#812?u`{hSv5(UN|0~`|8Ebyn)sP&S`(D~E2MQuWoRnu4z-`RDi$HyPh3+&Bz zrig|qE#>X8yvyvzdm5jL##|TN7m_fobja;fqDvZZV?}iBOv~+Fdv^n!{h*-5ugC5k z_eH;xs08g+VNa@`ep@dHN#GlYwld|VQ-SwC45MAByK2;wNf}|&LW`tbnd)idXjQU?V+lEY!dX1^50?@bQAyVxyO?!i2%4wa|3!W7GJ;heIcT}3@sK{1kRp=rEMeL2VJ*0&tz ziYI?Vjaw6Sfj~Z<7YB^zqt|Uei~DmFSjh{~xiieYGyRvo4=pbpuzZ%#3+@Fgci+Q+ zA`}v0YMAmg8kw}kDJjO^<7-_YGj0KoF1*OQYbbBKU@1O0Ca>dd2A9NdpSHzUMFulPEN;%QwzAE=Zn8($Vq``fP%=p%?RajT~ zi|NwUEZq}x?iKM8UXC1FJ^RZH;!uQ7IeYz^@fL6vhr5Sc`OH&O!g;n;q+hv@7``tm*t zb9WIUd#}|B42z#onO3z1dhuI)tBPMEx%~CeJWZu_=aut~Me37cII=`o-np{xnmsV2 ze3L)&Tlq&qYFwx|h~)toSfbdr)UfB%GkN_^K55;BL}QRWF2xsETCzsMC+yezG4{augTEXb(0OSBk#at z5!>HXYkN|N1yl-p4K|h#87N%95_}T`l-jpZ*Xr#=Q-G{$(g-t4lWC6mow*0<2N+1s zcO6H^g#r`Zdygi(xNFr~f$Eiy4cSEANm4Bszd8Z~jq_p8o6@ei7#*cKh%_p`8)4cJ zEek2-%+>T3XL+#9OXa~>$+!4#9W?$(sWtq1hbx+JeVbUyg~G6-yaj%Ng!RtF4 zG5@pwW{605lHEDfcD;c#@Q5nUPT%)2!*e&WTftjlu7>%845pGBdzzK3J(a}JcMuuG zq(0?}=|eCn-s>zC;!hKvUc$n@i1h7~o_ej-{aX)hQ*(A}&RX%a#rZaukOUeqxu(=5 zSMFtT!P-MSFO*;$@(fxKC^B%=!rSV340@++!tf{&#u}Mlc4wxpe%@Ri2@7dd_D)$C z@Kkm@7EWcNf=->m`<&YjqY5O*KsPIQQTsItLFW7G>2l#O5QD`@A7m9#fU$3-C>M;N zyQ}{1a^cf}J9((HG^u$T4yVgQb*sMUBklfC8wRNhgv%xL6XC%mjrsTucGSux9=cPR zOP!;8s+m?%_A%r<{3*G!bvn3wp{X)>Lh79Xw{A$zpwxC#wDa{?dM^d$+Of$M zbG&0<0zxauAve8r(-7}N6ZISs4dm`q>LzP7?TdHylYKa@TyRVQc?%Nq=X~xCBAQZV zg82D*C6F)9$yHpuXJ-$4t={-nC!e{fy&PDn#p<-j(NlS+3*-aeG?h>KGaK2slj%99 zqLEOakuX)YJG^;7G70EwM#j&_oG?HXz~iuy<7!nN20`798*C%F<%T(HE~!jTiX0yv zg)M?_ZJ}UL;N2+{&H4zs;s>0$5SVSWpA^Nr-jW)AgdndJ=A4)HY=l3qc2&D8MB#Ni zTMr0%L>iBR8{aFF1MV-}$jIycR^54~)bKrCsdubJJ)fQyd6SPf zD9)1<+OnU`GhN^y#5SAX$EQ?o;&W`ePj<^a{JYEuk| zXqhe3EwAdZ)xfuiIdXZa^ibPj!(BgAaVfSu{j*5XJ}mkXWsNHZ-Mth`U28Q8*q&9> zETfQQda8(f8#`~<*|+ZoP$nI{fv^m#=GEHxt4WsY)<#3o36$9OR9d! zX&VKCD5a*h2a<{z&GFZGWH$9vw#8ZYMxha|=A}=4aPFNuZtc+W?6f$Hy0gZN>G<)+ z>FaPnTEKA&RQ&w#Gh8qwsuWNhj56FiX0zHXWeY;_d*$Q@J=;I(d^sE(!oQU(hMj)g zQRXOchyM-^Zvxc`1X2Bb2x94GtexSxy;slpb(6NI%To< zk8X4FueZsI;KJbEOzvYUpU+{c(LXAn|D!R~9Y{(2xNwQ!qEQ9{%KlFish7JR(xz1B4(840*Nrhc?Bvwx&$`RMz7@N;G4K`LWSKK8+JFn4%j5UW zDuj5T;8AZf54-W%{#WEYflH5F7=uI0cf6A=+WuR+<;6UQnImRmEn0tu#viW&vpc{4 z#H+0~UXKvjjxDu zTyOj@9#)SOgS?TTi)>5}(Uo?<_hcJe@*S(=6lgHrg8OnNS8nn>Do9c$@Y*YaYEMX* zyuwc?*fouvNs8Vv`GtM{X;7|6Bdfp7c$8?JDz}KXgM8?J@SJxD`jH2T&|MFaLgnKW zv5hQT{*Qyc>?2%fqEJveLXDa5hk59kB0-n#eM$r(rgHbC2~71*K-7PfQbGIyz445QZ*DUv^*0V{wi0GJZeyrXO+6_U{)o%B_COR^TY9EME$ zon~1b4Z%IV5h$UtqpH;Vu>L_u!&>PVw#kh6UYE1j`A+_hiF!&L;e+1HJwM1<+K#tM z(N0s;^H2uMJb)sz7erH%$04QSQ6}X>o%;(#N+}(6;r%P|WeV09aspH0$bz?@KUL{r zH>pADw~P#wgjT5pZ$L2V{0Wj8c<1QF^y*9Th)#BPcIym>xq(4O`wEHmLDn*#`-Y0S zjmEJSDd`ZqQt!pCAE(YM{kGKblgayTpuX8TVo0~U6Z)DxTf7o;r%p%J`ZMU3R10Z z4bASeugh2ehL;Ztezbs0!D@Qv{=6v#7oe1&Atco*foPnoNR?@*FsB{bVYA&a(2m6} z{=hbdXmWPzxEIxDIxR4qUAqO(WtDgT;A9?G$9WP|CM1yl#ZUE!RWvl5uw5lj#t*=B z2`t!LkQcxyh^U1iWDWwlz7AY{(AG6K57kYU#G;zZWXQ+)LyhR~mz8)5J)Zl#q%Hn5 z*qS+7JnRV_!x9cp_7j)Wx*eet3O|%Yz0wcp*B{uJQv!xz7|wBex`)GdY;g0bcHGGA4gtgOLdSDr3e1%QuJ0Rdoj}$t})RvRNsyD2%8g z`{R`zQD3&Gm++U!=Xgrxsbhnq!!!5q`r|)nnH?3x{T8S)YoU(s%#TN7H;Dyh0<@}= z`n#_`37z*!s7sUReAsYZ{89d0<*52_Ewmp{$gp^4Ae(ac+^i8!AEW3!BCzWB*!-Fi zpRYjK6!9Y5TfySvTnE9O%k~-IK|bWnAR(o>k)BhcA!4bRvQ>7sqNer5WMGVs24@U?YK`TyoK7sQ2v?$HS< zF4NEP&p@Z>cBX_(MMa+?WP`NX_peU--CkwlIu*(aXdmO!)R%3a{{tO#VC$sku7;O{ zbVC{&t}$otk8^lE2J-_%vT42VwRDnzvE{;LS_LZ(joW9#yx?`JVNL7a#o8v-zdQQV=Dg-;_BIO-k7TbBO7C1YH-#Uu8ZNG4) z%JXzI=z6Jsd7X+Uf_4u}Sp2wSKJJTyy#goq+_EbM%6C+_ZKM<;L&Vb)f-b6RI_%%< z4fE#2x(uEWGIr{(Q%!Q$2N5oJveFPh>XGwTzaMv5(V3Io*(B0@ngQeJOOF)0X(MWM zjbS~htAt&*?olq<@~lwVYO;I1z+H@m#{C%!oq+xrO_KEW$_wEc;fkL>wfVcg)Azcb zWpA&2`2j5gf>&Bc<0Pe9fOCC}X&G~f{sE12wrc!08GkS%#mxq{y>&V62p?A1?!2#y zwXV%@5JI8RINn# zCLCkGb~G8jmLhql%_m=p&y`(7;Zq~bpDF=5(-@K!(Ws7Z)|eA`EePOv;9i%lLQIX=}^2$pA`Df60W1te(q-qZ4dAV2U3s+)XXAGy`qh z4LGblph~i7eD0hEpqLIYO&h^ZW4l_f?X;>P^X7+9x zr7hRFrpd&IT_5Yc%MiIAX`RIt<3+h7$wb4*4j~y`kO44ysC9Z;FTUW=^;m~n3HJI# zk+3>9G%7AqAXBV}XytQi)Qot?tOGgDFk9--pOa!AFrFvRSKz*|X=01x%=XY*rtIX# z{Yo_TLJ1V!R9xqZEs0R@l-dArQ4fT*2%av+kFOTCJrek=xDg+rAf~4U(Z{{zbREer z_h;XbS(@q!7}^zkfRE-qYJ=Q*RPA?iN5r^mPis$wi@YRIhu=HqDzpt)251Cl&|hoj zpaAQg&HzdDL`%jT6=&zJm_e1%X=0pMg@0N0fiIsvAqTi)(*|Em z804Y_ShZ{T?VL+YX+91;)=+6 zs%0HES@S@Lf|!~Q`sZ|yH_BC};IUZYk$h>Y5cCmo27*pB6uZD#Jl3}hLS&xfQ&*ta zb<0-K6~j5+<;g<*A`E=7x8Q>HCjF)7BUTH>RYudO%nmq7oe|Dvy3)mmuW%cNK;_k1 z==D4|*jzO5mvI+8#+{wWfDiiu-pTThvz^l#vU?zk{o=+nag{Geu2CZ(lNIfFvTWmDc zE|%8ZLqB3tL_=+T=$&*=x`#Fx#eI`%`$0qzZ@?;Hfe0F7(Zer`?%3i%c>WUOSgHdT z3O=&Myyg4s%Rq0d{as%VNgd6Ec}#EVb% z?v@m6i`}sW;@s%l$kSt2FEt0}yBKR)(|sdv6PG%cn6v{-eQBr~@B;PxZjgdbiPco6 ztwaob1%0hWFwU7mmF`_0Bv@pWzaT^r2ppHCV#%6a>x`qNv#I31645ngHL~L0Me4`p zR}QV2c>c#A5&RFe2ghC1`B_<@b{x715vvDXG~-he(z=1un{7!Lam^%w*u4>F`-7(_Gy9MTw8)wVm9i+v}1^xcQ?t;taWVg(f)+29n zr|NsAO*7Q{XNGF}L!z_nrqPfazi`QE z=7-$z2MT*UpRKX@VXNyvie>Xgl2z;McW~3xs)g3vAzP69Vo0LIL6}EMI`82;zVB%A zZU4Aud|lH{T0OeMfdp(`&W$uF!k;NbmJXjZR=D=LqUb=MLmU&#Y4Rw!Q=`L-t z>rAi@ose#V52dj3* z8{~0Ft=$$jxNto)ewRm5(iCiXhq{K;I(n0l)E}Tx6lh4#zNn2UrkFbXhc4@(HQJNr zw;Q3z^_*0tko^a#qD^$1D*N%aypg}`k_s#hrS?eRq2zlkQBCs<2xCkVdwO|!>7SS% zc&4ghUw44l^HP8Q*OeOU#UVYB#`+-v=d1V}UX|#VjzRH1LH(S%Fm!Ji=2fgLgzXxI zH}Warcmg!+@vfXl;Y%7!k=%dfA*xg5c-Ki%-$<|Iuz7z>@)R9(5Vr@@puWvC2KQDg zuu(3}xDJ~p}Q z6?xjbA?7fMh4)(K12Q~1>6IvvLR2D==u?I0WO+GyXp}sDr}A0xV^?<;pIfRF-R-Cs zhr7)@LN!JWjhxUoYHugePtjEIKle&mjCq!T6{$dU!TPtY@9eaN7Dmy0+3mVkf`O3&T*}PZ7q<;Nqcn$~>Hq0!!?8waD1pE-C z_!>we=GzUbyIDzI$J+K3%rZ3Xkry73y~yE9J_?XzMMJf#pA0pN2bI4KB@+vit2G&4 z72~g&=ut5dmvY6e^yP|EVM=IiHJP5B{odM2v`K2q#=Tqti>d)YR+_!`6Nn$964ynl zNWnNBc3MyqM;0{|pUr=nzd_I%1)~+r964 zc#!gg9F~=NlX`M4UfTm3DaU`~eCqAl8VnkKR2filw#=kJzO@ zk+HH!C-;e7YUR^F2wuOYCk;Anu`Iq=NOzmA`|GA=c^D7`$?v6hsAiMubIfWv*HC>IvaLM=af-GGgI$|Ppfa^Qh{KCUR%F^tQI!+%KuuE0=(A zoelaW!o*zM_g#B+SkUJSK`8m_1{(M|35`} zv*hb3KX^iai{C}+;2vn3b|PGHOH5rlNXKRFtB9??D@M?vRr*#^qH3lRj~RW#HLZ}l zG@Q2<{=3Yq-ot-W$IyI)aJ0;(H0&ylX6bn1{&a1=M4p*DFmJce7`5cqZ6dH)mA z_#+jjg}i~v&hlQ~0(EGo{*kbs6VO%#2h(ev#t(zQ%Ta1PE$_gLw-4vzc}5k3TV*-U zJ-S-brGW1(uHAPDf@58_ndVW!$VCzH5dk{i)hFiKs{e|193w4fe>fY_8p2eY$T>xFxwdXv*H16Y#?J~$ z_@e_GNSvAD9#5Bc!=ng1uS@JI*em^zZB4n2O%d)?yo1bGIV4!Kul@&D95jES0>xNH zQc0RyZJQhvl3;aH@bKe>maW@AC?Ee1`_6949=;7P^nRN1{Pwj|r#A&>h2Uq7m? zv)P+&f{++%TOL*}w8;2Se&@riJOu1(K@*E2ytzZt=O%nsf??RN=gFEJ)dC+Tl$%kl z`?+62&n3Z=cOoC?lGj!g0Sqh6|FwzNsgNW;qQJzUl1Juo8+sE#wiGnUK*iK@4qp{pQJkV2csLzZ^837WCm7J4?+t&Y) z*DcSvE4fX43nRh7aJba0mQ)FSm|sn6=C#*^UWPRP1Ii2gZ9I$Q8X1OQN0i_dwEIvb z)8&g`BA!<%8hnx|5iBa6=rO{hHLl3l|4NM9rjj` zYNuU`6OS=aS19p+@?j{;Bo+HvU<_+1%9lDAyZ+(M;W@2e^^?ay&y)*J7O&G*O8TJ! z=XO#wPDQn!p1RmZDt2#Az|42W_{M(>Pn9ln4Lc68q@EIfp}KcgR%DWdUzw{FXPuo- z5{W~|vYsteQZU4nls$@+oF( zP2*?wD|Pf|zMF>XU=>+KDrNGtTDIl%-iJNyb2U0s3&~0%iZhx2cej+SUN^sq`8rd$Ajm9WO=)LL#zWxe)JMjh1>-IW(G5@m()_GA= z88vC?aGmoZj^`hq{(J?i9lb8`Q0}vjmr)e7A+|L6Avwn>BcnEUn5wJk+x>_b!Hw)w zrqNl~_OiHy91H8@3s@$5@PJx`l#hy%ezW%!oURX@m*EOxZHV|6;Je5?yaNQD^ zuX1aB>@SL0ZVrIfmv9 z(3kx4j_ixMl1WBreoNNOMFEI^o1|Q&r-8>=|3D25l;*d)KHZt}`5f105pv4j0{)b8 zVRw=wik){s!iKyPHC(%x(v;KDNr_#;UxEK35*(hDESxnK2x2+vxOhLEA^I3NN7)V` zcvyQab~cGS4JT79RL_<9s5fIKgpL@RGZg+nL#{PMxGXqi0 zQ;gw-fa_}5id_JvSm;|8e91MJliTp-)4TmsG~+_T{@Z-^Q)-jgTL{_~(P@BkAE0;k zexR<5I-Ooy1h-rQ0=Bld5pbX7()eUEHnB&jtU>5{%~oy5y=j}(Kpr+Gnp}VP3C+&| z?v8?2_97Oy7G+U7k>7UBPNoV(Oi1oT&QN#hS;i}_YfTi;5Irau>eEt$6=hSRc~1;~Bg zP)b8G40K%rBP@6r+(evm8HGf_U5iee?}QyMT*~ilJ`pBduc=Cg1lMq`O;KqI-9kZly?K&` zp#L0TWY!lQI@jktzAXgHv$*Djbhlzvyc|AK*o!BB1AP803Neg2Yx^Qflg`0dk**^B<@17IH`o*{Ozx85%O`3? z*3?3cE%8Ewg>ZyIDOH-sRaFe5_`Do(qoyf<$S7MC4$oL+bYxreixklrbQPN`xRN+c zZ{is63?^P{>(Mb6QK_UFTx>W*)86p4*kP2uMphqrzB0WEVD22eDi#G}L=2V*2($0` znQE3}e685SB``*`cWDqCnL;3=&53zO@N(2*x$j6q319uv67uSvh8VkO$ME-$+?333F*%vvAHy)PHN!vf&Nm zC|7vOwF&fJ|HVEtDJWmB#i*HZZqT5vFI}%Dz`o~^R7Z zFX((Zx$*9WZrJz7^O+7T-c+FCCmnQY-!m85Ja2W5xveWEfeh(PL&rE$OBI*AtR$~F zIeL-)ub)gOvNh-!3|OX+B~`Po{99xXZbBoj(+RA&t)vkk&~E>Z0PxpA^YN7u+X0%+ ztNQ@66<3y=#RN_Kx&v+E+iRph-&&It3|G!SyKn5OKYp_idv(J!tV|$NL{V+kyPBvgano)t#6j ztt@wTbv4iXSSc1{*hfcPy2$f5YUI#fh*DyqrhoCEAktIvIh{Vlz{hwuz+Ap8*PII3 zaimkpz;Bgn>0uY<*fD0U-lxw0pFYbTgc#CA#6695ZCiF z+G#0ipfC zl^>^Ms$vVjX)*uuI%pl*cTnk+pZIS>i^AX{p*@lloe8k_lkSdOB^QBEKK9qkze3IU z^=-suY=%99N5MjP>4KK^`P;Ava*BB=$sJ{Kh~!y!)@2f~#Ek9WMwpB&YDVyH^$)<0 ztmcQxxgIm*O95_}kNIAgG-G9)l(B617^oL`(F8KGy5nC|oencV7NJzmqhCo&C^L%5 zg6++J#ma=byZRgI5e}EI)b?T3rctD`x&lsSunk$>9x{m7_AV#VUa*fwTa#5hx17Xvbh;90V%&J|juk{i=mBtJ0Se)YJIcgyVRU zyfS$ySwFBjjU`j;W{lS!{IFPsU1B$_-CpX=AG0Sz9V}^gdsR?iFp(kc-A0LtZroO} z@Clp3RmBnw)sBQ{m@ZuMvFGjwRs#hlWsL*1F_KgM;eL3hSdO^aUByfVu3|I?a%xgg zQc6nH_BJ&3u0^G1%n_ZyR_2h|t;;+irx4>}oLEZ76OZk&Sw)5!PqK*mD&s9s*i)%~ ztqPeG5lKu&d5~-|DVPM&%F~fO4P(i(`5gh#ZkJEZx8H7bbx8YVt80`KNT6p^OW8|K zKwhvQe!_f;J4BDYNu?$=I4IN8l(mqloxUEN%uIfdIkw}GNGyy4xfR#$aJf6TGtUrx zmIjjT4EV6CfrR;IXB$NZq*s-o>r*57`pNj>*&|}ioMV67U)qUOBKOUpHqKv z8xN{|<#?_#1Nd$6go}Z^RTMSR4friix&}MJp87-Lxs>7eNX7+!L{pUm2j1k&xHYLR zM`G;2yLLZkS0?;r-ZcWnf2tBkwlxJ8bInSb3C0kVlC{4BdYxC7>3Wl{9ABPcmcCu3 zN{vB|@8|}FhpozC)7K6KU904&qTQsVp%GCCCVdxb$xPyln16iM@{f4Ga>>t@o5F^q z{mr|OgE;ubJAj&p4g9ES#Wx5Dx^+5jLblOj#}Ny$`hc5uH!QB?7nEV-CvJ$<&(7SG zZBex`jlmItkUT}p{muE{zxqy5Pe{x9SLuOokxMOI3))Q5*&vWB_Y+q8)K~*z?9CDJfpNt$?9G?`A3vRr0oa?Tna#~CqYFDBC=7YZ z&vROf#&6H0CIbyP6#yn_I)0=)@7vzGC@kf*#s~q12#whdLi=Q!jfv5wEOBm?l6a)eWh>D@hrVd zN$rR0&GulFt$r1|$5j_SNCS?SSHXT&7mRYmVH_Z+S}~LTu>T8=>F6Ku&+!4p5Qma* z^_#)Oe_P84tifA>z?58Ntf}Uu^?K^s&KGt_WXt>l0jqm{n+Wsj$w@l_igoPqY+wj% zNEyCW=sMX8)_NnReLF`a_ULQJ|KeOwjk%HNO#PQ%!gpsonr6J;FJ&X__3G&r-r^xC z>r6Vm&A6PDx82`-H}fGew6Vc@Phy*zS*^cFo|N6wT!>Z(-KmAmWz3;!mhsrRJ{xHY zyT&PJjCisRIZj8S zU64P2yk;GeQfq^}_LkFBrS|HwtBvm*@=zK#2>?(=<&J;g+w(~*P)P_DAVs|5NXo$x zv7`(1oQd&1?}pK(C@!%EF}^ekd=|r{RAg!!!Ox~qHWsl8B`01j>~ydgbvN%^JZYf? z9OMkberVx^=Abeu5XdC8guaWbA*yQvCZ~!&n+^C{49A;s--onoFEOsgU9$Bq@ zu{ZX!BoTHvFd!IvDbv2y(@475g;aC6-o^g&K1*ePZkPo`P6n$f<2lhmPw-PiyTJ_s zazhE9|Cw$!k&RPPK_}T(WVk}K2=*8*SOh&Rf4Yl0SaNjj@+|cjJTQCT^-s3aU1bEH zA`Q`DPO}wiPn^;I;nkfSODVBnBMqYyQ0)}|DS3<1oLs7T-plu~^LAt`zJ!c62-zrZ z*DkSX-+ybVQC}$JNj{UliQX!c`#YP09YT{x2tdCGJ!}fFI(bicb4{p*Ur{om)s9kwWOQtZM4BX=lKF{E@o6B9=k6+|egm+vY715j443 z^gf*>Le$`Be*yA#%j z*+OaOzWkB&W5JvKoD`USj)X=O zBcx9)uvTwG*g3YrMiBd#I@}LD9sXb#b6O4)?l1N-I<$kSo}Pw|pR2lcB^OLXmeWPV z)n=NCC{;)48(^w%tIzMkeUN^^z9atTr1Y}cmVc#A8xbJ1${jf>)*6 z{t@MN5AylDg-Oc9`}rkwzMd5qFGEO8nLI=H1<<^U;o4HP%~gy}#bDlohiDOr^h9kW zI~=2j`Nvkt0;T$(PQpPHRNYG@nJk6^@**E7>BmHLe8_FA?`+wB!e@)Amk<|?XuqJ7 zn)XphCW4A-_kY2&^8Wi2xnug&$Hlc!w5YwU=7RQ6#;n_GvXMzw0sYx*K4QZ7Re&_f zf7TWS77IJZ{G(vDW*FBDoUW^>A4=0#$~t=;cHC?!MD~0B)jZW00r}c~8XK75xMH%F znD_7>6>?hZ=18;jR7Dqg zK(wi#P-Tk6>=8a&Lh67k9|*IMi-f?#Ubw&{o>Edo{vyM98-K_QVfWyv)c>fYw4|(5 zJ9Q^5@fi?R_pt2P|Aie*(t+44x>+6hd%BT!hd!JV^k4pn=~f?HF{ph7nT?6|(I4J7 z$GH8We-Wq4BHd>w6cCB%F+E?(ZXc!?7@E;KGX=~IUD*sz1H>Db4;Is7ZVf~u~O zy7l<|Jw)&ACI@uKUqVI#V8R_>@eiPk=ewiAcBfCe8)OZ*%Xk=@*D~Ge%yKaTxv$F| zNT09+InYjfrLyh>6AA22T^Qe@r3z5?6A{ADowEh1Y`u;lJ zN&;z7T^Wrgl8ZYnnMBy9j7@EH7?J5RrqgILy~1ny&N|-^ncp20a61}8@~vYnjT?he z8*LBaPChKUwZMqt$bVWco5enI`Tob16NB84jMw{Qq~l0tam~_qS0&mx@XZ*Y*F>;& za%M8VH*8Vr@Rny$?ln*tzclj;>ft$^; z=PbK5*D;;amY9$Hd6aGE^SQL=c{2-}l{*G~$^gc_N1C}PAP8xVbrQ!?#vezjg0-*t zjRLTTMUK}CSSp;y(8N`OCK}!G{H9Crc6}wwXt-QB|8q%3#+GP^R{`ZCbVpsyg0?v_ zq-hWhYu#1qJU$Z&1!C)|+`y(jC_|=MJUPsre$j1iql0#RMV^ZFm@GYW-Tbj}K9*_$ZP>@wXGA$(3?SB`T{dm}8SCHeI~h<%B5J%yJr*pL<@%R`}kWtiCs|B=W^S2S6EN=#jCB#5s~MxWjUq3XmBV5@qdReLX@RwBGyF`cE6p>TE96@U63`&yXqGd(IKnS z&4Zo%g&P({AftiCZD&7lHr$9I0Qq8w-!{K8>n#dvwVrCXOAUgUP<M|x5(`rB98$FxzimoTeq6V!$O5xLxD|)^;JCzJ&mS4O|JAByd+`{A91w4I zUXbZo@F+v=*OXt!KYr$};l^0l>2&W34qGj&w876eUaTJnyf!c1SRdhcADw-l;eC79 z$zdW+UN-Uzdlz_X!(vwsyzRf9;xD4feE$V%Q~V1NXuox!FD0F7&cRCG5q|9XiFqiZ zYglpzh6vh74-DLRnR}kRU#`9_?u=Gh#p!RXDm?N>|~I40LYCT?9y)G3&z_pNQfxVi?{emp~x>EgN^Vdd~izgt8Qo!dPFe_ zq6s@kZuJwfN(63^P|7R;?Bh>b>_v)L;3@O&_X86HH*C&J0X%SAZzyd=S`+ek7-u<`LgAtE z)H*TFgHXpz zg)@VTkqwm=auV-2#^JyM&mu_t0tb8?`Cqf+T^X5eVquB9gj~#(^oR3pF4jEb(|F=C z_~sCkd2mKYZWGhxHmp%(YqFvfc*;BXXQU8j`BDvOj~H6zX6}H(OP0}L6&YI(KP%*F zn@bh4s+S<7S-M0Y)=jyQM{Een*;cTuRL*gC7kjje_C94!@(B27+HJ ze)$z`s-H5vZ*7M{-}rD{bLBekS(KB!ZOyc zxX%%g`w~=!p%+uRydX)}GYWKd1Sb<-4y-{+t5>^z?iX4}x`_L80yes*pfh+_#Xutn z((uJc6MiE!^!z5+t-TIocOqSc8iFpW1yl+2WQPHN3_~jyKx9;xC^SiPD6An5)36(O zIE;}MxEyB}cYYJn|o4=mWzs+C>RD7SDmZw)Ovhwh=K7_m?<)o8sgro$WPI6 zxgvxi{MduGaI>}SXz1K>l1!fwZHXca^!pa~3#RftCR|qufzucpqUu_nV0@{_ojah^ z2MRCkhzMxRS+u`m@|Y^5D#+4G&vZ7Nu+N1Qcxtq4xN`D&Um311k%x2aO?ki4 zUN;i2$6(i@Q$}ui-Tiip_cL#dM8 zb!K-RV>@ngyv=S^Y;}{uu-Nu)XLMz$A137)+iIlqb8*|lj0X}i7g2oQ+l4VgHv`^zO-&L-k|Ji9{f47b?}|E8#hD$UTb4$3N>uVV-r(3IFAmn1 zckmV>>O`)ZAE>S_)$%>h0!Boek-zt2u&h6MekSquCop`r#!9b^D`^N{jRh8`uEnm+ zL{IUw{=SM%DOn4;VuZzz+oL!Jh%T*?T7b8-b$O9VClEG^XoUyWraEKO7&K*2un8NO zKvyUxzr1*lbo(EsWrmYGwEFiC2RZ0Bx_^nm*SI}Or>y)IZ=(SO)tLR14`wJwg z=g;SVwL@w)bhS5`MKj6w{MF#YYmF-Q=wOsz#7<;Bj7oC-nO?BPGfW4M7bx)0VS(P^ z;JGeghW^li-G2W`F|Jtdo~co90{MXSR%d~JEXUL@`~m5U_}tFm@{{2qbKYq-DZGrl zP6ew$o6i#iYw1G~6>a#KV0g&TZ%hQKAMQ878|Hk!@5BYn$KljCzf8o<8Gj@XV1QAi z##dpI%!Q6iL?yQU=eR!P(3?JZ>%go(H4&qA*TKEtk5F{JtkbA3T$U8;gwyWVCPCHV zIB+a;#s}$QCUp}95C@4UKkcX`MI6=Gv<5lHa&D6{?-OZvt9_bBrk^ef6f2RZ=lz_Z zLX5RY;l4@&V4yLHrm_AVvg)*leIqILMmER!Q5kDe!rc!ZrCuHz+g+-_KV%3+Qsuh? z{6~&)mNPZrgGOS%f9c$MI0L##rn{=K`1ft<$Kj!;&>M|U5@8aGxux9D$SL^V>@Gq)*=5@jL~!{ z_0?T95o!^puz|!r#E013R1KdZdD&;&B$*PgGssu=lk+-$6f?vrkSJp;kBcf; z)u?B_n`%n1xbC3ENPl`*f*5KRODT!3RG<6qfZk>n!}W@k7MIzoZrJJ0`$@GZ!L<*;P%)MO9@|j}tEs?*^`~$Iu6&f%+YipWC^uO?!@X>OoNc0Q zVL1j4JbhYRi#+m*aXAE|Sd<%DF02A!V)u3bbXP^eL*XpkV$=KA;a?Q>eK?KCv{ z%e{V9&967b^s1qC-)r06A|EZ@z-XcrW<33GDit#EeJkP4nOz=q>zTN{;#1?Go(n$+ z>H3wKo?&d)u<(+GUL)&?2zZ^%J18LRz$t0g6e@1V{rJefcvU?1D&1))+`!&w5f4wn z!GHvDjETOBiYMi0MQ$fEA1+kql&6TPN6uB1?1!s0tv5MeSo4sctE{0|p%Pc)uD57J z4y50WG4%pp!*`}hUX!+V2CR;((;)_|>+mu&o`*#78~mSil3!=NZ}mKK`$H0fxba>7 z%~`Lt^?&q`ka^Ov0P-k_j|>_9keVUCn1lbf*tJ(GuroPVg&tb-{oWe@36HOvhJ;99 z39O?pR)p^F@tb;NWW>p|`*WS(Km3(Xq`tE|C9;Ox;7HNWUyIQfOp364nTNY*uWS3^i+|WMs3r1NMWX?N^v%dNJcAH zqc%#rH&}Xx(T*oTH-c0omlRvlrr$2qKI7pqrLINmSH+=expb!(CTdf=45Ali5eEs# zf%HL1i*z}Q^i+G#RLqgb*=;vDJNWb7zpy{K>(L3d3U=&Ks)3TGJo9f#l#dUZcii`x zb+KXR7lun&R5Q54y8kv#ce%nv@9|-u+#(jc9@J#=Jkk++jRThK$MYjcAFg!gB7#;} zhsokk`-AYC54Nt5AL|_U7~MvHrno@Qw1(d0q&t2|m1Hw>z)7$Ans_kkhdl0Dm~N5# zD9SW@`Bo%6)R}AGa~x=y_RYXmtzh@B98YR%%`50zRn;CbZedn2GJuMk zbuzoC;+3pw1{fR_hkw@gL_my$h#F~o>>ChT_}R{qt6^flPW{__%l9Obau$ACJhR~o z+SeoUMfONzy1*F)qP@3_1I8Zo*H35z_ez39fS-)tnQo#mnYgQdFiB0p2k{5J@^X?-C`m^TkHn*yt6yL%)&LiwJ*^W#NCFfkyv}T zHWqdy-Qjm5lS7C7%sdr7!n__*iXt=&V~QaQ{f6FPNyt?PKLRW8_1q&HpUF$z?qr32N6r z2txji1Ug7wp68MsI}O>zG%&-+8{r=#n0>TUzTIBTyIH)z3|I#qZ`uE9w!oi(X|v7u zVJo6-Z$BrFI?e;1)%ZiruPrznt5b7dtFPdI^RyG}{kO#kQ(mbh0q!pF#2`|ooOeErB$&g77HLzEReoI@_%Q@%$b&^rD& z7T0QW5%p?4NyW}pvc1NH_W|KQ)4K&i+k=F72@D$5~ z5h8t-fVS>~gtmUK#FSxQ5|-BAFDB1>!y}*X^6|&0mdXC7d(+1kyj^c1IacCd?nFDD zSIrg`KNJe(>d~Z0mW*1F2nDKWq5XUKblpszVwFE25FAj;jX_`si00;L#%~RD`{PF8 z4hH;Yr$P#JhzGSII3jM54Uf-eMl_2vrDMiY8b!7s$f zhiMT(e$el<%fhG1#&xSwlS*eKb~RqeK-<$@Pj&K zD`)AzS&+&4o0#`Gx&D*vSeXG5rRT+L*-~9S;;*>V1d=>ce6A++*C&tU7#Rl6UgD#T zPX)C@GdMYkIXPi}#5;^--oM_Q<_G0|jqgIU*i(^z{sBGPvl1BnLl>EJ4W`5bS+!nO zVu$4BaG3z+8Bfk@MyS>ZqE&4YSJ7bHA7Z#rb<$+sOEnuTG;Pm7#Biw4Vw>3o{;I^M z#*8DQx<`Q(cE8G{N^wq2U-;e3Jn(5&)6~ohlUK)(n794=I&Btt!JNq;!DYr~p;i)58GVt7xS;Wt*C43<9Ys{brN3EtWu_EPs-C6c)vG>%WL{B z+$^Wt^4y!7TT(E@Fw2eEz(-i*4p>`P%u=e^^-z&M8x#91EqSIdK)c36=Sq!cPeNSj0L0q4>b6F>p*6-(RNwU-2e10BxX+M ze;4*y{KA_~5k3z(27}+WpnB;xHuVYX$Dgp|l13o<+llM~e)b z0>)qAZcvjikJnt2+WMPf^_0C(Oj~Ui&s}tkMIR0%Z;od_fvt&!pTRm0yMHs-9_!55 zZVxX^1`q4$&gTe73O+SjP4=cF2u2bVbSE?@ob;YK!V9z25i)5&r|z+C7TqF(5CoArjfW%> z(dka53Tx$u;d<}!uQa5g;o)!w*55@;|8{Ua>`gHbE?!%bZS~QLB_0CcQ+wQcbMWs71c~ck;z+&S`g3c}LPE`D0Z3$!P+lA1v3x51why%q{!P_}^MgE}R~ zs2UOKX5GpbQiirxLq~V-rY)(7f?;SUtXWMz0E*M_JbGV#M*YC>94xP2;LVNv;mf25 z*-kd$G#QYJj$ydmq!5XnR;?yJ)pz=)|F%80j{UWQjF%5uTmtzG3s!lK?EK2 zih|GjZYS$`X;lmsLO`hg3ZaB#^pp8 zEaFC(rsFEoM{t!Pc@c3~PP>sj0!NV!$+M@aQ%X#NB)iy6eMb4-2!h^s zVj-~`pL^N~Q)vB}7cCG!ciap*)8@y9ppnL%3*LX2m`tr<0Ik-(;uZMcK+?Lpf!e91 zB<^h=wPcJ(*5gJ)y`u zP;XA_$MHDCukM|McQeqLpskT`pL=a$5DPugQKu_EfBMa5L49(0^0Q{J->We(dJ*WK zlMA>_K{mEaCHon;_q~F8_-pTpWvk@OpO(@cm&kg_71;!aFf-JXSR|0U!be5$C6 z0)3hkBTjga@y9Elcu5|m-BT19;nQv)LM4xB57$k^+{4uei>D*~xgQ2FIJf2#Pq25IjW33xn-Uxl* zo&&ddkwlQywDt@B^jOT7Fc7l3IA_t|r-DUmRLH){d>c?r%~&MIcZh&xn9bxf<85ew zUa~XxIpwFq>+%lWyp3Ly5U`6TLWZ)kjM}Xn$`9!6b zB?j`FL3MaI#Dv^k1l_goEqyEKrug1ALRFpZ-<@X|0-V(>`q80_z$3UK&E~s-I+E-n z^I#K6#kLnAJFd3{3U&OxlNfR*-s*uce?0qB8r8*BERt3&Q@|a?Upo;L`ukdAXT~su z&qRiW`|0+#w4#T|6LJ-UO)uK@_Ji-XYL&i0v|q%nR6&gmGC^YPE_wD`^qBILfqH^c zw@%b!%tEoxy`riX5rI`@qY>2A6*N1pO)BIeY40IO<7-rv9eB6#i~GsLmC~?PsyyzK z-?O`DM9a({Y#&CTDC_M(HE1P{6GCfe17) zc8oN(L|$gI&+u^Q2?P*4-hz5zMFp{AKoh#1ESBu~@;4_aMWF@;#B2S_PXZMcwj!d; zT#~SVn%}{P95)iX%}2~;GG|JisC$KK>|qj3m_sq^(nD9@(4Epoh*O(slcw)#e#-2$ zw`y&jDQS@>B_n%7W!ni-@3o}{idU;Ga7jSN>m%u-ji>e7W$G|O$Jao~Gc2k`6FT{N zKKwp_^sOR*!WFMkgRE$_KN+0=5Dc519c#!M&y>rCq+t&~l?wQ96_>NO^3+I{e|7d& zxE8)MnJ^8zPHQLo@aYjDu$|z?rK;> zdUjY&r`{H~SC7uCXRSmiJg}%x!~cDx{O{S~H2v}V?mrfV0oLbxiQ;HO)sXSK9>GVd ze6Mp}E?)P!Khgu_8!tE3gdyb$+C9R7T@j?g_1_B;Ql>i5hjX0}`?u;aRrDS3!q0p@ zDDv(=$MU~IBMToYr>0g7Bs5wU*VLdUX(QXOxcBnn8N}N;c4GOQ`H=Yrp(op9C)iSq zA4;{_rm?yohc`X7|6vAXXP5X)doZ-upY4Zt@YtR@Q^Fz`A4*Z8?GdId?rE)4#P1ja+NU@1jJLb-YFsc$E1;>{fg26 zApke}B^j~H&+zmQzx8KGds6q(ytC3R{xo4+tF6kbK1~U^UZ(YuH56A-7lx9wB$#83 zhJ+&KM@kgWFas7ZW?a&$sB9{6LJ4E$QVHM3l5X4AY(g7hE+5MZc7=g?bJ(UMY?4WIgN15^`c#MC zb_EI`?Jl}APO4rzcb8!lv!XK1rSvn^#-TnA6^|xF&=-0WS;{b)O0lEOWS|kUCwUtg z%?PAGjP&)q@iNusy+?U@I8)Q^Iz*aFWs$1tR^KnlifJyJRS|f{QLphu^Vfp*q6p=(Qt&UlHuvhzgpogX$f!L@Zd3Fvv`zDA=Y|<-X z9IrN3TDHb&Vu+#)*)W7z=aatoXBWS1_mO&9=LkY~3Q(EX?i0ne!UBPT<6%ZKNPL@O zk<1{$ylc}PQlT6X`0@nlBCQ&~`dcq@DiVJZ7n#*G^1nhQ>Apbod_U8&=*o-78A~?? z_qS&XfaL_96NbSHV@h`KhF)(MZO`!=o4=(=2RBFq(C^>hzP!Btc~)*o&kooXo3#_A zuRs32F_L26K(XkU{9ku~e{I;!UZ{utk^kJrU#WeA$fV+gaJ62aX!PI4PMnX@v`Px= znA$KD*+Eg?bHj}czj62j4r)90XD$i5}Jj%#h+ngc5DdKyaBmBy;Nk+y^H|ri5>3par<` zjqbnVAknTzSj^`4HXOb8b|Rpe+~IvIF+E~%8qQ#V>fKQskf!xIpVNw!N}BZq(RWh!7w5^kt7ZcImRk%>sZwqGR-VKf}1>)hkd% z4q-V1=%WH}gc$~(elH|FQ6;FCo!RJRmc3GJg}=J}l0jxS!$D5Y-4;_+Oq@q5HF2q` z0-8K^+NNq!X^>DMg#`bsV>&(Q-@AP<7sJ4Otv-fiKM>`%h85&V-v{e>KKT$jL z9k`*2{&t1ZSv)@Z>2}_j!wi&m)k4;(r0R;LZr1$0QgjkNGS9=|-{P6w+v|;iOJ#3n z`rIj{eZ3;olA6J4WAD^GXd$HZe$KG=KD_F*!d@iCsbh?q zbEsxWs8mV*UOGT?2Oc%ayiGW*p)Z6K+YEHr%xZI`9PSj@l<1Wx@Y(kKQMi#}!ll|9 z+$H9oJL7B9xsV>U_;SX@oF~RdAW4O((h#z7kU@7;J4cEfEnhlS4!2;lmmw~?|v_S(unbM{|umU(SQoZEd>ldA#4Aq3a-ms{LJ+A752;;DqPsua&nBZ^Pr z6!El(0k#B~I0cj{cNlB8vlut(Hby|VLJ&r_NAYq|@(=9px9*R#mKj_vArg4We5I@s z#T01340$K<^~5h?TZK(yVb-x`hoUAmE zofk}+kdhAjd^IzMl;T+C*v&?$=AOhRzEDlp#cK;NGnWq%DGFj57AI9KNHzlfdz66K zRCiR{?3$|9oY{%sWDgmxInKXEb*{trpkLvcd~_+=eKY9_iP5lqW4 zUkd)asB5hm*;7>Ixil-8+;7(pOKu>>hK7wM0m8i^Qk&9#GhyWk#eK?t~jNc7pb&E5XnD^DL(8iLZmpmp*;F2PySQfQ zDAH2kv6JgGnRn!QlfQ~%VodZ>t4fV2!R%4l%Z|1sp_```CuWM9q5=6Wt2}dgYq5pL ztHm@>R)PIWh`>?9CmAL-oo;yFD2ocf8@|QZhDg&DzvnDY@&k4&t#(b4J&!#Wz z2t+ZPLBQFDmUNt2P%$sZ;A`MyBBHk6*gqH;>RLRT+qmcqw5kRP9gtnsepyf0R_WJcpDf@&9Hf8xaz@XFcN+U{g8m0VZy_`UKt;$7DGqjN>Is8 z;NR%rXnP?KN^e6U2oR2Wr1C z7>LdCwV^Jr`~3D{wz2v&CN(R$eaeQ$Ce>-*?1>8VH;?sb3{{3YedQwjfo$FlIVQD= zMKQg|N_j}ixYp!RW)5cK| z)8_&RaiQv5a)v<2OmX}>Icr6Ezyd(xJ6U`n?DuYNBd*KfGKviOkuM){ybsCeZ^p~9 z3%y*ip!_t5@rR=Q&_GzqC};YpA;(eU+1PF0or@&Ul4KhV!Uqa9L^HCCpj%?_wLGN8 z0bLBPSLz^+8O;v-0+!^t-A2%O@mY|6vXbC(7;ksrO_`AvUo1ui#B(B$SxcssNQdO% zz{))2FV8jCe;DstsPv~C%MBB;N6jY##hA@>*eTs?mVhvDFguBzdc?h%^d7%aSicRU z>^PlNtgxATde@Apms9^r%DI*znsOSsK?dWLw6L*CDozW9I_2Z+3|9c1(qz8_-+vtn zc=7h)8zk0g|Nn_O|M@iFv-p;2>62Zk_}N?u>t=h4ZC5sY6);B74NF>P&Rso}0~)q5anvxEHAeV4M3S?_oHP_b)w;>V6f(Y@fN zw#5pqZjvM+mjv5)q`y6PQ(NY7ZT^u)8j*DKRiw`!R9$fFY)J~qDK47AYOMuCRMCfs z0Ha_0m$dUN9U|oNxX6+UNCZ}x=gr5zf99ztz<5?DM$h!CmmPu9p8I`HQU|Wb26ujx zJx)XzQ%udkp9OnyOHN{&kq77K$7_Ia!C*bG3)Q5bjSMIba8#LQ`=T_n5*EarryO7s+bd>>@@P5A{nn=gSp!$<0;H>34l97+4+rf9 zyzQtBSuzCu%TY~CfcoJ|x9WBbM~lPBo;gyuBL05AEQ53N`3r}FpeT?Ghw2)YmJjH^ z=SXo~K%u!@K$sj1qSQY5zULh-qnN)vZGkwEWwqi(cx~Sy?S7DW3SfBnFrgI!A6{`# za8k~e$shx<6=7Y%C{sAIGb(z7ic^sa!y{v`eWtYUd31m@7^E7H#<574QxM3TE!V-Q zaa@wdVuUq?5>iwZvgDwiHORgGLkVYy5Ae2NN_QV?LPpmDz3y>)&y@Nb6SS9hSQM-_ z^B$lBa|gnIEf8aZHu1Z%g>3^Chd^Juk}~ckz=XYW!Xj0xG{Rx4F{lP47*{`}{{0Zs zuS zrmV_S#U>XGTNju5$S}2jHmQDvT}y~KS*o7xI2(E^L6JcCVX)*`#ra|Z>B1f=6L8tK z38QPJ{;Ng$@Hog0Xws$>27}+a&m33{4|#hh}*_c%VsyYwHx}?EMb$Ta$HMd+UgL-Mnx=4W>o8A zks6^X7HL6ZNltz5ug@}9rYT-4-|~?Hd{vphqY%CW+0I8TynScEjmiXI!Df~lt{*js z^UD1|V7Y^BW|ylr|Bg~#Jp}pXo;J(V3J9C9>Rh_`SbV4?U9H$H9}dei*BuBNPWz}z zKz}~eu;X@fU2wOZUKiRMwM$ec`a*QBh#rM3*dfK4TzF4wxe%v1dGry?Ib+++mRq0v z@DM6d7`K%PeCM5Bh4X(-C;@aclM$!@QwGTo6AmC9b;7!eH8c`npvp zXcvd=dp|&k?K7%%k+G~M&U97ok${pK)jz`2e(cyPC>a>j(4%3L9^xxX9RrEvi76@z zCUGcy8>;EVfF3P`3h&2<(`?Lm$(S5J(krrC-|ar)wqBhmd2uy;l$q~UWW0=pEg$5w zQ_jkg$fd=-*%q;xi3(!cayva#db&*PyVJh-9uWN_kMrO?pE6XJuUmWT{XyN<{_M;y ztHJNtfWbh6OoUAaAxL<_ce(+Fv9cjVm-FT-bSe$`3bpugETREp(QA>R?$-Ceba~1Ibj2)+}>> z@_FW^|L*ePr{>qGEb zjb)M|O+yA4>MIdXcFX7`rF`czr!dAX2=oxoLk%;Nv}n4@?8V%5ZHc_6v4l{c2WtKV z6&kpgGOWAOej5o`(UvKR!dEC`n^_TcRGfi{U4S`A)cg^LIQsb$Cpn;|IZ%w5V$s;A zZG!s+oBA+1!3ydReNeJpAWkTM*3r+w-T@F_7??+9+%q;d{#>2p$E@?<@bFYK=w)bl zd{XcZ0dW1NSB>mNU;W^mNvOCzS9eTsXFJfi(ZUB+dWl-Gq*-!1Ge>rTJC)lf1_E)j zDU>8CiVsY!9Ys$Q%liQOlWV~Wu`S#P3B-Biqp^_MOC6=@h*@&{x8TbV*SmF1{b^@z zP8=QxqIzjLh=x?Vn(>Xzg0ODKZKoMs+SA{sV>sBc!M?O_!edk&Vrm%5qxyAb-wF7Z zVF%Jg)J2+I+G{j1-tF68(HX){NI$l&UD`jxJDb8)K|wjF?X}q_(Rg}VbKadkQsrbK zyJQ|ek(QJE>s<4gJ}s1Iu1omIx?%E}W}MIB0^2m&yfh;}m>OcYKscOzsWnfl_orEx z@oUp2sGXWv{-Sbl^pnk5Geb?nD$rfPaX^HA{=F^7x1tlR@VhMhQ;?wkpImRH} z0sbZ5+Go1I;RylwYeZc0m_2mSU!-=w?wD=Y>CY`-EN}hK;Ol?OtGidy-Q$S=R>#z_ zZcMH4!UFA+=*zU~QOx%8Ds`l4kN==<{KOP=+v9A#Sm`)h^39Ua(cwf}b`f2^$@~NJ zM*di96XNee4rptzT2VPr6%M#$&*_Mdp!fVU5+vN05;pMPr< zD?RN5_1$&Q`}VH-riQ&fE?ckM#!#N$zOrJb>s^6iJ%HrHV88lh@xY{i{-{X)*A z8bgwZ0|9W(kg+3_d%{VtuN8qay;~OGEvZ}i`$1IY2w9L!P7_u3z{Fn~5(OF(qemT3 zXtt&{ZWRwdBsefSRtR;7Zs#sRe-rC2E)gGbj6II(qfBLxt#Od3`84d!BCkQwa*EL~ zDl(MJ-1C6c5W-TB<|dlUTrWDrdc3qdd?v@AyrdisQA`DbW?HTEVjvYtF_0yVyLD`_9{{ocMme&!>l z890+75NK0A2$l08xVV4{Nl&rCx6e6P`}~pws}7}A9l+lTwC6~vhNPCX)Ty3FFAC{s zEsGQ{4QR#+YX!1m52bdUXe>}f7BwW7W5&tl6*7OZGXYEI%bpZq{0tQ?TZgAiXQPKQ zXaA-z&wqDJOg7#5DvbBXvwrS3iyyA?Ag|jvOVcMNrEz@Dop4DVloc}%-LYseIZ^-3 znfZQUEFBLZ@4y4 zI%n83)|PEaFNn`s{nX78-{+v+<9^@VUT?8Xas16ivISGe7$eD9b#9@4({4KVD_Y;A z-h%v`$-}ZMmsJ)1nq>E)JCet<($@rBrz13^QdThabE&1vc*H=~`W1fRkPtC4G$!$Qb6lp5oQ{ABn1;#qIM3^ZG&$}az)Id0 zQKGs{DFQ_@T=zM7tgjTC{cP;|A;Kcc!r<8ygH1QVxEvTNEACJuG1OK%LOaN%3p6iI22ae|@1U<{Ya#M^bMFk2Xi5@lI_VF?%lspY6fd z{tS~xZf!0(#E^0`WbTvpbEyH$~mO9BsSA&m`7#El5(_$_f5!4&$C|RFwt?u55 zWH=pt-+oZd6KjbbMTOXdy1_YIe~ByFz9OS1m3ArS-*o4k*nivx{(;HW>(X9d+XJS8 z?tJ701hcG+o;|yJ0(o>x zTTA~gA|9Z>h}?J1V7g$?(F)Fy?b!R9645kb7)mOb;$O|}IMo?Qs&GgQj2Miw=U0jd z@7D-Bp8raU&h1B15c&R-K%)F0XXoKC)b3$~C??W%FgBKb-9^IwmG-rhIzM`ziIr{_}jIqUY};WuZ9BxJ(u;^%v|9MW)#)cZ*V%U)g(E zQ@?^OH7`WudWW7io4|M--5uF(*opW*K*LK3!EJwuzSm5Z!J*fV6N2bLK|!je0XA>< z?!tFQu5YWX8f>Leoc^!Y0KXqy%+9u`|L-|}it!_j!VMzhU^hd-Xg9(p>sX zAoBI#CUpBE29cXzkWdteU1OCT2FXlx_Z1_jme?_|>d4XN%E~C0)@hm+=W?t$EgK}x zn`?>NYf8RD+&z*XAQ|>1?XP)`J}M(`cES~Z1$*@;O8~37ne1ZZ7t&KF*$R6X5Tqsqxq z$d0Hk)jQW#+^QwqUdy@8Y*=n*2O0ta-K1Ew{~Da6UY&JCiD_#@=`qWc?~Z z)5s!eH2jgqk{H@`NX;0U=GOY}Pd}E>r$0?pVdATrfo*mF<~X&+WbCzz?1Q1dkA%tg zL1A-yaw^^Nw!+@t0T2q%DC6jaXNaaNlwx0Rxt{u? zF+Db66Eq*+JUw1`*(gIRZ%6DMEYHH{Ff4Ci4AvAG-pJhAg~f~Wt0c>hCB>0Ge4w`2LzB_|%g0&i{T zb%|9*mkXn2J#2&7PPg8E*pXTd=fRghshh(=r z4Ck_qcOSM;BU)=XMz0x7$^=H^tLG3B$-lYw>1(JV zf1n8WseZvE;{V`z?3zv^O@h9#1YiBOtC*LuEWrQYgRWeeh4 z;B#x!J!)9<;kl~pDNR`=gvW#2ZBf4bTC6eCVmmb29*k=|2_{u(2?$6MvB6&ReHAE& z2Of>4b1Q7!{WHF)EqY7u-`eW6;xv!Ivl|${&CDIULpdFqZ*9>{pDKMI$?`0c_BYNk z4kXU`nL(q^1chnM>zw%HaWzW4$*XFv&s*m)tlP(UORzGx{)@hlR%0y9eIRM?S+S9p zxnR)s!}HtioxOaWNBI84c+!J*VMU3UgbC8{h)g1f2%bohv1r}RALgj##9!%}CQgrw z2gwg8=U_Y~zyKB1wVVA~Hf0ZvQMBqi)a51YA}Jkbd>`jNBz2x!DJZiemrMM0=f!kY z{}ku=PW(lojXx(i16*h!=TWa<#PM0%=X@Clu-gleQ<`1?ASWh$?8T4sVbaX48}=3R z|H7tpY{eKZCpx1WAElKz~Ozg>xNOeM?eCstuou1iV zAtKK$n^$=6yC~Dcy0t5wg598{fX$&da}p2hYplK@@My88r_HU&ae51fDNrxzI(lFv zRZqa#MF{Y2Js*|l{EqhLRp`4$QXgUYdbPTt#ub22ZP!s^klRg%UVf#VR)&BrQS)wD zg1ZXvI8Wnu3R%r}g8k^^wal0%^!fE(qnm;DXWYT_g>9g5-L@3k&-4*wbjJ{*a@ z5@Weod$0sBWXNX8kfe-lQ;z9A3MzyPGZu*F^pnE9C?tp3EV~R2jZN~G!o!%}C04(j zxqhNHlDLT1@PsJ6<1{)aG3`3MRcD&#JJz)fye2fCufnr^TJlCGO@d?#OaT^ISMjiIkjtgH7Xy>b1$eRA)c5YMRyBoQOm#JyMbx0i{5J&HhNkPG zO~Y13P2t<$oqSvRGF7HyBrDE)nG7tSstxA`QfcOE#s!zro=<;uv~3Nvqhg`>x`DSZ9v#0;3r4Bd_5$jx3 zTqn)m{a=&mKiFTh)0OClW+kTnuKHi3!dv6s{b-y9E2#A9g2>C^juYRoerNhL<1Y!E zpJl&B!s)rAXmycow|_}ppKcn8IrY_qb!eiiK?0w)6nh)RSk9Vt2G5bc6QSh(S~75< zVMpcpoSqX-#VthHuyRcmEpYyERk*yoNO*s#PWo?76CT8BsrERq)!&P=LQ$!j;M^P$ z1LKp>I}O@iV3r^1**&@d^vtf#`)9w%u$JqQ3s zlTNa?S|00fdyclxQERPuNb5jTvUZ!Zzf`x5!GF44Is=FJ?6Z(?)yS4~2_((N;*kQ=t-2YcEh z-LO`&j;H>9#rarC#LTnFZN&Bm7lQXU`+;!RcZ^G}#2`k~AM6P5Gkf*PmjfNo&6f_Z zz_c_HZJ!s#e`{6he9G@DCJK&?*Kqx)-A;}Z?~Y1Ne{NQVYz`uzt;;;2WNVrF&C@?i z=gTkEHA2&If101{4PRo4mV06@?IB!au%%w223Cs}g0VU;?Z&zy7iH|18Uwx<#*WH- z%oQ2qZ>r0-(Bt;{N*jGEm>FfOv$WAm+njH7!q=G4EAB5vLZL^Ulvv+&H=(9~KWrGu zYmI_Qu`5Q^7j+DUSg+V(y@Lp5$RL<}fOW@h3Lbk>V5q~Gt4vWaS?YJUQHw7Do5XUwYJ&4E=z z4(b4}WfqJU>AP8?^bA{a3x6>=fy2Fb=@C%hyXP==Fyn1yg$a zjHpiRKJ1nb+s!@AM-*Uu8oc2#T{e_y1;QoQ6Ms_M4#NC?GFqz&WZ+@A;tvgj;aD%S zk?#6qI6k>V(?@!aAV05E+{bJ*Em`dk0bF-TsN)M#5G0CuJZ%=4J7SO15xyAdtKcMF zper2bePpg(1k)AXwJ4F4Nd-LxpWQ+XXk>hPF1K&1biSbb5FhH0OGrpG-uII#YG_#W z)kdbGnfwbsP=1HhV2H5od=y(D~^F5d|Auan zGk+FQ8vB1`z)U--J@7{o4gfBN@U z(eJEkQ6Y?CLq)F^Tl_37e)L!EFXVQmDKQffNe11`i3jb>x_+*zEWI@mrkj)wFY%l* zRn6`F@PGwTZf}z`qA?5>fHG?9^%4`$?M(j9p~bD<%s@v4ihz6g<_<~B{_ZmUX-9y} z1aXAS&Qrl&MqqN*E4O9wr|S&1{Aonb_(f~aic@V1`<2k70p9$uVA6A2r=tZ_vyAhv zD~|)|_5&DZ8_=H1O0y8kKeLxCd>b~ka&3M$Zg`nGcKHf(p8t|BQ8EA3q3vbOP~NUM znhbFb2LL?2E7wwRyC-$T(`$%Zj#E6VE#B^nm$1&&WB)?2uUhoJkgo( zuJ#2wm^GT;ta7rRA@f((cLMC>a%yo2VsEW}08T2IWm;l>2#tM;a}&mmnsn>AghZ3D z&zUhXq=;vt%wP2arYd>T&pPw(2juL0oE6GMa8%~RXP_$b^^>~2Q64vIJ1|vJF?^H< zXrew701n#(>`OppFCyC9E+BThx=<0H&f3A7!b#xUpMVAUt|$--)@; zPPQqPSNx1*-bnK8OmIGl{Y>hNhe~qXxC4J29NFNm>Hu%v2AX+dz-hGi!SEQi5E)iF zWx}zxs<6~rOkP^wMwYvRjtm5rTAO)HvutNRiq=zAZP%T19$Rs2u_bv4vs*3mbT9J7 zI#$}>FZfP3tuZHmT_?Xi@nVuIg^i3a5x%<4&o;h1l&~338}mt5~Bd@dBEAH?KnDLY=dSOi?jSoj=E8}aNH-RX_`rX)}Tp{wlWryZAcK0cEc zkX?Yb!#Jbceb8@3;2~R>eqbA&@$g)*q(#s-f(%FWk`XptALQ&5A&ggz3tB<-HX^+W zoyogz_f=0U?akIKSqYb~I(*1N2^A9JySL>imcIEe?PGCvp&df^(CDpKwDwG%N$Ry) zT(@l7{BqOJNvsaCCH3z?hT(lLuI0S{M-TClPT@xXU*pm@B#S+C3FH=j^Ke7g{+bEv zLgFI0tkOL6m+Z9ta$Isu1%%!eeUObr)NNxBx)i+k3nQ}~%xO3s9_cv$9pbG_`=2hu>g5W~W91}SHg)J7%5 zC-~s#EdT-rZ1y82=v0fgZs&Xv;tsI+^5c`-g`98(mY+TWrr@^zic=4M<5lT%rNVrl zIi4qZ*HS}VgvQ``sUN*YxN)thHjuyY7k%CPzYC(s zv`ClZC7B&vz_f^cKXby=k6Hm!F-ECyuBz{;vDibFnG>zoGe>7+yklfU_B)COHD1Qu z5Kx_11~jX4k!(`mi5{=t)QN~ON1BTcN04q}485N@!IL5CR_r`f!j+cS&H5k%8kPs~ z;U?yg==g7NogpoE@8Ip(MSw&vhBNZWK;2=WDYs9d)zY|Od7nzm6981)2Zsk6acozf z2+i{FW52^Mm2tToWzHVR6@(;BP*h?k?Bhck=f?7>*ekT4IxfMd50Vi=4MYIqfq6-4 z1Od|=;(3E;_Z!zHVP2xe=U}kr3srUXg)y`TWv@<3RTufLdWnXq1*3aIdlp+9p38bG z&WB#*M1&D$J=5>-{Rd?N55%W+Y65x%WZa6QW&igp!{2r)$=corczD-FHh}0)^Bcs^ zTz!CO_eE-m9>8-(B0r=}6BgqAd&Tk~&pb5zkNF8arPij6t>+_z?F`vC!-W5iz3;mQ zT*I6dl^Edtw;N}#`~4ELj;}z)2yYtV)PESZTSjy<%*)G8S%Cyg_Hm3vY5TjsplW~P zJaG6OE2De~69G0$Z2h~gXHIY0p-8en-Z&9@CG-*PzzfFQDhOE^O`BGaCOamX0VND( z+3az$S!1Ffb6*JDmub@+$1rtSZ>_H|SQhpr_l=y-bQ9m19!oa~a%Y;EZS@iA zb`B>pm3_zaxH)1x+)IiC*7hE<<$ z6i=7gljS(_gEj=3WSqdo7x zO=euTsolLrsvkUbX5@`(2WoAWG0if3*vp%b+&-LYg>x0f#Ac=i$2O3O_)5#&+<8$H z_2dIkD3=*&@@XxCNhGw3JOTxn6#qStv~|b-oI`EW9r^1RD@YV2q=y6s!!L9vG3pLUUzJV(5A?z}wqUFm15+NkBK80uD&W2nM}SGe zh9Bu6MSK$2iB;EF{xkW$lhP6c#0IdD;$jlL7(CAj{w7y`f99ZV@xiR?f@qgD#&8@0 zU&V~?ZZ!eh+mGsMM5GHW6+Yh-q3^x=$Ze-FyTwd9n}Ef);NKjc^cv5Y+O>Cr&Z zLV=m(@bkutI^inbkMd{03cAdvhdc&$M47o=Lmi~Lb*Q2;VNWq`P9Zzi$lOE03lTv% z$Y9Q};clz2IEIwa)U^C4+@yf~yKW-HUS9eeuDZ^FsN#>e z(#36?Uh05j9p%;cO!Gs`4xWjBYCLoVOj)Ei4lPVlnkp&KReRZN4A6vF!VHi3AcWfL z^xo-h9ASA6FAOrrw8s?8&NA7S9)@yYvZ_E7MdK!8cebRmFsl}|Qs<2jB*js!M5b!# zywW_1FnFG#cyviMTSa5bAdFj8<+{%>ZnCsMcStKJ81$iT>c;s8b!qWQSOLCwrS?>5 z=?VSyso&=C8%s+X5dE~0>btMW4{Syf$g-(>18QsY>m@}dcLqKPu+j3qQVF(Ejgx_? zVS%%)gZh-VLfr>|RqTfc%{Xck0dF{@qk}?5jlQy!A*xA+M!i{bZWak6_9XNuev^=R ztU}U6M^moJei&*}PONMWSom|kbXAnE$Eh+zre?!do?~yz7aV0oA}7_sBUb(uHq52& zijp~!dY;g-Q>U-P`Ov^vmZ`ABVlt4>n<)7o#ajNKrIlskopEvEm8z<0YJyeF@pjrD z$+@f%mL}|ZZTELK2lXWP=U8!>S&U)Q+Yd1yjTy-VVYoG1zB@(23)~A7%$mB7FvfTq z3PPD_i=oh1+l<_L+?ZF>^MAfsRy(ZU$=f|-f5@{6Cr@HuRCO>>VSbmNJFF?BURE0v zW<7MyteQ5ylme7LK-FEAK5tf4z;*~8P2?(XO?ho4KuIgq|(@X ztfrZzXef2LTrzce4+mp~yY|O4h|1-pGXBlZ@a;lUmBmZ(aiy2Q>ywa3;Z-ijKrZud zyZNgXGviTjI5dCYTKPOUb{ekFu!hF_zg~x*>-wJS(hYZ916?jXK9}*RQZtw@1C=hv znza_wk{$ZbjGe5p_lAk-0+U9ArVl?cc!3^1QdMAgrabMU5# z;%AN9N)xFiAF*pU98%v^znP?E*XKtosh+!v?)ticb!R*Lk;(Yy)DZnvUIeS^>l9Gt zES=Q$&)Of^4A+-?p6lA_(m&B6G@0GVB?LzHQIn#7G#Sp2*~&eAx9=^`3a&e&{=p-x zH<}O2dsdnp%hVmyPetElIU%|?-8b%!3vD#U%O_shb22)gl6M5p57a{y^$2^ESz`u# zkSR*%j~o@AF%b>Fy$K-M%&+bW{-O7`HAJdS14H;L;QIr_dOdX1X(fQ^iE``Nu;t~wi>lc6h z<|aBD%=kjOZ5u<0s`l1W+tX<7!kYi~LJE!n$b*=!6x-01!`;wM>zE_nIh3x?YtKBJ z|BO`NLs`jq89`2)tC11b{->szb!ll|2~+EixiUmz2;PyLj|(d!eg1AC4h&OE43m4= zxhG>kl@34tW-xBQRyI2{3_yJo?;k$oN7}H$lN`_)Yc2arD)_5GwpF+piDhT*d@o#P zXWhDH@C8AzW3tTBmG@(DlhrXzOdKxAzAi>>_+}ZTj6;>8{b#uv687cesc_6#7f9le z2C~Kn15EuF1T9Mqc$u^IjDG^k5CQ%+Ip9xf(*3OXiTAYoJN!0G1?y_vSeH{A1UuRC z5>UE&KNSY>9%eXHgJ2IgGsCFEUG);=5@yDhfe=W_cHsJU%#qP}RBrjRI~e0;g@Y!y z=`$)Q^#g2C==`h|W`rB{1$j91LLc#&Zys1!mN)bjx6v&v$inpe6K_Ny;f;)`vC=RI zDB&~Z+AxZ5lfw7|IXShAOOr`}bxBV+Z&kpfO7&`4s9nQaaI0y^g20!{j25 z+v&SntWn`4D^3Wi?jDTbxTAJ*^s|^~!b$orc$sIO$25agT6?A|-fDG~!kI$DGb!l& zY2TUegz>l}g=5}(sigqZ6Wq$Z|KZ?)kJ{?=gku8*?2S+>>b>6#7+xftyhCMB|_cLCX zzmX|ttU@l=i}jvFcULVBOS@Pr+DVN1BdbJP=(9X;G+G~qnN$b6ZZ`iuo({kTV8z-C zPuZ6XMW(r~8^ej`ammxSQd<8tF1E(H`!x9C|u>9f7qU*NgThO@;#REMwayHV*G;1h24rTdnL@>-o9Ej#N-UwLN@vr{MtBtT z7wd&DW1gdI1L{?u14umyb)0bcoDZPYP}6tANe;~q2PI`Hqyvr<0>2%0k}u(y%`>6x zSh2J1cm++yw4Vdyu7%nI(d1TrJU=TPabjiEu!bQxm)V%=g{f|af?3w)fViS9pV<3VD^7yNw1MGE!9M5 z_OtfWwPn6&_ah;A(#^I^Vx!;oeTQ<_$f%G9M%(yVZ!4dE>|5AGnLao==6)iQKAI}! zPr3`Yp`@IV;Op)K7?cuU&B* zgg;m~cQ+FHY-@Q5rr(fBq^9RZ6>BN$b2p<1$nCkQKY-n!r%lAkGK-UOmxEt``@z5( zp;oDqva&7Px&&5tZFt@hiBn+}ok@Cr^#hnDAbm+FEwmT#%n%31!w08kzb?vSf%#!L z&ClgfbcmNa#nz%KE(IK4o1`%(Wa@8!*hd;i9rv@yG?|Cf1H{8J7B*yK#{XV?i?J8N z*jr%PEWU!Rs7@aPnE9@ZhW`!-jSSo_$cCjF9zeBs6CK>fQ-~n>GbU32x%<&%r-)1Q zRO#(Mwcypp-8&!zkQmFKq-q#oGZpy?YLx~BEcoCmECj2s^fJBe4Oa+ng;-a7wCh%) z=WMHFxB(C6beAGdgLSO)IdozGTK|NI(Z?fr4&(ieJ;E-{g_Mn7e|m|J!w0#}Bzbm^tZM_#=xolxN8(7ozBdusbL5^A> zlx$Jy*B*Uy7;n4JY}S@0pAp_2jK4mcTfmW3yIGd^TrGIs{CkU^#!X;;Zm#esQ2^@h zh7S?nNm?6vm*G0T&tse|>V)$2M$ds566Qhfn>Mz&Vu%T8Uy-(@xeOL3RmMD&m*)9I zh@(Xqd)+p%W!G=R03|g=~fS8y~u{y&b5IC zH5PN{3kx5r;go zy&sD39V*-YO%+76zfvWAeiDtrtfvG7xE%AsrQZK4g*LE%!fnu%eQ-JI(Eg-p&k&yG zYw5cDHz(tZ!8@Oq%j~VXdEMzsjI^%*Fz)!;f97xXuczC!hb`N6kb53gh2VnH^4r@f zOiWBv3sG6yu5g1t5a(?}g3t+zZ^#XYAV9aPNvUgz58RYm2y5QAu~tf-J8EfZ>C&3R04NaGCd=o+;v*rU6&Wf|!snf<1)~^) zZ10<{1k#)ewP%;*mgaqMN;22)|Iq<(AhQK9S&R@ z#_(BhX^<|3nzG{GDwd4B`6Pwf6ViuEQoslW-;9%XOBfw7h~1 z=i8g>FrL5KY&y{{mQnVbfO(^8=hm9#@jo44Ng0E9eNR^`dHk-a^ z7pj7jWg1sqSQMDX1og6YQyxI!?rH)bU#CfltU4uMa{MSTu;2qz395Z|SatkT>Ir1w zF(ZTLOXO}7aaPgpK#N2q)*VQrD6NIy;F!w$4Fd_p+OimMu;JUPy~*ESuC&TBeP z#WZ-REp3LR*~~R-*&_MLI=esYD}~f&s&Lb|1w}z-x^q~;eOz6 z`}XS;e|Ti1>`yepp6~6+YSpdaVj~4 z3N9bB+)c%lS;x+2lofJerkA9V+-qJnkfcx+Z zT@H%el;)N?o{sJAp5cC?blWDR+d;nTrwG=~{>P`wyMWRi z=DnM5C!Givj~Cs(F9D=Jm!z{OH_DrXv@x|_EtHxM(obiK`OJEFpje*U*2~iGc%aUr zijo@9vJggKNmXh66xuP*Os|of@3kR3N0`Yky{ldorF&_hE=TJM1R{Ca_3-w&+UI_Q z5P}i!#Su^3^XC~;hsZXo3(@yYiFUoBeqT%~^TzI8QPWurg!`{P5u>g{abb7r4`;A<~A0_0l%TL~}?0?m_RXtf;BGW`;(Y zlSS%#%VqR|To<%ek=v1@C15RLkyvCz>X$uEMJq_VxD(c8!yXSW)eP~Hn?Z|Ebb)R)eW6c2zac|E!zz!!}D5iUwzF*zMd<*EtioZ zvk!boW_?hqIDFL;9&_QW1J7_Dr3l{stGN_9`aiYSx-T({dx}kv+Ivi{U(Ynmc+rLA zNBudx3~66zs^Cr+ZK;hnFn>QNW^mGi+CzEmD^w!tm%fa{@4xglxurpUwx0%ltIGxq@(LCH1GE z;KuWQQv28ETPrg7x}&vGfH-y97!9bmX)nujW{nImQ_0^R2)oHerf}=zLs)_DAT(Z% zf3x2VqyNNfDbv|(PGMzr!SfTYPO<7lRtVm;;V)rVsgq2!Y8wZotzX)UjYQQ430@sh zh@MhVH#QN@d@xD0Zx!_EsW3{-F8?wSL$Uhq-x@c1R{z+asQh}aFvjT;HdkuyUOz?T zJ)^-l%LyVQZq849Dk^DmHF6s((|lAPt#k3T`~(qVx?;U2EYE$6{$rMEKbG2K(Mg~Z zb3RRf*CE>uo@=X?Ge>J#??$&Dp71dZ;);e-KUeOT*NW@wGNb;J8vM#tO?P?#=dE^6 zR5Xfm7h4$SIo!!O5$D1T?Uq~S05BuJ2+Z9*1<-&7Kp zW_4gsuRRh)v_DcL_8qFEE6AsdI#KcwiN)}fAz%^bre~-36v_**)#kvTiObn-a!231 zj%%jn-x`we5Yqj2|=_)(vD97)>KIo`TAxfAhQQ(lqsh*Ki8 z>ZZAY^NWjdF`PM3f_mTv&uR9pbE21ry~ne0Qr4XMaMNb4BQsn;#oc7RH?p=@7bB79 zPwb$q)StkS*!A+dU!=P$qpH~-MI5BX_(Q`ru?|S53S(f3T7)4J>5{t9gyd*#gP7tQ z&JuDSj3H^XD|38cQ4H?Chf@NTg@$_kXLn2~H_sg4bS_g9K&sa6{OT=#=;Q!JjBsZR z2mpI#WM%EU?s!5XU`_e$K<#v=A{IXL`{E;goOE-pDS2{gi8S!LQph3?cN`?uv{VHl zMuKdTeN%~!v*QanQ>>${!gF46;&zOXu;Mb7%%=kFh} zYaqArTafRs{*-gvxHFR62t`j1+sriR%Ekjw>?^yh2-YyV(Rw8|#xvY5&b)ph@A-{88#?RMEESy41&mYwZj`&CZ0 z^;m)Y!2zeH1SS)mt>*uSsIv-dvx~NMi+cLFpAikT9N76NNke^V-{k8O^F{k-artoW!Agvtk&InWlKadNVRobV?mYZIBVbUEg=bIl!bj@`2r$2XQaes6$nG}`P0R}~JqjWsoh;b)In@H+NnYHlI z$K6qH-XcV2q#-j7M>jMypWioa#oa@qos|B;77%M8Sf$t#d0k1nLw%WB>2(u=dU`pH zdYS^`Amma|RRJ4L=x=avmfnJiuHO0#lrxJj~t_Bn9Ai{qlx@-Cgz6O^Zs>7aNxO%+lzXq}>xgIz|R%$X

        s?jnljJa{f2qdcb_r8l zlHAnK!eE!skGj*k<5uOC?_txwwZ+_@zybOZ8P%S3z^B;|VI@L#?;}+WlEHS7+lS3M zmi7yG<`K#@qBX)5wYRIka5(g3gGIWkn*)mrxvj>ps4dcL!io>>_Eec(1$cZDpxrcj z5$+9p(p0YX=ylmslxroeb03GDh=|=ZsJnir2Z5w}zU!p`6ZCd@-<8+esxcX3=sFHq zEbgKra=hq?*d;V)^mwTmwEfTdziYQ+yTNhreJf}W>qYWD)uQTELI)l%TFWBc%2|}r7Y<7}h=>i>6i67gKS#np!%-+5G`# zBT;;68QnnISyla&bV*O12AFfN7PNCuIV{(U(7}n zz%qHR6BeI2C~cUAWMd7p3C~rE09`V!%tkSP^h16Y(xrXvv$I@CSAl7|gqIAskbsC| z>Wgg0V^CBFNXqa^!eI{bGNnv^qp)iDELQSMSnF5sON9aHUKJ%$U{GQIyy?D}Lyg!c)}j=^x5RVKM#yEJ6nj6DS_&3bzW=fsPzwxT+DqwD{$d zYx~{pPX?J;1&R5QmZEZ=mdt_~uzLdWtVerLy%@bNTTZ;~UUq#BMd5_Z_UN$4gXK1o zC$AYclsX%3)5+Mo2vOa>E^$h(SqfY+RZHCl7)WHzonQ^V6~*3O6shEiwV9tboqyZi z!#RAR-YU0~9v7HhoL~5T1!0di#IlldAR#Zsx5-uFOtj9do~u|M~OAc(sK)LfSu z^snuJOBD zDw{>zE@5uLL2c_3B@}q8)=2J$7*}?&<`c&3p;M7y;3aG%W6kX21oLxInAuGOkm=Ka zhn$3m-vr0d;(#+}#-l4!`s-?ZVRN-a+4Z?kv7CWrm++Y)wzZYAaH1IO1JNm)tXxIr zRsC0L@bCW{`+NQ&bu!!k2OS#E)$Q_je}PIiOnSX=w>FI8{A9-`C%4T!#dXrg|Lqr} zDng<2!Z*fA&z!f@y2;}js;RGEYdBcdgVfKXFFqe z20ZqAJ8OIWVY!IQ@tC$CK1;AEx^57~?YFX`K{dAKJW6j4^M^o5e1uYArxNm7X(wc} zq~igoJQ-(pUSl6cczK)PQYPjD1sF*&>ugQlcI0fZ5Fqfxtk)mg~k$FE{ z%z|6$q3>BqqqJ?Q3fpfhv1eIwhvAG9n|R4USa*e%g2x&yj=a3Do6yd^`Q9D-zLQ%r zqKRo4(bR8$hrA|=NIRo~|2^^)%07L%6oVY7T?bb{#E3{)xuLkcM9j$P>!|9yUT;07CvyYZ=;Ab6ICEbf;k6>pXvE-lc4)f1 zdri5`*>qD^3qlPDyM#G7ZU4&=?v5!q=-#y_NCXAk5BsJRjwks8>{ zRVR;#>uf7_>V-|RZk0-Zktl2V@eJbc)gVD+rxZ3Nx1%hIrpyhkN1>9fXBw1FAp~Qk zaW2-YQ;E$>Q$!k)6&6|Mdjq~CSj#^aByMrv50w1|w(*U}1A3CC#l zJv|JvQyE>Rlb9KYo1J>sq6Q`FHN{gBVJAHqd9J0a#wxCiI?g%fno&-$b4YQN29XJ= z)#wjgRuNI@Dxn%{X_KTP=hBi+NW^kdMzIC|O&!x}*e#8SVO!9esl~H-Jj*+yIh=2q z|L%j8$V&Y!JKc5sP^)pA~9f` zeZ;8OS8VP1K?f!mBfKoRAK?CT9Q~D3@^Uq$BEm&wz?b+$&~I%KlrU9MCL?Fq&a@<9 z2^s$V@G(LahT9|0eDS@kpUM$*s$V|cngxG^eU^fmP@izQ>nTSDV%FZ#X>+5KcDzUS zOFav}&6#42jR<;s=M1UsGMH_+-x_f{Le8PL30)~Z{Scbn6)btKp>Q+ER#ns+qKHK^ zN!%&TyPAY358R?S>-nkO3Q(F}+u%{-)86~jJ5R`gO(&MJ1!(RjIn zJ#r_KuQR5e$LPxN#R_+pU088J$K$->%_!})IuCI!*PIVG6IjU;Nx1&$8D(5$ocU6i zAj?MyN;(I=@s@fl{xnUy@)cla^Qz?X#)184uM%E zPxgbpfy+VCsIJCdI0*91_oqNH;gzSsBn#3|xBRXCcoE_x%); zIU9>+GsGA7NpISXnXrNVZ;wSLlbOd&4H#dbT6sE2Nx>#`i`or&y91$e*;fD5pP!Ks z@25~Py&gjInCh(1)hV3a~9G}BqQM(#iNUTQ|VU0W-B@igN!{EcT4e)1>s z%*-C<30uzrW-|Tp_KAujlszX}^Mvy%+KQDnI_*THX~H*xb6s^6Z3+0qx)?wV-`U-@ zT{{}jG>eHtuaU32wzA}KC_lOg_vXB0d|$dtlG8FwK{$uP;;}&Y(~zy;Oxjik4GsqS zr0z`xSXBSL55><0H^05MsJGb3ul6j($<_+WxL!wqH1>?PPyfo;;3!^?^HsKb*QNbU z+1x+!vF;+|^S*3=p4i4#h5sr9uE#Asx|9)7>`PlqVdUPg6&orQ5% z@)Cj{T1V`?zHGf@QQiW&>coA1drl8mZRTH-JmS5-&?pIZr)ra6a>sslEt@K+{`h>} zb?zSZDPD+$?5NS`PDXhTM}3d9b-cje!1# zP^|Ep>)40s@cQhuQAbQML4}}1qDm=x1FtK;jBq=`aiKHn(xX6w{Ej$^XN)-DQ~(C( zvVd=4`X<8IvEL?3Nlao2aW@LFMwc>rMq(MW>de%!&?;rqjUuklkW)cDx1a=^j*(I* zBUuTLNjAN3@{yy8eoLaw>X_y*r~J%&c3N7QzmL|Ol}t}^R^nW|FdDd0!8V@Y8tdS= zU2Cb-+{n|Ht)8%abnl8cbUd6Wp17wwCZ3jNJYD*%?8 zU5cchUO;a%WN59Z_5Al8+BTN)Jgp|_eGcWI`xjSKh_PW#pXAlnDlUZo5GGfcn_D0! zkO>)s3F+4=wg?$zX0VTOEAwKlqpkCB)@?X;|U3;+tAh7*B0c+j8xHx~Z zk}b^r7FW;X@z0k;+kQ)~BKAb%-;tKYgJ+2q_ygGFktm0?DV>G3jilSeWt`~k)=Yt$wCJ6TZ zz74W@iE!TYu&CREaNZf}^LD1U=5Szhv4gIJ5hY35AU>P8KgD6{`Q)N0pBAF0Zk2#- zj(^Vg=HhwV>r*k6sJDz>cTuIg-Yg-*PFc!Oy3rZ&Jnnn%k#Zjb7pk+P(R^+iDTKZ* zKf9B^ewr6YS}3>Z0>_2fZqs=>BgJe-v72uO@u{L_L)6KeW0)hdq&TNQO!ev5D@?l> zY&+lB?7S-a)Bv%K_$yjk?d&ugERhBq3cPdB8+7)5E#Aq7z1mx@=7ABYi+6P4qSf*4F)s#3Xpb#S_G3UT``xRvodwzug+Dn{%S zZ+=iaer1F7!XGnP?)WmrG<$ots=97AK1R`X(Tg16_Q0EBeco{oo)#mG$bxEl5u{@O zKEJ%4`z!*d9ci+f+_<+xC8^h%O{sJ^pavO!b~*PgtNH}I$Mn}#sY_LrBg%PJa@KBumBI5}Qt#u3Q{a*{Cp+Yu_)_wl5Qrr@^_vGWetD(-i5 zx^ymB1+$-3*ooF$>q}N^U$*zz0IyEMgFuD{E#-@5O#3kFAvhg$fN3*^T&sctF29{R z!5(%)acO0e1-qXxH)7XhM6V~G`~3zi1v+sUMN|jIV0Z^ga1;kJY*0AAvOg(gqMV<5 zFX?J&;42JoRD4>HDhWKy279em*;JQ{3DrwB4r{S>>1YDp% zZtf6oE8zj(2pxTrwERZaJ@=bLz2)2W(6zLTA96$T&}XKPo0u7A@XyKgYdA1ef==NY$_(4Vk;g%I#6{jA)!nyom3k& zXOAV9UC8ja^%Je;u9VWRVPWE9^Pf~G(0+?!2f>_XtxMcSTH!QVub6e?=nx<}BBp%o zRT}NyQmWf&<7$TuG|MC>qNGL5rm|bxv!rpA3#M<|E_t&s{0Va&GfYlc@CpH2k2K$xS{lY6gzzXKG}oItiIZ+Lc`-AJh$f1b1@ZCt-1Rt51>In~Yz`E?`-+i1P*}I`vuH<^{TRug zWG+{4`D*iiug-l}#C18;(KT@L{)mgim>#Ca7E2~M;ZtYL794Z@RJ%?if*X~E`3qgL*_u48k$bSm~XD-IGrxT<#awZ4Mce$ z8wCSNTtqzUOI(~PLdG|WOgy_6XS_Hsx34G59!t|~+P^sLkJaeA5ML0GI`w}!)~$IU z)b?-0g@5EdHHuMt&}yzU+zDt%oT|D9XZ>`j>o}aJ&rh|O;4Od^B~FjBO?(_*$D~tV z`1ABhi5k$>SU-jW0jVzNIQSK&Heqx1mDl*czw@K+H8!q}`xd_8(y3)f2J}b|MtL0; zYqMgdxb077RYel?J!Yny3ztZEcD>$NIE|Y@-K8<9*9K{>=k=4k&!(h&?=KEK_qU6> z7OknNso+MN&^kaX)~VQa=d>48wfxVBmcT9~b2#2}cd^bS;}05yW`2O*9ggQpN(-R$ z6>It0S*QWctl)o-cN`7xxXs^--8SB^(eSUsH0^P<Q} zt-2i;-$bpZ0=*5Aq6=Jdh5o8rSKXl0gT!cwZnLAFVyY$KjD6jy%hAsxH+Yq>Fr9Qe zizLu~rbSmMVhaA3YPqn{vf|JB*TboWXlTx^MWJwm{!>>L3-ZX{NTz6-iBRO60vp#95mXR3{zPb^>F*TdE)1#>sNGzpRbx8h`dNQlTvZA# zdS7c+7uPphF9aZ4(x%$ztp28xYdMlA_^-jXg|%pV9i-FGN79D-?)Fsmpmz)xpZJxc zB<;w!udT8XX|G@a3K9!QEk&B=&oNTxqNAGyy7i*&#S2Hb^5@D4=-}!3z^)x}DuJ%W z$*uD8qo_R9>KH1ii;j<>L$So@2m4z8!&w)mNUlBebf;w=_Wj*5+lT3c?I{YmK13Sb zaMp=7oC9rdT=#Ph91F>o7%R31)5{qgVDK(%R~vygXOjR^d>*}V!5q}j!qk|x!kV0! z%3G`;+1A5{!(vqOYKSh*vSr-b4=9wT+BEkxn+%}Laji!yfH&<)*A=Y{z*LR@rC+rb z-ZV00t}Z*fV)N8M#^GB%iGR^9kvFd)8%i-Jop(l_&tNXEU>}|Nm7`X+F|4p-Nv^B^ z@_Vg9*GpjwtbHaW&W>sYzjPe69c5m}l^ilQ-ZhBxDV7{Diw3QVt1_QXhSq_6csOtK zbQ(YZ2%s{qF+KP;s(aVOjCw#(P?DEd6NJ+59BVl6rgj-oZCI&bOijqKY!q9MIh$wx zrUw%{IM*^==R*2l4O}?)uC3!K<$Z^}&bVGpGzuH~>Wb5X|L$J$ObXE6+D_*xU&6xB zj6aKB(<-S~vM8lL#+Bk7k1dwv0I_h3Zz5QY&Q~qnJIQ=5Oc<-!#mY^V07$_G7xHc1QaCu_uxpT@N&9cHra7eV~s% zxL)FWoU7!YNQd&mLL{S;zXRAMz&f^ufEv2O>0I?>d5bChRhxL9X3P)_dy) zbTQHCx<4S3nyaCtOL5YFcb98auHEMBe-E4PLz89y7khs^QiM9G^b>tpll@;Pl`EVISW>`?;sc^#cUTSZ5i=AtZw)W=P+GU#(c8Z-4ppC3!(9= zXVh?%vxYq(MX)@ymn-Omp`rZRi+)_+2WtH&CF^M5RfM|c-j^Ss5%wgVncG;Wi=m5R zl-WtPs_}b3O5`iW1ke52?UU%e6*6h(n)^wGd!(C0y&>^>n~Ru&!k5a9JB^?73%;Zq zOHNm>ERe}KPa&+iqAc&$*uww8DOVsopXK{&qrN}kUUb8%@L!DT+SBx##zM=_Sjft; z{IGx0O^SX4DK$Un=UoOFJ2G_4nHJYv-mP}OJrgQUF8I-%(PY)b_%Uez;W~%2ZtlUb zelkhseVEPqgR5H)gXXMyk+Ze#0#S~WGs$!-1jlg50jAH}uOoxf{QIN*(KyA|mrb%F zpq@R|9h=TaW3P~9l4?3@%$c>GEcQX?Z{E+VkmDF#bm@tuQ_r0U(2WImXEX21MPJ2I zVoV8fQI6gyo9o5Lu+2Ud2l<90=qeyej`vZRG&zJ;sj#>l|Gc|LE@ENE+rZx#@iQaH zX90q|O!<)T+AFf3x)Uay+G38D*izO9s}xGYrWDQQ#M&|#D8A-js$sqvlFci~B8n8~rjFNm-^0EiZ^2~wKzlf4B)5z0 zC@O1BR_kyTlLW!BT6Ge7_eJ=<`{m$w6ps(}p4+c7c()I1ftz_q>AwVJP7M*_mhw!{ zE3$I+PFn0p!<0_KF3ZN27%=JTy|`;*QoOOK)dTv`%+<`o3vh7fZ7EQv#7iJDm?6`~ z`t~C&^<-^qi6z3s6sm!kS>j9i0d6`A-aL#5Kjn5>P?GPAdc&ulqS@c=MxSKQ7$q?JSD*d?@LKK6c8k<6i9U5cP z+?DH%VrNB3L~%8Qv14e8hkU0Yp~|VxDC|(2`=>87TW7^9srlkel7uNP?ImqIqO9;^ zhJ`rpqE#G;rT<$KJEm>;a8Wag9VSUkUv!Sg*5Qs^cd|j`U~^VRq|ziOIxGTu0%Z3V zM1OWUB5ce)JIOI@XN2->zMIM6LMQ%bneAs(ygw%w3+xJLR$yViK+NWp>jmS~qnm8W z=0WdpswS;GZ~2M~C!X`wG{k+EAihTY5#zIQ&(5tHA*~(Nw!&Meu;8|SaY@7|02v@8 z!kU&|WVO;b7|nAJ4)GV&d+-g;acIhv{G6jg-j<-^KxbMNF?rl3$RnetDa*|Q7`CLG zVj45S^6=+n=;~>AAx9mhcpV-^?#?KUZw@F&rls7~;ueUFxe*%?Z(hk3>ry!6dth=r zok4$u&xp3FU~X|cn`-PMIpo{@oo+j_$9`BHH`O2|*MggOhlo!)tgEgbd?lHv>XHnv+)_p9`_AdDGgMtW?MX==VMiVHbMTX!E2N zo376}E~C!cw#_4$2(aDgsQbI^KfuKZAJ*L0ZkcKN0b6rL>!2}{3vK)?&zDQlVFoV3 zl>4K$xKBCK;k?J+c@ir#f>%--j%`pW4ZUgvl$167)g8ufM{jdY(9QQXNLR15)HTfa zWobq|?Wvm?W(^k}q9ph3`|Gm^TnWgZes(AyZk+sXiCDf!S@QK?@RK=SSG?$pPFySe zT{JvAtROf6kE@m4kC&=S{;<)KZ}=>OrF4SUbCu@vFw6vrA+;YOBcQHnX{qZuC>!gX zHp*<$E85{OM>HlzS9=zI!AsO|X@qyqc=;B8e)G7IeE#tvZ9cZq1!@ra50co^*w^0R zP<=wC6b8PYB(wtXJ>&0MM>?7*R+aeUHorO>q?$W?%Q=V<8&dgTDtZ`9`lo55Ru(Cd z0iMKj3ds__9M@IyA_o!4y8ZQ^OORzBudUGG%e4%__R|S{l>a)h;e8yv+O}Wl!)oE`1irMr9cnea$PSF=Bs^n5*gaJ!jc|8iwTYkEfsx!-;_WY2qfZy{2}W~dx-RQZ?v|(* z1?@XTP4w1F9}jkRuYnZ>`cgf(k!4}y`x3#_WGgU2T^{{{A z=s=n36h6CW&~)iSLawV`9Af=`afk>V7$pb25feL|JsSDc4`8`<%H?t3X;uuplV(2K3I|Nh4$p_CRLsmO&*A_>DxFv)Nu>R`t9psqKRMq)(~v4 z{@wz{(2!=El}`&TQQf(1pZ3cgi20UlwCu&Ymt0STeC$X@=6{f;wU4p7v+lVj<51u{ z-pfsiQo|dnY$d0nnJi6OhuR{F$ZVPA1djjdombgMbmmH*gkY^E&i$_GCNY=GO5kj{ ztVT%4naKvbi!FA>K@N*kj$*LNNgy6@Ak!W8`6Vf zeA5!eP5MaUZucjsr`Uq*DSg8X$ZHkUP5IPuCR0=N-e<)lCWVzUF4Zu_h}=-XnfBC? zd`E0Vj)$hh+r8V$3Z7i7L7}Yr$()S7%Thea9h4DNqf*RUX`y)UcdM=k8JDgeFRty6 z3u#XZeQoC*!IPaSfsBQ}c6LGm&>CU;uN4*17DG{~shpQdIaa~e?AE7dhtqXcz&?Un z@ZHaRK9v(}=X$}tsX0QA$}c*PsD{a1TQ5Aj0BIKDDw7fQQAZCbS-LV@Qy82;ePsAH z#9>~#_0)Z`j&&MhYmNKhznt1xBD*8be)TM53b8{EXTK3Xb=kzLw}2q(M2-D3 z6t4{YMqYb+QCpiTF2i0Pd`cT}D+vh@?J<@7F}JlR#FsI7GFY4^ z*K0?U5oiF;@O92;m1t9EzE+d(qMseZQaQTgw}joUHJ+ma%1$MNa-7&Y#?q>fAS+$G zw~SgelNXD_4(?K2dxQ=LSsvD5_wbErD}HxLO6B8I^zfnmlwVEs-`d?YUr;(Yrq+z5 z?oBGToD|HSJHj|lZXMrros`Z*!$J#dHLS1=vo~yxUZU~trMnw%{@OQ`a z$j|@Us-DbpNB*BKIpsd&dcFTU>0^UFotEj#+^@PXN~nh`*bjZAe`aOt$Qv;Y1}o)y zYsBF+;jM4t42AqA!JWoWJEZhc+0Cx2Y-j9CMs{-wVq1Z@I`Vv0ixZhVny)F}%mNMZ zF@K5A;DfB!oa2mid|sUzYNRfDj-er5mG?;S0A(8D+pCR1RF*D@=hIQqF$7adBL$9V zf1T(d+9a)Fo{h=w|{wCS?Fw^a!g^oYxL6Ss%(-@ zRw&$`C;h#c5G(kuK`691@iE;=GFX&Vg$s%DX)IGU48P8T`LgYY=ZgqOrd!MB9X>jd zi1{}w--_2D4P)m7i)TUgV5#Pg2&;kzb_(uPPdnej$vW8+uIqghtS^``^4CGqG9 z1+ox$+|l|opNWGRc!EkFIeY78{gjEr6juVZ!mMp@VuuvzaSJ2s&D(zS*qOIT3`EBf z0^RcK*5(TF2@*$d|46# z-_pKkN{h#pPzAx&7T0U12OOzLOXr>*9yXC)qm~rbIPyfN_uYyA zQRm3|1-9fnF(GJNH6iN5w3)?7%|^s74Wz+Nx{I+DQv5iYHG?qnm z91zPd%N`E2TJ1SUC%D2HM}33>IL286?5*UKcv1}Fj%->dP);4%8|Q}2?)U*)OTt7G zaiU6EGhFoksvq^9)3#a6<1G3kCbZiqf(i1kt_oh~?BV8s%?iKv`%>-s7L?)Tb#R4^ zI!F`dQK3eZ0`8ymiGweJ$13G&4EK*x0PCZ_m~^^ny?>oZpl$TZWgijQPZ0pquCKg~ z$1|vpfmUfNtrGs+|y3AA?awu!XzKct7$4aD=H#{xGaZ+#f*9ZhBy9h^ei#3 z_&zegt451Td01=fO=Bd3q88OOWd((P{10HY!69Op@ie64jyO=j|4vwi|5#2mAH~dn zZ^@7|wTYsMJ|_A$IAQ4JN}e$3kAXo_Nds+987;UQ=_H^|gW8OZ(kSY68Nc~db#Z4z z_w|z)u?q_fkyynlLon??6+WGt+5uhzPl%;e!{czKt z*>DKsXT8y82bqkviQkpY@ag`-@4IsK=Dq#2%j=(&rk8K!fHlq&o%tlseGEbB2KZqeJMW?m_RhR}? znpKJ3S2#zfqx{eBOa0NEO&@r#Cp^s;VX1ww;*DAWv-gYZOE^Ie96ImAH-@%TmfLfb zDKy5OB%isBi-(;ki-)UGMw>afdRkl79`DBoM$AQ^KXkJo8Z}2QT&Jk%Cq2JG$cnJj z-BTIn?BMx!Sg?vjvrDfVx8mGe>+j4JaUQ1k(xzqj z8lT*{@AIB{vue~g%Y^+=710abBQdMjLXfrw3_!*4j6?C2)cZmJygwxu+=s?TWI&g2 z0ma$4ZjirQAyJaNF?qFOYmhE)F+l+hbIl4DU1*p-ysx`hFGrovjc(j0CnwDQ8mO$@ zkhPBc)9}B(j`kC210?#41CxqueOQ$L5fW z4Sy|NJ-^Q}ITtvb_u+HxP!waeOOAb9be75Hpuogsj~px9e=mReY7yI5a(F;$)Z2U$ z$g*lU1X|FdU!flXk1)bS)-rla>ivm+-LsPMBsDZR(LC78xe6P*B)80wyuO z{Y|>taW*zE^ov?3zR_q2VtD-WsS&ZI3BkuKIl!8$r?pCn8N1w)cT8pC&i!nEN=DX6 zWPedPhhdXdUi6*Rqt&X*z#re|Y=?u$&kr1=;_*A_CLd>f)OX^ED9K6$-i<5CG?H4S zliLXe4NLccWGNwf(|(VKOEt)?PA8#xQCtfD>YheY#qbI7LRX9`vmmCU%S_%<0x4EV zY^3u9A(q>q*rC(&NEkq}R%gULZl72<)B*c&w`xNVS@5U4XnVg1URT5#TiEW0Dk<4i zT~tzun-Pn;s_*|knU7PdFr<7tnOflM6EP?OAB-6NBu~CHpyz!kC$eeR&AkV5ERzti zc%DGo6bUE96erRjD=aYC6HGM-i(kX;U3F#4`=7JoEp(Btyx6TQJy7uR5+Nalw=^j+ zRaEj6R)t(QhpSF9PU$<1b5_XSKTz3$qM9cNH65f(5qn}|Fy3sAP&EhCS+=gYbk5!w z{O9^GFX}jEWebgG&NF?UAQ@TGjDno<~b<-v9W>=Cm$7MKqkK zB-K^}HgpLLlBm71-?~g4e?1eiZfi`m5qbb#YPJJRj|%FRldaGS9gcK8@;o}mt&ghY_^j zqJAC(IS5jfY0RJQG*ERsX~3Seb$!|I!$=5B*q~lo+WV5S zRp^{rzoP0yO*~$pF#9)ED(>2n22d&g6J47wGx4rAg0e3ppxhOw;Hq(-M1tjoCz6dV z+f?QY4t+Y~qO@R@SQ+ruVrq_h-)yxpLuYi3ND>p_{5q}9)ULzF>2%~@seRAyJQZlm6lgn?mv5BzVDKc!xZ_EV z(iKVCLrLc{TWw*)8Mp9{uc`&4`Tur5GcMa z_)*5clXhN^(%w7FDN4wz+^;)KQbR~jOYxX~e}FPIOWv@4Vs60ee|=S1j6dEI>m@T%(A%bKLSDI&ZskrUk&tCz}kRdz>Ji1%JT zrKx1Hm_7frN&3A{#0o*UL){6tJDYBdHZ*!GJQUc9d**{47=UDt8hTiW4;l%#T9%Pm zIG%4G8W##Q>kK!+c|!MdV8MT7$;vYH)0K?xncHDb@SGg|o+pCztc<2)e@!SzQ?gsn zWBykOyLlYnRshxof`$Ob1y8+Ir-#QS)azBGkQZh3_kSl~PTPM|E+X|7O`ZE`tdqOi zW!Os}ztcBx`-P{?ssvi;_`>uIIFPC&y(!7UA+c7hxm*4{J|M&z=EoLL!?AbDS^?p;tH@uf-_lmSs2+e1xy+Y4c0Ue#pCt_$G zjvsrorA5c7-U?FT@B!gpT=2E*Nr*q%5QvaB?E}b0?GtgA`R?dE1sZMlrC6#=h#GgG z#4O5@fl2qd%U1T5o9QCBold*mb5@t432yaeE+0yfp)7y-g-3a^NZ+(hZGU&Pay#XZ zt`E)3EG#GXRF(XDdOcS#O<~U^c*)XrgXZb>@wL2<3S9TP-Wz~te_qkqKQwJvcaFTg z!$bXaP#uWVlS|KU&jLn*ZPnjlf(Q40==^obZimUTszbvOikaw2ja!O8k*~fS7mBnR zxjMAn7}jbh$s4vs6&JtvGl*FunY%y&y{v9Yu1`*RZwfmq?@GmTIvPugkNBwcyc7tu zvsS4V`{?8Rv^7Czg*y`F^j`+Q8BrZ*|G?6;rVHL%vDX_3&#Ujyog_+kwq#8A5=2jD zX=U|xc63R%ceF`oYek-5uf+9s{w0_0CP*qVOGra94QnF4q7-!&M)u12O}v6OK6}E3 zB6#F4i~3+ExQNu}`=AYz*RjjPc3c#*)$!N4Ikp((S(d6fqcPkkR**AZV@8EG<+bOx z!@empkIj56vF)#RMG;(hMd?hKG$bD1p!f&$NFIIC^xL|=OV&`XlXwO8*IfmBYj*JP zNO9Ql012-v&7s$?9efIQM`I1JNN67c@fBJviVX_oIvoTS z3*`zj#=z4J<_gq1-@REX@#gxlL_X@2gr$kK5O6>Q{K{2b)Tw`BnzT4ixI-C`D5f4W zTFV~w_$BF4QALO1ayi?r+%$c~R$P{)c3-U(b09=)VZ=*7+FoSep0}p(BdNk9 z1O-jJY8-To?R#6?pYq9vPB-pc8%T8>5js!~)jMW&%d}rJHh+lXzQYSbBQ~FJyxj!U zoqIp4lfh#4Lk}{j!)9-@;cnm{OEc$P`-1l=2=XEda!a7}ndB+0(R1lHm6|nn8z%py zTrU3(?X%ZEJs4@{X5?(VH#p3;On21Md=;nQvY1WV8nfY3jV+$7tdQetWIx%3ULS0( zWYZO?EK1y)2%;!IVCgYoBRLFpjqF?B?44- zPw!+_6SP9PtV&Wh@7sCR2d#zEGxaXh!eMH=t2Yae|FB)#c~QKIENBAb%${ANE=`me zR!Gp%KKMLTqBUnHxQKE)I$k_QK5n~Ff4e{QIMe6NP0Q4v^`zbiVpOt>qQ4 zs;!r2Vg4#2QjAKCqH{iPtmoe4fBu+%@VV#uEtLYXpGC6pCw+agDqaSIb4Az;&0pZ* zuM9PWEg|^jSGvAWr1lROjm*^%zwBg`)8C<1 zxVD8ZWqqZi>T`k``sB@Wl=;yOL{9fG7n4^ zb_5Vv-QY~GAcHmh#au63HynAvzd)V0)H~W58UuWNLIbB!g_=Wk%8{;suVrZ`bXkbd z^Bsbyw{XncybE63loVB-ja)n!SigV6A53SLJ)l_pG%;{hi>Y;eJz8V>rWH|lUgUb# z;Ak`83Y3kR5FxOly{vVpoDLl?EUfWF@H*RCwNn_iM(b%?an-jaSZ95Y-wllG9 zeDmLXf9qt<=3uUwHNSVQ=eciLN7#ty=)5)@uH48qVkhvmTM>fMKdIp$2ne>JQYm6M z%d8YTy)e3=!iJe;ahp`)FZR)KoZg(!cgHkb0IHf&VWJ~3p9M>IWh-OdR+NOT27O%t zvRQ*cBdK&4hlO$`vrWf|EH>mm1(eqdJ}mszeIhX@oSV#JscI2krF?_Mu^5k>8p%@WObw_Oht^{Bzw^n2Rdq=u~0~S5p@TL z*sF2pobe%8H=Z!G?t%=kV`{XWr5XS)7YFO!Q|PPApURiZz0VpOy>sZM~fklzWc@xI{>I8{K8lHAC87pp%aC^cKOHJu10 z(PLtHRwUjR+%b^_V*mAb)pr~L_sA@IepT0$RB8!A*g@MP+89(7UmFNhVu z_IX7NUYhba2C!)?!lFVh83J0}5i`+)GGb;&0A|1)QY0Z<4^`3~bDL{RnU4orZ=%!d z#!Y^efBJ;2Mu$hgs2vbDaM=-=4>Ne5`u``=Aby$#F(|9 z+)ohG9ifLmxO#T{CEYY$@&iIeEmmUy4u*WHyftc z(YEYN19AE_7`9~BE(Nu|3g|Z8D$R|jzxB2y_dYgyV`e?uCig&03jAv{=sBc_0Dgpn z*=12&0+qbm{@><xz^IL>0 z!sN<><8X3dBp$wM^#2JJ{x<1%E!x+P3)zmuTg-++;?x6>c~RUyJZS6DiIDeVmPcfF zT|sS!baC6uM*qb*5LuI*XQe31a`nhM?`EZcckg`rLP+#9oha44g8KI$_<*LArLSi7 z$-jx(Nuvr%>pK#gAS;J}*j3RIxSyg4Zhj-$w(f+AR|$DP%h3yXbIA)MPSNXjy7S#2 z_F>-rNBSI&!7VWu%Rx@$b>w~eGF~@Iwgs+jvM4q>uBs;3xl)|fK(|S?HwaDgKtzO^ZengTn~Yl5 zD~%Eo6x(#FmLksGT_<|I@uT{5c57;8jscr1bXJZo9|(bmRX5I9{6`i%k27^VmwqYE zhe2igtl&6&FPd2H3$kb&C*D}D9ph*&+pIz!{4jh6gqs_9XM7T_5}mMEEVdUcJfD8f z1?arXmg7QARoQcTvS@o29~~+3a@?=}99kTJ750pXT~kgrG4~BP=hGvhIEJ>Xr>|&J zi}mm6jFUq(IAn`)(&Uz?Rap`43kW*2HeX>U@8XjLWqHV4D|MOlWRdGW*JF#B(E;}A z-`7NLVu*#)GPD4MGrTz-mDXSRi#-SJ1ggj202HDa(6$iSK6;`nC z?J(0_HhiAV6~MnaaAz#jQ3l`E3ZxHRX(-V$z<)=lFM~iLZH;6!B3i*_l z1sO6hAj4sngz-;cKg-?nzS+D;k+_Ee^4lh-_a>QRLl>+&09Fw@PC8a7Ztxl9szf1; zQbJFuiFtptXvCSU+5tfdiR76W1>v~MhdD=qg}MpMq3axlHzDTXkn*L1Xhomtpc9LSqeAQ2Ta^}j(WnFOH9>thm4$hgC=Y}V z;Q;$sUQ;~r@eJ>NsS<;UI?A0ikbECgJv*UOKXpAuE}7L`84kbmyt$4Wb!MS94_IT@ zzf%yGeE&q2p6S?Q)RcN&r&;iexrw~f<|rxI=$Sp35i5RcG*=_fMkMvaXXdi^z6oed zBH>Hw3dS4@Re4S3Rz36QKl4o=T%k{Pa13aeqYFd`JbPf>A_~Y{fbF8!76_2@eVLs zgZ_ztb?*Lj$?h8%0OF4`WOJ2M!R7!y)2GEgXo^OTdb0I4s%6_+Cd9Qtnin5H*31Q$ z?-me5W!aLGlX1P@+SvZmF}5F(*c_6Ac^TIrpwUXb3DWcM{~q@*3z-i|K*ChT`hDV> zKNKOCI)FNFztm?7d@M(&Uz;fa?~gDHZG%tvXRbs8 zIngie?c599SKxlkI4jL8=7{lSi|9iuI5ficzG&V<%>R1EqN1i&Q}Q0F|32Su)RVNC z1`?Tm2rR^G=2NEkreNrKbL5+1+_;DGV*#^_)u!gymV6W8)}nv19Viqa=~3KRg?QW^ z9CNK{OFJnH9fPYhWtr%cKrn%c(E57kX4C8PPaF5D9p0HaonGV4_X{0}#yLG*TN%gY z=36%m^~am!19FR&e|_}6Qe%jD7hOoIpFl#NLaTN80HGl09XGd)BF6qQ^u4M2e^=kD z>4j1mbm$0wx&6zMedt>(7jN7cTwTHWn;w!2Ki@frmpOa2i1rks;}pHzS6Eafw0tVD zwml5Tz7hh(c>*tDx`Ba!#f9fZP`9(>$KLv9m2chC6f5(`^C zn!~YdhaxL6tTRy9_;7acH-A03jG>?^r`G7#J|bB(k8N}bwAd*^!LECrijYAf&#Vbpk zSuyVAhESp7h16Y<-iEY}0^Bbw$gq!wCd9-cp`OUM?olbU{@5P*ZH zr+00p^OzumTqeR6RHkwm?5t!z3oLAw;yC*AFuzJ7H~#C8Eyn#AVJG-m7GJYw+9>f4&so2*1jp%H5+1G4j9`zhT{E211%H66`)||i zv1kaZ%2}zwLc)c62T{X=Ow~z9yO!u6xgfrv`3R zV-#XYKNS^~ph2c^+abMR_tWiu`)KNE_!8O_`p@PBqdaatvu9jTrSpVU*mDzW(`6|I z(SoCKOb4J9jaeu0rUP#V(L2L6YNRtp+^9T;5hLn%dt-)Id1C+4fb7S`9UA?7bGc1~@2n zKJn#;MKGHgYwo!Wz9K%ZWjo2vB>8*1RZgZT_flHwvA@`N%=}hu)3nSCvd(sbN0;kq&r?})vz9|V>OQ{C6HEKg3vntL%xYLX*@|#1?ti()4kg%*U z-Zzc!i5BGcE=S8{E3KuF3ueROmQ5#Hs&^BccXsnf;|!v{VO2}(LJFDlqu^`d`wEk@ zy7U(}^sCK8(<YBt?zX~ea}S~oS+7LUZEOAU^W+oqE>(AToHIU?#dHk#0@lNUMstYNu-Tp=w4 z%I?G*{!?pl&+*7{249#ip2vc*d4zY8lOgmLF&2mlrwD92DBdOGubnBiMT5AwlMyA} z0u#&_bn5;J<~slEPfy zVl=RtNDbz5t+a+-Na{LH)qF|FMHY?FSGPJdb)6QQS^v-i&ca-B=Usk0DR`j$am#DG zX5b+^jO3?n0j``%_NTJ`^md=@UZ$w<lCcHE1Wy7IN} zyun;F3)2^PxiZvuR>?OuaOm17Xi3auB&V_5!c63{;DT|CgX@H5hMQ;DX_P=ha^Jr7 zl{5jjl$XPI&TrojCKDPPSYv^0Xu!_#REEV#zo21y6CDn12Fo&9AAU#fbwD2mr@+NX6-=$sUnUhE6NPO;<0h3pjbw~07U z#6v?}1w(|B!Q?7c@wQrY0VM`;d1eN224)3Y-I#{kSJJ<>{iEs*!@n~f`8(~cmyOu=5E{ZETUuH! z7%Tq*+q;cF6mXr--N;_fohYEs+!#C&d4BlpbLxM7ADrqu%%9@NG>Gf^C#Je)V7W_) zlUO%XEXg=;(J*)&H-j?xP>(FmgOdFq_?gKX3M-;;iZ~yPN^V$^6h9^-XTkNGhuLFJ z@yXlP!b{?3Ghwv7u7G=Bwj$>DeBy(l_IlXGlp#fpOmU4rIONGnT4Png@EH9RM|#hM zNY4qG=W6)~95FtQT_*|uE|+4$h70g>ch1~<_DXUkcyd;?Ic;XKeM}_xNo))rCA~>^ zCK=xyyr{U)+V_0(*dsIATSqcPQ8JRHOTAsH(*mQjjOjFVg?%yMTGaN8i_4z}NNLBu zNPT;w-|zC0m5l)$a!7U8=|?gfGv(y#(JBLfTBmPte-qDCf3DbPs&RlUiH1hH2(Ez61F8;YlK6)rke-1paC0ACMik z{mk>JeI;HJA;AEa?@Ke8VJxktr;(ms$L;2_c(qsd%+(1lu5dLNcO|oVurD2WG?3#j z8EABvIpTjPE}m+rQ(4{3ihaM|93ScPzdvrGm~O6ib3L75;Q`Z%A{LnI9i8k)jr;(o zHn*8zgxLj0k9h9;W1TR)k>KXA?DmzaN9n5P=(or^=NC_l#Q+$Q0v))OGyZtB3n=qVoybyz94*h^Q ze);dA3MTz%k=#Gf+XxQvuKj^`8Z70g z1?g|$zR$b&u7>?(PsfMTs^F^o-_BTbs{cS7T}{u2=lxo6Zq<;yf#=%)j+;-P*#B*j z+a*F%IlVvRv8veIHZ3+EmjA+04};S-KoOS?5b)b&ml-S{yBu#qZss>k9b>UZ5_2t= z{of!;R5O^m$^SWv@2d{lkLtEu&w48RcG;gy@T(_>dN(C|s$ANl8i{P?Qt zcDm{Ig^>^~f>qboX~WaDe~;#r?$>=-#{Iv^95u6SrqU|;-9$#(JCn0YE*HmcjKq>Z zprEO-!VAMnO_3^;8)Z%sy@g;qYIEPnZME)wFeP9s9gEi()|c`T`|Woc7rj5@F3^)$$|#!)iswF7fBjS=|L9!^R#g zG=DB2JFfLIMb1pU*fbpnS_E-|GjYZF=F#-+uRZ5ww06W z^1I^sMpFrrZEFSfnm2<#e#h1y=5vP@X#>jk;w&1+7D=|vlL|+Zvd2Q10WJy=lIid4 z`!}5tW)MoQG!(b+Bja#+1$S0g;nGaTd&yXyS5tLM221)i12qHT1$M(DMz+J@Mz(`} zz>V+$;3kzLCte<%My7ho0&hw#`VBFyIV&ADYxY!dvq_>pu8rB>^Au~E++oh%Lzk#G zAJ|~8e50CzX@fW>sxxkQ4}4@{B0Kq35ub#+`#{=d7z;mn_W_@Tn?|+WXxd4uATl!D zFvOQk$#c$Ntx-8L9Fu=T#ShEd9?dpj;f;EOX^e}{vg0P~9^UPBhP6zI$3!brsL`sk zY$Y;FQn8L~z4h<$)1+%UY6c%eJrDdu*a6tc#?IZ`=*}r_gBrl493`7a2+YL!t3`g44sQvNA7RLK9(uk2yJa%Y7f| zsg#oJ@uZHJrIrbEcHG0!s+LpL@$0v9xs07wuIKKNxE*=YPdGQbcT+$sLxIYfYr}Dcu+m~2$ zw2&+3%3U*eP}`8`*Be7KZG&L8PY!cLg-YmOWpBs2<~7{50tWuA-CbG&71+6(0O{cR z$G1>qwLl$;V&Bg$%fwZ*MrS{<9}-ni87=w6o7piwk88*+>ZT>`dXhIWRo4b?!!tm< z0^mtxvZG$3%)0>kVs#Wa-{K1{6X^PtK+1oXz<$PcReXuBXkXoWY9HK?3J)W5MrSn^UPP~89ssXORiqw(VOO_%(H9tk6)(8%({RE5l6$%S=xWN5iLwHDJXVtsqe7*{c&`TmcD_H z)`LG=HNfNMIWdJ>XY+kdKE9IJR-*(--o0DInrEl-*K`bFr{~8p>-y}A=c5iz4At+C#VTkbwcq{H+wT0_^zz(DCrSs&->eJWAS&wo3CYEG zfVAyAE}m>xmgD<#+p(SC`5lu^L7*q8eFv;6xF%06Wex$}|L17}5_r*lIBfYWyIko{ zN=W~@JSS5ASU;8Oea`zY+zm_}Oo|goX?l5I?IoaM)HM=fo3^q2JoR;8ZC}bpgTXGxkZg%SwswSvdt4n z&|*q=bkz=@4ueOkb^XXRmIs=q3y|0lWdkzv@v-@sV}IWcdtTL^K@Di zkCv_6?y!Clyobs4`|k)0OmD;uP1gbSM~(^>5Vzj3_FQoyhfC#0(Vk^epb@#nv$X-hGK93x0^?{hZO zS~^j4{g}SR#JG^;?%|do%lfeRm?LnML*Z^%9UJTAkY7|B=SICwoVDmV#(gZWL}kCf zIKho4AJ385W)w1NK4oi`?@C_B*#m{%cL9%E%|`wzlAXM(H)aSm&H5jb1Rsg5w+7?;TrgPX8e@65;p8ebIy;{ae+LR+q&w^L6o%}jlVtQ}wXr=N-8#N|j}rR+`lyXKpXn%h z&T1w<;_LmOn%(uo{V$ay-NkG9(!#4KXg`3+v0XcWr2N@z`0@7qqU{MLXH-B9sCYlD zn6-j$!od7~X&x;raFgX~#lg?a?+x5oE?BA(lCI#!_}|5Ykt2G8OC8lLdb9SIY}K)} z;0D5`=iR?dS@!84Prx`Mhp#XJ(#}V}Ho^4tZs#dIG&=7ON*sao#W(@mx6A=_wJ&ZP zCU0ScNS*g7*IMdl#&}?#OKFvjZPD&)E!f|=i|qFl^rODEb{WT7{S~oTwrvg02EWug z>ph#xvDB;uh1+Gloe|~)*D$T8^dB7g&aFp$`pzGZwv|j(`$3~#4yR1N^m;DmQ?yw< z-u7+Gx;NoQue<@*@}f*K>-m9Vjut9Xe>7Ntu{a<^ z4*iXG7de?V!{w`;r|cz6~Y6e{oYi)H8YjAt;Y z{?WsOEOJyNilOD>-S)rWKsju*IH@CIeyjPn>drF~I*nEZV*pX_8FjX6FVn`Jgc3Fu z&3b})67K~n!mJSZxK{Ez5gHja2`alas`|!giFhC(B`3msFg~7nc5c7xuUyn@tO~FD#5=JLA9JPcny*1Y2pO+*dR>QgsE=k9HTwWB%(T^ zrq8dY#Nn7f;)F&Cem3?5{PllB`zjpL(f#vxvTeEa_2kQAU`(K*S` z>2%tER;X6ZHn%{hU~`!wgd!6LxNUjLo@6l8XSb0%ze|uAUoc@-Zk#7eT!cX$X8O_t zT`&?{ehkyQ@dj=@5>VR6CwhdBHYOOW1~tfY!-a&LHf}%?3LRapcER|1jXGcnxbw}T zRqUmg$VvHiO0+Ui>%=&WVgVFH0OW9{{1)GO`W5oyBpztu+73Cva8mV9iGaEg1c_Z@ z(YFpmDF;U0_Zykc&pse?&3%1&QRl;-)gqDJw%-un{!LF8gnFb&fMfzQ*DJI9uRYz& zzlzWSSNArZFDZwAXTE=YseT`D;k-{$p6=G+iP=(}sGu5#IaRLwX$QT2nCiy|10|i3 z*WM@t$93NBGStflB%${jm)z{wYaH0&gXYZ3MQSBnpWS^1kR|!?U-eR467J@~5Dse5 z=cHN~gcx5n_m(HqURR7WI0^HBu_%cB=WF&8udj)eATWs9MHo7D-09yUnx(GqF*$EH zBK-E{x46ab6StnkF2-m#y%$81ovK%U;1Iy%zO+1ogmx}W=v(tgdVFxE__ItZJVQex zE92@R)O4MQ0{yf#ymZRaG3tm`p!4$tr?JAR&7R_LRO*tUhyx@dqJy#Ido~XgQ>k9) z*;=NB;CEwVm%%=Xt?m`Cq5k};-q)w7pA~J|ZjIgjhlILP{I0o-Ph6+f9T&5t-02tG z90F1vZ@RldNuX9gO0U8HXwQ_8U=U(netth3xezU9Qcu@*T+lLfpwG^XU&lpzg=T&_ zi&^Y2G9ITw6^7l(@~2TO7j#Y6Lk0oqK0(X^&TuS#6qw8g@3!T`;ro87$5SW8`*Kvk z`MB=1&|@$VTI||&Ge*mK(F$Uncv8`}?}PHRUcffXs*@eW|NcKK%4Q%%pi1klRnRHc z>*5#^lEsWWN0kV%R6kAHU4iS{ z`a_ZExc6ZO1YphLI763nSOWN6NiKk2d_CO$N;}H+fi>YLPns~vk{6gM48t*mp9NsS zi*FoeV*8_-;Y12ijT2=wmmwMw_alN#`;+#W%iD~WOgHhc%f$-CUZzSR4K2XPZue;n zS;blWenO4=T3VIHF~&0uqAi?GE!b(sUDgpVPmMAM`%iut5Jqfh=#RnY4&|2q#TZKY zZV-x44o&0=|A$h>BI&ZN$jEi?WkEb&Qu?Xc)c{1m08xN*8y){QLXx`Q;nG$#F$6H6`K>yY>u zm6LX|YP@7q;Lg7Ifdo8x|8lJ@n`(__ zKz_dPyJN0i8YYJAG+(0a!b!3c5Dg62k=|F?OAsA=sLi#mNf$vgZVXs;#twiSMFD8- zx)&`FYAP7Yxd!=A^oas{v0=}1zX6;jrzPXP3qVD6;e&fVdF+AhtDb}TsN~<`1*HM7 zhwDk8H|ezf!hiOyii;s!IZ~OW=g9(aY3;I^;Qg%%x83!;d@Lx3&x;0?5}p3A#H7`N zKD|$|26w2=Jo;*L`-shtLg5A$D4UHrD?7^QJF2BdDDLA^fTrA7^^+?0Jx091u?CAI z4V$7`QJJkq)@Pm*%x1(*b{=??>OR~*JS;E*#?n|R>wDm9B}k%$qX`-NW{Y|dUymu? zWH9jjvJ$nkCy&FjZug z=a~6E$suQMbk%k@@Uy5Ys<|=vX%kt$2(ZmJe}nBUjrW+BqOWb`!Eq?bxq-?#Quokh zyAW+dv4zrcC%-ghy(ZjE9D1J7G;`Q9Lt4*dtY3_#-#wKECE(Xg*F)VxeS?^gb1^iM zx5DZC>B{M;1cOJXrm3=l1I}%na+F=BVqox~k(FFEP~%6ibvnK$sBFyMZ0Q5PGQ?ej z>H=jB-5|W>^6%^0oDOZB2MPB}0{3uzk&ZXJc#snK_S#RY2UeS`)`Go7oKNQA?8eNl zM3DJZa{ov+{#O=H@*W_>spCfja)@;kul9dMa#*z}vG58{)tYJhiGjh*|9=}EAv~DI22Y9dPf3>j z|1-IN&Y73i^m;Ms5!<7Cd!r0_iVr2 zawz4jyG-$c@%6bsUK|V^{!nk~bX20VnXVbA`%1{1tuDdY2$Zfn(r?pg)Qet91jap+ z^*{Booes9~GlFN4Ft8gdUCqfm0^>G5Exx?+5AkTN@ocB9Xu}lZXmoTeDG@_><(c+b z#}oml<*YfvrE-ilT_A@lgGVbe<@RGbs8pR(yvQ}n7~vWygA)OkdYJx^T}b%b>zw=Z z)=)$Wl2DemkHxOKzrDY<5YS4@+(qX7T+{`Z00Pqcb>PAfaF<0S2}*M&qnosz^*hxW z_kAr(#L$$XY`y?dj!XIiBV)qUBBZCkhD%%+H9_{%p<-igVv08df5h`PUJ1{JMZ?4? zDxESWQ6?5*2uT{pZ5=vBkEv7u{zp*3-e~3 z9E&eRq9o=4#?{a!B&wF&a(i8H)9Ey8KIDFR*l@yX-=kE(9ZfQr5RtR(W?iU|K$8;t zt!~g-+z!9H-6g@z>1qbY5e_y_ikbIpyKN-7|u;Uj~8Q5?4z- zDyD@W`EC0+hVGzyGWt}nn$fSZ5yGmW$gk&{1Yt5*!8(tfUqpZeWo_x^rFa+1D0i9n zOs7#x*V8^6hBuT^$^L`9OxRIQjO}<}z0<%FOYu$xxLT~dIW@~tZ;X<~Ce=oLPWHs_ zHZ25m%mjUgiB5HUFsZzcwj^Wq_fLjm0Z{*GMA7|mlH+Qj@>njaD8^IoD#!k0=lud9 zY;nZXVqbExnkNo=H`V1bvEHxiP%(PbNl#+{qRXz01pfOH2+%MkD%7`X3X&$|Vo6W8 z;B?mJczf#wQ{d(pU!fj3E}(b;u^z@H+wDID9&rJ=SQJ9Q2@UN_^p^!sq>lcZdSCY~ zac>_*1&%L?0(xOfn;C%%6{@57lH(lOsbr67?ARLCsdJ1gad-WgF=k+H=o$wt3*oWG z3bRDICNi9HQIS|_O~qnC^u%WGrZV(*#qb3DZ@?*(nvHANF(=5lPpi58doA~S`$jD@b4}2 z7=NzuTj_weLU=(#3j7wO+Qb3gia|MdJFm4UDD>mcD>Xeab@O z*H$W^aynJQcX8~qK#R&$CfzHlJgV{v8YY)jna+<*j-$EpO|hg21erB!Pt8 z0<`mIIK6cRcth;!i2%?eI7r2#r=4l+*}?z3 zjhba)!Gh%VZ8oG9(Q3+h5Nii2qv|@?7YXWenFtf@#7b+DU-3_O-cL6x$`q(?l(gpj zi(ggHt0h=PxOD7pCP+FPaI1-`CD%Ul-UmaNIWNy2sq4W0Sequ;jGQGT^%y5*z4t5 zqIR@z%mfnmc;O7kTBf6>RtXHJ_sg3>zO#F{hO-7?$6hitlKQWj592A@xBFIA>gan+ zL^ev zxs zzK2RlgvGOX-57XIybV5TLwbzi;D+c+)%)tRcCiHfpRq;2m8{nD*(`R;&}-+hBu~pu zq%xb=qh6PO6&mJUGB)@3kb}Ty8x5{fo%690@58c@+=%{6zF6A&7!!raFR$VDryQ&ruYQ|s7DMg7EylvaP& zoe%3$uk9q5>S=&xl+_J0v3mMGXWXIUAfFGhCRFpJb4srgJ&Rr6TP&4s9k*6|AQ`HB z$dU&V#DK&n&0^=Q+6|XPo|ngZmT@E6S5Kum(_pNDZ&RWew?YHSb~M_^nEKF-pWT!@ zlFNJzkRpK_8lg-G^yTxF>L(i@GY=50wpccx%5_LEQ+WyRftji1iC9t$4MbnH!JTd>hs2Zdo) zA!Njx9h0}mBld!j+HPbhXpIMbE>c#UneBcq8lyPXr4gXSbQ4Q_tCKVMB$Z(k-smRW z^9oLKvl*J$pEF)*YQ?mmaePw3-5g%gw|7NU!hlOvw_(~#`o0P~?{M^SsZB@vt+WR$ zYI>scJT`_g1jxW60dp)l?swiSpKJ8`#}5oMU3(}w&U5Rxvm?E2{~+W6p~Tq1zA$`x zulsb))3>ed%I`HvyghwwfX@+-oNxz{j`2k1<&ZVaT7}cjT~Sp6#bpfeeiJ>&agB$` z<{Q9P?uf@YEWyi_!X5ID6;Of?%!i&FS$6@8jNhBr*tsbpB-YN`mUQLJU$47;!=2bDdh@;NM;<~-4;lg@KvzdI_e^}LZ9c}e|#?30pFnVnAIM0$%CJllG z5dnVdJ}m@1VkYNXpARiDKl4RGk%pEhHH6+!^W9V#_#%3!7FnTH1$&Z$BJ3L zJ|oxCFR4$%wJ=su`R;y}OaxvIP@7MsUuc&U^DHb~^^%8o)RCFMX7+wkll*c)5VtIL zy{WmZ$N6y4@LVoUe_?Hx6mx)x*h~dBzDOaHewOs+a;qG9t|X}}54o%qXPNydL~vo0 zS{us^X3~`Ebt~pfE3pbyp5V*n$L{>$W9Ems6!O;(e*!{u_>nYeZ*a))tAx=v`eXA1 z3j4GC*n3)$3DN|iVbv2`^JpTx118N?JSQ8=f^U=~?OaL(@-io^$!Q6WQc#Uw2A_A$ zGq6Y_8M6c=;`{gVWF9)?R`F{zW5?R$3(OZusj{Abv4_)UzZ0rVyfgmp@j@#4t}C=~ z^Qh2qpvr79k<`Hx&u{5`plj*Nxhr(;>{QB+%&6;`TiC2nY8;n&I2gcB$52)CKdD^`^nZ@#DbHcL>i z<*jHQ4VpM9=IHT(dE4DLmq}$gU9|n%Y=7TwSb6if z&59p-Fl?DASjd39tYV`r=B~q7i)y^nZt^!WFn|DyqxfW}zG$5=v#?~({{Ia_E3El> z&tj&Ta}Nbb>i%r9ogd|H`gIEHiyRN4`?VOQqWwu(@1^e{r0*B+*D8?1)j?+HFJ~Zr zuPg_|lJ;DCCf6Lb{(ob|wX(#YAx)s!48{?kzF(J8`ZkRreKR3U3BTU^h&>qlSpZhH z%27oi3%sG2V-!~`R_UuD+ z9Xd9u{DQbq)^oHac}(-6@C)%ZIyao}k)R|6Gd}?~g;68Ay!>~fn6|7eo28YNN`#yQ zHY@68p0e59nhDASPK$uA>%{f4(-z#w#KfZTMR?jv7B@DvoQNZNU4PUs-iTlQh)wFP z_QbkgAfLCx^tfxVie`7fZnn1693_&ZKoNu=_0p?8?;-JbQ{XFNz)tBkf|y4k<6=tF zK-Li0dFg;k;AeuLiOMy~Z*ih>)r)9B5dcbcne?mT<(@f0we4 zxX#$5(`q!1wUk>K75|fb^j8?Q8QnUW6y!;CaMBHla)GQyiyY}nLX8C(fhP40vK?*$&F2@E@>gpa?1oveSjr@4qUzH4PxDempzw(Oe@$ zBGANgxsu&aTLwvo>aX=Dd@+ppdqDd1d*wvMU%Vn2^+yRYwG?3)hAy={Hkm;>X+)C$ zoUzzY(yhJB5J;uqS3Q~Ra9J%~>=11Q3i8t5YJKkfq6X9&&FIj`saEM;22ep_&bvfSCuY`HQu=JjY;Q5z6!5nN&_uWGh> znDF4qi%V!z^qe$k1kWK}XlFbMD`~my6&2dVhqHlTjchWFhO~ws;mPFYz^3c#ho1xX zZRB{F;q$+iNXo;N2*5BCS>Kg%-0tI$CB!o|3?m)A9C(Jh!r^9<5TV0S%mw z?{jM~+X3JCT@95G8i8{q6WK9C-w*O?_4!Ut%Xh9lW*X!L@Lr>of0-XiKAFfLW(!NI zEwt%RTAoYz*u?2Lt%0H;Nay>tQaa6S5#6&Ez$}<26F=q68n5+Fq}3L?xB@LMaZ50# z2+UfM>$R)ttp9U^SVaWbn^E1qHm}-fz*vKROjc|+`^JwAG8Zp-&4hciFTay=-()@!zP959!q2`aXj zjXTP8n{kQ2<4)1|E!?kfSkL-%r~NboKd+YS3Uj+8KKxz4f7KjoyqvbSxfy;4(WNw! zwcKzHDmm_4`1mL%J;qnV<9F{0_TTzU;Gnj{5W0H3u~cIIB=5d5*Sde_y7u~2i=W|c zo&*t|MeiLWKX81CFSgC8Til?}vgu*ELCsIwY2bX>>J2QA%YS;Qz@{PV(cy7E-Ta=X zfa9(`jmszy26i~2-DuBOo4Pn! zE#d=TIE%@-atHcqR^){wa)NIb6m&JC1MjUAYxBNTEMXM1(nU*7+|6*R9#Daj&kU0; zql*l=cM$ter3dI+wqmY-P?BKDh^#YNDE&XKzA~z zL`h5`muUAs??C{22!CIVuMUyU+3J=2muv@p#Lw{|1DC%^-uB-qrQnGJzPG6vXwJkr z!SbxXC-v8a?e)Hb<(EYhT$*$@iB0BfP|bfU0(u7=5=RjZ4}zqfo$C#FRdqgw$kuDe zzIU+%J=N=Wc=5k^6TXE{`pT8m*NGW+jq=_Gh*X}_w7Hz?Oh{!bJJ&p6bEH>qNjYD+ zkrm0~9no`~O%KqoGf6Wtwc6^*JHMkEmt`Aw%k{kkfuZEHJdiTNy?t&Owh!H}LWRCn zUdQ|A6P_nwH#b`kDnxBvWID_IfpCkBM`#0SP4t;UN1hao(i-|^XG2k_C!#jzNau95 z7MY%*)%kOj4D#2MBCfJ7%8;FD1t)frq#6$O1-Ya4=r^v0xG^9SLJOIqGNzg8w}hdv zjN~)v1uSbp%UiaH(_=ZlVf!2TkNHC9g0%M7{^HOeQ3nY*dgYtF>9>2|r$C$DPsW{bzj*s+mvMHE)e}y04W-m_nh#Y35x_UAmxSdb*6s#LBtgKEofGBv>I`TY>f! z`PH_G*y{+cn5W~_d=Vel=MAoxF6k-V4PW>{wOy+s{(kD=x~Ky8eoHox9J4tRD1--* zx>$!Mr$>RkA5FLO;PIDow#Dy)2dG-G|9GGHXliTA+eo!^k|hzHCso)~wqq4$IJ{Y| zA6aOkM85g@p?p;u9;91TDcgLqhFQa5aAz(tl6V_4Zk>FPoE*@xreswsHf5s`}8!D|L$=9euk$bD|RiZSv@eYA+PYvYIct%ztYqqO%8Z{zWJH)+_Q_* z-hI#6r2)S>vZ!oF04i#?68azDw8{#C>Zc;8yL^KFLwTK9se?o_My-(09(p0`sE1dMg!5)-%kZ7O;Pezns& zO4BzDDF=^oPIOWbKR>W&afn^+m?hoZ4_Ga9;E%W8EgUSjC+>M)?(UyYwl`)+BT=w7 zo%^JefEJ`Q3mB6=ZYRH%?xx9>3KiO(-k};C8k3gwc-=akB`_P;&p9JR>~i!GOz{YzySo-mPuu8KPUnb} ziaPe09?o0AYjq#|-~15_<(Yo{l{MZOFb#q&^&_z(=10RFZN1-F1AZrs+qX$Mn7B*w zB0}6WmJ8gs`0x8N)6?_KmYQu`>wUNV&&5gKk9)hj)0-OfsPhnoo5I!5csd+DRC>sP zQZzd|J6Up3RG_lvQ302Uhq4`z%0%VfEnuB%@m6E7ocRuK<6OB4ya;cYbm zH3}l)^})j3>NEhfr#Brnk0=DX`T@FH)A&<*>LR{5vuDf!yh2R*mFVXPhd;*Q`I~ zy4m=#sgWAa-}3;_E+Da+jAcp~$qS|m6NTK4AFSPWftGHKzTfM4@m_|6Eqqm0y^ z<}dOkG$&4noZaEMr1Zl?F(?v6r#`AFxivSOu^UpNk6mJOH0H6dKeZNUlR#A0yP?S` zA}JA6gCC*z!7=826!_V0pflrrrq3%i%{m0^7uc`6%{3hhO3kk0*bYUP`Zsx)JA$B* zKI(Ay$zmJgG}om$!J{VpS?KsqBe-Y7wuLM|-(ot)Nl%(WLxXw%z;wIM57L{U4kGUTu-Tt#t3879HS%`dn;2W{E~~;U z{OhaRpBqM=HCVif*o%n;?2Ky;3#_vM7T zC%R2YX>i9Lyl^6R2UAR|^q=^)Ky6tnaMBa5uXx2=h)%F3Gjo`$~-<)*cjRA@^i-`3Lr67oZ z?8@&M-Ks_Zmo+WARSr}EG(N?h;8xIVR$4<)z%C3?*g=?{@j|^5JDB+{_*CPH|HZNE zm$ap2Ff=+$Q6YXO&kSJ3Z@VrEj{&!#D8CJqLeP5cdb(`L?i5ociOfM+ZfyUH);-$c zu!KcXwa$bcz8i^S>*}z7!8r6gbwL$erlyJqBBBjpDADE9_%=bmFiq&TWFu2N#8u^9 zEGj}+2cnLDsQ1c0Pn!*_2eQa+$(u^v5?>WkPU4vl1l18DFq4P%&USBMpxA95e5n}-7TJfXItkE1C5 zkQ!sA&pVH+lYH&4`EqcO3S%eB^KBRLD3@~sBAy+V*p(^dNjB7OwW0BZ z@mKmY`7fkrONA0=?st00iR%~O7NYO>uwPteM<^+> zs=-n9TcO-#AKWXyd9EZvv;$Sua3RYKg|7GaZhHd_J|3^Bb5gPuO?51y?URME5RNe*dG* zj^CFPSrb(W6zyA%?Mv{Rf2eV69pT+~c_EqU{-2L&stKB)$eX9@{x)~zuAd^m{)%M~ zLindy2tVyYp-!S>*5G!l5(=K)W{h%o+~2O95bsIhw}}g!YnQ`TN)yC2>xVcy=$=?L zAyF(KDzkvP&gscw;^V`=i=T@IW2}7GD}Hmk@vPH!f8gdVwu? zw9i-)AL_c{hWuRv5rXY1afcKfMNz7-*$DPVz+RU|948|&Y_4H`dJ5PBV-)??(2Xq zOQk}JZs2a|NOc7hTkaY0eVGnf(R1YIS656t`p+>|X7atGF*M7dmq58;?)5SxF`qDP z4W}ge_{~K!i$al$&t?5)sDhqn)gm_}Q)p%)L^SMb0jgYob(-f9QjBvyZeI7{7V>B6 z0=K2_EX!BrSbN}3zx+i-MTDWj#xpb$l&8W@P@zHGrLxF?(|ML`%Ycb9`Wf|@l!>t( z`!XiZID5`H@DvNi5Qmv7c|>)OaJJ$XDvzCBj3tI)kwNrIqrK@wh^jWq`N*BZ3h(r* zyY1BbJ0~z^fzMY+99<|24gg`FVkyznx-%Rdo$Kqc$aE&hAo2cqp(p=s`Jq5m_u*uA z0JMBjS^qrC86c2u?9<3u?_3WLUc&acJq>R(`i|h(kupp%3ec%Qu&*1>IrbZmTR5M! zw?Hx?DOgygD+{-|Zt(mQ!0mZf3V08}l^5*mBe#3uRMA2gEY3qruwUt$%e{>?vsbtk zDgQy!uz~Y!bjs~SLLU6upct@vP;GBe2tc+LYOHgd^VF&sn-4i}9kUyVI9SfbesS0j zAQAF#g$w#%J-6%K@EciH&pLEf=lX|ijz^vjEm30gIg=j5Q6A4=fWy#!nscIOklWLD z;Gq5LB-U+by|ctQK8f+eXMoVqY!A2bl1)WBQDKG@x*)twmiC`t6?gmNJ(?tLc(eG% z>10u@T!|7eF_0Fe9u#!*>s&p@xskZDlhaeN;qoCMBHRvBnpYOn(^{&*?Y8@`;q<1TS4+ru9zKMob^3IKhit{y`QC6%^2wh}L|2{`@IJ41s_oGo6P%kJ#Vug80#B~tp(+c_FUNh%_ zvA}mso3ghiIZ_V|o4-h=D+;4Tgbd!ij!upbviFSaTBK<{IAHDLXn!0mLe78j)#pXa z+YPk|xqAABn*XVX7$hg#LX5rUOxgi9h)^l0jD1`v6CNKS-3JFl(p$5#J8&)NWsdbrVGnak(n|sq{?+Z2}XPOi1d)sUl%B8K{gQ&u<&r&(fZpy47 zqU(ups`Eo6t5F41rDuo*d7LEFOC<*kRWbxjta;q#lCcgGe9H8q4GVt* z$ZSqz(pWkE0k`2>wf&Y>Av-qm+zrc@p{ih?!D;XXk}n)Z(wuRf)Q$O(^OQm-q2uvf z7jE`mCkc5B(TN+loua>Z(j5BTQIVvIN=y5X;#sSFPRZzZCJ{Bv%mVahjW=d^YojwV z{My>Qt`6qV4O^TOxd-2eo)~`b+?}}Fd0tS{F^Y1-M;IuNF>l4GXg?E9yLd$@Y4N`; z@893fVL`t<{9uh%ij!?O;he$r~QSCNZn|Y9nge9v)OBIp9w!-tLql?{Sd^Lw5*|_Q z)hkqw#@&7)#!oN!{26j-aJcl1%Ab8nf-*zo?@X8>6fS(iuBTX?8-;TGV<|VJ@DWw% z)!?16Gh}?h0Q$!Gx+M_V8oNi+pI0_D*+1{I=;7V=QEV(cWV1XFUsx;7G1El!ING4X zPOh0_t-Dtm0?d2~z`;nNOSihGUtRp+y6$CIuA(ZLK_OB2WEnl03gj7W$Y(lR!b+sb zvu7BK2-JBvprY(?lh)+U0pS^w{d@`r)Tyl>hv)J2#(qsJQh+|MXfvLe{IVnmzu2 zg&(~v6>e}G%r=KZ&4rzgB3@p-Hi7G%xZD=)Feu;Q(V0h437f`&U6-7>JgyHzR=v#n z3M3z%?&Gk}9~4z`OKOyMr?)j}x6bHZi}E-<1)`DAOc>Nr{L9h#xAeCBH-6}zpi;O4 zCOg{k?YcPCRYY-_*qv$ry$KueydZadoOk%&8M_fOMIb``XmBXKj!>QOiGxJC?+YJZ zzW{G%S88R)kBb`9-@36+Sd^1GgdKE$W7s=8d&h9VLk8LH@j9`}Y0DKaVFH=f7f9$) zBv^3q@zkbit{M^Li$6=JMv5sx4+DN~d?g)cijEm2F0)0-&v?$ms}{)z=;?1J=D;w| zdOUnrb}(1W4iU?0z;6^pJW3sZf5q2ar}^FMe7>d!2FGITQ_F(*6={HoCx#!Y`iEI8 zoz23T#)jkzpGh6taf6Av>tN4cpESnai#Z{2!j$Qc99IES{`u zXxn};Jc&kpc=B;pv&S7suKTN7?PjhNn3U&4H-oy6HLSA)jTWX}d94BN8wtl{%w@X$ zr0l}rAbc(3bL%(wWdq-ODLwl4CmM#+NO~^{$y3Ji`(6tQ`Oz#H#$me^6&^}Tc`<@9 zSOXr^@7^7oWI9T_L`N7}i}91b z7$fwDCvUi2C9QkE9IFg%>ZN43pjP~@Zif^1dW=}gu41@A(lc8=|Cca`5GCCzclCe4 z(f@gZBw07+b?eaXSc^(4T@aad>rhDqupRFY zL6iy-Dl?e=Omu%yE>rBd4rAf)hj{k$V(0w3)WO%#fk|EH+t2_&QpK7_j%_BGM8ZV$ zM#7F(HewkQ|3(A{A6uLNh0=jbHi|TIz1`!jL}xpV-5{f_)@t}cza5g_dmOPAm%c7T zm!DwIUy%XWLIfeo!W6N8r=n0f$K7G~6s@^Pclvn4WpWh}%tO3BhZ&0ITijB?b@|5u z-id;h`o!6ek6qO~NEw0pHMpHKI+XI~4joRb@e~%r%{`LG+D!qB&9ULWK^L#0)Nj&3keo28iJ+!I~0VH?j5{Xd$;)Fx>=WvgbNT zFCU(L(mDov_mFUtGG(PNkyR68aza=v5E2w}%OcN2n`zDo)jjysHU!_d?nrG%3d`#( z;T6j@$9Tm`wW$rf2!ti>ke`wEtK*}mP@HL{5y0yCzswpDf15!X&Awz`2yP+sdN~)l zTQF?gP9C7{I_7*KHuAZtKB?a@IX#MJV$lt`w$U+rZkf|vKOH0Fu&^{#6ngru9_&}F z+JEWky$5G#CF%XW$%G%kkQ$!Na8BRUZ-^Z21WasBc~fb2 zX_o&Q6)T^QAYDfg6W-5K{1bXGTTdN~MGm*?bkSmcS7$tvpIQx$O-zK_XZ!jJ_ys?Z zm93~krfVGF^AyH%KCy89L|=upTxosYODjgNui@)#lqkk+d!SfLuG~b%;Q07^pKnAw z0hk_j;}`tbOf2QG33kdBl4Dr)!S$f4*Xf0YP2H_=lOotuwWGk;&l_N_nsp~}W!rCxqtB7oBnh{_eZoU5+LO++`>3e|WG*80 zJOe>GIg!=S+}l)0p@N;G;AFg&Df95PE#g^HG>)bI=KP^Ak8Zmg4BA+hhvT^K6=ZGX z<$v$kso@XfvA?wZ9%S2@9NO%VE`H6cbiZlX_HyBPw-ex6WxnNFwZhbEslc@sKAm9B=6bHxj9|XYMuJ13eD7>nKc)IWLMum^dYT>z0 zWwjN_Fh|5p;=9$!i$!Mt2~w~1O~(*;-9SQecj8-Tkb2dADoKqIYpnML+`eEo8hq#f z*1Dy?`mnzNqd`-7z7ykn2gNYvYeG{&tOjBr+vu3?Lhp4O+&IGCERW)s){GL?VBUO!Q6Mf5AqRg^Yimy$F^B~AV_0wgJQhFyApZy$XHPzf>9bxa0) zWlbf=PmEs!hoV~_l8zSjqS0<%(ou!eh>78gdEUf}8scJj#H7Zenf>gIPVjocS$004 zt>B%W&54Macmp!t<`)n!nvu5Fn+|sBrL1}Nk)BoA>q``IwP2Lj8--Rxj|jY(_B2L& z0_%r9G7O<^)=N3W-m+=d#&H#m%uon3&FAEc<-V1gUA!1-Pt zVa+R!n4PGRfRLV5RjYw)Zr4WDs9yGAhN)XOCT5JG4|Ic5cxqOsQQpeYfNi<1lnyXX z&Tz-|o6z8N1i*;UN7NIpNfSLe7><)oAmL>?5cGx4h1B;RDb%EgdmyHU7}|iJe5XKt z{gx)aq1cLq7^QMi{fLBML4oBrr`To!NHl-__2)_+D5?1jXlepdw9NXn_`vB30&LO} zyWC>&Rk2|SCPCU`#4Sk%5n7bQ1r{~fGEEF1rgIxZQSFgg)??6a4KjNF{dYzVm|*> z>Z~tbao=qC(RRD;MsF=*pMyYDoDPP!Es!Pgd;Ii0>$-YY; zFYl*+{QqWTldW#}YKZSO_Um<@R%g8bS}Xm1+WSrr!`U(zq}xFF<#58(G^}$Su2Emw zL6UE$E<`TJx9WQVm71N?md|Kn-aN3^3k(DEtLIp=0HKi^(&~YG+~*uhlc=;b!0=Z4 z&tpNSTvjY4$p_rK(DBd&o!GwnSU~-kYw=BNEh(gf5hu>MM+2!K-oY=iB&8 zz;X2A`x?l5XwnyhFt(wg&IE6lDW1v~f&DPSnva|lH>uyw`7*ma{6t9>L>iFSeM zKE;qYiYBhyk+f0a+2&Ez2X8}*3`jx)XXXHa(9`UCicSf?X{}$TTURKvW6#@0x?HD5 zx`L-ZY{~b35l!3?CwO0@CU`#!CVamnz;i~oz~n1(DwhN=4m<=G3FFxd&iBiwezXT< z)Dd-B4}`VVytB^kTO|kEQXIbM?^w>}WP31cv%Mg(68VJ1hl?j3GwQZGv1oJNBOdE~ zklQ+{RI9omZ}wr7*5vSJ(CdAbDY*73Ppr66IqQz0K&P ztb?6;e!TChv{6HICS$aK0p^mtBh)*`bi2xmEu_cpU<@eVXi@((2{ zvBV}LkLL^FeRD_A51}DNvc6^@Q`_%nmiG;N1d^c9Bk(1bD148RWB&MBpwPPZK3DTn z4q%hT$uHv|d^)F!Zyma2-iFZgnr$0OdAG1gGSzYZBln?2SW`zkr=mie5{-zzehyWx z`v_Z(3^!aZIzE}h``s8Zshp0*?s$vdvzS`yoEf*n@mhm52gF^P0OKmvaHBdx~p&ifJ03 z71!$S^-KTK?{}k;Z$*g@&+mUL8nk_8FpW3Ls<7iZ3TL3BQwzd*1?Ws663LCWqa-CJ*kBX~d%uHR5=6yD#{%|LYg%8E5XbZ5efu(7j~9Dx znT&L4lbMDl??=8rA0s@V;IA+3w1QVco*fkH5ens5`w@I z#lOtd@_~(Ty)MGEEC(QZHKQJ41RJyE9<4tlA!Xj1?`KU_%8|oYk2~|YzObU;WT5gO zdAQv`jzMKNc8k;OqHA3DfoW;ReZ!HoFP^De)ZJgyZgQ@zwS01RyGo)l`_LP$vW`%bm+9Z|tEeXo7&9+2Oh9 z&qr}T;4KUPhrBd%1C5p@;iXGA43hHsB<0>1Dh1^+(`|PkoG;T4wHQe>4Qi^lSukB&zGjN?&Z{a??fDzn|M`GOKtKTJ+YYrl;U;ie zyb$VkNUdJ%>eBNha2P^{k64NqLg3c1COr?%!u{+q5wHlMSEE9O$Smm^k#jnR%+Ry* zAiIMtx!g~`#6MTFu-wY=k!eBaSUE+R&Gb2hFzr~ZLrXpu=t-&caW7OT6qLS79}ywbIZ>a&EOmI0k>F64XBSEp|o8BqrQY!eG^ z57N!i2K3zqXwz7Zr-lB*O;J$0Q2$CEgdKS#XFzd1#++HQTBbzHHyUN=;9Pq?Y?Vvm zqWN>ooP=g5%7&%ajZikb%pzHbU6Csd9{LXbNPCS+K0t;t^bWvSGzUqN9#kccCD<<_ zJB0r0I)tYTvhwnCrPn}k0!^i5Ho1!i&kn{-Uc%7$WydK>Nbpu~lu={HpZBDs7juNxJL%QoeM#p5v`-hti zt(z?aBsacPJ`P%VvdM^>3X!dD(A)@7c0=D_soq0!-f6A2MK&y#xMb)RRg z(Uh0`hL!i88%VrSLxS`ML+#ORuB&|Kjt1V=O)zR~3tGUv(y}~~PZ@&p z74+jI7abO@uV`uNzd^ENM!uj`P|~k7AFDZlT2%UDAtv*Z=#rnE<%W~mgFUg+rC;y{ z?z2>Qtb}H;5RM(6v2^7=N6eV}EagKnM&m1&&1vhS@e7}$-z7hgZsOWn;|+-QvNN&H zQ1{kpBlwm}Gn`mgCHVw(J z)Gvg`Y|md}X(RzDN1sLE-b=b|Zq-zVCe_X$I9Ke<^TaO~B7DTCs9s!D)RpNVaJsW&gl@edsiei)Mr7cSvYj&_3K**>A>2Sw9gre$OV zM~ph{?3o|8dA3hq1apegKWrOv&y<7ri~NGtQnj#KW~lvBpJg$PV@Gk(~{< zk?%73$fV-&?VmF0EOfa~JQ6r&`NJ71$&CZZM!OT4fvG>Nj@J z$4mm_ex1uH4heEb%372MS2n4-Y*cOw>+^%0CcK8CyL}3K%zGeM)&mEg6Bx7$ZhNsu z>v)3yG%7#>+#^kAoUqg)PC*@Q+dxq+jdO_ATj27@|9G~rmtOh+2LZql12kzVQ={k! z6fm5ZMGR39MjfDD#f1y6-jboQCespJD3VJT6~~{`*-KtHG6-?hmB2X=ncoeA_SeCY z*D`x@jFtsU0SR2`AP!H+D|tZ!!EfI*8ko@o*xvs6aLdH`;e78dKaGtVBASH`S?m-! zA|uO_=>LqpAS7?*3^&<@&wDLI z#`5zIRMcR#=SzG}#24m)*hlaKOaEhJs#m$vfxRGF*NT_#b1M4|7;gQ#cp7N@&@ z!7yAySxE29TCuBoktZ%be#_lm*{I`7@<|N)hAmqMHYq77iNH4staQF&>pwJiCpB(o zsZ7iUMHA#iA5k(z2b>Q?NnVA-=KT^S{s;X1`_BDB%!V-V-)q&hFsC}3jJm@fvpaH5 zIijz@^rR_#GIs)ev`+_TvV%kE6%(u$O;_wks|U8rYA0NzB-o#J_fomd9-J6wg`=Z`^4PpgOawG+Fkm~(rRWsg)bH`_% zI&u`=y|K+f&|6yiTa^sIxUqQ)zeA8Wyz}LJwBm%rZ1!B7fFBgh&}K@fsB#S$>V0)u zH0fsjCW<5^)IbwjfDS2wnaN={*FMWQh|QGL#4Yvd3yEt3msCkhLNH2e=uVfE&J zG-#}s8K7TwO4I<>(N;a&0`vBuJ2+)CD)D%gvnH+MEv*m3REk_!4s!-zlaJby82YiK z`7X||YN5!0FRWJiV=!=`l{NMeeq z0~yztX}X99ut`%*ktB0cCGK5E`@(jtk5UHD^M~S@X<3#1p^gN^={vbWba-|koMq3- zHT&*7FerR1z8=UbtF90jV=j%S%%?D-pq}}T)9*(aZ`5i}?Vi@wSkyvJQ=E3NZZl0r z9v^TE;vQ={XC06_222IX@~@!*`hFh~D0b(?;>E?2cJ;Q4m}RaBGff2`kqnOv1Ke5s zf`gf!Br{iU(VVk=bwV`(o1=PUJtMz3By)FiK}KCstUj)E9=97Z=J%>PI;C>T<@y(t z4*t6}C2uUO=Z7eQ^V^8^C6n)w;5GJ?CySWatC0kbzDpGeze-Cb$NrF0Mj_cJp7%r5u+lP=b?Q0-dJ{$w zMXTq!H!_NvKAF^wYu?l@8;;aS($+=g|J`Js$aG$qwv@F4H~^pD^( zxX2Kk>bq+^$?-hZX~c;^HA|kp{AoA^5^Bbqiz+Afqu0MErv20I5v`YqEjJOnelTWG zUr|LxJhyH1eGWf`{udqqg+``Eu3Mx9c|d`-Jfje?-cmDGA#S=*=2lkjeJ=Ba`St*8}_8fjn^UI|E-iD7@@cjat zpzMAaP45e9%k?s)r&7}_+W$R7u>a2?V!D;4Q}w%5Cmk;H&63_Xl^T?O9=9u}0x`!$(_ZsnmfxH2mKyr4`BpIaNjeD zQHr&=4uCx)x--mP=eRDsUACB`2{d)f$^V_BtiY!rumAD9>sTd(Gde1%ll3$0X;p)u zpY1;J_6%o7_tQPPnxSF2IYuUxV{bD}dr;U(6O^$iy1)XJiXBde4SZ%)pkmn`!xh`j zhid>r2o;GGblSqTRgo zL#iS8iGp|p)4f9^+?91SlBWK%`{&R)e5ePr$}+&h3e!SkvuVnBcnamZck@Nh$_gOa zA8^#dHEnTn{JE#dHlll9@h#48IF?UGfRV*bAtM+QdAN~ad|rcRo_Alh0T!Dot&PxN zE0d$Nu9SC*d3k8Jr zM4=q}M)VJwm~poj*ywdG5IzRdkWu;+rT=6?2%}k@weg!jz|B=fvF; z$LHzlHg}{#we2;5N-#XP4eMoUxSyyANxJ<=&$_syF9tKSH3WT|9u({JBrL-*N z4-UhY(t64uzAzgARd`m*-N)H4cSz?}{48{9sziqnj`rZ3KfZnnKhW~?&4zM<+#V#N zwpMH{t&J#gm)GNB@IZ7H>9Jq-`cvDd%W%?}Y*Vg!SiNtyZoWU^o87FEXR8XcunhA< zOT^n@VfwRmdtdnPGdqbBtk(lzv)>v z!xzF0^mJ;lfo9@JQcFBl?x>!^IW$uU$KkNMqgMXAtINtN<1P4haDK1}L~Z_Ss(vJ) z@GAMb=F>9S*AO(g011}W1L=w0%8lCuqSLh{F8%@WO=|`p$3N%QQ_E{EMeI}Uz&sK= zg=!1TE><{8@-vc7Xo6?=;u5_8n+Be1&Vm*w)RKe=?M^;2XhhlxSw$W5SI)d|O`KJ~ ziC~N!TMY?H@Ob@xd2G6+{$nRav=X44F1)oRN3Hc8uDtiU+H*c?Tm-w>EuP;FdqPg8 z{>5_tCg8y(ZvXHy7Ok@oKV7iuQH2(_tb#qvD0U}HM{LNLFuUE4jU ztJC;3p~?Y~=47oH#bxa4uiiQ_P**ay+3Sk7i(&1ktP6Uw=+xMdjg323CE+7Mt%BHy zE;IM}O0b_TJlH-Cd%dTo?@|@49dT6hW(Xg~$Q3_{^eiY#U-f#n5_BK8r#)8o4NJc* zl;*EWPG2~iF@j1AFP7oVk6YRy=F|w8k1clAp%|k50U$tld?9DUq6sRMknH2z#NNxI zSx0luK+rY%n_J4(yEBw&>Me=-*8=@ZAk3CX;EDGl-DeCgH)(CbF?Il$HlFn@wW`n{Op>U%stbg+ckIqpd*z zgduT-f*8>}e>dy)06A58_xco=ZrAzr8xUw9fDI8EYZYm!K^;XpLFeTEBIqWJ8-Gn9 z2Q{nv0Ffcw1y!@mXB%#(fZnowi0qHd$xLu^8&3bBA*4TEtR0R@qS-tu?T@~%kf6dQ z>nR`#4uc%#$yAH7n#*g1Kts*Ft^}!>CH1~-q%6lr*NE%0tE07OgBo~fh{Txv)=krp*5CGg9A{4bKv zkUn^5&<}}Pimpz7p?n+^e6UsvTB1*bMw(=nT{@2c!F-KHRRD-8S_L}S^XqmTkUN1m zB^zuprTmzNS;^I?hk&$ZNDn79C~%%!S&h;Pljal8UQC!RPI(HAR<9c6acFl-#o#d? zoKbQOZ3EK>aimC4bBg`JNMO@{d%sAc(LoA=szJ&3V-A%mFFy5y9~f=GzXXyUJ14?d z&RVd|Zr63@b5$N=q95zjZuV=H#j#|_!}8MAiB}XQTa*tHB|?p<9UL9GziqVJ9rUho zml@%ZQZ0ENB`TT*l{rdhnAAS`K-d>JLoLAc5{J)+BT~H!n2{X_x`uI~w*_7yQH4r< z%g)C*YBqv#KlwjBn0_X#&iJ)P-bo0d4qS>cC892-5ryNd-OpYtTJW??0fPDPxx1vulFaOz^?9cOH0TWQ6;e)yAW}oXh2QO$*^x zqkEK;7jDXDZf?GLyI>H|x#7;}aeH>!%Wys@jh&sH{SytIPlJa>zb@Kny8bTK_D2bb zZvA5;MrE1)j~1r*F_G8B$G!?WI@T3$teVy3^}*V~DMu{y3(;@3ZjmSJb*L%qPtfjW z*j+b+J2ygR#+xw$f+13HbwEr^a`~_tt|i5Dg%Y8yd8v+MjxWr464-GbGTH1%OyM{S zFtB@&BoQb>xDRDU?x06dojA zQu=TgQ;$pB0wYMc3H*#f57tL?`F(Xd`NCl7Ga6jKuv06(FypsH!(WC!k?v{9bVQkx zKChMf8cS~5ukNj&yh*~_Zvf+N=FvCRA9q&dN}r0v z=e_D$P(Zk&U1a0GEC<--vzbH!Ag>O^RQEc*=UR z{RjGT!6m1sRf9Gb`5`n%ptD!XaJ85c*ZEL2-F@&B1LUH;=H@^%PB0-i@vGg+&qW3y zW${;`j<3FHFze)3?QbvSe>F`yb6OZQqo!!K-X7;+jBng@8uCr<9n#g zvOr@y`&NwS6wa!kk$h4Gw40U?K4eehZx5d7-K6@2I{|A6sBW8dd!*xr0Pu#f?V^*@2Vv>0%kY&)oNMADc-v3Br zWN&+9yM6`OL9^Hp6rb;Ay5yRqqju7(|D>wRdfP$2QAc@~rrc|aTc#(j^-Q!9^>p*h zcHjR`advm-L{465LH{MtL;6edGX=%NPm$w|#2!yeeNyW8aY=~21_WS>FP=X;!Ton^ zg*yNc;RmZa+YK-~fx%;lL=j<-rYgeI3GakpHf2<>E&*q`zHgF=wH zW~R?YaEmRh2t@Lt%E})25+Z0n!wadlz&jXjF)`89Pm1-D|sL6-}wwv zGw|%86ucUYoh;YkG`HOUN$phDAjl)Hp8dwKr|pMh{CGu4qJlk3p7qasxm&8c`|6Ob zMQM~A*KyH2e&ry>VVG@B30Gl`K`7=nT#$W@hWBbvCJQg+|1tFz3~jd2y5?7)#i2-{ zcyWhf#i6*nySux)Yj7#AL4xHpxk0S7q-z5lJ8;@uK=~J z=&pFmb*k*g*}`HH5XOfDy0slfnhKCL6aJ>4#DAhntqKjTtB$_B9Cwm$av$Xdk_{fMqWw~oITOmiK z-;_;XtF_cDNxCJ}vzf{1*AT|xl0&4?@OGmdk2>bzLZN?rPLhJ|ccp&%^eG_xRafxi zwm0Hc?+d=b`vp0FOB`Ho6T8-NN)czlMB;Rjy1L}Uh@`^5u4=nb$rc$y8ufvz+vpwPW5Gn&-}lU9xy#pSt>t>GPIlbG7?`2AK@*N+ z+fhi7^u}gsPj9blgUg5%$fIy2g!xd%MFQhr7cNIqyp4g^`OIy3{6q+4!0l$w1Nu)` zI!CvXnJA_Dog#hY{M?tK!V#men2(pQ9-)rYWWRFaLo>?q+UlQDN~B20OL&FF2SyFr znRR=6WU6Xu2cNrZ4fwHkuc!RpUJS&cXLauXE$#mIiH!Lh zM!ECvME5$Vq^Vind$FMm?bYTIfHpzIgg;AT*Jk|6$7rDySFKyVD&tp{G*9M- z!q^LoTr76*+J6czP(gOgS>KV2VL`mnnsvGrUHTo4KQ24(#C5$^GuuGnHY_%4xRrlO zgVk#&292*hyHB=?a36>R{_}TPbOXQmDeT1F`Nz%r$o@>P<%foyN*c2&3v(CL0?P(( z{>$f*G`t}f>?NWi;`tB}dmhhpx=o6$hoDfnWhysVBCqZA9avdzXvHSR!h{n?N?2Ng z4HeJx2Jr!yR=&AkU!#-{yn2W0b4$2Dg99w4CyE$CF!GA)Kiej6y&#j4sH*;0QJyff zlA6PTV}5j9ddA@+Hwg$o!+03&zOx~6F}430VR5vP>aU4dJz4x-q&z%Lb9(A@i=%)SHx_%^JMGP5tZ4HYn{Wa)G9KxDcZz)uJoYM1$pW%%(;lc{*%lQDdq?W|&0+ zRL((2ge5Ylxca)>pN;%17gt?pW&hQr5|`a8+jq1MRr${8>11)Rayo3OuR001kesrL zNntw6gS?!Ume{tifvC{<2^T+2mco$o&Ls{{tE-iE(Lt7b zh9D}BhSV1cG97Pi1g*>uro}#sjnNmw&H=|{%*+bF#0{!T)QzIwzkfsb?C@%oyraiw zQwrbk|N5KvRp|^Nqb+SS57wK`i$%+Ww33c&0orLkf$6}{quta`lN%%6QFm>W+KJz2 znQQ-=ty^24-{+cJ{mlb=BH>5z=&Cf;O+Av<*QQ%! z{D0TV@*1<4I7R!9MUNpzMC|t+*~kN`15dn7#Y>GI_0Am65aCT0?8$d;J`y79Zm{Y0 zr|x?u&P`^&axN?zjln11v}U~rt~mJLbQR}8c^Y8n;POmM-_FfIz?nNbSEyEkPWL>}AwW=WXD-HRe zDuq&6C+G$m15Lf;8}$00wF+KX@`7JU?@xZ0{i8+wzrPjzYXZXm`P1cn&Gmn_LLuhU ztie;P7&DlSC*VXw=erI}F5-TBnhw~5Vs2*kC3)O0%Eub?+*dyW_#ZNo2l|bHCZNXY zpY!iH(3%E~=248S))#0 zeheM`tx_EkS&-ECc9dGYAS2lCkUuERLD}g*Nuod@Pe6X;8zI_$YPx~DFz+W-s-7Ni z7HRzR?2Hx(&4;w*;`lMgBCL7${G?{QpulH6HHOZFrcihg$0GPP`LW)zPdBPCn7052 zSDncq_Uuerv=Afe?i(XH7Q`Jd7Ftuw@#YMKw4FY@IK7S@7rLa|dt=KgpUNE8s^{ZQ z)%y_2d}j;|p^66v`8`kj*R%jq#GCI3^V=TA{UWPL~(;t%$lnwVHP#!3q8 z5-=ex%oNDk6dH8K56j0xjetjt!7!*2Nt*-gIqNTpAXQkA=hdxj@UCAU!b{V~nv zV=4D2hjIVe{P#rc@itRmnc^|hU#4eOLU(iG_2wq&2iDQoV!F~EE1y28QSq;pr=TQl zFEHyL<-_BXwHMS%uOy^eV zYV<5b{YY|^BPy$tixsqZAN4)9|O#RF^xlxYTOcy3WKIy##8!xcee<1d8AvCJOEPU=XQ80 z^&iuu1T1yLX1KKC-nKu)L4chVa`d0u0^O8aM}cr;{$WG%8Dx9Ka@hoUb)nV7m%O{* zABEASqmjQq#U0;V5=`%IF6RyL?wy_4xG__mmK#FwY%!fre6Qcmk{SYlvDG48GiMbd{Br*)vex(694v3jta- zmr`EcU?y0HEpgwL|kqts4!25-UJy8hfuZP&uO zZlFcag9hMrnc%xtRG>~Urphl>eQig_v72k;@=QqCU_JC%GCvolb;uADC!h3yaK~hw1*-acHEG$cgc5u`( zaKiuC_tg8$$n^3TbTZf685udQEgPsVm_jiJN0;Gs5k=Ao*d)RNq6_7@pC{rn{Pdpr z{9i0vC_&PP6=J&X3V?mA=jS;1!H+{vYC==&y#O4=Sl4F|7%wVP=B2wq+7-bs!cW3% zFBB_Y{QKvmc2Xf>-Q+I>bekq?%)QktNlv=s%$4=a4J^`jYCEI7!hpiUxjZB{9=y-| zJTVf~7^T_B@>RUe(gOK>SnQ5-nqn%$DTLb1U7i$i^WrgNvSxe{(TB9lZlOMQsB68Y zud!B{oLa3nZ2a74)#=}cf&)S;rblKQFx!Bz7`}@w(ac&|QZo9enu9e(c*Xe@5>~2; z#0EnAWS8vChj5ph2vWe* z5xqpLZH{FZ3>NCuZrOzhu}XjcI!B(A!AWLDhS8{QNd(;J>@)n6Agx>MnFT0|^&_LJ zYw{)cf8gY1fU)Y;t|h~ZGV+oVrBEjv<95uA&@j- zf2$vW;=MO4q-z9PT0&ZJ@mHN#{F8wo_;`&yvSYR>h{O>P&+kKB=_VmtJa<$qs@pJr z#*YnG{g(mq^5D08Pp&=l_cF z=gce>bx?)-kZ5%#c0w=jo)^6zJ^yZEPGo9?NV<;qG-UUdw`3BAx59l4GwOPFXCd}? z=FjzOR(z%Od`K1M0}t|ak=@8{m9VCv7 zOt=~+@1$Qt8(fBn8ks>Svjb6^Une9E|9sKVuMquNSlfaF9TWLh{=w>wl1G`IGeY=p zq(5O4%j9#iXB1$ebkDx%!||Mi4__FeBm+m`$-bw;k4>rx6Hnn?y%z|!<#lRdP;IEs zLgi-L#$gZ@o+xfR9zTL!;xa~1o(lzC&y~Bh8;nmDw;d4hg=1mwe6Hm;!qDS#+&3jA z=3(8OK;3ej2Y8suNHjRq#1g|z>DR}GfSqV$g#nIqgV^I-Z5BNF}ASass{{L^s4g_;bN`m6V#sW8H+tnxAkov1WX@$f47nPuS&*6aWx_CdHBCVXM#pF9)8v_dI*B|XN2pS3M5mp-eLVB zZ{zz6C9+IuzlgvAI!fj!xTbueMoB-v?lHv}{L7!*l0*vpOCu7PfS1G+t0ROG)1Kl& z0FR)?mBs65lX*fR!zQbq6h2wHRm!yB5ouy@VprQBsqj1(N!EY!D(Bz*rKyu{nC>MB z(h_+Vlp}^Sn~w5z^;c=)Eb#%R{!_v(8E;%4KE%ve<-|%#&9_7sVQW)K^)D37ykZxU zh9wTMihq?d{ZuWfuX5WG8sCnczyG|$Z;XVeMK@4UT`?(-4XFUp%}yLBW@xdtqZBhy zN@ir3|8@SYm^Kx5wDf@2lzpe#{^^%N9ZVTa3nLpj(W#ZcX~|1sI+n0_xW?sly*57b zSP!&ep;S~7^WxP%Ps`^fqj*&9t=oCp(~PH|uS3qkcldX(DT%8syZkfIq)f8Mh-`m@ z?}&^Tqg0ezBAi&ojA6ST;YHU#r%0nEMuV>H^zlj3Fv(xJdT`#%%wjhI)?EUS&2c;2 zfFc06A9sipY1-Nc-D*~p-v{lVN!U>kP`c^W7q*f2=w-&$r5Bs@{X)T3KP)2Ml7G%% zdg9tz`&uJXCbuk3_@+t9Q&!jC*5KCw%=M9EZd0H1POa9KE!bqUJM@zu=k56qxSC^d zOn0g)@w`F0ILwV^@8pI0asHs+8Q+M`D4dD{w)UdsPfDQNx}s?1-!Md#~5d-rSqtWug*RPB5B zsO2SwedVheEs?7ac<<4SOy6c$Iwx1aHC)Q3JN9!1lGB&buXzyeg#Q1WduuR^y?XyM z+`t(7>khq(=SC4krAs!-P76vByEUy_{ZJyW3-$0$Rb9_qQN~%4>~8sx=dTr1mb)ETxOb&7$E>yc%DUD!mpVC6W3;=+({*o- zu~hA_;O*l4da@!AdCyK)6WEOTeyby<*>m<{W=FzzvgpwDEbx3iKm{YC6JoHI+?Af5 zP7RUSftCdiHA9d02D#pq9Z<7w7N#W>&1DM-t5!m?k4=^rXdg9wUE{EE+-zRn!;a!r zcxX_O=Rthj_Q<27c?x?M!!>}4X+G9lIjF61f|S0mvl8*lQHWSnwrO0B{ZZ7=o8y+( ziyftW69@E}dFzv!5=O7SmpeZN48hfp$E)iOyA4K_lg>MvW1V<+rOSofF}8ss4GgzZ zrrG^nGPD|r-Aq%OK5TGI`h5E$4!I2WD#y0ag&~EKFJ7IJ``dngqj`ga3W4EaF2{ze zdt%ls;@mX;B)`AyAP3@5X+{sFI_{)+FnU8Zi-u04i3InNo4O!Q^%Cf$Bf0j%P}D-4 z36|u_4F?@&X0R{^kLK0%0aY~ik}K%1Pw$&OEyldNuBY(3o|O>I8DfhH1z<6n`7k2@ zJU-}vxWtxvnHw74C^FYcTA)$Hr9*uBoH|~8ovP=&Ga5uGlh-8$h0*S7Qw!&JW=5@_ zFGC2UBJfk)Rk7|iR%k?c=F5RM)Z{1_VM_8d6*2Ptzbqp;r2`E=;Vk+x81AH5#hb3k ztuOQ}^JHt8DLK`8mPyGO@(~qnoLtomCoW>Hp|^KbN$n0=RU@dc+K1KrX_6Rg8~cgl z{@do4Q>^9IR2ob&DAQ?QcgT!bGb0~Ft^JdA5CNB9S_CWF)y! zAWz~lF|zBJ;{=k2gY->LSN+$@+J(hLvDI3emx}9-OVTtzDM1x|qj(!a>Wa3i%pzixzB@yDiRcou8WC6SJmrLt**rQ^17 zsw*o7qkm26u9{3Er(@M157QJ()0JDW7`?yBd!mg+p5 zVp^BMi}NEftq&AbPK%e}c|OSr!h^J#0R925}^W!H| z$@PPl4f2|PEW^C|2dQ^%Hp0TA**d>sAa2eSh~#X1dJQ5)jLM=Pcvk6~?lu{YwW1ri z-yMk9pAkVNyYcAGFns2?f{?AIe zSB8G)>hRAFeUtoWER`N)or0qiPAU@4)pNu}Gc+cur+03EqNUmNu|JN3M)NKeYt3JF zg%|x8(wNmTA29n-Lg6fsG=%luXW&;yhW5a&n~J4vB)wMn$TUZ^0Wsy`S9gvWf)I*4 zKv|lKV92GOFc)NyiEBTUiR*Mlp6juxmg}q@?YV^3O`HPeZ~oQV7otuyA@i1oxqjw# z4{Wg6+uzphT7%$C-+4K3C-`_WC#JHJ&dtF0jl1@JKJQl#-}=zgUIit%O8zP0S0o)b)UElu0E0xHe&9S$wWyv<&U7@F=8H1m zswE7`sh2bMeo**gj@RJI?P!<3n)@W31zkq4+!sAe*xNvY9AlM4vV3KM4Ou3}CBCuH zI0v)hGxdjodtLpUZegh9{?+C6)9C7Vq-WEdi||BqiqhaTOVwY=GrH!O+m9Q~CDUf3 z0tqOFdk89w`?3^ujApEW^B*6Rx14QJ*yCA=8jj}346p`jteGOXORAl9L~8jw zR2hD*{$f^YJdrt{871}A$lI|VY*u$8iUbDhC* z8Kqpnu5hgU*0!BAa)Opeij_em^o!PSWTB{6vYs?E5a)@nX@l~VVgcGFWNl!4lM$*F zZ<9er7)1MRG*y(CjcpwbQ=AjNQZh*jJD`I$UGC+S{fbS0E;kZ0{eDZR5bgk!= zi0Q=OP6+nxB2TTS&mlmMqR+F1vA|t+&E*Zq1kuk~2L}WAvl|L%vy-91)(+ z+G*Lj%lDg!fcKaPV&D2GQ-vo5K@j#Es4l=NgX?aBZBct^O0@NIb5R<-!TEGp0$LUB z?T*gjSIhTuP|Ni;62IaB&@B!#txIIQ`+fT5mazHM$6+TB1tKfy@ynNq|KU3RD>u7N zP3Dcuu7p8~!+m?o4aJV5!o@11+}TBF%=BeEviucQ9wTp&UeA+nhpid3jcU7Ld;U7( zPp;pin=lRzRQ=h~hXy%#F6CUeeeY1WlBXe@8;-D0k3}35P|MSvY)Ba3d6HH_>9BnB z)vx2}?wGe7^=L9Hg4^ZDwgu%}!B4>at*-a2qXK1KixYtQdMx-J)%~z0Gs?nvv+1$j ztgT?J$H6ff<&%=74LCQS{8fT8MkSwJUQF?C6Nf5Z?~Ix-|FY;q3JA5%S<-XNJu3pg z$14m9ZwBh1r?~!KhX&tpYzST_7imc@|5C&9?yZH{EAOSzY7be1ocjV^KbE1(@Y!t?3(uVQv)X6L<{ zIkz`J&E74V!iNkH%@&Y zxtjE*FGp(Fygf@oQ^Ybm=u3Q^IM(T@ePRw+)oR z!XB+5@ifM+kH`Gp6R1(6dw()d@+j~OW8eAmA=_z-@++S&1#4rYn$vg^Uu8+TBfkK| zl65QK7`0t+?3eamx_A`|ZfiX#>WY~o4~`Y_3J9cpl0?_epCoQHb!mJf#Cx>jTW zrDnZ~^|j{<)M7t@mBP_hQ&&s?4a#-w@@oV7$qZO1VZSa(k{rrC59;ou(5&%WvFjhr zQKWPd0L8>fXtBZua4|Nu)nqA>Gwd|JP7uQX_SI(c@Ts!vb+XMiK?OrkWL9#wI^S0P z=?>%qlDv{3>#AP36{B)wL=@1Sdp|o8N0KNe&8@Vw`IFr2y(#fz-PA-nTHKPIBtqyI z+>&-6o;G zm)bV02|uV){w);C6%~ab9rwG=<9PK_K8YLa24_l)(HKQ|seNX&E|G$!23YXw0-^A* zJ#X|o{=j0PbVFe=mQEhWoo^@!-PH3M-%KzQAylO}j)k)s2e<`|B%vmFnq5p-F6m1J z7TcRQzxSDjov8K02mIanKB40WPUYMtJ z9XR!nk@4arcT+1x*Z%GQ+9cz!36F)SUB~iRKkpZWC{`j!v0^%|>w2|?Rp9FNBl)dS zP|y2bJYp(`0`~>KKfi!{rt0dm+&Ql!mv}tB4T4l7dzDS4>lJyQWF@9!ccXoUSavO~ zxC1<0KPuFa`SjSE?$8eVd;4Vu(GCy1^}O@3cdMF`5K|3TZR{m-2yFnxOMr=)-UTXw zji)mM!;bR+Pj^S$ER#YXuY$3~+-#;#p<(KQx0kEBHyE$WvgWL%pL4xc3}s?DvnIp; z{+NQqdwv=Q8sU4vOD~;_JI6wgE@tMX=z6>n-@QeD$n$kz30occS+6lXT_kPT{vxHA z_GyZi29mhnpWyU|cDpn@X6VWRMt`rKaU4aEFo7RDz@$)=!ip}TpC)_-o0R$4ia_81 z`dR)ucZ1<*Jmrq-X+ze%%d!7aBltaxzP3#mz+1ZSfy>$w{yU%RxM zW^)SGGEuQ)6eJpF_rZ}B5)lbG+I_@+wGT;iL`X7G?&XvdJD$qntQ>G_65hhMjM|tS zc$mmwfenF2Ut&*6l9d17(pWoxpb@YGR*OB z{0qs*0TpKpqngUjO4{1d3Z+exb%P3M_a!ZOvu>*I#i6_WCS{CBw6TJX zbk$>U`?rL~f!Qzyvc@+I04ZkF>5YPuR8e!LW`9H>5;G1HJ@9OiKv7Gp&WfA+0}3Jg ze-cFR1iCk6?>oWtm;J>>)4;(21)!9Lewg6vAxpM*AAdReWlT5%j!F9AWN|jxa>Brzl~Y5LH&DrrOSn+notDrF4oC&K z9QT9DhA}F3(;)ItPOsK?&{^=?f+O4a$s6gP=ii^?Ry>uRBhzoKzJ$(DRcxmit(KRRS&kepqUDPc-B12` zGWWlLPT1YaP4ul-*w52jB#S*xm;nfUPsyJrH{cV0Ds%&y%_}sPgGSQQ#=f#k8^nF2 z?V)rXx+$@k3hk>dTFy2l4y=Qn}4+Br!tOXMNbk2>)|K8KJh2_5S%@wPVrLKea& zJhw*lg`aWuN@*1E!9v$f)E#T0g7*YZGT8x#uv{;Vy?goOQ$u|c*+E!SZTPr)Zi4dM zFP|g3ZnaFb|=**z`0Bd#r$L4Sg3?j#X$E2!YfUc5y!;_PJR8RMWlRg|E#X71Qg=9E> z?1zp%^7Wl$ggq`F3+dn>0S z7s(BPWA3^R*8kts@f+t%$EVSMoA#ar;v44vZp37I#jD$=X{sX(m8@sAaOAZ1=d&uO zr^9sm-S8z0946gJEP1XE|Mc7B@&3ZUO6py3i(k&63bI6}@7<8Jp2)eu#2gPAAdBo7 zBsI^>|H5sMP^-Nj=vWML_VSW)o-Cb6U^cLe;iKX&oy;)4#6!%wZ=V^ zu|0!bpMpygnhY-Qf z37T|mlxn6gUH(=YU$y#_?@!ie1W zFQZP($MBscT)2>KCnqv#6B&*jd9=k`oJGzp?fmK`tyj}nH(b*;vtQF1Rm?Euj3jcA zIdc!CM5V;6Bj4JpD@q$Ng$&rVrjQv!Kiej8dygCx#HwayNwAhFoJrQYs5oJz23zTC zFBP~In^vTl+rjCDBu(*6l`@&e-|E;-R1-QW6+rNF~53{^+ z|Mksz8M$pguWoO6J+II1u`4iu588?2eCz_=uTj{4?iC2JvG;}P?R?wb3&8Jvxie{# z-f-i5hhN^l{aotHBXU+OxSGE|_QQ97w>gLfGkx1zkL`&0!okjXeL3yt!wMf?~g?C+vmg z@w?pEM6E1yxU6qNM0;sBIzi3NS=9MG5CA;kcFS&zg~1ksQgePS{%p=qQ}BD_ToNX~ z^&v2D;rM3d2;k0`IPF14=DKg(lFBL+T8*lFM)>#xTsLRUw;B4z8wD<0k|*FF^ZoEwol$c?KT{sA`P z8$UT#km1iqJi6cKHZ~2{oetM4u#Y>z^8jF8Ee}av*Eg@cxveYCWaX!PWlHoqRE1xB1{lSD_KE77|tXJ+Rf0c!^y`hz5N zBWt_GC5dd)k>rCyImTcEXwa>^I_X#_XJ%Jau^0_59OCEe5Vp=9)7IeFq_ zib*!wcwKTWGHzl*5!Ct4L{+o7b>?3J2;cm;u zLJFBkp`3b@$`fNgMtHf&H-E-I!AEm&=1%>Dy>X_r%E(`xp?PU3uEk8AjWn$LJHPe8 zwl31YRj*m@nXa|13suQ#A2}B(pH5vrQ6xE;+pA_D?cdXkiY*hJ7nfjhPQ*@RMw@CL zD&`((MB#7G%+Oq!e4$xUWbirtRIQ^C+27BK{Uz1JPY7d4#xtb&3wD~}=Cg4WR)7%V zQY~}RF#rZyoS{FyuyF0k9i%?$!%H`{AyY~fEPy4Q&{aB>V2!fklV;)-9QPm-m5(Dc z@?SmsBMosn5JHKKRM69-4qdn@Lq%|L+{qBs^G;!q|%p7RDz)Mm96Ma9TlX@O<96)w0}Wrsi)6mU0U z@e{!;DJL{9>z3|5p4Xy4QFf7qipl|YUn&E8538<5bRj^?&141>D6d=uPLs6{F%wAw zu8A)@_i<9vvBxXP`V@cgv}j?DA9RCO-vxr2>2XKj7R%3rP5PuyD3e?+MQzEW39`NH zKQyI@-|Kbuu=-~jtx3B2@_X+-^$9r*{ zTYoSl2zNtKJoSB`Z3RaYnIRJsvfW!yUwGwLa>R(@Y{urdgjeHj=rFq;OCB{)u&1?r zei59;DG%5KyL)e_%3P161PJ~Xs#&?<`34JrwLK*zwHNm&UGFRh+u??|cPx>y?_o*0 zGh2qdz=Jl*6+tp+VDAvSH}_rNrwk4h@0Ro6^#Nsz0~Q%)xu9tx1Ag01^T)#`n+Ax> zE)E*|sNXgUP=7z{edB;ai)!CUFeyg)ZdXjKPeXdM1r%aNQIqFT9st zD4>t$Hq%~ooY%JfeOO<7KP}7KLj(4b3yJNkX&BT*19O5Nhw!FBO zhJGl!&SGzJS%0``dMmXpbR?FYwkOlz6t>Z*jbua_FsGDL=c^h+{*5WJ>lF<=SyE;= zx1w!2c+`JvB`VuOPAnv5#s;#Sk_YWk|LfD#gcGT@&)H8i6HKOjQ+dsdZK zQhn(_W^hLF2K9$8#3IzU>22pDAPWhM`k{d(H^OZ;s_l4J;Slct){hDS?zQdjluyHz zKYaONwj@{ei?yB|Diik=1A{^1Osot&39nX?7kOakq5BVx*XPfv#zE?(9iql)R2r~&3D+B`TiJdsR=)ODmJIold^`wsc9{4lKs z6;H``vcd@s-}^bfwYzG!)h_%VG9nGOwC*O9nId|T@RDUa*X{bX{pW9)ZgX{_g?JHn z6WrnTSQoxIYN;(&Mk$hm6o%k(HXRP$w_>#Y!OH}OMO-=JpkS6OVUk9{pvh_i}>yi@cWGNF{fo1*I%2AF|sGHQWsX{_vcL>Q{eSKiBoMa6~p@%Axa{K3)Zr zqlH!_1Dy}O7ZyG!<3l|~E*MDcJn9L>#Zyu6MhfT*v?Or>f}B_my?610q6fLDzVVhz zgAlgQC`KcZ{Ei?J`@vd~i2ifr=wvm5IC6Ze!7lFY9l)|~kXu!n;iDhgpj26Id{9Wl z2=N)PFbw&6&PBm!7?*@x*T7_0+dM+uJ1QoS8u(%1#v8or|F9KHIO05JDp@t`_Ou$8okCC^8jD+42z7JG|gL6bt%IH zHMjf(q~X)#aX%8T8VKwe-7jx}BPiBmmVAl4@i{VD zxMl#gQnpc{2^?LGjM#QxK@;IIPW!{B7%CciZeQLWT6?)0!Y?FbHtKqw>Cm_jK6gEC z`N&82Ns#!3MqyD`Zu|K^3tUG;^66);%(1>I?Qc!ZPF~*W(XAY9LoPj}2X`^vm@d2S zY?v75KR8{GSU1x+Q{lgl$n_dmAjT)L)FrfWC zJzfFQnf_8^l-~VHIWrX|Gg2IuD8QSM`Ewy;uKkBGwZ_<(QDyhpIUX>CINL{?6YgLQ z-`d&)Y--J&R%dNb8*xZQv_kCXV+Ua-Y{f2m;6wIvUp1(S(}k|Z@)zha+XgPE4_g)_ zpx*1(JI}LG>czb11?Kmsl6U9}H#(EeoU1|#O8P)4%XUTzN97DfByIq;uG_1;zhiQt z{iC{i;pzrLAtt;HIsie)4Zzxp>PtY!+jC8et+RHKjV15uhz~wqA zHy~%^*I-pl%t2BS!9<~+QEd2+z~Qu+<0ZeFEgMJO!@N#6M9o`?88t zM1F-)#B_R6z;rApq?Q_0{3`h;>SRR8%N~JBHJ2B9*-M%A#9M}o;$^^!NI$@;*bZA) zZ*AuphVej^j1AY3aQ>9#w#-Q8L?_gL>6xLW5PYNaFmc#4JG!ooNQX0`y7S7FDd&#| zkC`&jAVvtQEo)VqeTX09Bl+|C41Xs{?JO+X*_6XAk`heDO%XS$ORmjql2f&ALDmew zcR=E1ff-{V_A9wC#cQY16Kp*n{t4%oWO1c?W?UdD*eB6lF`D~f zk^RTiq*0Vy;Q|XKM1l4p0Z|tlx!ARhzsSwH;P{jsE|*F6Ae57Zy zC!V7_N&cz$RSz&O=&}EHY}WI2$l-d7zVVSA!;wotykm)uxNaLD4|NpfOGy}QghFNu zOsG}W)pla01^U+Ox+76-G^7PEabXe0j*gI_%>aG~%bYYp-%0J}m&RmtFB7>Ah^b%(> zp`T(%a3wX{PniSyzI*jh5qp7+x^AA&&pi70n0ucqFX5XiJ;PiMkoKi=1$PIr78PXu zulOlv4g80`tXOROaa`^pGutj&%j@jnQfCLw`#;IBFK8Iw(x;F2B>U!V5&M#Su(<5U zmwhS}elRth7_q(h&6`)0Wl9oT)2R)wLQN8-$0===2?pf9QE1wE=^q&;d6Lj_u!5h?E4Uy_tN|6)($ zHxaB|9qO$a)L$y#2;cG}o^;Z7JxX6^6JjPY96dJ#59_-v^89`f``s&1Q%e0Q7*f!_ za$1)Fa=q;&3P#I{(S10UI(|ulmTy1`C=M~8yQ=`P@3qkX9i|TXhpqMhrYVk~&~-Yw zf*_>nIh{$blH{NVo$m?)4Gycn!;|>tldv)}_#@FU*bmNq0ckdN5&!OGGl&;>dJQin z&wtop^dP@QZ7?q3_K!ZUgWVq~5^8`bQ z{T@^U#tot%id<(WMOh=9^l8k%yJ`Nix3nD=@g`r98CM9&8(3lk`jy$efF?ko^+yH0 z)qdbv38(Rz)*p!u2*d?S9=0c{2zYUS=u|6)Tav_x?F*ZfN*m)!5=1sJs(TI{S=o1elOeHAxh^#BiH@)FTIu zunLSh6B*61ABb8Bc+GkbC3grk(ekiJwfR{g&f7~^(iPuVN@p-!G(P`Tt z?}|HAsxe4tHOZNn-dfM4uqWM8V^HY}^dyxEzg<&viFp?`y_j96!hDiYLY< zVT)xvd}s0sD4`%IXHYRnepTfN!k=3jh4*-bi>yb$G3&Q+UotMvk9WBI%4b$`=qFXe%S4Hp z->*nIAn1<`!#%aSeI=i@EjkD56QP7t{DNo4Q%0*XG&3t5*Z=8^qC@o(oSqgik&6ZR z^`lI+0WkwbzoOG+x#wi9hPiQ0%w3!Cw2zCG)z?}NNbMu>eP^CA)Gf3GHPKS`Xznle z`ZRk_xgf=J? zEh{_w!l}TRY0Dgu_T+Xo8Z5O}*0tZ2!mQ&uAshZv?!I)lsesn2LNE@E-tDBvwtrO` zmQL`Pr3dq#pZv@oN)#`3j&CD$>_mbd*ByY6$IUY7J8>tba?hn= zRXZR1EkdZ@_qjdE{<2?NHb*P!*nqhom`89chx;Vk4z!;{gsIrkPsO>dR1pb5v$i(& z+>ImiWoy+ww51iuQ778J+H2c%cR@3XjUqpQyD*qN4$BJtm~#7nA7<$N{%bAJ5GR=A1LJm^W~Y12 z{yN_$G{O^btnhOGUfF;C+|N@HC7zE(%Dz9kVYV5|XPFg5tn?v;&X2RIKOABy=~0Br zOkTb@H)iRmK)ob#H7lQGG=2yQj}DD3qIzDYl2vbi7WeL0;9w#FlB{BEcK#}g0h^u1 zIN%uR39Zw}DgTS0UBl0TkgKKzUnZg;yWfp^At^saW^R`Z-k+CCndh|!dP$&6hwkS} zI-w}2f-pP_Bn*KTtMNUo2L!mDEl7=itiaKuc?`g-Qm^U1x0;8(p^S#_PoGN+=!P$Q zeCC;7TX6V{cY=|bRmEgYY3y!!9GwZX?ETcGsB;YFn0QoXNvegohX@+mvVF$%m2SNx{yq$gbrc|35%CB)% z3Igj}o&cs@3z;*?uyy%DFE0^ANjU&e@=WriLAaE3kL!4XIzU&W0+fYpV4T#ypKxNz z$mK6`ztbasi?BbjNO)&9H<|j9YO*+lXv598A5MhFSQp<*+Z~l6CJ1n4bE4uu3e{O4 zeH(mlc>MC8`Zm#_O7XI(aaET-&37L%?JR z`hS@E#^6ZTZtWf0_9W@pwrx#p+jb__#GcrhBokW`+v(W0&9C?So^$G3Kc22iDnGg^ z_j=ZStqY-mfsJJME&p4gtxUeFu8s2{u7uB{wH(jkqX`giYQyuW!*ah|vAVywQQ>G0 zw;|24vt2EIktyzA1^O)i0qd7xHBdSIob7G;JuCjkfcVDNCsspa-{6Nvwh1svlIn?C zwllF);RluYw2boUPFKXl3P8pCCrvqhE_Y$t5L@6~A#x{Yt zD$TosvrZs)ica-!O3GC<`)Eo|m?W&T;;D~(<(nZmTV-iMYGkn3M-_~KHgCE~Q zwS>Vh1xF@~4MdS)JRSIqutK?qN zbH@_Q;n(hmj9SB12P*V5){+aGct;=;4d4vVg-zbQS^A6QeEunZJ8mG8&oKyZIzt2t z$JUG&C{)z-37yAi%C1j*oF>vuw9O* z3ER?VJWGawUESi=vrY((F#oBDFQit6azapfkY4Y2or=|b=LaniTL0>zZq*uxe73F; zK8HMk05(Yw9i-0h#f8aZzBYy%8F?-GVk4NAiZ3YkK8P{m+P=T4>L1=FC9&yCJlF^V zlDvvFr3(S}8kMA}H4;pt*?L<4`RhJ5-bG)~41?YqQ&Tg0Yp)Zw@ZDR(!o@jo=-kEc z)tu!SkxzGbn!n-$+27Q8f|RR3{g>dg)2{fs@3eryxl%~i(>?(5BBB zw)O@Yug7UIO6xPHwxmUAH%CvvhtEVFm(mtt5mfeBvBU1?+hu0lS$s<_({sgw{}ONvQfwJo0mf&?q&D{ zq{q8wAmCE?p@Hx4b}wLd=-?-SpaNK5-{HU~M8`5-{%u2;NkB7iDCJ{M*gkfWiVQVTw#jI8bnt99+Rcx(3EUOi z;qP@K%x-=WlSD_HKOmK-u@4jQR&8 z6E^6(S5II#v94Q$(Ej3o+;Tr`d(6l{P39`y7TzKk-I!){8kKVq<>DWQvX z>exh<6Yqjh+0g3Z6|bhhJ0bcqhQs39OP4!o6=bT34cmW(Gz?WR5TE4Y`?Tf9!TiRpXKJdzz&K~Qlqu2()`)C zaM@HKh@ulQkhKrZocQoy7DpML2RHh_Mnj&XnG1u*s$rpXKkK0#pTwCl8HzWvs-OaK z!=|x^xk!#@m;2qyrM?Eq_|5p0@p_d*!|^x?5^w&Wvn1pJTeIw8w|iUS$#L5CKp!IiCv3(}^`MjN+NeCo(;O`5mJX*~X}hV#JuE&wV8L$;tC=+Rw9=%ks z?=L>4Q>z=-*KAkgPYdaDzjUGw+#SyDiWJr!pC5od!;xK5#w)u}tY6*nARt@fyQX)j zfkg>^G7Mz@N$cn0SMpVzpZv=^hP=-gLrNN^Y}urq@UHQ~TJYG2sqCES%mdeE(0m(| zdQA0JaC9O6^Il7&6QeDpYxgreilJK@&Z-BY(?B!tS!O8zlX~_HlFnV5B>U=SPx4W{ZqlYPEz zebKUv_Wq}K0%78U_O`dTYh!{OYi^`y7!+potbcKihE4wKIs31`ze>A-*A`~vW@mCGCCX9p8!UEv6D zKnln<{1KIhSs}#MA8%CtDT=A0o4jst8hKMa+o0S28U^~DEKzE{$WJyUyZFxRpClsz zJk^j}@@yytFW=Ho%se6MUHP{2iyU$CP?q$4tGl%y)QkrVe0MyT3~Nx1t#1yMS~fJM zZ6+UgW7(z$M$57bKji{H&KM}69T2Q84z9`LmT3z|AA@7?fHaN>u8DiI!z7vr!n*L? zq@K;kH0~myy8ry^k14IB6t|Lxk1!s6y?Fa#U}fs}Jka2E_XnnPrn%rs(06Ake(NZV zb0|OUqBii&0n|T5=3pn&lY{y%h?2Lb%V2}c(@50xsFCya%N)4x-VIH!X5R`V#x-1; zTx_v3)qc}nKcwgF%)VU>MVH(;&5#ZopNmA~e_i@Y6O(Av=*2PhJY!yc9$}?m+9za{ zIDEJt?lEyZ4DEsG{}VU(&b@b!;e5KIKSNNkS*4S`4YnANKC4`$ zZYb4|JfsjNiDH?AXTYYIHz})=AKh_nF4~%91YwO+UQq#vf-yerLj%snYd2C_I;0&~ zA7>^Ap#~FXVrN5SK-C2PYDcqXvo5E(8++97f^J`1RW0?`t41PObIzJW#??34nAoAL zI1D2}RW*pERPTe`_u7v@WUnOHjAu~_9TQHi5%qx01&|DdE*HZKP+p0a>E3A~x2(^F z1+Ug+-Moo^WARw`Lb~(K*&-(Z!J#WuL=i}`e-r7X{v1^X_!Gvhlo4k3y2C;jvQj0S zQ(`$ICw(r7i(WVJV%z%=#mCyc8a4yy=ghvkF;vm9N)mYoEcD z5+QDt8(+?ZU|t9I{2bx8?!V=##dHhh*97ae)Fbg0mvghGd-=EfjVLnGPf9~Q&Gfby z<$7H$-sC2jq}agK0M^yvhlV}x-VZ7R@s?cw1A_)kR}01A{-;kOSIfW%t71h9$W;be z3~%xD-IfEf0_HzGH4H;)|?w?!aBPn#N!rYC3XKmI_DrIGh-ORKnQywAf1QbK z9S=Bi??rLxG&^LAtD=4U`uPx?K*c_R&O$*daDcxXVjGqlc`auDV$=1IyhxEz|Y2hS?kuG+(XDYZLBhLb(;wPWi;5yuuZJx9+g@*(v{plC|nBFXSHhMIzG6R$x#b(1asCv~;C2$F!- zG~)~*PML0FfjGatTJk!VQBA%SzXtNZ{vQmql_t~-KkfGEU&6I&Tf5)S;3vqGDzOVB zN4W+Zx*GUNl)u|mv7W=aU9o8h`fGvaRVCT(72Ew0pZ#BJU$^N*vfVpkHCMSQMWp8-C)*axx5qU{E*}E#<62`Ox?7}KmImia zcI>xYKf?OkJ5Vdz$w%O_SE!t~Fk2?{3Xmq;@vMN_JC>H88Pw`Q;dxJa)I=b?gmA%8-YN5?kk-1 z-6{k|iGXoV)s{w5byw#M=IWV2cb3xpazt~EllE_u2d0NdX|!qE=!oJo)nfRoO`}8M zh43jU8BjzJZ^BtpXIw@Eb?q+Su@$BCN1tG&d!&z}d{K%`RRh0$E7?V(H{cfIZ{+V) zg3W)KsO(vJ6dGOZR>hQ2={lqlclwjhA=o^b4=&wLbIoaEDl zZ$4KfGHLmHkvb2Zsu)V)kEUuOZPCpyC)vjD$(W(Dyn-XKHvdH1H&Dvqq6blyEM&r8 zfX`R$iNwhU)N(`#X_q~#Yg$ZXxMXP?7vYOO$Xbz2hf1+0);3f5*B_K4xDp=&M6-EZ zb;xE3<9!T(rn`1v&=@M59(hzkNjt3x);Oo_3p2I}IUG8b^Aie)3(G)tV}?HD2Etd$kGk1H2;DRX~& zBAD~M8QwEq7`UzV5X;n=WZU~oop!XCZHOMWTV5Sw)icM&W`^t#brV4ncINnr@rYYr z!zq_>r}&(ZlN^DV+0gdWpu^*W#UziV^*E_=rXH!KtDtFc-%y}jZ165Z-Kqov~dWROt*Dn+T{orA1Yhm^9~iomQ(NR>DD`?NcT&Bb&ErqpI9*?^!(}; z$m(lzzl)~DsZPU#fRXIVijdhMdrAou<)qbR@*AhaR-}v%rB^tFXQ01jE0tn|tK(_9 z?+0H72*iG^a?k60l4A4ZIa=3fJrq7g2$PUFl&H`LTLWE4n_~`RhzEvA0%MuFpG7~A z|65-K%g>|vA)xA?#s*DS#Bl!GYxg1oGj9 zKqILJPl3pDmF6G=r9wb1$aX*<$CZfC1CYk}JaG5HudGYZe~ZO&dIc1KfQg-QoNKb5 z*ML+SuKb%qiqmv zlxyANbh>3D+?w_2T>3olFWB*FQ|0TH&)uYj@3JLJKU*8;q+(nogS-=JJK%-}ul^vlA zDd(SIzH{%$JJb6PIcOc#G^uiy(U#UBoaA2O#^1%(0|6n;Dbk{ zz&-C;rK&}sbyya;J7C%_Ri%JbqWwCZC=bPCaaxV=KnXUL?sxs?U5i8ka)Hpudn(#H zlB2&Fk;(?zF(eiY=qknNi4h1JD)Ghr5o2z8%;a@pG50cd3*~7A4Koq%r>0-lb^VNW z4GfQ43w?f#=Y2im*4Q_lDKWKWiYQSii~uj|X2FWpePFx~^G#KJ%*B0!&mD%&f%*Q> zpnM9=5crVyO#V>~OhwFx33Qs$!j;J0@htCPO{!NaMT5)@X4k6dZlfTQQ|JlxT>||C zf9#QW3E?PzXgU)GtM=S8P=;43J5lMKRj|)d*-WJ2`ONJ z;*3G)^Ph3am^-5n>jMX$m(g*n-)Xz=mencfJ3yaT1zACSi&0ZJZ}+iD}dg z;O!D4z2PGV&$^ZEEmvz}A2r2Mr}h1^`czqS+@t+&?>Jfg8w z*Q$UH^ltV5{Z1n&YOTKZZQHo@)w9KDB$CBodJW>&KVMMN#OvP zn-_mtpkf>QCNFSs?rP#^NA6?B<-pNz^5v>1)KkSvSDS3RW`?#o8$B-9W_uv;cfXxr)cMUG zxx^;{M6XyAqD%*6@7~z>#_jUfQMddIqiNLS7J7yqw7HGGBjgNcVQl!|(UBq}3vpOI z3>M0zGv;0$q42>tAb3p!QL{Cryw{|KKJMpz+?@VX&s#y{+y4#~=c4)AK(0+M2rMkD z3_<_)EFJwWpQdgWQMK|MKF>!NO6Ptgu5FOsez;H~CZ$TOPeDc|N>HzeBj@4;>|}ce z)x4xqrB)EciOD05Q5|6iDVuu#ey%9+b~L3Xd1z2>Z96Ot*{OZk!5+NV9!l||eO`R9 zG{o^G&9^NhGW}WXe?%%RH?599nCJIihtuKO8zI{BFv8`h3-V@p4w<6iLl+B2?5zp- zuzi?+o%98@tj|MmxJX}Qo7d{=!#-l)^F%M#<=_}1-F6^0j(YdUApw&aYQi0>pZL6Z zN*+4IEtmaV;1x!EZ-8YM!*DaSz6VK=+Lu=mjt!vz2p1=|TGs(C1|w9re`A`tl7DNW zQQ2u^KX16gZM2(J#VHQV7J%^lc!+Pk`5oijuio?bPDwCU^(C$}HH=u`^;qxb0Vi)a zm(QX9PDvmbNT+!W?hp{8v22@HH!?N3G-%L4@A!#}k=k4|gudwavRPvT7f4M~U?e<> z4i-Oy@zZ6e4Le5{XkwHOZf1l=I|d(H3s)R)HH=olAaZibq}=&z4tbhp<*OHKseiJQ zulE)}Wa+MA1Z<}+ol1Hw<`vQgMU+j4`A(^=w+EYBw*~uGFMWs5%Hf1GHQk*49`Jjr z%Qb(I6993iB~{ER_M+~qI#v8Dn^KV+GKq2)z?g7c6q>9MG%AVMaICaIM+RmuA$T9F zq7j~HfnTW9pT=K2Kz&0e5bX`yOd41!P$5%@G0BXeP36W}o+l#|FRN&*byhF+GH+tg zqYhn3GM_eT1dpdrklB>+H#&p522H1drsjI6%08Q=ak)JGTExVNdkwGOQh%%XLLID&;3tz1*TVX#%= zie**zV$Jxcq!37J(C|Z87$+QLGLE`Wu$nX|ZC`8Q|1Ta8y~-=rY8sGK$&OQrF>GI; z{2~C4-5FHhWJsqySLcOq zGfOPDBo4~dva1eWn{amJNgif*6cEXL>fcG25V25HWi?`s-GD|OGVf^v`+z}CuU`ku z)D&V?=|-)ALT2>>513f)-YR5;$Hvlp2Yba5(|Ub{_&oSC`JJYi#W|Qv2xd6=aJ0#E z)nF~nw))vo;>7l-ndth{)k?hzauCqRm^$8F zx`wP&P7i-Mtdfm$VXJ{gh+zR13n7Q171a-<-j^M#D~WFgZ@RX<&bBjUN+kEkD{3Ed z*q@yS=ga6$XZumfF|`FVT2+LNzRgqm70<67s(vrkb$)DSM#w{#4SNh*?BdKBaf%y~ zKBO=adC2ROTMlyW_p?%!>X%<6Gq_+8|4QW_q`{Gooc|9l=LV1acW_~h1d(XZ+m3SE zYh2zQFS?c$ilpL+U;90lYmG-HHv%gEK}P;*JnDC;TU|*fL_n`))|@;xg`98ys}zSf zGIxU&J%$DWo1&!}pM@KyH(w@$zXZ4D-Iqx4A4+K`@`X*nzHKvVCn)y%ed-(2DzokY=yMfen#jzs9?PD!FTyS4IO}@({w+tVVWTO zxQ?%$d%o0?j9qs@fSr4RiDihr%UNakvl~M7wo{#H(M6e=!Ss~F>fD4<6qt845PhoD z>HR@-ue_3J_CmfHG6aPOHC^B?fl=N8UQEa3ErBScbO_#(H}5_Bv;`D05vi}I6_lRq z5AN9Y$#0?fh0j*1*y|d<5rVSmujcBi;&#*5)_UdGvimboFvK$B@i9uy)#Ekqt9Dz8@~&*pAqcwNr?MQnDE~i&ZT^G5Q%g( z3Q`?uWz)OE$NDlOfmpJFQ?^Z!!@p50v?Di%i@t!)Z z+?pzQ!G%hVLX8`Cw(-)8r? zJXL=PL@OUx@8C-b;nMbw*@nd*Xlidl@kp9cLYGip$`G?IM@<_NQjB}O5E_V7VPQiL zaMNlhHk`$tuW7tPPh2+MWWK@4X2gXe>o^%7RZUa9G#P-lcNmNm6a1xu z&UWLk6ewqn7l1X?o{@=qJCt00N#rrRy^_n6c6q+@h*)bTgK=x#_)>nq(#clBy{dk? zO6%NCxRovs|9~3$vnFe@O5QQDlScZzmVFBJ>)od7L7V&X;4GC;dki=O!kdBRB8ogLuCu z8MF3lgxn%q1E&x;;y5?jw|}SSikAiWcV;M%vvI-T2slxN6FEoX%yYL}926+DljiW* z2?@R)lXsykuiyq=_qOhXg39m@uR?!0w1OevFy5=SAkuSL&jB7>JI*R=+ANCf6=Yi9 z9w^dB+>I}*1+%%Glha(9an5m6Y6AqvqBVbi9Yup~BiC1+i(jVERJxk_M1TW}$-9|uR91ofTZ=Q}O`qu$=7_DfD1`Ao%|G^7~cAq5&t1j8U` zNm%6y6XouQR|1NhkR{Y>cdH1`^V)@DIvN@oPrmxiX+Kk;M&+NoQe!B@Af~C4)jsKf z?zcF~iBG4d{5Kul194f9A@OdIxEmHke^9!=+A>_Twz0JmRI^63%ytehz47dB2>ut- z-rm0M3E5ZU_-_k@iMaTug+QzB`KZZ}gJFeUZY5w$*VG0bWE1XYH6F%oG<$2)&`M?n zWDPY%u?^|uznd}J2-orZ5^Kvs`q~+G`Tkw};patxuf^W>2SK2#n{8s^3c5Yt`JYde zfZ&TVokpu4wl!TE42D{I&Or5lZEQJD7~AeunLN=OXZm2C(hUOI(0x8#-Y&d$263E0 z3-7(Z5GeBWgzFw__RlxNBwebL5X~HltM3)e78AJB>5$a~+H-xS*E~~&H#en&7|OC=UZ(%@FCIy#lSA5XL{Gr-%^Q$OvGUo2I*fj5_PzAYRQ1Q3Z&{rev zBDQL|)5nSf{9LYFgt(V-ud^h@>UFO@;lD-k`-CSYuMdzVb^;XA0%bmp##hqya3Hu6 z5secc*d|?LIB7aWUeo41{+sz?m^DRn2sQa7)|4N8M}?hfN#JZh%?q$9PKQ%u@(`%P zekGXcc`4c(k5Xi`nY?^mG$GRP89rvNL?*zCp?#7~w;a?q^`an+ReL#><%YTFHgNBK z@OUq4W zd0A5o4-82${-UF$izTcpk6Ma8(5rQ@PiBOYL2JhIZMKRzM;#WPw*t12|M7mn%XYhS zw^}1_13J;x>+G9?u7blque!s*OdlUi2w(;`%j~HzoR&$yk(yhEtTo@}uK79QB~5^q zhs(!Z-oN?YvR&B&X>)xK@!AaFfz#=Jmu**q*-pDrHc)rh{V2m*SM3NeUQfSlHEM=j zrv*V5p??^}V;?V510B}zxx!sukXrrJf3~Mq+U`HeiII+3=25%CdwzQm%(MhSiUnqw-|tU> zaz|{zfb@S2HG#j?K}&r&kZDkv`%Fo9N*`;dC+RYA6z4BG)2onXZ2z}MplRxR^WI&| z!`YJQ!C0zRrx(lNR8HlE-HBWhcB7zI92Zy5{hZwY-a?ljc9IF=>^t`Udnt8tlJ1SB zFx*|6CcYKr!*+Lfp3t}21e`CB5;5?TO&ls4;0-334<#w2E1ryuulTiboY|mL_P@DJ zi|hEDil*JWy8k?+VTu=Nv64Z^SFil$<1t#E?&&)lIBhyeREAQ;_&Lbb{6ae0T&UmS z;dOsA+%=Q7cUIHgm-lr~#bo9*R#CPKie9-Eedx8Xru2U%{d_pB^n zY89>$+L-gx=Llj9+Afk}|0F9@mvh787LL~qP7n%W^FbCj@OrCOb{6p%OQC56Y33im z{&YdNCG<%+23Enhc{5z^_E3SsI31{ISAz)td~$TZ*cI-RW{M4YniKu$xIoVKcnq^S zu)M4yar)rEF&*vWiCmO$T7*j9$&O(ZspPc3J}HiBeS7>>Yw}{!@P`iTIz!Kcv?M$< zh`HVKDy~71j}Yc(!pn>hME9|elN@yi>QsGGQ)6^5zW6G)42}q7urUu+zyN5yP%Xxc zn#_vE&=2LP&zCObU@rlI3HWD*ce)VE-RnN}CFA}8dSOtSY(!W-Y|o?xrDe;T>5<4c zD9Q18rc=>PQ?Hd+^Yhh&-hf%@fK2s>g%O{Vqo!iv20t;`weDWd#7z#ArVd{S=PWpb z5BoMkI3x>K0T+wF{1f32;8Sjn&LeB+2ge$Mc^e_Y1Q1Jb64xg{7Zb>Aj325Dd!FWI zlFo&Q(n=Y{+=Cg#Ncoi(oH2zhFJTwP(+Gd{PPwY)pE1TRfM$PR>|U;pk;J~tjPbBl z95WxL#XG6Qq$U8sPy4j#yw}=IiS1{eMysw0iixO-@wO+@fW}*LxwK}8v}eXp%e46L z7?(=h@jh|_h@@)AW@o7zzpE-{lV$_vBgOMnm6_t)SK~&7=H<5#wMbl--|;b-&5{5= z!Qt7bFi|t!=`D(qKFvbY$NeZ*IZhDgS9p^T&iYgC?)zX*f0zyq-}NHQAquN?`2nN_ z-qRa1^r%=5f3myS)AbH_EEOQq#$#(}ecX)LK1{ul3>mz|YV;wEa>-ZzrXQvmCJaY9 z<5Fgqr7~GKbq5xiqNe9G@JXKMQalNjI!uAd9wpVwjwOzUNS&tbjbBj}L@bd;WKPfs z#?|qr{&a=DD#^%u!1b@Q#48szoLHNIVCsIPpj3F(I^4HO?2Vf>tGTBpv0wA-YvS67 zgFxYvJ&iTGjUd_PO3wwEJNoQ#aea_H5({Y5zbI=M#A(l$?H(NE4M<&m5tNjufG(6o zOB=UT=R%*#q4RS$t8&vjKYF&J`wC4mJ?BdT418q-!VmZkK|bPtPs(z_(-@i^V#>p{ zv@}9n(x#t4F|+N1a&;Pd+9ITL4Xm@jU8y#*5;Yc^A$=RIVw{QEeMuuO20^Qif8A$& z3UVSqIUPHWfnOast1j}-+Ysx4TmA;rQ4SmJ6%u3Nx+SG1EA{5jG3$G-2S!)`8=fF>q5qAzsbALHh!S0Lxgu+i8Q5UgM)6Y&U}7#ZIn>tStO4sufK9 zMX_6Ud=!aw9d?@Qy|weP!4Dk#1`2a9{16@>uj4G4io4;P+WvJU*=01 z(iaTAfnP~;ZEt$YiN!wKvjmdJ7UWTJr}0@H><;fDMV|JZmWss4`K|S+eF+}(=aa0u zT}3xeFa%QbcAF|$*K}8W*+Y#&(3y31gQQ`v;YCnKV2miPXxsta3ZF#pmk=*K-8TYVA)5qiEnA z@F?T)!Lqz+d-H2Gk}-fzwKTmIa%_xNnE)=|{w>#Pg$$?HD{5eoI&rAX3`QrJ8R5uA zfO1U26J50RSU)CTDB4SYg;TcC7($Oe-kDTy&5Wotw;rD4lg}DyGp7@uqbVgO=AD%M z7o-e5e&9#}nVgh=&?IZGvh=IUkEbnfkemQruKAw@6?DIAMOJVTZSIJMzyONo=Mtgy zw3u%!1I4c1IY%H(WDvP?qXF3ofYqwAl!b1TXZ=uW%&LR_41*|XU(8<`pKVNq?4Iz( z>Ycv7c9yFJVQ#1TBqb~q_Ec||J&Pj-cB0sM;)n=pRq7_I8@@5u3_B?xwvP(=Y%`-3CqaRtAk+7qbMb5mSxfN!Z&eQ>s!Qpgme9 zPk4?rZ1$H1j}~HMlY3y^+4$NWCMhjwZdPQVl5vzLC-$-j z^-#&nWN0#1I-E=VLUSExT8T|}pl7fCmd6arF%#pJDxOz;yA2Bmxg4J)Xt>i(91 z4t^3{rwxBP2V53!qHw?jc;5`RA57GT<(WL(Rv4VeNsYfJd@hb}^`-OTgHrm=uO!ZN zS`bN@(h;s+?H2%|x4-I)R}^@fo4StquB998Hr5b$xX%f%DH6jSijDHkY+`15vrcqO=u$sRv5h>)>3%?OOXYY2N5>{i2eGXT0=s2qb@p)^|58Wn935a8>KSEqI|M`0%~Uz9|4cB|UvF_-;zAP?FZ+qo0Hs6eh-$ zGSKdRwqT=ps_U=E-}TiC<39bO4>nFGdy{AG+7cPsP`zBKAay=(F?Z9T@G4v=!D;r&x~DNwV97AqdROsn2==`5x&O-S;HVduJ}U6 z3Aq5E-D|`x>?lR47bL8M5q8;a`sytlEWo4w5zau^K(C5%BF&B&6@(mQ;oCYc1*U1O zM~vABQOaw_QyJ<;x`zRvq>%*Yz~@SogRnrv(|NiNUk`SVT-5`@aW0 zov;W;lPl-CRS(~8sb|Ry=%%zr^J6X63TltT5p-EzNOkG{#PLvIVtQL+4KU%8sr=R5 zKPu#52p*70xEZ7F{qf*@md_6408ZX5m3exebJ=8s%GfbOg6p^yd`g=|FG&8)omoX~ zLD*euZoI`zJ%<`Rcz#Z%@zEdNYn9H1NI!Wtj}DE)B;5)ZVTCuc@RtQ-1RR#hc4Ru$ zDWOWfhOI1^n63+>@(Z6rah^H^Qo72>(WKoRUCsZR?uGn!*5RX+q}l2Camo=bK1PpF zB*^m9_&Wddc(JXkcvxJ~mDnpsT|i$QV59J_@qtbd}m-Dl2}) z_0ZR)zUl&tB2j6N#b^&)Qrn-^NE(Kc9F)=a>wav+wi0)l3xyoIIq9qo+S)o?Z}5y% z2M6e6;Uf%3Zet#eh%st(X3#_$K3(=l%ouJsf56+G+72T0`Jofxd%(}7hV_3q!=-q> z+MBS}QWA0ZUJ4nPlNJiC^*UEtv4h*0_w;X7E%2y3-}k^`iTMp2v8>gjwuM-yH`1!j@0Kl3M;G+Lk$Gj4|63^ZwB zjtFV`?JK2M3;3N4!;>5}QXYpo^5};GH?xC)l^U{00P$HBXbqYd@B6>49*se+<3!xs z`C=-%nlUwkZ;9U2vY{-)`+ zQ)~M7<#WAZdea(kn*+xPX=!eLg3Y`bt?yc-R;K8+T@c|G@cf*ktE^{r*+tll67T{_ zTYL`u#^67Ux;tCpg1`5}!o5D*j!qLDBYVZd&sp~g3gt8yM)=ARcYHOh>sYl*z|*pzv>Rjx{L*#+nJdTWLjUAV8(Cy ze#s3uV!vR~A~1N=W~<^f@{e-Sk4tov$1X|h=jbe0KX23~3JL&jWmvo1s&tErW1E5b z^l}-h=y}p?0O(&sPyxKv^Of=5+UXa3YsistAj;ElMwhR#*_Tf2vF6WS0lEQo6Q>&5 zb6^d$FH-qnf&mbBQ)%vP(L`BkbiM;x492X$^XXBxwEi3E53&lvRY7Z7d9FlBNp#CsWiD`I8tV)yxv>^+u05= zIB1W`zqtax2kV&78u#KH+Og6}SzZdm&x^0|RbTA2ctz2%B<5TTU9PthjQwn)!ZcEG zEqdCt#t|FQO@G6N2ZL0km?BiJ)eK?w^=I@Nt6n(|cH#*HXx$C!%#vO%w!NxW!GNu-ts{vXGxRzCowM9Ss z4TMVhbG*m1#W4ehGZ^~c%YXk)DXPmAKi0Y)yMEWy7-o4{6YacTWPNWf#|OHvOGZDq z6lhvdJB*{3WzWf>&DzNfW)(LsOf%eY!>Ay;B1=cY=OZ(y?2v?pK?&UC!MR=^>SEM+ zOybK>R45Kr#L>-*jhTMoR(7Fz%QUOhXA~!YlaeKt6F;@N-e@u0o)X#$^4#(vf`YO= z2ncdDLv7>nPU=5)2acJ0-K=-8YDaY4C-@&g90n#L z2k~yIaBm6{gZe)&#V8e&C+I%Q=tf!iMR86Bv*ip#@i&6^GB}Qn zk6#}wZS96>QknE=9%yNEK&tN)L_V*6gLbGHnA6){TtyE&Pb9K9C&8J-`%@iLz=%FD zA))TIQ*G|`5u&bDS1M_HU5|iEcGEjh>%chUOq#b1-t7=kSWhLVT^x5cly8Rjka%=4GAC0n5#2UKW-~ny;!fr5F}bnYRFHkeE5Ar=+)p*4HOO%5kD)UmcUd`M-c634fl7Bka<_Sci)uD& z0=v{1`(iLwd{mk`G~?g-IkcFOJn>X@$(xgwFt2yui%(T~VHoZhY1FM_RZf%?@{kSI zo`j2agbP*m{>-TY@hSL+a&XtpMxln+PLt#H;Tnm_!>M}GmR2?EV;d|(im>W0GIRFd zi@u9hIzK>mqd>>{UwZEDz>JT6cK+M=p6%|QFA~AmZT*Q%4v6t|hM_)hA(LHS$DK{S zui$vf&Zx2ITXCMnUcs_vAmKNWhY?19=0~ZTIdg?-6i*x9Dy7T+r7cA(L58;O{RPNUQ9?i-+hX;E4Org<#&u04* z&p#J@D55elaKr)EA`Mo@wHwR!PaDqfa8zCedBlyu{b5s}-Iy;6^mrQM;Ch=Yuzm6s ziQu}W=hMBY`gb@INgOCaXa(UyXB!*0_n-oQZ?2vMCO$38y4}}Jf$OxEm0?zjg_eY>6<3cNLqu;%I9}Hs^w_%~RY^`i z9I(t=f|zrhuP{!CxK@PW2XqB_(o*myb-EakCE{gJ0N}EgJL0Okt z`j|tW^El-PBuQ9^)}#-9ncWqHv<+~T(~i67rt%5bzZ|?s&U;9zbqHm~03K(LfvXZ5 zpCb?J<0UqwDNntYZ@Z6b=VI;(3@#1x?g$iP!u@9KkD>@n^i#ZxI1)Gg>*y&O8D}fG z!}}aYtIGb`#`u2+e!bt1tJ4w3siT|XPTx2lk~GW3Xtr~t#>E3Tf#E+;q=-EEL3+r- zJKP$>DX2!```bIEqTkV50<0bjyh$fTyaLb4Y6Si5eLD17s^P3Bj^9wlJv49&@|E1h zwP~u+%ZdrrQ7r>o{d1Tw+!L;XodUl@Lz_5@=*qvFU~PJxvB|$V@J3sGD6Mj=DLNBN zvsW{Jm=KIEOWQMGGl8yx$&@4OcbugGZxst_`8?l|iOo0n)*D?`&?j;qh`Qh94|kuo z2KVE)22+%T2F^*k#k{qhyY8@H7*OgO8xK#CH3lCE8b}`3T~W-;%&gYq{yDp%+_KMM zb*(LJCj`RL@$1I3&)#Kt=+^~CIJitkO%ZueYtS41!G2D7x*ZMvmxBzdeht%`P861pGs~`o{>RG}3lN<(Bpr1w4)!4bMmF1zY6YuHp49lh2wPpJ2(6-)PcFcmr5KI4M22A{mXJ3>u4Wu%P595HkkORb zy*YL`N)Z|okmaBtujggZr+ac3iplYa|AGrN&UL@F zag{+E_>$f$9euWtCe9;6)gOFDXcc0cML@F4-!M;y(ZR65Q>MxL)O85P5xFc<5f*tD z@Rm&zZ%11SCQW)`Y?4tP06MNMewAU%-A!0xZtjmM{dO`YE*yU!_W|dKd#PHREQca> zDwBwJu1Dsql%>gxl78z`w7i7ckkxz8T{3VP!vtH{c{v|Dmtomn1%U%xthW&_y!0S zGwkSg;t>|VXhxOhFx;6|%}KVCZ%CJlK%US|747O&g$-}S-soad=hZ%>E6F!#nZK0y zPf;PkWD+0E1bKy34~A6S*vx63)J{{rayFzMjRMstK|q99p>Sz@w}5FSXGw@ z`wJ_DDQya^sTuD~2ix%{vO3_|EI@{*VRCiG0@abD?qTIAg$D$Dp4WbOB-0gPvMFTP z(=5Z^_Q2QSrQ(=xj!1! zX6q#oey+`KKWFLc1YIF4n&`WS;dFSL!SpY8Nf019tRSDTauQ|1Yz5pQIlS$W{O5=t z>N*bA8uu%!=?8m$xwqk*)pi{V9dqAr?P)RX|A+JPpGR%Ozlx~;)>_!yE>_0`;AB#hMOb}P#7?35O{e%pe|WG)FU(fKd#O) zEXws=`wImDLAo1e=mtrFp<(Ed8YGAAmImo=hL8q9q&o!Zp&7c7Zcypgch*1NwfFu4 z4}9V{xaYaAIM4H^-Z$V8;(ECRv2m4+#s_XDoowJTu)m?Kf;7vnG*?Z1(thJ%v;K0) zz*Z6KVUADE(TMX4TZM*xElq`9O?UR3eciVLY&5yK&+%mVDx+46hE)eq>-|}= zNfzq&tDYeFc341WRYpp(o*Gv`3dz$bo0(EI@4%K zC2eHVB7X9t6jz9{xDuaMh@=WwxZN?sLlMC_bI1&qnqE?X-T1Ab*tVbndBZ|bcB~?k zv$z((VF5AhJ@6f~wZNv;UVH^(DHe-mvv)?bk-aHox>fARS+00I0+d^lp8BqEe_*Dj zxqLsG_4}euQN}@}#mfaT>01EznN7&-m5YgfySkFnNO}vqZ#wA#T0WuzyP{rl}Elne^I!2 z=O~!~G+(yE!pQI$M6&&%M}gO)UqVq?edhQzMRZY72T>XIdti)3VAP=9CAJ36$R|ga z*Gad<#UW=Mg5F%g9XULZCPjs>f_HAJSF&HPbCZ&j8AZ2lxcBo|zI-WO)X`UYwP;!{edZ(#C-TkGOx%fHxcFJ9R zVwJq*qX2LN)ly~k@?m}ZQd>RUFU~*SUX5tvJ)nzOPY-td-XiPW4Zetp6#3UfzJ!au zqKiw8ChP@Xe!~)#Yeb<>_d_!l0%Wr97kMf(sFwSyI~12`?>FwBhc{{I)w*4M%>X=X z=;PFTI`IY{#gP9|A*lA@yZmQx*G$?E9!FwpN!T&vM|RnwE-58GcVYQBF#(~Wdg zNJXXMdJPB(Mxj#75E}4csq8% z?rRzo4uK2Du%z#SL4&4%4=Po|6Moeb*)z2qRH_uh*_ZMutp%R9G7QdmoxWGSeTiZT z5&`!iNc_=q!4>7aas>;pZ&EZCVjoRrFVL=&c#ypR0V_gt82Zq2F2)Dqj7hpx03oPH z>#(EAON~>+RK!seBm8BW{7x0yJynVUg+My96dwoVNF^tkg;C(}meGJwlARaA%?U?+ zOG5DJw(~sk>(72Hg!lyfEpv*dM~TF9oEH(h`3xzOs3z^VU~6*;5&j~3CmBomlEcsh z?VpO`HwSaHNGtm~ug3viYU!a?=a5Pp7@L7NV&27OO`db5_SGEgaY0^Nc)}E+XLsPr zH}@01t~q{cPOM}g5l&?McOVr(*OA`4QBt{ibVTo+^#Sy3W^oK+^(RnyZ9Ij$#WEUUHhAr12OnstE2!>1_ zt8u!&?SY2=;LU!T7xUQKoErW9`si@2`iUKmBm6mQdNB3BxMj`4A<0sLRnZ?!T$V7KzL`p&U6MQzu5 zDk6p?|CZB-cjXJ+GF|oIikHNSymCggW%?qScH2AJYMNbr6DXw7;O@4gFBP>Ohg#ga zboZGtpUfExv%`ZU_u<~Su;8co90*v( zbzD|(Id<&~al%>yw4{1`S056;{_1s41oN`x>eM;zm7#8B)JcPieM$lg!%X`ER*4lluYZf16!Tzf2!7HiihKRGY#unaDAdlQkWz?! zICPM$a2@Tr*r6LVi#vmHUyg1#(QH3+xZk$nll)e^g{rU6RB?M|dRkLQhjDl3jobvI zB_nTC2?s$08G;8aylih9*&YXm`1p`>Jm$D>({YpIltFHV$@%Kt1^{VVn#zu}Jqa=Z<4;JOX*lRB zV-Z1$-}dsV+G`a#yE-JYhB*#jB4$s0h_P3YVx!gs>VnTCvdB1G*JoX{lNIMh+vuX z5J>mo8hWDGz3|`3dVDUtb9w9|w{dn`E zJc)v|(aeJJ7WmY(dCFB8K3S2Q7TIgQ;72W(uI`at+b6AhN0`}zr)Q&^MRTV)2)QQ> z_50a|Bxu~GrCIrX(Z6q$sM6c=2A)M&D|}4BU<9zx_faPDHiM;OS?wjzv?M4lHlqNE zgT#8q;om#`>}fGaEFWxlEooIjsF zg7uwjy0bW_5$6<7?m}B0b&7t+#ZCZ0vzq9=VUHGxDNu z`hwlpDj#1O(It)~e#;b2i8$I(40*|^HmRk8+E`kcKw>@Xro#DnMsaKIK>#a;bQXHP zOb-Roheo+8QxP!ks1IWWg6!}=o@Slj~PKBzDisvE5^fRRC^g(GwbpH^xys4m$>RidWxj)fvPFXd9Ol~m>SMm4W?g4y9A*j_ z`>ubo{NSxod6FVrVVlp*9LOFWtG#cfQin7DY1fh}sRY{m7okGet|dlDduK8xnX>Y1 z`5C{2PS6Q|v`|`nU}=_{d|A0DedAB#j&b`Lt&3@d#ESnc;dZJc#S^~@=t5(_VIj#S zPArUZCDSWzfVy=HEL8(gXlCcpSFc24b7+q`u-FZ2=EmTsw7-c(C@y#>0K`Q(XGF zc^e6&wVuzUCE>-h(f9XWM+Rt&3K>&H(*xyeJLsdM*4s_>d+FEq*zmAzpQJ?i;?JZ$ zRa24+Teq3@%$(qMan1?I(WaH4TE92?|p$m9kS&?oofX^D;7 ztchjvvl%n4E7CYEd@}S(?(Rb+FzW9M5>bX`Y_=@mTPR0Eki8fv6Ts^r zC9V-9m^eNN*w)^5Seg|R(?UlDgPY?V`(R}No8+ORtXffMV1@m${(HA$L4KGPvSI_K z$>#f3nP*EY86Ul-#{!6TR#ca}A7&gZKh7!G(GpCy?%Yilw)|3Oj9X(-MSATAmb_1| z)pm%=4m}9UWz?z6wmB(gBID}@EwU`W&x)$#caVutcsjkS`M<|uokuyaR)NN)Nl! zPo#-i=e@^Q%V_0Cd?hQ(apm$_fvQ(&&t(QHaiJeZ*T;4U;|I?}$hL3p@PSJT!vqnl z=9rXX%qQw84x7q&LJauOwTRloWrf5sse1HbfEXX`aU&|;y#a0?jK}<9g|9N!l;Wb6 zDp4?zQ$2`Jok&1HfGsh7c;0yzfX_^~4~Nk&Nw3r$;b(S;Y3a@LsvX504(p8{kxlv= zOQBqlvtdOm@*-1U-WK6{cE5IieNL98+T}n&ZCTv#R9nwC9uY4FwnmW8R0d||7vy~= zr9?a;(O%1fJ+*THL|0X+kHN$qy~9c~4HmpX96nRCk~*c76sBW#pH=j^)U-jvE5)xv zB6C_a)!QJGXkX~ARs3mk&x+5fVPZ`;u<{?t$6Oe-+St`8;}IDPX)*Yr28@nWtq{Qc zY13`#jND%?>6Z_xW03>p6h(7O&>kBz>Ho0yYA{zKJd`C$&b+8aH<0cA0A^WE%*=$C z!Wye}Ui=I~0=F#JlS@tXi7Ll`{!aKV?!slu)_SX78=>(&)V=dBMD-&%*ayJfNp0h};Kn?h6v7LCU#mw(yxs&<&`+JaWapZMA z-wf{>K`sk=)r1B!_RN&?gS@^GgqpDVk1j2VAa3Gp=$xFmfq1PNoFDgTR?pJXQo5_$ zQA166qcHBW>}X-H!G}d6k!fj$_>X|Y2+xG@D>jFKi0R%l05R_b;OpXJyFhM+Hl^~1 zDrl-{(_^YTO-VRw%6`#z$)tXLF_v;GF3=LafZx z!YvT^S-pambAMoED=dy+TU9VwRvLXTTNzE}3W`mUm_Y`}n};6PH@*2EMakcfufzTw z^YGtaJMg#CQ7)jZzc}uA@vil%!%9<>QQJH@)7aTeobivmsTUIypZBhTE~Qel>5#yS zci)&eKd4WgyZvG(3uw!%NijH6$aGcg89mJPkyaQkV&CZ4Z&b50Vl6yU3&# z{x_6|aq8-!2yT$`r+Zn$^3&yF3^>>HkwRobF0b8*a2P+|TdNW9G%6(P~Z4-R|J36DK!rUD$lIR~w3 zO`jZtrkoj8n1hO7?F(~^tv%<9cP)LDA2-UuDx=Kz@!9dOqw}Nd=)h0b1mm^udR(s& z@ASryNeE>6StoU_nO+1*_E`&s&7pgUIp%T^t@C5KCz|va98|P=I?9=DME^hfq$k5e?M*hvCb@W z`yT^3930F=IS;PMGOiJ(c|Y>GA@eF^dZ)KYX1K|C<#AKAfFU>5N}bNKNBr3|CBvuB z9|jxic2yji&;zV0h`By|MBAVB_rhOS+T+ym^HB}_I$J|OY<2%L*##963ra^avm8}l zZ54g>&arsmR3_WSgjvFLr05Uq2@9dWeI7VFKVN_}d!ivtW_|abENpC&mU3C}1|Ecr zfdT7?l9C4GZP@e{gKb$hu~I;((3o|0T|HiN#+8(`Tr3Ia)E7_t@lp5jVn&N3o5Fp0 zs%Q%A)Ho?5lNT!_46QV^qo*FWYBmbt8Hao^GcH}K9sih}U(083j()LxmcC5VH#R8T zJEF$JB_(Or&Jwz8oq6xP)XrI7fAN~T$9(=QwB%zj_Y06B7d=WOH0Fx3>O568*H;u) zU#LNLx{MTh=fDoo6LobdOKG%cs@5Z_P9RnNpO9`VOZ`Mf{!b7fL*;jj`9U#{IP2WF z244o`l_P$X>S_4vk++5#x0&OD@QZzUJ{_1N2L{)FW$0~yw)YO$7q*iw%($VErR1e- zHF;5Hdv)B{-lTX%8D-q*t9U@4rRK}FP=o8)6;?2^3sW$CSlx%Wn`xU9uJtQV`{)+(HpGj2ij@ z{3;4tXctLIJ>JUA1?yZxsdRnNet^-hA)ZkPL!@{l%tNMR-fSBK29m#>%^$f2*nt| zCsxoxXWzb-k1KZaZZyrT*YdJAiU>5!PtW%`;24gWILi1PVZmgW;8SV&an=iyz|)~C zOI|vjaiyf${@8Re#qU5XT21#4hk^oVG@|b?rRLietv0Zn+Yr4e7gfO7Eg2}Ipojp1 zt2sn*Ir1xuS-lUlGxjTC&lw73PHTYfZ+Mgn^&~C^QWmOnUs1@|J;+<7H)<|IC`!xb z%@E2^#XY_|iapg=+Ez2L=#`EiI<-zOGIc(ba)GN{DLe6Z zVP*V|z(lYDLm~{%C(}-8R1-`XcTG=(qkM|}arsdKqE27_;rGs#VDuXpk<_yRd1@E~G+w~@9foNx4Hv_M z2t+UpCmK2HN2UnC-i>$Ur42s%d1i(nOrp55xU>(omOd6D$}EL*MAY~aGx-`kpDp!i zds-uStTpaQtp9{W(X*JjSF64_j8vH92~E7Jr5Y9h&JVTWFI7%>11saO8@hD$*vf=U z`6t@n7Ae}T`!sqQD%7gOy!*s-babLc6*C#8!fbW-IR;-J0h-jmV}&IIn|c z9bavrIBg2-<=&P5_bIk%$;L3UT@1ZuWSV6no7@s(R zoxPpTo?_Yp`$e*b{5h_f1<&vME2fp#Ddc43;{aw?%xOGo_qiGXab>J;t<56tE1zM( z{B-)P1*&*K$Dv@xN+gRz)$vU@ewJ3tf8PZE`7SfFF@yWhQHlH`<>Kmn)Uv+ybo0HB z)WrY8$cPg6fSF-I?Dltaha)X_b4Iry3u5ElVPwVOSf2? z1B^R-Uss5n%lH-8zPK!hQcja_Hj&jw-T64|@Srk4DoN@N4AVkpkxE>4OuFjd~b@W(?+=)hE?$G~T_oTi)=J z5rfNhkr?BD7$V&#PjcOfXLNs^zUa=j3{}&X^=Ama_oiXRjb;^~5eet3?~JIQLUOJa z(JR=GVEfsw$O^`%s=?>5MUjzYNl=S(aq&Wqyb9;g+Sm|x#_?-qejp7wqTN9xNI@t-Q#k*V&BdN530`3{opOmC`7qqs<9#chcWVg*^`^!zJ_h}~Z`Kq_Z zxH*}R6nhVp#J9w_|2T9=K8!D4g&?0Ay zk+{rivkz&Xlwsa=|EuJ{`O0;oP5nO)5IvE@VlX>*7gf+>AMLM==eQd+NXl=+gz$59 z@w*Z(sy8PXNn}ZwkUK@L@4ku#Jh}(H+<=tW=F&KSCCE`oy}|FMCSHlAqWfBradX~b z0+`1(r^g_W3b&V3QHF&RtMJm{R)#$40mzwNK)4?w{IJRSTiLU`3c_0Xwppk8#{Da+ z6XU?QBo4w@1y4f&q=U{U>K8Ad%IQGs4M6diX->aOp-Hclt)QnKDa4K*U*W>X3@WGa zNPvUZr<7F40u=8ba6}zvPXSX`4%nygLK0+Y7{#Li!y#8wh(|#OFpXe>LJB*_Szm}5 ztZ4^70z9#KWi^`GEoGo%j5)&!9%yiYZXa-Dg$BZ`JJTZ7q7|N%^3&!rrtolYvxXkc z0pgP!q{=LdfLD|4YOkhy&A?^GJAI+_T1iy&P&O<15<68eInX9)3?F}&FWg!tXTHbZ z>Ycui;v-;~RYxyuj{m{(N_wg4QH5FSX%_#uQM7O!ww*kYCv%^LfR%}HAl!SQb~MTz zW@6OG#T}O`fjkb!_4j2b%{U*O9=iFEW;g2fk0C@lYX(mPI=Q7?l^LSyA^Sz&Xow-v z;a49;Rn|0Jfxxp>WQv)wIwU`>X+Eh)6A(6Xl540PtCykIa;Yyt&b(Vb*c$hqoE_X7 zPv!X|*}c$RU9dODFXT{bzLb}CpEb*`<1VsT*>Li=wqT7M&0K1l1%SsW_do?efykn$ zxNiy+brfWbycL)jwVXiDeert2Y^Bz2S84Sex!Eql;_B|aSuMU{%`ovI|MB(4xHIs7 z4PL0cbZ)o&eg8X}t0mNIHKX5C38E&pwC^N~tdgS3j6iB%Womv$dh@Z54qlJbW#XXLQ^7`urRi8#8w{@Y zp!>tJ*7FheI=eYGm#MW!HwF}7$X|ANYFN<4p{JzW^zZ?!J@dJd-OrUQ7bGsnf5z&S z+pk~|0~HF+Jwk0n4&9%A#s^k`b>VekT-dSe97B{9ghw}M7T9HgE;)(iMyK%ARVs^; z$Yieb6c%kmQYlqO>XA`)O?~}JcLg7VtTD>QxE{t|nX|oUey*&jSkAWZdYU&7!635U z{2#4Y+i=>LqYINGu6u-v}c;UhAlxj{80Sp=vPzI!m3vCe|zVt1F!MpU5_GTz6g}yCj&VFh7)W0?*gx!c?z7JclIrm z{ZmeQ&`b$LILJc-7?R~5=nn;PsrRu6Y%;Az4f$RS(^N)omlqXDA0yW;>Ua`bK?!AL zWut8)a`N&orezbGU!{mIO7y|r^}2cJzGxmqj*M4p1K@RBDN+uZyUMcbsi22v>;4x4 zOy6!yDh(T?5w+5naQuS7Oa(#HIG}PBhN4dbeu~IvWl@6S6eIj6E33`48HCKJ?x`$D zDsCkReKBz+Ab0oogDH$9>eH0_TqgIV4`KwDa@x z3#d@<@9fx+&yV}oH#A%!Ct71N)+NQH?Nbh(hy-Rzh_EN`i8bro0DSU1yT6_Su$yV}oM1~OlS{$aaQM0xDKYz7 zb@KN<9P6;6Z{BQqw*0nh#d+bliZ_l*gaEk+4=`7IFzJaQX8(0EqYgc+x1{n%szqT8 zEbBpkqb^y?a?BOK(b(Cu^VlDavgm_oT_@h-7^0={8aACqu0`guxf{YrkN^9rM&bj+ zT~Mk1eY-^F#(ar+rs99$D+`DRdAwhA!(Kk7x;%KJ_Vn)c*T-q)I=5Y=S8p8N;81{Q zGK>O|$cC%#l?O`aR+I*-iA!?|g~0^svzD$u)Jq~F#$)P{+4@8kY$LUWr33>_0-v{G zG6b}jcS(dwG8K*39wTE?UN-yq#e&M+(F=4!+~^s9u5rmE+=v1*C0_9laOMb6+AmbY zx9;5Wv0bD@+cG}}>sr9-h_l1#A7;j?e=qa&2#dnA&L4Nq>$yf^FYcb%Ow|)3rKwTX zxhsVVE!PKAO~lL1BhtcnQo@RSk+e+ZvzHu3?JtiPoFyF{ z(;qc<7`#y>K%_rE(L3^Daw!fz9U|qat=oC%wF}>h@zY}(-0D4ft=F>WT6Z##c$Sc* zUvjpt(fu?RU@dIUD{P8(Qm(E&$mPi#mVl1V?Kp9UIsE-P#WQdvP9#+zP)+QK%H!u0 zC8c0x-!|^|#6(a|uzn-X(~Fac8H5NeK>kPQ^t9IF#Q^EAWsphQ3%mGK5<#YoS#bVQ z|4$i+FHXd%I7x<)=d1ghAK@f!Ty10ym?S_qm$M9acIsg=;N+r*awA<~ge`~tg`pNk zBBh{%Br=6GB}W)UN=&$Gd~isg%wgIL?1EP;*{#8{2P1cBh$jfbi1pfF={3dABqD zS#1dmD4sPt%sO6*YTAmA@;}oOVfmG6tt>{!i`J75otGoJi09hqzQD0gN2KLdm&G|aTz7*W3)J~AzTqZ7k_wuAo2pXP7&VTcZ!hWrkv)${o#9duI z%g@)-Idq2nsmcB6zVnuD^PwbtneIA_;rGe( z8#!#-tn0Ck#zeDk%{(p1V|K*SQ#Gu7qp``~_-uMKjt)sb#5phyJ>{JB#gVsO!3-}U zOGFcI{`gb*t-2c9ETHcfn;7}?#_YW5HhXaCjb`3Lav;y7yR8YG1|yo>JCgdEi&P)h zc#aB=JCgosWcseV|IyU2S*iJvV_9__hf_79S1n)mWXd>c{XqgVBf6fhYL4D7O1PZe z=l{9aGk0~?>kGpqbotYH<6Ec-9hxj`-JLfKO8IuKFcdN^J;r97Xu11|;QJ#YW&SX0 zk+Vj?%X#XBS-Dhc`7~H>&47PG z$FtM*!4<;0j8V#>ddi+ChF_H!UW!}c&v}8a-p&3ghkJkA<5UWTDYgDZBdzPj)&BlC zX0y+$uU7nPkzXXwIX^pI3@P0~MX<@vtJ@=>Gqxvwb1sSr9i^wuhiq>NSXI2)ed6)i zT3q<8>kqL?qXv13s9+!!qlrx{n6)*EHdVCsY2M_=H`0d$npji1FpWirrAD(S(RXfB zX!`Xod5;H`$$UTpMe1{e_Pw884srIsQHaF;ci7i6BIIjtkpT4LOQNTV!aH=Yf;gl&3Hm9a{=etLWFOg$Ad7Bd$($UM&y|DXzeTbjHWYirPdz_5lo9xq;7FqgIuj4BL|U$CMi%Z z;~Rsg1~s^*gx_zU#{K!`fYEWG4UqGrHr%5;EXB7d|4K7xOucv7_~9f{{KYE;o}365 z77jktUC1uk>vrqhMlP8mBcN8u1J~poVk5YS;1biy z*4?XNPyE^Qpw4~zxJ7HCY1wO~DcT1OBh3WuL=ZOGv94kulAcD#SMdpO8hOCXC7SGe zzC-o?bQ!HL@+1LY#<#$4@UMF5Pl`9B06gyG>x%S7Me-sy)fa8A(zz*{&S0OTcFcEu zP3Iq^mxU=j`V3vxx@x5{Q(G(8?aUd6J}c30x3N2qbGb;SwC?E2U0O=&gHt?sdS_44eB}vOB1+J4 z*_-#P;P=2|PO}7J(vut|$yVyk@6Umer-Oyet4IVzt_<6M;@BbrEve9+%OSLr-+pAnZp|jX;R#?a@p8JEepdU(?^j#x4*GB8ry9_JU zFSsUuUtObKz} z=hk#>4CI8n`*T3#c4nXa)<(cek@~~49aFAph70_J8hJY7zf3Aof49cP>N9Rl@fnff z7XMXv%Vu#qUudaD?dxe@Ja2P;zEV(BPa-$KXjj);sqTKZ!qHg~MPm?(wTA3ILVk$* zvD<#2qc5nhr~27>L825B+ZaqBOb{^r5-Dpu5Y%qW>8W2b5K&@4{>cNuYd75ob?61k z3qRU<)JAFU?l>o#jr=YTS8!z_euhsNeP!J&Xf60_rt4$G02Zmzn#Ie{xzr*`U)_ue zVoxa4_d`Ks@+;T5ybk@wHfvu#IU(evQ3q2QLx1@)6e8yb=4evSFnS(U8t&RYcOdnU zD)|!BCP7b4G+-PvF-+Q3g5i0&!TWM{m}PEdq#68zqO^%BrAv3zbEF=qF!?MtJ@iiT zv4DzWv^`56L_JLI5UH?dNzsQo$Llxo?(VyOyhww!lDGgL3`t$_iTn0!6=!JhH?KqY zUOa}p3De2pN>s#U9LMF!nmSzT8v&88$8l*tDf^qmw3QL3hg=E-&kTm2MNnJQ_s6@7 zv$gl@X3LGXO5X|-3?k_6q7p1Wzn|~BFNap}NB9`cNaG)G`2Z>>D!=PTD1_A4b%d*0 zf4vqvr^3tDgP)h>2Zs2#TeJ75%tCXbhCMze4vkFo9X#Rowua(n*q4*GM<1`1akqQ@ ztTt@)JpHZ>_tR^7oGo(>^7t{WT0JLmz_}nTl-1>Pvf><^cFO9m`j<(N2paJxx6^@R zNtt&qjnTi8xSZ1mTy91|)g}G1Kt&9o2gzT?r&mFpaco)kI*YBznqldS^qx^D?9a4a*A}b6r6OtK@gL%P zHZ~tje?p+ybr zmoSPD80vxB1j)08c3^=Z!oR_b`mLrPNR`b0Jjc=4V%QhKN*IiKXVRw-_siT1319y6 zM7b6!;y{Vqh`Y>cDwGFJ#03?XOpdMNtYFdJ3xFrm)>x$My&%O0>9>(-&(}<%!5!sZ)AZHHXmPM{%V$)+ zTML0IgvQ>$g8Rayu&Vz+o+X$(15%*c-1U-5vRE|NM$1BnMx8&!Za%-Eiun*4Sr|}O zje+`vJY~t3EOvISbf6ZIsp0YNGTy#57L?3;cD(h>UyS4fw{Ey(CC0ZQNaIjK(fgWeo26#v zm>71=cUln`q`ja1VijV;Jf1?cJ$z3Wd=^RbK@Dk{I}q9-;L6d}(b?#1S(gPTFFDCX zzi{PZpnQg{X-L{Pxd}+Kz{3uo`X+{XCWv@sGM2}F z?}h>EK|w3yV7Rdox{3!=$$2|v>d!ZEkHOy@DsF${S`E;|+&KrG)QDJ?Q-d>t;$Z-}u?^;=%#jSHQ zrtYIpTSdg1XTf}wMdE%?W^9nKAoP?r+&m80){i_*j7~J0E{V>3*yeCdY}0O%Q}jaP zT)8~%LifEstSI4~Crv#E!fVxx`yBE;E3o+nU5;6u!eyt!8^7E!@YRqw=qC=-s>@oE z*N8)sHw}QT0qJp+KgG~?+J%25^-b2flcJWW5=3|h3iEcJAu=>=F@2XP-V*>$!=$mVJMv1Y@+TR2!ASd>`mOwooxO$yDYz# zC99&1Bk{!wH`O+4&FpM!#eCmmEfaX4l3-J}x718&EP1ls%oj4sIWG5Y!UstJr1<>D z!P3_n8nD{YT3Hv>L$UK8lmq&+C*U`Qn(t(_E0UK#g#HQuelz*AHl=*-wyLX}wq1c> zK5X6eAGHs4)Nsmk&I^5l|5)Ha&0*YS^bRbhd7s?cP>vHX#lReb-zdUlEg z*N5-t-$;XV+>Xj`2e^Zx6LLk(&YAPQ>s~zKNZcmLTtZgUd4s--Jzk{iAse1+^T!@^ z=&vMtJ`sW{+9rv+N^dzypr|1lM9Mju}A{@2f5A}&)#v}tdIPZ;#u z3x0=sA{{n#c+wd(5kS7pP+SkGA+y0?i!>u*WF?reue^0js3z&9mcV8D^yB{6lk($R z7tIG`l>deFIJ(oPvyrW(Og+fPfCEVIt=`tITtlr2Y0O7btDZ%}-b=2Q>?6C5KYJCe z$Jd6xwzP3KJB8M}V|JB+OBNdpzFulv_c)8x3N(HUPPcuzw{to|TZ^fPfvA9MnT#Ku zNy%C4>3&$(_w=W~hQhzkGHU0S&pE6Ug@N$oZ)nzBR;RXIc3OWNgq*oUuG(kwGSF)EApT_46rme2%=asRhXj8$BFT zNt`j%grZp^k;QJ2Crw>(wOR`T6HNxAB#CvlK1TF9nz&!XQ2T@Jx_|iGYBqSslA`MF z@^Asyak*Kiw#&hv3VMx#wU3ywBYu@2Z%oNE z1?1FF@bp~W8p31A9L%#;uBTJXs|Au{$*}O~LP$9D3;KnOgBq+6x&%=KbwJQCKd_TG z!2<7yxhePUpr8S~+4`b^b7ew-HXv*`l^OcI!w1uxY^8pO!VpA#3?Nfqya%&vlACp| z@^LU7Hu@6ADhJ7lSnarKXfXTw3V{B^T_2>F(l{9m2)^>SYb*NF{&G%W8vPLW%27%r zEop1Oz(|{BM8SGHGxB`qXdDUA3k9b#vED^k0QaC2V1m_z7}r_M?bLdgsQCqcPgw=> zgU`4~E!PB+9P?|KIp5}uSVkO_LQ1?LCp|WSPy0qJrBY_lKP@)FTwn8Kj$?puqMst5 z3etu>Q>NN?GgCU^%2pcilup$(fE`g57*G2xKZ1N+wXe~+tEc``tX%a-zeuxnq@lLX z+cXBs+h6oZ`=r#^U>kEA8WFBX={_oF2!7tqG7b36Rz_R;%5%4bPsE&g zsf{k#abROT6vp3oPi{{`{>1U;_faGI@vP+0RYOsl)J%ws4++-nLpc47A#=Bg`nJ!@ zI3adyEc}*DMY7jI|yhnO>DuVi>@E09h)@Gf1d|bA|Fp&e0 z0d%+gAGO;qlTzr1t^-@#mOm=xP2I}T6D_9Z18Gb^I37Nb5S?^;fP$1Ghpx4XQT44g(JpgQ$yci`N@2Nn5Vjlkd zwpMwviwP7`D7K3ISk(J$R(Ii`$iHI#l*etouJyLQ!u3=&sKN#-sXMo##MCct?Q+Pp-Y@ueP(Fyd~C*Y9dZS*sIX@!_byo z-q<||x+OqUdYLY{xV@A~%8m}Rm*ZUnXJ~8UQ?WSCZ!q^ZzRI0HAJex#I3%2ziS^S2 zQ+0JGQn5mE;gr9S>9`wDE#JF8IzJMoB3TQx*5mzKa#)s?ht~ggSrO`kJADc(NRYVTT;bZI0p& zi3-Y-g(u6nhqNs}`SzpxUjjakC@4$WaYngrS&SVdhiaNiU{X3uI}C;ZBUU@akRt{< z%t#q3%3F@YOkj?v>>5F`sytRKbD`KhF3HBLr@Ki#Y6Bg^BS7SWU0_Bc;HE6}E5UM#H z;#(#7J%1u7jG5L4PhH}^wiW%XU*={b`QcB(AWf_CI>=Iu2er+_zN?6T8O>dcfhF>9d ztemCXy*T;YMc0KCfoh*0c0yBZ&{c)+JZiRQTQhq#Re%y;)1xHy|nMTCt@tnGu-AC#Z$NgPdgy7R@AXMJ2~ex0Xv&yM~s16vj9T7pvQcIzKOo`jB@v-veFf=bfa|MJL*H4=x5aZWuX%nL7F@Oh-Ka z`A zxXKJciGiw66mV*NqdxxS!n0(CoxMiM*ybmmpv{*=8EJM*N<~=#jc$bfDBHO5`GHUA zcm@5T7?|_|-hXmiG~c}~XfGj>H{_tyJ0_|uE~r#Var;@HyF4I-o|s9aX#Q z@$FTM|FAiE4O%8B=-Yu!IoFql6|wI?^pn5P|_S6MJ~8 zV-znJn{hyv4|1+9nJd4(6$A$<+m)UoHaX2zJrb2?ZJ#!zsI&)ikY?is`qq!Rhbw4wzI*> zkol?~;HmPoH+rS?cic^&U&4X4NQE2+i7I{x>8^Rk6RL%`(pB7LBOCI8$Vb(t-P@n1DQW1@D@gD zFF}o|h2D}kGCbT@hYV?de&ZAi`~4F?p(^cd9{bdX*+I_3g9VzA$hQ^H@J^;=Wlv^> zCio{dqAsdp&1UJOV7=(tu9tV5%XH#pgs>|8#E@Qws-)L+3CiKD8`SXD04{g3q~i_KC~!g8+Fj+R~qewXQQvCe9_-q zkZ9xV%*=g0p%?UUY?8kE|7bePs3_mJYbz;IiqbI%1A?@4OP7Fj42?*4*PwKFr*wA= z-Q8V7cSv`?_wWC#_X}$l9~fZ4eO>3?``kx-FzYCvlGjjP7O;dV{iaNM075ZG4nwB; z)R8rmyo98Mwus|gRowpU>DNB_Y5#lI{<)9nW^j_Y<}y8 zZ9Jx*6$~Ljmna-TlTE$ul$ELGYVBfWai`Uf=Dc8YM^_+X_4-Hy8-PeH;ZD~~)CiQw~o zY1+gBkQzgDm8Pd*Dm!f_e^4(=ca`M$Rq*x7o{p@~{@IVM4_A*$(|>&VxQ1}>{BUyO z=frOl)%dBGV-m#3m+pDJ0F>ARfvWENtN&`?yCjMeEP$&Sv^>s==G)n#W1tl>ZLu76 zu(K+Cq~V1pOu^Z=W#i89OC`A2^cNkWX2yE6O1(ZmndjO`{RLB7U-r!t=8NYOuE)#K zoO**r(pJcxq8&6Oo`BB+d`-rV$IacKiJQ=TXT0XaG)iU6$Zubq$t)g95d3t#?0{0O;b;BqLCdb?g4F!Wr0uu7Z-WD4Z-cdR?}lp z0&}`wgb~FT?*Ud`h*#S+6Q9RROa03+@7XxN^Ja(paksrZzwe!WUPzgla!cHHZX)}p zyT{`?YU25VgnF$(;bq)z3VYt~uso7NVsxrklJh(tj5kUj!M|+;Dt@9L{(BUSMn)Si zZ+mVOVBUKASXvnw+htecBWXF;IUBe5ywm<@;e$=(D%i)dC)xfCP_`><)`jC1R_0g) zyO5055x7XDK7lnWvUy{~3IPr7GNm+-s`JDx{D zW2u3P2)`O*?F!A$_TbY@vV18pypA#zvVwu3Az|C>yFx~apA`fMeJ&4Zql&5Ci57Dl z0Z9-RuB#IC|DresM&|&W@xk;h~jb~65cy_k%AxD zGisZ9zadC>xufHhNATR6FvTMEZ9^Z9cKxDnx3VMnR?7l*zytZ-_FL~I$bteuo*(B{ zZ4jaE%Z^;zHB-&gBR<=%UM~O)e#1Y-s#C)*qu>4cf~o$MSL>4#AN|dv`$-Ed;UWL^ ziIC*l=Xi_!tCaIWla^I)2V7i*q!-w~WJbExdcMPwQg&xfxOa5bn_0_(nMNm$#;e8K zMti_JLORKH#^Y!`0bai#CTKemmep^(WvX%g&wohJg*LSQ*a3nqr)@|lQYrtL*Ii?z z9v2B*|0=p{I*{=TRyX#tBW8(bJ`l0MErrf8N3QM192l|QIc4^CWHwYfZ96Ed;JIa% zN{AVK9DB4M5kEfLRoh(8SKH{Bn>85Z%q=KctYYCew-Re{`!!bjqH3k2-q=jU)Y6JK z*3yV#?OE~q1gid9?WGAzzPW-(DL>&T&@qug7`6gdxy6D1WW%qrw~I`Q+x813^kfvz z6ZpOn?*eSxs z!9=aQxxu~?NbxcK9Ivy4Q;!WDBcdAotyezPdVC1uY#tBqs5-|PrlmaZN z76H;qs~BWqDSc$&kUmmB^X?behtbXlZ2mvN8za^%Dq4`R^4aqLXhK>9TjTkxGSxdg zk~)}L4w;TXo7>+WLb4?1nJO`tmm{zBGt`sL!}8|efX)D{9Z26kz1EgAX3%<^?6I8% z?M_@&n+5G&(}CA(4#!_p24H_Xal)01U=SNuqnyKFkO${Z_BdvMYAczgi@sJA(I8%^ z`k!`DfbvGeHXo1$hPB^!H*T;|ZHhLCg*kOk3oRUOrT(bVYbGe|3}JQ?b;bbd)(r7B z*U@F(r>sVPp-1~fKWA?#Tbh%C#XNFL74eK@ zU#4`r=44uoq41~C?w3zORmtZE?=E-3rXhQ$LX>GC#CGkIUP=8AIQk z$3r6s-Q~OOKn3k}3HL_vb-EY%@`ZhK92a%#Vxz+sYLnfJnxidki>wjOdc!d90R$P< zEA)hf<*xhEKbTMWK_T)$ZHuEy?RD5D(?_`&rvg-w2Igb~Xj>>?+GhSv&5q67(=Zi zMfDwH7t58sz7U02edK@XMw_&Wo z?2DgWhDS$*GM*7_Z!7aR0QON26qO_}z7#U#`tGTpAeDCWM7O*-5I@}&M_2w1V+PlV zBBrJsw+cnGEpw)XntTCgQ|6hwj$r4;R@O02v@)k3?b+%L0FsL5GI`P8i)}(#pMQ(A z!Tx4YOaG16SB`9OTfai^jCdDK`AElLr`E7Wy59+Y-X@$II;>98n^jAw4x!&yX|6+% zR>ufZLg$$jAT@5*v%u8MXX;rIX*4)p6QZEsC1b@_WW0{_Wf2bE3%C~hX6IxeBdAg| zAaAZa+y$LJI*exU7g*Vm%Cb;vO!}R5%Ra3}Su zF0g0ma35Six7vigJMj5NEPwc9#rv)LaH@FSa3*zBQoE~=z^L=)#SYgWJ7>h5G z{nTdUyjA;e2T-e%QB!&AF`@Z#X*gpXDV-5tZ%&hh+MrLDFnZEbPms&nAFkb0dmG@G z+P9Bn=t*;4DLk4=*0-`^1Z>i5rsc=0a<419e_S?A)4ERwYI_se5*q@M=NV3mrpfVd zS0Hs}GjIQ+UK=E%phZrvuD(1wGf|^y;^vhpUiGZr8K*ho>3E!pG0pYf!dIW`6u29K zudrDMw^9meko^-cYq8Mk`7mqmd4H+USE{YV0uU1&_9w+2IuoQ)I{ol<3h-j2`YZIj zELtENqk=CU@pqJZ#YrlK0>v_YOgZ=p5H<5iL_M!3FRz$qIpEEqpe>vWq4>6hR zXnvJDn%h~5k{~PG4piFa^|U`~KJ7%;vGQRZ<6~8zcKlA_wwGDIo9>?Mp%L;VaMt~S z#ks7~MXs}?HIi}-9an)qPKQGbA@&DF)x){BwWa9TG z7`ZGkZxQEKZZ8;g9@?iEaezHi&UpIU?u#RrQ&$fm1=7|uouckUBf6rN*gT;j_CocF zpBG4}C%2vqd#Ei5Q=+%4b#yH0vyah^?9x zcF6>$y^eHWIyKHWpMgTTz5zu5TDk0JcVbzi-xY8u5|n`;xSiE`?H!_o*@2uS>uJn( z{p(WnE_`0W8pV##;T+GRuyX4Gbn4ZY>Yo68`8@ozVNSJ~W3Zj->T>feaRvaX+wsev z;UShptN3L?8q49jTGPmLdF^0X4pl`-f3#afpm4swe^C4(T)P6EE@C^L*%!!5f{1b) zH2ja`i0&{qn;l0JT}C+$fsr((zVpzle~rJwID=#hHGz`<#~+(OQFKbs7zb(Tu=0$N z-rYT$2Y)q6OzYC`u{LcV>sH;c^8E6yE$g?;`-h6(leYUxa+B1RV#6ENf5%A@FZqkp zA(blT_-*#Lo7D`c`<$VM&!U=H^bkEOx*CyDEC~0dh}!6EH0$|F;b4C614qNx_vYF7 zDSLb-)@vMUj>cajUeABXz7c%am+C+*$G>Zk>NLt^yEKq*_~L`rkuKtY5KrKG$MC)e z9%hPoSuqNh%J~%PLankL^+tf?^Fp8~Q8WYBvnx=D2*wxSqkiurfg`xr`g9E$PUna0 za(KH2O&^9m_m&B|x28z1ezbtDv}qKx#Kytd&OUMDQ__G+&m#Lf9sB{Q&aysdKF9u1 zMMd?m>b;d-Z$?c{_$p(KOO9MGXaJid%#&Ff<|!EsQXXO%RR0tD{VsiYRB?fp4mAEX zgNjkX*#QIMjb*geLI>Jdgxb7M+`@ z7ploj1AP_t{~(heBL1<$w9MXK^{{5Mg6$>YPDhnviBGn@uK1g$hH~GUu+rW|@f3e4 zt}wf^^Eh7@Z9ct>aoKIN*1HU@1I5G%4yRlPywBmp~T3=^C)qJ>zx@hQSL@a%C2*TOlQdr)Z)YAH!XtR4q#qG^D zl01Zy_>yRL01-FOEQ{fEgtWRGoM;ml>8m9-Q>0qr52TX@34{R(g3r+4srW_G`vI7&o5#x# zaoAJPNkW#A57QrxyW-TebCC!EV$bYG^bn(rg(1J?f%4-a*$zp!CDq z_Ltf@yll^U_VyTJk1XaNE>&dOgtRUF?o$xAaTSI&egw^}Xa&!Vh1Npg5WVme%wQOfKfYj^`1q5+^Aw`q7&73<+*D0%y;_%%TV%WqE$MECP zW7F!BTo4!{va|59tnJzDU(-pe%k6r=hcRncLCHH>x~b=rmuLA+w7jzi%d3MKo$piR zEPw3IpQ&({dJ}vd55B1A0z4+*sU-+3O>l|m&Tn~|iJa;*>2vc~rMO&-a2f(BEtj1n z?R=EDjiPP`+NGgMb$IY@cWGP(C zENPlW$Q-JsI*s66ZfC5=xtz59lweY?+R30P`F5ScgNp>n_F{>j zc+reD-I^_3_VL=@SzC2Kqml+QE;mx{?NWUGp`+;?Hm+M(ln8jV^Y!$L9_@L4b6}R;cs$A-tSViFe-7(x#QbGCdPZ`7tR% zNBd&D+S$6Cl(7}@y=kH$Ge3j&))}EW$PQfT*G-bg;^mq6OyEv8j9wFKZnJmVVso#t zyPkY#)sEZNK$aiu^{6jV#CtZ)YO{~4wh7~0@z&L{qr&3ZqH#D{fm~Xw#41&k##Sq~ zX)tvoB4;ITY^&;lRZhbMTF=J(Uh@cG>>|2FLvGs>v7Z}WeHRQO;OnFBLv6lHf#%g5 z`B`cmaGAZCf%sfb*Zc2VM9h7G|9S#@p1l?TnOtNtq6x=FVb3mn7UM1OqR`%AFMwgNu`r}9g`6&@8iZ8#4}+|6PveP&j3-djnXvO@^R)F z>_Tnxs2GMxH%NBE^l1fmSr1asss4QiVO5udtJy?F_}>@qc2KBzK@b@o)U{(AdM@OL zB&OL(LDEWX|32X37g&c=9k|5RCnsxKrr=o8t9VB0Nkk7EyJPiA<)`^gjkUh=@yC#` zl55rUqm8w{9#PZX=rPXdor>W1CR~-jlJww1Onuet4mv7MebYwONEJm86N=w=qJ15e z^HJcD`gN{!FS2}Uw6;eL*S3hbDxNq7X<%ymTi+)!yL72>%ClbH^jndyUAinbXaT_ThLv^)i|3;c1;b~6Tbrux^ zYrw6cQ9oL_SO(eM-fDUIwaP;tWr&!|mdaQgfq_Ex6}}YPw1xpqU-hye0+!bWXRfP zmv-0Siccic>a8GNxr84KF!8-ZSTH+E^Z!{--GK3WF!ZV`$qBI5aM%8bNVbC zv`6~t)yt)nsE~3PM0P^@Rma_Vr345dzY7$sGl;E1pK##ND3e?K2GH(}FY<1P{Ac-I z!w9}Cedubc%cRu7Y7#kZv2%vN!Dz+IZ{C@rZ?|1*Qp3j5Zt*553K zs#EB{-7)&*VqfAO8Tl`|o#vfI(}(kaStXrY4v0gf&w9cJl%%IOM*g{i;|KYFpc_`2 z8~ebMosOTUtQdAq+puNoD@8j--rFeZ4|I4qwY$?Ky=uTJ<~nWTY6x7Rfm!rn+H{4jj4+b$5!RDw^+u)7c>Z?%?jvi8lDRg z+`t%eqCnhfl`wb$8r@Y*2WD<1G^rRXxJWrKw;#e+_&?Ii_%QI7*NtL>R^OeBkqy2}6U$ zTW}6rES$%@Bfv0UzscQrLg_}khu@T#CNkMsQL$e*fA&RLQmkZMBYs~ zkztpYb9%MeTO-M*OjR$*_UosBW(Y}l-ipK0`@Q3q-2R?H_7oR_D%Nks>>+$~T%yIZ zrTn@$8X6h|&TD@TcCpXYwgVgt6Zy?m4Kls4Z~9z9Uh|@(hJnhlF`UF~-Zy=7NC{5o zcc=b-XZ0V|D0NrH8;L}~Wkhq0GqJW(^)v85%WDD=|7(|!PxCI6=n zj;#}tLnRL`M(~tRLN{WYVzvE6WPExidJFwr)5)vHoqLGQ60LF8>T%6lWIj^b!2!`n zD|H}n;28mXx%dJQ&~?uyStBwl^jfB=ytF=EA8@SAUuHX(lkKgrpf6-%zPbI7)g14~8s>j?*3KfuRI*s7k>?F3mZ&2H;sV;9P z+|>=R?bC`_O5bfyV1GA}7-2rq7&wv?9x{KKgDO2vosS{nkEI$^WAOS!X3yiiugCH_ zWitRyG672PC=8iSWo@XJ?fd%u5J<3x3+{i^a@wBZ0&3wWveiI8x3^3@r}3|(?7Vd! z?*O(XZfeXZ7xCwGC&v3D4oSzd-7YJM>fyy<_n)`Z#=&$rati0^fHKz(KfR z<wbfHzc%(O7y`D8`9UFN1V zHe|&^@COGg)g#49zt-e%Sl_8bPg-wWe^LharX_?dO@YX{dI_kA~R>*ZkV9sV@K#E`)4)6e%rl@TPTYtXsK}R zT0DRhT90o=)QtK)R0SK{oU4-{=a9Y?B56TTZuH}AuFKYRu)%ax|$ z)Kqtd365tY#KUGfr@;^*bDoeGz6IvAG4K%OKS9yqZaVZb!ssGmG-s z`Y@^irafN?vvfZERi~Lv#UY@y{qz<8?r10+{&r{ARU*fP0<}+REp}-GQ)<^o(9Dr8RD_V(Dv3 ztk}}bO@5k6c1vr9`Xl^~lird2$jwM5p?45rl68I)!>TC_wpr_t-a(DD90Qp}(>DIzV0S!~N}Pw*zLO5&2A@X$j{m~TVlqz7_k6qQ0%*_t z=uJD$J*BXfBGojLh5;bYrmxo5TV3^kW(dyGMdA)U+Df~Q-2j!D+*M`(*<^iQdx{#x z6(*m1_7T9H7>VGDXLy{x;AC=h8j_6EQ?)P{^K5!jhK&-Mta6lKYX9JEOkk zJw8QB=MuL)U&g|&hw+~fzRljS3*jcR*86jru>>R-)jSR}=*B=E8Me6Iut+Al!9vfl z>cXc!&eJi(`9kQ(4zE+0hBylbVh*XgWQHk_hUpm@J$ddrvkh0#!&0RsfW+H)rjjm+ z(=hE`8~huoQVmH=R8m;#65hS%P^l)+wNhcyq2P2=;{`3$!X9Dc@duQ zXIBnYD}OylBxSkY$tK0U+~_2n;t>@3krHQ{B57+{Oj2XJKx9ps<=(f*qzO$@ zS)qOAQO9)OGSbt);%vyQ!T2!}PECFZ{0`1N)M_TBW|+LZVl&{`mAcdRxmzDH zo26?F?*5h$j9kc=gPV1?#6|5!TS~y%NeEH|Nr`_p2lry#He7c^)cj4Cfi!3X4G74r z4ON5ktdu~N>~8QV9y#P)v00h4vr@Cce%sF0({(;6W{+<`VRGq3V(yc*CLZ1Arlk0& zAeIME;0JkLOwaqPDb$5jR+po=N$J^OBSrG?_48$y^L^uun(DE*O%1Lc-V_~GzQPQTXzHWgtPVT(mFKnc37((f)WMF&=$`SXw zhJB+qy_lKbHpOh*%YKs=jgyu(g$Y5;HK#W49KaW+L^42IAMZaF2l{YPRhf50cz ze7?=UNXDDTg2z#&{V1Qq?_?z{aQ_2`j`9-D$1<%j&J&IhV_AJ6(+jJV!6R{EZ}bRA z6-^JU#8iU?H`ND!IOD_*`aDl~vyUxs`WweO-Rrm^tS)L^@$z69elg&AyVQ_wZFs7= zd##MrCg^s3ko%nWS|=f%rsk(W>FPXT$z5dBCwoz^3wU_j;oA^cIMQN+$mF1stnAaO z-@?M{f3r;J**AlI8lPbjFDpq-c<}uSCMQ4~$2WBcw+8M+PDaMmrGBPpJ>k z=PuJ9ue$cUS{;t{!X)b0EXtM7Je@k)=C zLr;@RvaWCtqLY3X;4D`_uPl^fsYVhxInV7eUkA9KaH0r&tNodrzC4nW!rx@PXS;o% z$&R-24mWN|v-`HXh4T}!$V1%#C(o>P{v5xPp5|{)@hF)*ES46Ct)m_ zz9z#I*j~yI8+cJ~d%&CgbSJ{2sLoZfr_bW>=fC@17<5$agv=)1{^`tA<{K$! zDiAl-tL@Cc^{lQ`U0b773Y~3g#T8_ZM}IC1!M18T@1T@-&Frnr%1T<{OVBs%`$hAy z_xGPJ+m3QCpN9-Lq695R{`;dkREqZ^HrtEtfCs1rB4*z01D&pTz4-B3zaUz*JWKPv zbU!5uKJec1(Q!2X{m3c99ESbGrCB>HWaY;Gc=i?=bSPZCbED;`{ib+!F0(#IdXhpC zJ%HtB`5D(~f5=4U;c+xA&7JzMO_awDjGSG}Z}mOQ-5am9SBgR+pAnIAD50Y3Ate&| zP79LqWBO>ed5k#fX6A;GQUWBSE!2E-d!T3C};AAV}eX^!F^V?#jT1 zY5oxZslzqN&W_~|^x6mVYH|!(DX&Fd@$}ORfo%QH$gL9Ddz+G5PX+#)*W8^6 z_oPxuL@`5`+-sb(kp+g)tlVQtC+0)1h6mAh%;CPDa2yg7LR$E$_|kgv92(gx zcr4X*i^`OyXs`h#1v@rH0w*mogQsS*)4Pf_H9pF!j!pWHX=gb0lnyh2Y9|?*XGsQR zK3B%o>PTFMi}IS#$54(7?Q@0`O1R)Q8;R#*5Z85%l1(r7?xB-PUxtT2$ykSNe(Im6 z-Y|UEsv4+e7FwJFRywwoNH0g62W3=an9elbxlAfZo2OPp{IBvT9Rs8%Hb-I-#4vGs zsXYCYJpZY+fAEkxf#W2gx#9aEa|U0X$pRLo1jw&Ng47?cbdiGSBD;#m8`qq!qO3yo z;PWRr(fEe2C9+Y5Kvl}$I5nnmen3Vx+n&A z+2ppBz_C4(>mf^bX#ONHaoD`ZZK}-BcQh zDzb@#cTU!{Ul*&EEtzB%ax?Er+zDKkOj^)Ywe;9{->9Y_lqP75XLXGt^aw9_w|`kTw@kmz*3|1yUvTrfQu@RT2iaG$)0b(k+& z6wZ+OOGf{s4PI-W-$#l(>kR17g&AWdQV8;52Q9aG?e3P|Hx(nu;h!ET=u4}{lNAmB zBCBZjf}gKpZ8HzD71@=n_sax|Uij=wI-#>(F3S@J)F(5y@bJb>RcjBHKXZY#SU+vY z0J=?`DUi5vH6Z5F>|Q5Ag#~YNs25uPw=wZAxZnlc|KBRbx-oX^cE=GiwQRDll03i4 zrVHgz3*6P-yaOg+1>^~@>@&8M*>)pdqXsC`Yed#G*RcN3HYan+%jblK7{W3(i1(M9 zh!Et;t$LGR;~U~JEX==^V~+HA^+RFdQdmq*^?cpTRKuR$I2=`M-ie*Q9|`u@zpDXF-m z(!sf)h%fp^VA||<2lz$7f?dfJh3q;$L zig>@=?fBzIwWYNWCsJRdW8vC{wWc^qIQKqVs>A)l9^8xk>({SWJb^uw1tlesENw_Y zqJp5D?*{4Fp^N>t4N}&D4{Gt*@ScedxDXvgU_6w!^oBOppCO6V%*TcQF2|`f3G1~N z*u+Djmqur1cN8k2E9meSwvxw{h*)XTzZH=9>j*zqM0`=yH}Fu5STO2G^`gNyy?YX) zi2e-L`4Zm!yU_$AQ;$T$w6=c;ZP0O9<9wVaoK_cq-8Jwt8IqkshW*D~6`-0W42$sV z8pl`DeT{kZ)h7TrRhtuKp%75G>JipQ){O1ddgolf8!ou9ZA{i7GsYL(2dXE&S-nzQ z^14|)n{8WdAH*F}kfmd?!@4Hn``B`Sd1J=GUoFXR?H@_rd8!+pYA=~(fX0XwQ(_>+ z;Ss|wl=ZH!Asi|6zrHYj)h|TEAUw$V8uO<)j^Eq#8h(FQq`v*#?2>QwltjSVHePiJ zpP$nT`s^wJa?599h~9Jk`h~4gafs8_@O5ARAX{A;pJvCtl>aKqV9NfB$=Ehvk2{mU8~-$JeEwhL47^3Q)BqurU{ z`p;HeVhnL@a5yfJaR&3~l2t*jztM!v%36e!v}=XUvQW|SVpHDmzwrt9=a-5B`s&SI zP(&l4U)hh7*~4@&wC86T^?ffwCCf1cqh?Nwyv}L|m&ZHcEg{`1^s3=9U(->}oD*mr zfBo!sLRo+Ha@^he5cXkN902d({kKkc4|o0-xK1gNsWf+N78VlU63?Lddta$dxOTcL zc?1NH&Yt^A)=~$a;h>-Oc&HMEKlv*+v z9>gx9sdSZAp6|?;4EWIPHm1peYK7i?DX#G6VC|%^s1-&7b^d?f#wk>~xOqIU82snM$?-ZxDL_0&-V-O`uj;+csjwke5GQ}xT;=#mtN=_IwR=Hks* z!thE`1EulS=t|3OlQF%dL-sb2Rke5;vKP}?iyep$H#H=fy_#37_dnsbkT zr>t0K%4A74ymvSX9EZqFex<4_BfkDjHBgQ%ACybC?ZGf6VBixch}B@JVwkNllrAa9 zg568p$p6E$Bj8OFCP{%6(EG#n@3hOdFU@(Q07zg42!U5U?gu{W92E7NEGkEMwCgVO zJs$&WI1eC?cTe{>bIdTj3hE-XFUBy=f;V~5b6@^C#inprYG%_I7oD`pPUqAt;uP3y ztE=|;$_w_4a4sunKLpe_{luEyfhH>6;Tg!PU%HRXMjrTVG<%dJo0H8>`^x6R`*7lr z`ywEhk@P#*-9=*YUkh28I8p75N85KnZ4vI)ZG>~$u8cY^8_?klIzy}s0k#-i#i2Fn z^)vIL_E8`~S+w-|@CV<94;0+{`VT?+r~OWvW6y&}8XA;f=?3<2Y_zk=z3E&|9tTpI zg}dLQsz2#sz7~xLd08OfOf5=hF2z%Wk7A}3IbeR7-m4Kfw?iQld9uVz0pBK1Uz5vh zuzWNSpu`?{Ju!YQnU*J8h3CBI&8Y4ECFxH*)35I--U%6AD1sh0wK$0e+fb@^#6R#c zs3lhj=ymE}fm$E%sJ$+7aX5m5gQH?oy#W$na%=5KF@kv2+=yn`frFH!j2M_aQu3Q( zFqP6f3?)?^5PbqR&H_hob=tLi_&A5yRc_eodp&IuVjNbQCaT{*$jsyXzD`-+_vKr@ zjf>ll`s;^BSse!npCsXs;#U60t4Tk}p{Z6ImWMr^&-fi(^7*%>@?VRN`M-JV{IrL; z!~fg|Mehp8Gef_3**6CmWlWXlO7j`9*%2l3)K0#g{)iv8cQG?mU2!&Z7#yE;q^GN7 zH8{u-nJ9uT@~ETlHX8GLbr{4TB1qSW~4`vZ2a-om7q zdaDJCsx%ib9ePr+ntqgrE@P@7cCjjBmzgcVd!M|J!DABMDN@l)_qM!Rl$o!i8xTvq zE-x``^mjRum68>5P28f*qnhydEfhuapu&+y=X#HHl^mpSh*{Yz{(+aAqb#W=ZVmF~h4WKOzZ&!j?v)MJDP==rl3aWW>^!N)Gz_(xR(G%breM z*rWEtnOckkF=gY!NmF_6$wl(g5o}p?v*nMY%+F_WpSez!K9Wtp1AnpJd$E3+SsW;1<&;R2FXYE7F$eqpz)cWa%OONBK@9@${e3 zBDRPHzfRJXu8UH(k^ABn%SejpK^2byXgwbYYBgZiOxj~-weh+Lw{RCx|U5u{iR+k(huN;2Bca2X5vQ9n0?)xSc ztAP(EZMqTHH(T+ir(M{GH^go3QY#y*&}(f=FbEy41Ai`E2a+Pim1LSJg_uAGMM2_+ zrQ;(&Lhj}V3RHI`BiAoF4l0;leej6t#F=_yenvx-%6h#ru4$*;FsW{}rNwhKtu*sL z|BWu&imvv5YOGucA{N)H^5*m4`-T9lhC@=Rkx*tI$vY!KUEjJFlke#V@LM zPTgIegI8N06xMzxK|pM*=)y9e4v778y9nZm`}i@7 ztL^;HcaaKO^U_^7NpAYNgL`{HZWtXcgOI+^>)BsM>j5XN?e_9~zQkp%NU$Xvs@8{d zrP#RGWK_qMs?59QVUK3@tM}QMuEuQGxFb8S^(;z2`Z$I^(>6soH49mcl%g0JwSsL- zqv*dInJhH&E;^HW|JBSX(3DXj5c(cgV~Z1E1C|=({P{^!A#h!|aG;(_p+PGJZG)4$ zpn2Dc9jr3W5^s*k;Go=}&wOC_@FQ*_t?ByP)URKM1+v7PYbi|B`n3Ws7v~i&Qss_? ztC7s-=N$UI(}EQ)?@QHhBUiwPgm&d0LPKIwcgA*LwXA=kN-b~SeZkJoDfvDJ78nM< z4tV-*hde+Yn*A8Mt7&8up)*#8l9EqdVZoEq>%VU%e965N#FzqwqmbQ^$3SuDUBaO} zIK)Ggy#{alXgSDDx70QAX=B9T8?Gf#9fMG%r0=0pCrSoM*J+nb1B5^uH!(=OS}tBp zgWwm>C@Y;g&BsaCp974Te~u^*>u}>NIlJixdpTiJU$(U>E`06%cMEc6ounlq1H0`@ zv`L$?gg+hz{ViYy>B=Vu0yT8#H_NWP$1P8IOHUbIYw7UkpqCX}^y8MJ)%wkNuZ?T3 zW#6VPm$4(*hE-70cHSZQ*lo%2P}Z(l=%VF%(!PIS!6dj2SItL!s2*uyZjvwD@5qah zIm#|ZN?gsG<*WSTn{MArGCG>WcVm(5)M{V*T_Qhyf?-LS8Uf z7kVoWD;gRZi2_In6eVM$oztt(&X|Ztd|f#Y)SHzvd5`mF-bB_5Z2ClA(inleSJ*4| z#MGYmWuX$8btB*C3cm($Q4QBHJI>+fer2ljCAkwY#jseE=KjM&6G(&zzN@>4&AAei z_1##k^D3Z|BoLH17CLEpI3_w7BRaShcXsT&8^zF^so~n_r)0@mgd8Ew1w37^f_78g z%kY)1+~(8&+pIAPLe*5=+QQqWLhuJ@uuUPqiDQb*rgh!h+JYy}-n$=ZS!Y{=a=DAr&=6 z!vEeNgi{f`=gn$mSocO}9ACYxaWX88O7%D&Fk82hnYA@lNW0rJ8Q98A&{0(6*1fHP z_|Kr=WSAfass^;aJiC{Mgu`pBFcWm#X#d+WZqtzLEM#(dk+m2*p_FN_M512VgfkS< zuRtFx0krih>+D-a?KfOC_no^pO9Dp$AZYuXu2-q2L`Vw6n`&kL+8PtChz*;nvfnr; zE>|6b{-?Wc4a7J?Eiu79Vyn6qn5p^JEm!eYg4_SM*Ykg9%UjT^8;x3WL%w8Fxgji| zd3uiD^p5(Cm#>Bs_t+Uqvh^z-u76+17yN#;?6*F+eh_%}Al31p{7^g_yVo@_;hsxL z=?VN<;xo{F9mJ6`MB~KM=1F3{`gCpCXY!Amt2S#`FmHD~C_#0723CE#*refd-ZOJ+ zv%yoMrG2Mr;-R(K>i2;-uE z2tTPulmOX>3eXRX4Rsy8++n9f4`@{$3(v<8<2GJ~)EgZNTcuh{rGHr=zk8|!32nQb z2zWOCSng3ggY~m>^%PA3(#W#M4NhW7+3G3H@t4r>e00d!4FIA9*;Ejj~ z3BVHc3AI)oBu`36szfJtLA+lLfNWIePGpueDleYBeJwvbGZyhAj*gSBqauFi2Pr zX#_hc;fAoh4IjhwT`l_c#q5i|caoCIk&|BrXLQb!^|HRWmuGn{ici7Z()YUwlR~%2 zt+u=F7b5to#_qnQJjqpIZf~@Fc}T?jNg)42E+qNBO4y%fI+l@W<|5Gver-iKYz+U# zP0RZbZ~bR-taaOCy;+}_5Fa1E{K;GaqEbU&t-q{Uds_4J450-NZzLm#sw$p7T~Hg1 z0)1z+7bucr)?E@lV@l>Emcf@=N~Kk2b`S0zQ7+~h+HUguy67YhOMo77$&pYFO8tOd zBlrF3=GEc#_$i8`U@H}+wOYj}d0$mkQNj;iv_&tDw7S`fSa*TNN;} z!GlC`@qfB+3A&Ln8ki`q&PnY3jH1XZD?%UE?hqQCqGJtri1Y`;2*e{AtEzB@lg}xi zofb4)o`WRLhPJHZ947ClJmC)h15S6lwwkHg)wk?lPUKg)akJ~qoN0Zg3 zM>!EWpj%#A&0qJj^;z=#u+l)r7V3%@V#Mup(n>KG>C_{%=n^?1&QbIkZ1xt%)prP^ zkFFQ74zdVoJ{{3LA!ie}X9v6YjsOaDBdU+AOU3JnuB`rCddcbG$mMQE&30isAzP(b zH90(RrP0j&&+2RN^SdEDC}g*`QJ{YSQ{}Pj@$N>;#1uvO73WrrJ!vI zGL4|wASH`gAS1WoTpTnuhP_#eUBz;jK%&w2J=Le{<#Xh3eOMv|3z%pEGV$LX)clBg z(Lhsa48fX>`1OVA-w(|M1x87w8o0-cwZ)p*4O+9V zGUV&_D9<|!M7L?fyYDB$nf#;GmGIT+xN538Eule;*8x;n7V@Hyn0#D7w&)RRle#x`@uS(P8<7uXge|=K;@zgxLv5@tArrTMA#=9o=6&CMb+WRXG z>q6ze&K`f4*&=S(Ucr4=r6-&V$#BGSg2Fnb$OOrUh3ohfk6`?>#?uyd$*QuyBk|y6 zrrDev8kfl`1`|6PSD1UqOzV)13g5&a%BtqVL?Vyl7db*sxn&LG)IY^QEAZ0G>dOI# zG!nzs65Tq0X)@&^ia+fOxOX2|>|)6Ohe-H*+qQ8&RBVy`@u{M7=Sdf3bv)$}(BBK7 zYm2(tge(>j{0EPEIXsPyC*j5AEp@_o%kN^X*LmqaQ6X1CDk7CYY^G9&wCt1wxtCTL zqI3sg2=n>Y4Q-dhfDqh2oUrL<0nbK~%-rc)1r= zbBQ695t{gF4qeJJ_%e1Sj`>=Yf`*3vo0KU*E5Vn{!oPW)i#bN5;L%$HiYirtTrW5A zOty{o3Y#Lqu#+LL_WQWYJ)r+j21kucmxjqGS1UGV@HJ0wOuraH z5Y^{JC%7971s=cngZ5>|NGzk8v5{}k7?;q4M*hw<+|mHzS`w+fF;cHgB_tU&v&9Ov z8%0ngD}NpBWRNq)1r-1tzA-_-QF4HDC;4k_JSv9k!Wx3(rZ%>arYepX+c`8&7Y!4? z+LKtkq_FuTNlwawmGc}G#mfN5Z|Rr2s6+xL{V2{Fsc3wOxRLDL@{-Zte!(FjGLhWx zra5~1`Y1jLi0_mw+=u-n(`=n!C=(U0YvaQ?e6KVwY?&KB((vp3gi~Mt{g1$e4CpI0 zZI`!guImFXI}=S6W<7l6*54a_r~ftvmJ~0Y%PCBtK+3ok8Q}s@RclqxcTI68 z`O`Zie7aqcvsu?Ck`&5X56+H;e;p5J&A4qLCv^9hM-Z_Fsc}2181Gtd4qC10Y6yW?^fqN zydTOP!L@_5UCviAQz~DyT&7SrrM6U|dqC?@_j{@YOF5nC!1Gs_3qP`S672gC%V&SF zRj@H|*Ahl^R^e$jY&1md^+lDk5N?iaz7pqwQ?@>Lua{4a+e*&G+LX9Ym;g2bNJBYM z*y&|P^2P`Q1iy~Swwmk^g8A}%=6A&Y?O2I_-)60~Nt2-(C&cnS7`7Ppvu(BrExT*W z7hBQ#diJ=?E;F8~=$~250a`jsCumKpDn9aR@1%s$ZQ`Kev=x(N**a5)Xo4eO>nMa{ z-29B>;6I9#?w@stVqvcTZOncZ&abT%5D8 zkk^difBI5x*M?S?vgSFw5sp zVjk(^E*fx4oc9A=x!Y0d^^&YG`=(+v1`rbtxqmvpxwE_+4KCg>5569^lFz<57=!8fM$Db!uni67q_GTO#Slh z$J280X|{#t$_~8v@U1tHp(E$X#4I04BC?|n6}x^SXQE#Pkr(QNySz37Xl*++aG&P1 z;V+4|V+5~~Pnb_fJ2p1W*88v++X7$tZ{KBkLVb9lmm!Tihkkj|F>ew2J*?Cc9T!T{ z+F}_4o&vmgcCd#Zdg<*;a*DTp^}fNRGn{=VW5^V+)0?w{LRtX&MIX3dzHL@ghAzrQ zyK$FfNpK|3RlsMm8_XJ)on36YHkQPYjX|>|qo+msE=;m@T+*9_PNC$(j<=*k9L;PR zJ6k=XVPJKr2(>s{%TD>=I9ZRQgsh}!_zuZt$WQ;RZqkpqQvo4GWj{=F6VQnAyF97? zEY0`-K>H5WPmt1FW4zd8c-GE1e!%gmdwC$`X57vBgJj+Q_leihn(ksqQ^24jmbI5T z*N8A#yX(r~LJ&kgl5YKBGX!CKNO)QiJFd0aSXLy^sduOTJQTz6`**3?cDnd#158Zb zyrlKSAjfJuD50PbYL6;nYa#sT%|UHH+;0B%O4YN~J__WUz{KwE?l3{6M@!A`Jn8Jd z`?%z_k0;!&B9GC(`dl#l)Bv6&UOB`~@KJV^wZbMu)_g&*8+czli)24(k(N3JS%rLm|81cPPV5`wO2qyvFYl9Ox-_Fg?llrS-yoCd z#Kh#>M$pf#Cu}PE;badZIv47^Vpz)LW+}ZUO-MXfDI`Q}5=0)VPgl+`v`lg7WJ60| zcthBfLWT0B^2^Vt40cJ>+FMJKp9C5z%JTbKk!3Od>X>dqil&ibUw<`+qiG0uj3<`t z)8#$S3F6hGfm46Gf+SvT!+y>3>wNSW!LXRGxvm>+YwUPM*EgnvhJN&TLA%@jXNYlmd14y+F?UBz$ zUrngZXi?)j5bCpY~ACd;(l|BQv7o2;sd*<<$^HX}od&8dAYE1eA%Dug+m~kobUUuf+eK9hf<(!rSi?c z&pL06*R-tA1L05<=eg;ZV}A&rpTNDmIa#dE4+g`WZa-WM5Yq;}cDz1U0(~x%oK&>5 z-9OzJggNVMAcwOs?P2#%M`?%acE)fI*DC=kA)lF?WZ$-@Ti)b{x*r@ z;?xG{jj$2!U?y`o?YRSj70gum*kbj+A;QDyogulvdjG4PZO~_xR&du2fthL^jHjqL zV}F^JvXP1{5CL{${;kyFvHGC$xZrl2pFrR!>qCGq4F| zqw^bmdECyEt`rfgHI-6!-wiTjzSxebve<@;6R&udD82s1C7m?t;Fu^jP3!j_9u0^> zWrgYbJRUqxdD*pvE$I4Uv|nOE<3`SirG(Q0DTvEGM22Up`?~ZoAJEp2%=GLrnq3Y< z=jqc$F+vI$rJ}HLbpKSgKm1;Ea(F~ZciiVzRa?x4G@Q&~JUg{Eu)4gh^wKmoz;kXT zK3=FKez-mPgC;A9Z16cgTuMq>p2Fz5Z(-eV_Y(X5{MjuwWrW?~d(X7^R-N*2|0S#Z zTN+FmzQk(i_dB}+LU8WX14m2fo%MwlEc`KI!kuB#)l2O?_Z8RCN%i@mp# zeMUnL>N0CBW+-&l8|LjG%Vty0vLY$9^~@x3iB3TUcmLcae&O=?Mq2+__PCcO-i4|B&18JT8}Agdq+gL}&+77*_B>Ko@v=IU0%fA$Sr5g+DBXN=i0L46q%l*aip)B zlN-n$yeU~;RMB`EKW8^Qd+)muBtauZeMGiFxY502?PJyE^Se~Nl=YLBAD5FbOBS!hN?1vccaEfd7puob?i+C_)vC+n z_2KzRB=p11L7gyd5~WHDsN>Rn!^I%u=}&Py`K5!@QTpFci%8?4uwoq3e z%XPS|fUH0aV$p9ac!JX9udPs1M&oaP=vF?L^8eHO&$a7q$Qs3>Kl3dku@Nw~-EU>L zw_(#S#EQtsE4a>}aFlc~ciNORl7C!4)9i~}yKSx(w6d7szawZAJ(Sa1k71+5Uobqw zCpISYvMIG?cDeVz0dwA5kEA^W0FKe2MKgCS#s-@9R}-wF?;KXIc$5udmQp9fThr4B zS?&%=4=rvooq|TA(kfAC#Qj7bxbcdb?gsE7{qW!~H8||%lKB+pzT1Il{F9F-fXq$w z3dEmUS%5%7n@V+*;>}~ddDXGonuquh=~QnN5bnaF%yQ3r@IVu=#Rmfh8wn=Tu7qS` zfP2Kj*kD_=V~&q-b2I26Csn=?eW+{YL4hN z;E2Klm{GT;1>wMVzQfgZ&()mULCWRToD6q3TWgz}NGX-bTmKAbv&t7+ltUtQ!0!P)I@j0{X_1|oj2=GZT_U-9=(A@#LladBL7GQ>rj~`@cIsVFf-uYg)jD&KP z?hf?C*SF7ntARQ2YuipRg86L72Y$rkq<*1Q{XH!Qq@R5r*V`am%g>>OS(EoS$}HaG zJN|5_))Ajp;4endCx^#Ub9vSHCIG2{Mn3+JZpmp)$R-fx@^7H9c)(=P4MX5Et8lm< z!*H7P9hRL~R)OmtV6V@Hc?*lYx;xsNTbF5H3g^e$eSVLW@`;vCL_-6nk9;?SOS+xp z*j2?vRMLUVbd(uQ{qe4Bg|eA>vN}TnS)RFxCEgB!|F~L0M&`yF&Q;GfAlXTR^mmlE zaG@#uS?&~2ZPtJf4bBPJIwymfX|Y5D*S{`A$kgg+C4H%Yh+i=G@_k~#P=ED1p>(&jgXRe8@ zW^8gmBg;2U>e<9179fSBt;l?A0^7On4*f5Y6(`%1ZAwb30VX!LpCyfE2jPlzx78aQ zkb{MxR7YnX}hLHXV5{=VCYVnZPIqcR7hbmQ&-3k zOr?QJuN8R_--iS|C)0`Ea1&`Z0s7_0rL#BAXLI-$7l^^goy%#e+R9Ppb4B#G1pFTe zxm~7GQI6&fWcDn{A0|no-%64?&T~Uq3RA1|Gh21Hw(d7r1G@8sqH56|O3|yLPe`ZI zj0uWLQTM8CwG@<^w1l01@hZwTgozMfihOG5#m5u@D&vEm$Kd-*vs8#}1w|LDBa;g~ zGd}Gss(S|XmKYInC#+rj$Uh|SR%calumdsz{ja4OsD8GOG#)i0HnP?cnpQUK$Zv+D zWO+V6*5jt-aV0U^a^V{E$3*e?@Wp+c?>#4T>OYhIG<>yCp`f71(UR$x&Z@h1E-+&i z)l6`%4^PONB0vn2R7{C9VNwNOZ{2j?NAA&Me3uZCvTV+bm^s^^z{69FiHuX$S|V40 z^pZ_n)Fs7S1)Xe6X_jyKYeB}+xv)JvGUREDdaS5q=YRef#cfg1F|0xs)mYE5-?mN+ ziIC~ie52#s`IyM<#9>OtNQo~K|3lX1o%x!`&bH?+`NB!#6LTmc=nKINvWC@FY*HHe zR|j9wN-MeqKe)sRobH7*51$oTC89rjy(D*RHw5$NhuFn=&(QHZ6jQFFzXyyjZ1kUj|GH|t zuFv@ic-^yIiomTKk!`KmCW4IQY=UClTJD^uN0Tg1$j%G6i!gm8+Nl|qf0n60ObNFq z#F|#bH3rrCWc~NbJ$WvpdR*V1?IZC20ZGVHq!m$!$BzQ-fO!Yj4-Y?f5P;KdjXt8p zyNP-2NNL(HO)r1{Dk%((et2Aetq|wm{*r4VT_S5)rRBcf4y#BF>GU#M+t%2U))CC( zya3+DkE$uobsM341DM6|j{{M#6qI>Z~$EFWbYfVJo_juGi!*6VOz zJAz^z9dbopNoWHd2>3}KV9e6axe4ex8&&_Gtn)5inLIEHt))mNqi9(3v}^czu?ZIY z&a#sBJ}|}F$LzV^z)Sz2+m3gA{B7-X;!;DYT_uRXMdC_R2QuFeyjmxTQbmyNSR(=k zBUTH-@bKZd)D7_te#y18;GQ$IJe^{`x!0xMFwYgdIEXZ`~@lAbKo zK{$H6llf?GBpYZ3T0M~B(saVB7=_EXehPv1691?$YW~UHO`g3sME;8-G6{amVkRr> zt6MQ#E*f_Aq5LU9zn~Q%=*Ud}Bo7UPW@P3j21JlWo6Hui%K5IEc@fZ54{DRsFO?a{ zbg7gn7Ao|Jf5vZgh4eZ+Y)qkl9i__P6~iI&chOi%W$_B;H{b2)Wms+5KE7h?HV`NN z13Bv@2OZ*k^^GTZCkQHLQ?L>$&i3KIQTZ!`21<;eFU&~`PxVBg1j2^oU zTMDKv!KDlCa}8TT)D^Y!j8wF>Lqj9k5OJkEjWb$Jm-Z|YIg^xl>BJqCNqF!?>P7Pw z)nJ35QnsXNdGeXHl)sdzG=`ZXtI@T|TF3XnPo9I%~Qgc(JAHlxUN0M98QW1q6BN)j2Bb*oMkvVl`$`5rC zNC;Bv4y_u$G1t`#HGh=Stv7THcafQ3XAk%AtL42%^uso?tkS=bvR+ZnF@bvfj*VcD z3ieNGkxE>fk=f0GKJL=RUuD`+R0jA)F~zMk+b!h*h8lf}^y0^PWiP=Bh5uJ z3~5#PnY}$j3PHu+3qs~p^Lw}uXRLFX3}4L)LTZbBTe-063K;`7fIL?|o<BiIMqgi4U>2T<7ie4hY#r2Gw z)uQ2eCRcjQ&*WguE6&S7GTJQqDj86Ma(&i^`hf2B!#Zay6ssiDr~8Y>!{2|{TV4xY za5cF}PTPQ)(!yskD35I*&M7N97fQyU6|27 zAQI68uai^vbwx95(sPtNR`5{Ur}A}l#@6!yqW@J4HAJ3(4SD{zeZrL&WCn@?B0n(; zfrS=T7varOQKQ0Sj#9pu2^aPy{CXRajMK$G0LUkJCy?H`Lr)hDEs4p`<2BfQhn0v= zI?V<~5_i{r2fx_V+lrKZ5gzR)+wnqUtXd&|*a<^O*;7lTM$e8cNKC~2Arwm-;Cp%N zx#6Tka4L6_-B<>AyyS0HQOKXb@C742thuMn*C;UK)9o9?2tK~FSL7<&mi-pkF>%Jy z{2;RS8$Ou_w$I*!EavC>jCD>qZp+DI3TTUd$f#{kq>RdL*F@F0(GQU1F)BCdp>Iq@ z7evDjvdi#_Q@=IhbsPJl>E2K=&~*Qq;EO_%14imk0PL1etX!RG3>ex316_bbXzN#U zyjS;p?oS=B{kyo4JwGqb^1cY*B8DOUUH9Vvk=w~`7}=}@he@5XS$$=;8{#gbwS5co z)p$ixJygY{McF8nlS&v;6!eLQ4ri#HJoOSEobVwdNP3ex5-&P2pEoh2l}*6#`Dq`6 zPA@>8>Br)a#GZE=re)QRO1h`Q4P{~_w_rw9iK-`#eD7jd6}trxoA>%cEe-#2&s=b`tn zK|TNuY-q@W3SdNU2fIx7XIGoQXrH_%1DEz(XNkXwfACX?E$(U5CjK7BT*i)d*}LeNFvQ#g%9MOmLJmIf;u`qzJnR%{mU^%h{6) zOq!n8Zg;ihJf^>jOfmiqEIk$QQBmdfWtG2L>Q;?E zZsBf3C2-h@!@m1lHwZOigLO0t)QYUPm=W^^uEtiUmzO2XnuR38C$pot1S2|+({}vw zvC=yr*1TrD+WtEU4tQIIL!@9a8&`e>e2nD-%bhkM+@7kf^cKb3jc`+!NZERqcPwD9 zty_^^@)Yd=fITJpJm;|C4^QI}1Z}dNx3mncAqy39fw&B)8OxR#nx(_CW z(Ntb_0NNjbhs^^}O`2#XUlc+ia43Y_$}{S*tw!|s=dhBPxzHNa-Qt@uAWNhUZYRgv zTXCA0bG~^CE~rVKJ(4b{h9QVgwXAiYE|kXg(eSr&1%Q&yJWRG{iyeM`^$g0yfY9wC zYUC5LfD8Je5$oJg4xG??Pl}&?s?AO=>O0|91-K~MV87u{Gm;HEFViRIGF!(d zB%}ZO=?`pD&dnE^05^(jDXZ|rMfwcAwbxb_`{9#U5$&ycu-NrbAJ^e5mcv^9o$6@Q za+TMN4P}WfB06x^nuu`EdR2`t+cko18nVkQYHQzXPDgiN=lsdsE}S*KpTF&x1m z>BpV2N``2{8b#41meUb*J;<2czr?rd@)n@IE3Kh8_%ZBFUMe9FWWqQ3 zV%Q=18RFLbJ++(J>9F$tJ`h}O3B`;P_*tWvUuC&m#s!DAiWL}g61Dkw97EC*obNL* zZaxi?Im{<*BLFVa`@M*;``v-FdVwbI1izkYl2KPF6~9YO4`mpx0ak;UH{JDApc6{T zpCTXlc}=wbx@YavDfBh}f=!I-MT!?(M5X!INaQ42MXyb~2-gs0;ppU8uS2ljsGnJ6 zk{z#Y@KjX!o16bS30iVBTeq6U;_IvG3*QT87?+e(SOa51Uu8l4em4*BT54cM*u0m_ z;I$iBovLyaTOcNE=%thXV(2F>V7~9s5C_Q!5?bjVReuO$VEi1(I5-w}v_ZJyIJ55X zuR*rr_36Fa%B9=WV?XWrM2B9mny$OzgJTpZ*p{9{aC+^20SWlCPNbiX8<(!{rUm)i z@WknCL`{JOtZr|{tMo7;LjOpPO10azUq{whXB-m7Gv12Cl{mIx*K=}d>e;jl_1X^? z4%JfkNH9-SbTmmHzgD!Kn&=?dJz-dx@&2esTK^{b@{YRr+lM$dac~q(Pk;SYwL1_2 zN^D2S53c{_$UCI9wZkgu5IoxF^*)WID|v9-&OiG#H71ERSz6CQ#z5m~KRYb~n?(`d zVr0V`$O71=h|4oXsk82*wchPnol6pQC`EH!d?aw53)}-D$U>HnOji8~CEx z%Bf3ZE~VAV$EK9O{K9_v1?_)aI@I;Gih2<%@PkTSkq+d%9r`=tO-`WF7e(i6auy*A@GLZ-`tSak8IoBNQ}xyo1j|sR&YUm2Edb|dAs>=R5@^c zFv9`iH`nUi|3vI_9cN2E*W_dtwS9%`t9FqUX$;aNtqg;?0)Y32$=aZ*bMVLPXYbo3 zGpTSQPWznOF@ONIQ&=HDXJNPnynX8Fs>LE0(`U)MBE{PtBmE-4*W@fx5wzu#t(hs) zs7?IY_c-zZbZ2cgo-{yOXH;rxMMc9fP+M6s&+!|2ySXMj)5=o6 z-6l70xO<4H!k_JBX$AE^61K1?7!Fh*ML*9KtyRB1O#Yd*ipjQ;Dj{nV^c>SD?9H$3 zbTgMKV3);J{odigB;_EGhF>|i?;XuwKD8E-Asamz9Xd{9u3q`U;nQZ>enb`)TG>btEa_yr zF6`-!sSSK(Ilkv>)gkf}9mg>Kjqv`l*C(@lUS4bK(d9av1Xachp?WgAXE^VR>xk5^ zn@&5%l~;x+65|IfmW}Z)%eTKXo$CF2v)@C~o92OEMMC^T*JC${TMbdA_xE%?vhPPS zvNlAZKasGB=z&Cl5e@wM=;_V=f+G2;bM28Jl;_mzqvQ~^`+3&uM!gyFJiSo?dOqm( z(P4GWZF{39CXRIo&?XQY&l>RKnhZ;q#DYSbGlwz0d4NI}8(}itx2Ax(2!nYx>-(;A zDe4LW5|vP>GW9sUQa7s?32dUcAvzWWhWUbUGsce0#EB=*JI5G>v`<=rXgG+@2~!-_ z1;#;8pj(kB>2N6Qq8SbcCxqF?m-@xy^=xqYqsXUV>(0-Mly?FTAYghZw17l&(x|$# zXWgwg&I2!v>jXig8KeF+goS#Qpi0+0{Tm%!Df$_e_d^Jg%R6r8!+^wD)Nf$QzmiH3q!^Ni6)9AKh11_Up7hV!Oec{iue2n9knp!&bP9KcpO9mCcyo(rPx5MZ-ee;Iyir@pm6b z3jDgie!ur;!uS-YMr&vNNu_&Uw1uJis~U=b47K4mByL9l&FdR@3jn@!g89D|Mc|GN zSWO574e7}-!Q?EuBNMTIP}BAzi&s*t(qGeF@p+_IuMM|)FX_1VK!)r;To>o@>a*Xr z=yoiK-HYG9ziZQNF+fDNF!y;#@Bu}Vwh%!i++k{n&wjAPnbl4RNkK77*9e1rH!;}} zi8W4q9@*9i7mI8mO918NCu*pSb-9%sNIBF#&YLo^BK9aT*|RY%Es@NFiq<5r420be z!xDRj|C6x@?tD?n?yss7v$mIyi5SfZcf;6VYWzHm5gPyJRj=DQ&T--faq#2}{Uvf2 z1L%lph|@u^wr@3y>{js4yiH*ghOt?Bzn5KmfLgYf$N($pZX%hklo=20Kvc4$ZR-U^ zrt@@|gk8;v7FS%s{cs-MqPk|woM=Rvo==FKt|wuHZwBd+feNPWA6uQOfvFIK-p1{@ zcjL*OuJLJnr@?RPi^iI5hJnLiZpd#HL{i;LrKbL~*uO6t z4bIf3t=rMzkGUtXn#Nu)LAcjEM+;{}UB68_+|54Y+Ih!D9oHBBo#iJAAy)UZl9%hq zEQJs(zc+8a5oe;c1d$%hAuzUg!?$O}qq<)Z4wA=7-D(%eAi36z9B_mpj*qK@#U# zZ4VE+_||$Cx)toR$-x&|!{W1v!FSD|F+0S$EA>k`fC+;lsI#-KYF&ODoVnjbZ(wEf z+o}azm{p!+Gtka(^WWY(glyx#X8QfyekClxSuTx0S-?_jA2&BF2TG+z{DOy--(F`7Ej zX*Qy}t$GyGG=g!1V?Oy?9a*fodu_%?Fs_YGPXJitAfNuo3!#iaJDSyv6AQa8c&`cG zJMCY@$0z2kZO*8w*y-?pwBGN_-%gthY9vI}Oe?ZlEWM-Wc3b`}G)3A)+*zvgNX9&Q z&f!h}HpEUtRiSK%6%3PEM`6*pSJdKgjxq4Jr$l8Wc`L|_sE4@Y<;QWEO5?V_S=B=5 z)S=&T*CUhBupJc*-8U&sxPBt%Ptkk_$^`}N20a(2_>9}o;+KeejWh*IU4J(X(QiDQ zppM={{CKl$2V^m{NI|K4jgkyIX~RDZxY ziV?KXfT_#tagj+{c-uiRf{}bro@T&%Jx$>KDqfLD_-!#I$Hb{s;#12}2b#fMZcm~_ zFDE}}Vq7y2X@dJbkaA3PEZ}bt9IximR-z8YwD+!QaEhSAYuTy8`P4L_9=T@cS7$l* zxw`so{a#mj#0R7Z`PA%~l}v)~*|+fRPu9H2^jUvw!oGY#N#er1pjPM<-+BjIU@1T$ zn?6AgAjc)rp57#%!C2@qF(AGVK^_Q7(Ta<)TZKe-L4IVS8E|Rd z0|kxsc8J5nS96a`w{H!0et)L046iL&3#q@curXP5uV^|p;%-Njf<@d%f(XC+xR0Tr z2w=QV+krC4=#(RVy$=ZzmF8L%^jQT>j(Xpsw~W`OKVu_u)@fqnX8*(hp63Y@oVYd+ zm)_|@r1KRlw5|QK_DTLrcr0e;vuB5!b-URIv$520h#eHShDFW7r*-8x_M&EiyO6%M zLL%#E)s92ORZCGpQj$cL{}91?xh^+vYW2(oNg0 z$#+nb)JKSv7+eybU^UEWg|vXJI_y$fMi-e=Cfsb3RFJ>@StRz0@H-N6h7>jmf_36r z7M_hIwT@n(>x)d~r^t)q0dAA5D4kT%RU%5fFyMo+-(9!s3RQR{<5#$p_IW!`jOq_D zscy^k3v-O##%5rduP~>kqN^F`%Q(Z+#QglahVOnpo>8SRpMkKzW6`#N9j>q4x-zp8 z>OlEx_RBle>bx(wXY?6=PD+u&FE3;3-P17D5~daB4rLNlUDQlbZ06y-z~=iwu7u|{ zCr1@+^GJB-Yw>pi+|l(LwoR2~?JjU&C2pX?tX00}+tCM(b@zPSx*uQ zt@}f1F%$prG>pRPVBXRU+ue`gaL^6+$!Xo%d@JK;xmhr>guc9N}aLz>IE zAa7y&KQtL3JNNq*X`Pv+|;jSm*S_Y>V)q7kzqPS+VMpp`P+ zdZ}`3-lvT~PQcT4F*HD|Ms;BMe*MiO1c*V946)c8D%aC=@v?^S7(F=iK1~WY-lkhM z&_aW&Oi$e42%OKmvMMo&eb4>(|KJhF5T8M5s?U5MOSjz2`UFp!=hM)I3!O*Ce@z-y z8vNz)gfYJ;s@TETjf1Z%_tJqNTl#9GamEYrJQki+CK}}_V~o`g}`U~ zVvlLn$p_iB-2OVh%dqR=LlX$3)bm7&;k%=e<=Gc9HfB{)?0q<9`}BHx<;W^RtSfUH z9xlP>4C=Y}Ho1Jy@UswDK)1sZn5{%H!;Rp->_|_wBL$HHa|@4vWcw#l(jgqsT5Pfs zs%CWVR+<#6X21s9r}qNGLIyf!Mn+sQ-k}jlKOllhiHT$#ARMgrk^UGZM-U%uSaNhY z)bZy?lnPd|jL@3}WKHvp2Bl_I&!Io@sFB&yA)0BitsXTD-|zpvU-4dLYka7QIIqO7 z=;8yvVxg^i0l~%X^~QtdKMp22l2r%SAfclBE};V35o8}j@u75Cs{6!=nL8BrN+-ei-;)>ZVUT>BTxG#sWXoyAB)l+)nwgjI}F zd0vI3N_vBbZ&svow7+dG$nOG?deLg9o%8swQCxg-__Tc3xL~}bgfodT!frF8(q%aL z>v^-X1eQd%k@R1h2c@l9$K+Ai;gK`+h92D>WUVEHcwKc;aE{k*plE7s0Rl8AUT+>h zxtNdqfEp>LthTNWnMC7tb~p<3MT3IWQ9-sN8>)^AZejV!jA<$5}*+Q(+Yo z!=D{IwEkMM--trIz^oK+k&q`On@mmJcd;CeGASkZ?G$!9X>g!?rV%?`nf7M5x!6jL zYgkGeRNQomSfM480gg5LHe=bE^}9sDM*))+;Uqzkxel5&Ua>6zTCF0n{X=n@)(VLQ*|0F z$L#hwxDQv=uZz{qIufkrjt>LC@*t!lXeGf$9dAi`dHh`h6~;m2ktnoK=H(=Gs+>Dd z$#FXat5OD0E{LxDdi4GozV+e~iHdGiDae|M1gN5}@0m0po2(bN15M_MSV+)QT>qWJ z)oHmA(@ZD|jgbBpxn8OD+IlyRKR7(9y6YfnqkR860Zs1hafCgj2;Ffx@92HN0IVd#idl&W@7g!l9%Y|=?Q1%Y7opsFrWpu7gx@Nne2 zmPSs{*T>j|vw?d?mWw^g2n-sIc!!TC5?_Op9ZPsA{R6|j$0g&j+zXNjb?<0+1vDCo zpqoupLTD3CgkPrY#tv0dS)Sdz1rD&j-*3=AU9T>vS9>E~UO7f}XQn$OMBpX;&6&6V zKAFWljszJm)Q+SWgr{gUk6d6QCrj`{g7rNYl%Qb=%mr<3#XmFE5!d*^&p z{a0$@q(8?3!=u;9iAG?cyHGSpbZ~4)R8q3~+AOUB;yRgpG)1H`U_7;&y964g8ZR$n zOKWD+Qc%cEJf7iRoH*8tmr#$XZdA+@VH+NNF>P${H6?0Je*ke$BtzuGnv2M+R}+&i zAt&vNL`R(KHrYxBKD}YBsG;pp3A218?)yA~IS2E8a|}solRT<;9662u2QF zoUD@4DXhCv;+wZpl8BP&di(5^L7^mD>Ysd=9z%#6wsup`n@x}_dB)L(CzzRVs#p`g zSz=U5kiUHTo{`halm|_FNY( z{56N}`K1Dcx190Ta!nR2w~{4+*1ydJWni~izUgcixUTAHl_xjP9mSmZy`7Yzw|2Zj zIlb!BqSK%h*Oeq)hD&jJ&t8dbVBud zfL^Mwx9{QHa|MW%r}uXE3{Nw;bRz+~uT%B<%cGjQLRC&5NqZqdRNL(`5ZUpi4C>HdF$mFi{iU{1nE=`HXO~*(pZ$FB*U&1 zyque~h7-u2prA%~OfGZ(e%{H#Aoyfl{GBN(8|mwlKlJk?kX6kpx|XB*2F>Si5AaTaAY0cNEpP*FH2nOCL!&{)A2&xu`d;c| zj-swq!qpDEe3+aGFUAG5aK+L4zR!~Pb&YffyIPkFR`3XG_xz7yy6v%l2!JYU(8R@t zf=KQEl*j=)xeRvOSk~Y~p(bingV}xM7yLr*kr;`z7k%D`TL?=2?J92m9nTx1exiUl zVEyuMIrAst^CDxTCxnIdprRR_Yqci0imTJ-mRm+QNF(wF3HSb(_p9UA#KhG5g8ng$ z$MDX;>kAh(#)U)w2L#BsKOYiP!nH8z%`YOHIx%S_Iu|ih7ijkCSBWgc$v#yOsbMuJ z6`zP~F>P>pJI-Bcr92PFe!}jpa3- z&=7gdS5We{vB>XYb&)i~SY1yp>1Mw@UDbjVs#>%{yWDT#2Q~rsYUgy{RsFhEKwQtg z2lga|ijX1Z?V^=krsrPMqSx%Ff`UQ|k7IQ|5I@%w}_lA(iMU_^<6dA?hbSy>hBQ#2dSZX(7IXTj? zVvw%)K}OVkiVjvrk+%Gz7sk7}qKZHKyW*EHw*EsD@VsGbb!4BrZG>6(wA%}EA{@Md ziGf_}fsQ&jjqnt#9Os;1KYJR z0-Y(@J^_f^>peh@y}vhxzjHs^_a`E8Tg(Jy{H@c_)q(ig=D=Bp znCdN!4y6x&txS^YpKR+u;(W2F{vR*TbHhqTIaa^RY;wOE!yn&8_HqHzF{`<4&=ZzO5zK5tKQayqPV zI-ji(9@Xv}bREmJsslGNFo2tC$p1Gpu}1W+&ea0j-Z%mkHk6*W23|HH0%-W`)}4S( zYDEC1Z`zI#Ad-{>)&I9OU?pe|^@-p4Pv+dHLZMq5kjtym=S`3aGOB2s$wC-#R-e=<(J&#v%iWb9j4wNX6eqLb`SNE+A^Mz6r$d zzL}buCcev(T10<}Gvv~Y|AFQJ7&4aII%vA#PxwFLjiu*W)Z#p#GcuDXB=x|G!VV5= z2OhIooj*;*9e8O1kt!sDx*&Qt5I^c6>H0leVGpMv!JGv5uf3Yya*wqbny7B6k zvuWL#D~~SV#k7x9iBN`BN-O*X`?e5-+h=s(Bs-KMr@@K-+EXkz90nPzY);+gfJ2s%SydNQp* zEB2=~^km}Ey`BE==j_U{rsDMDGEzb;Sj-HP8|C^tVo>lU-Wa7B9FSo$^fF!rg#3nB z*tf?{8dE9HWf=B_1K04TIAKg(q^bE-9d+zeEmt;I`=K(qwD3)&@vd=iB?GS z!eIH~TH~hfW=IPw?@Ihpvawp#lcD)9>GcUjt^BTvuXUUbFQoSe(D03-=Y5M2Zmv)W zr#vV{>C~u_A-nk6Da>qn{i)7+bs1v$TN_cIE5mWJ#)LL41W}#Ija}CdszIm8g!b$T zAsmR|dC%v06Yo{6_{0R|c{&M~HsJ?JK{Z?bl`+}Jmu&o(Km2eNuF5c&_j_j!j# zwZm%VxZeVljwE)eZXkz3m2^ZyQ=5pNIAZy2!kD1R4<7ks9mYZuLqpA7@6$!u)}T7z zAUSe%jt@C85r_jxEO}4wZP^n@`J5==9EU(@-`}6l5TB2M6XrZINn1@#qGIa6l4G8;JCh9sRwR{6+Uo?JIP_=C8GH7O+R-ycn^FOE`LSa@s5Dpe_9U zT~Sm-#J~;5+P}d@C_s*kvZH&d_C=vEt7P(7K=_+B|M9Wm^yh|agAh3Xy#J_jdk*MD z6N0OwxbF-^%S-b}7lBLG+ z9dTA~cwa&r3o1(A;CnlfnZ4Ej+tdD!1{K&7{lg>bA6WX|VSpc3Z`n+?&PvMdiib$U zu~4ZMqQPS3Sq+@qDF}p0FHz#M;{1W3cNdb1;cz1L{lD?Sf}Zcx$vYyS9gMT@_G@^Q8)Zr{eb8d!7$i9X)P<*Ap(WC{c{Eq zDE)HM^11fv{R}ckRMhkeBg~)@d7OAYD#qu;7z=a6kY1c&^R6proT+E@6H4o5&D}rA z?fjw1fi<-R<9L{M2*FFJ(rbB0L0lb?bEPE|%84dhRA`8_%%7SE)*8>JX&n|7#7Ees zrZeLlB}AZ(TQHG+XF5B3vGN-;C&vse4{$3UuiKnQtr1hzPG+mq44|8GEwJjq0wyQT zVMMjdSH%jAriP?c$^*LGP^Yd;js-R~4$bthKk51-zU$(VlRzudwSI`}rG*r)Y5!P? zkW$dLEPI_?MsXTOkN92}slxEw#UJO8@~%6MQ=?5YkBSK)$N}ESqYJ&2%>ee)M^IYQtF_M?p{m;skY$B4 z5IY~}{AN@fnA#NM+FB#qE`Qi=z7_?1U5uuXSki@!+>_?boCcj&vq6sDIB~+lBL`OZ zsHgp8tt$PlcdN1o%YQ1@BE7d$Ty`_B#;=4>2DbVl2%$w7%-;9*0lT5T&D*p_q! z1r4q{`2SLw|2ski-bVk}{_in9`Q;<7icjasB>MeiE`;hv!Qq=ps_-@-{#0k#?e{1E zhAv2|GCX*?@g`Zz{?P_(W9kqnwXP&5u!?k|nG^3PQ9IAs@@Tu5@1doFIghPOdTTSS z9mZhx02)0)beY#iQH z`o>53@$(YKbX3DQB?rrEle&a4Y33^zIbM_)hGsHp;V|=mid2y%B+#N+mwd?i3ek(0 zR%?mgMKq`01@!K&)N1&Aoe){YJh=z*0C@|EWo)smYZYH2aK8F}~ zdjhX%yuUMk=u1G;$}S6kH#&)VT%f85l?!4%EGG)Entkt#siQbBpKrz11lttfBqt@3m~B&xrt|A`o7(KGEMQ#pOO{W% zyRdw(`5-BD?358~gucmcTlWQvBy2o3bSJU9;fFYoV=hD6oUvQj-h(gR-c(E3ZlUf| zPyZG0?plb-f$?X8ST4wyGyDK^AWwZhKQD2+`u|XMRsnG}S=SB{2%6yT-MG6G+=IJA z2oPL@ySux)yK8WFhv04r?((0^%s2D?bwMAv04}P#cI~~^v*`C3Wwh1^sytc|o8Im) z0H>|iV~3iiBBk-@<5u1cUWpd?CI|f{L$ya#>X?yd02G^KDfOwJ6;Vp4;j4FaQ_1jxSZ%$lwhMdCG`V+23Y} z43e7_8;J3_1=277yLeDvz2JGf{&h+VjbL((XkWKp~b3%aF%P}ozAxAJ)$|iy9gYy?_A?I=<)wP z!kf1Ve&{b1QR$Z!Wx%L?JSZ_Y)|u-HuEEYb$)~nV`I#1lAzh@FieF0OnAc0rC7?n; zci_xQy;m#$!NujhdZRno^T`9(^TCL4pJAdqH=#hiog9XS1Eg=J`l&9_|6=u&*ZpP` zxBYEdsGY@t#4|H93`4^JJy9No=rf3%I3OP@|>)qv8(^|gZv zdlMj!-75${L$zuih@Tn>$=4#k;^Cpe18~$zc8FnLOHKvqv|a606f`<7($G@HI|j(s z3dAS;kTcpyJIq+}$tm)5R@qaNYGbs8V&ND02^XvMsuokh`!*-!(!r(3i3Y2LXHiyO zvIil@TaP^pf)7VU<$(Tmp8s1*qmBjHs$3Y0zzZi%7}i7*Q??M7CT5}uK1#Us=QkhW zsWLe)y09Il9}5od_rLJ~>7rZ>Jq<#Ooh8<=w)I+Tf~JGCgoFq&z(BSO=P1_;g4+@3 zE6NIAWzUV%XQ8zb&6F)tO9E-g zGz1e)QX=tBXLh+qjiOh%Hj$(c@r?0r2MHSc{kjLv`TX$WH# zeHOibz8lM6fd!&xaS!CZ9L^Sy7PZ~zn3 zPk+OZCrAYPXlZ@u4szq4yRP@KlcyE6X|Cn0b4CVlB}=5HmSf=iSKv6~Q?xz@gmX6v zfwGQGaq5qM!HZTE886za#?VdlrA9+s$&2G-pDJc7II6d!uNgFG}FehsZP4SI;xer)2iPVB#4=J*EYPtEGUF%9w!ZyG~%F14dSq zl+&Z^lCn&HhcnKlq`*DY(pz@#RHF`T1GBI(sA-mpmb%XbjlX{Y>7+n=pDCsIp5h*d z2rJ4+juY;UO zcQsY3LbJ9W9BMNWb~+~WwNjS~HL$=&^G~#&d-0{VvB}5FbY_uHXdiM#Pa3i7pMFby zl9Y*l0NW{fatrGRXE!%vcfCHAp$bV<6HAh;kYcQ2$i5ac7hF%9k%w8{J7G+tSCCG-65RbU zvW~>!VK4Rf+K+cLEUCVju`5lMVfFQM@F`RXPss+F{TiU1QO}}h#JaAKiklG2wEl$| zfXDnr=hFU!Y62=&U*e}h@?~s(ziqZrvKf%Ej+fHbF2KA{Nt=6;!@)%L{sjg}u&8n^ zCLh59~g`x~#!#FW>YZn^JT{PM1yK}AnOmwc3I2xocqyJNKNp^!@7 zdOyJJAX5+t&m32gbkI-Wx~t%N#!Od%-aq3j#|6j9kjLm17Y?ezk{lHnm!6T8hu@u! zzILcMUqDPzrKFA2e<@U?)#yZKIiT&Y^0GNg2_^DM_s#Ok2sE2DF?f9zRqyy7;l8ma zp@%VQEV+$D=Xx>J5Dr=U&BqnI8PJhH`6!IMuAp@?u53-{MiM~IGR?cy?JV=f^{Yp; ze`9{|;y^K?R5dP_9s1+VNm*ax8B(le>HwHhqv1!~H*DgKi08;(vYj+$7?sje+?wPd z62XO?H-^oH+}R?zL6{cuMrhQ6%JyUGmr7HabJwE&(&ajnMN`{BgOknFnIbtNZMwUo zU!Ehtp6Fbv_YCMKP|77lhXRqsQ+- zA3frSKqkSqfuvtUSlDI3!=D9I9*i%i<+hn$v)#;gj8A41^ke;U%Ilx^GCN&~7A-pG6o`3i;$+EGw?$}`xjThe@7 z(H||5_Nb@rbE?(@0u@9Y{!BcWqhFpH`5uLahS_ZJ{n#0mB+5(9Po`9^qUg{7Jizxg zrfZF8p7*ajV;O8nEolp>C!c4;KGCRYm*W>$L)jsLU}BQvDX%yQwRzAoto%SpuFS6jU#DpkW35!H3Y9vFhUmaQ06FQ3L+ zw`0ohtrv;ulm$BSxJ>KMwBiEIk)oIzaT&mm&HPg-zi1O9i4t5o9zWm}DX`D@o*?X4 z@Jsf3MjMGr>U!#I&zbP!l=1Ufeg)!sN4pz>?o7!E0JrDAbl}alJJB&Qzx%mQO>O90 z0I~ALjhdbdQv&gW&97k!BcSe`>|;wXPZ56k$re}1ZbMUQ=UK!vhX9g;HT+SrA@JY2 z7WvKG1{(kWu9vVu8Hk{F&zDz|tsO$1f)Fc>mSxtqv!wyOk%EA)=H*5?&^rpVs~9;- zbyQXKT8^%c4}*`KUXyCfS^B3zcu1W3!=f`d&h+z0Na?JSCySUzcs$h32c^8iIaZk4 z!-ClClHR)WpR;o^ZlO+M%8BC9-YAKFB*Y3eUW0y<2G^aiInB)?tNmTFY3!T1_LDue z;IRC5Dbj!j?_RQ|O71s?q+FLU%vO(yosR;+!yE1a+qpsyIZ~(}Dr&3wg@5KWAdNGK zA`vp9Q)Ig1!XN@HE3B;y4!vG2>vrFnT=#MD63L~IdsCIMPd3@1yxc^-7m`bscOACB zfyS!V!57om)N&3;wQ<{Ai%)jb-g~!Ip8#rz^xU*Z@gI0dh=nR@bIlgZERBH zU#$}Rni6GuVY(2T2oI^=WJMt5$V0AcqDE-BA!U$Y>&W$v}8#RAPnM3gn zqnZ$>Gn9YZ7(FKHiO3687;x2KceN~x3LBtf9PH$iiRsV6ppGZ6Td*0^c022{4(dXE zTgOgL7>E;j;|Ss^a%sub@B#PSV^auLMFk($%sZuyS$K%zl5$4{3=B^XFn=^KVb*a# zMshQbcY{v1i}E%q0A~3=H>%!v1^~DS+2$!UpwK7ueAvU%sWM9m)xt$u_qc->O8?Kr z>)$WEk^UaH|NF$>td8?mrM+GC@=ABPU2XEbuF)A~e={g8fz0 zkvDpZE_=!<=xw~_w2RIHv&o{bBWzg;3u^mcxiZC-Qsht_WIP;{?UcqXA_t~j zkq9I)4Y)+#3q%=jONn|bhA;#&DAIbyzT2fdP)~fw6V32$&hC2>g^5uqMGR;*Ml%jo zK;Zl?7`Un-d4xIbd20r6B)}05=2D?$KEJ#=0pf;V~jj-$xk4yd!G>UF+@NtMAg3}sy|jj2-_S?tM@HRGv6Rx z3`asY>z3>)p-kpDiOG;qQ^SA&TmZ&Uwfq3g4rHL|5|%w1EKAoHGT_o-*=$2`5Jt7}zR z^^Hz5&p6FVQ%+=?cD^rM_{?JnBWMR3E1nCDwU3bCV+g|VFMXZ-rs8=5@cj~3PXh=f zEe7Yl=ODV>EH<>#?buVt+;1c!vY(hA5p&beS;^C08UCKmEFjieS#`uxBudDb*i{!h zOM>!EB^JSXU6)6tl4QWm%Dmdq%=4j+t38%ioeSRy=K63M?O&0EZO?Y;tXBAe$asZ| zx&Qxu%7S=8@BiOT0O);}1uIYYiJjQ1aB2IMArD|{A||ven@V$EBqcm4pdx20Yd7;g z7Nr(+CG)~xB-cjdN${h(%%$M_m#kB^kzq98nhbG|NgGD0!Avgkt~bhd+M(K)vmyJI zh>B?jOx4?IhF~ZLq5}Mu$W5UOL z5k3)l`RF25Cn1s;h5=ZwpH-j_XIG&PV`lob%O9w;od7$xYYHfnh>KA|?bw)gvu z*g?2|N+JJh%iMxE?Pz`3?`oItBPJ)rF~O=MrX_(#GEd`NBjc}ymjc8uqwJawrD5u# z-xjFsnREv%fx-CSoK&nI5XgWHPi-B7Bmpt<$B;c zb-kTC$uc(oUAkDtTB=yLHL}Q+_3$5`Hh&-GA+A`*{<&dt2#bUERUG?bGo`fTYDVRD zcJmp0K9M*3F76YsYj=__NFo0r!H{=?kj$wn;AEAXZ!I9vIdG8>Umh- zD@ajMnS@c9OU_6ZG@)aT;*azzb4zDxWNZ0Lk5GuhN^UKwfb zU#?Q{b7z+Asw|WqTNkkCM>ykC^=9^FZF3|Sv|)h8=+3oaNbqSDK{X(r_CP|2#K3pN zBbI_vz_^Gk1k61~7jTHUm2I1|>st}8B?(^~dVB$@2Ex)h^Rp&2Gq;#dQN(-&W38Wq zS9Lw5!< z0=M!8vSn9qB_w5q4HZMJ6#6|ar)$B;{LiKUJ?TAQK{3E)wU9%^Wk$@qBM961!uuYU z(2jF^dq)|$Rmyo6L+(SSqPYsGzyV*yZ~32}Ek5_`*(E&fwE~!&q5oC` z)!vY!`7k@COo?ENZp1iYA*+Xl;&9Q(&lY0wk({Fsa$>J$%iCCj<25rl&iU9%#qrtdUV+#^W8_OXX2(;nY+jlvruQUHu992ARtU1tvA>RFy@Vi_%Y(xCvX)Zvl*t&OErOw>JWV0nrA~Bsxg->{> zHx=Hi2Wu}~7AH5|%#w}(H+Kc?zB6-op!EyB{pH4)%3)1!(xJ?5%T~R1#^WFq6sc1` z5gThrMi}~55>IOn1U}FsjA1n>naZOr|tMfDw)$XBk%dz_<%!iZL) zrRU;;>*k#Jh$bt9CP{N^T5)63MjLA_VQ0t{-&P5oPS<@aZdpufk5qibyL0NK0YYFJ zdu;^aHVaO-gig(3aE$3jO`c}^R-;mSmQx$!0*B4H zKEA_H4iJWwhHB4A4B{v#EXdKC%;Y?r>a97@?Jbb8KU48du+w1z%EwAZka$232^Edx zbD)Gc4Q~$PlRtv8)KjhBSZng+eB1LN_t~ zWrKB2)xw+XgYYKOw4mcHO$CKy*s99IWnD5>otv?L?2NyUZyQ@c%=tf-*5`uUUq2ru zNU=NKx|_GHId+cI{`46PX8MLFo^6I*l%=i|7tvsh^HyVn1*Y&KMhs0lymz4D`}HVy!OABCsjS^=ysT$?Twv z8Xw(Wm8l$`yjJG%UJa6}u5|d8%Po&F@a26|cJ5y4%8&^9>IflTxOh}%$8?AIN1Qg1 zVFCbthQPSBb9a8GmX$}$01MnYdcA%8rdutwGU{?{QpTR`0<{~{Is8j?gpbalzPH+8c3d58KEcPUynZ%6c?J2HnroKDX} z!EEl&yjeh`lv&Q6^Wfq0KX%H$9{vAoocfpQcMeLG01s_vku7_~c?sY?f_$V-N{_YntDbiR=35~2u)C8#K{6R{3!R54L53yeZD)s?=e?_h ztV);aa!d`WxipJ}v16yspialZ$T{Bdel#Ah7%_cyn1jBQlg5spjK{)5JZ3_to;8Go z(1f6hdyVlHF?D&4*00|+U;Jt~QGP^8P5s&39kTW2FaS-Ci-01_mOb!{3zcrQUR=nK z88tQ*U=u4(64?ypa6VkK)GV%(#iYlE&di|F>ejy-O{8UV#11)9h~81q$O|>%&$q4d zQ3ru3(wwC5;XZ(>u^|IU0{n$Y_%3;e;eUA+ljw6zS5{UZbX+?7OK=Nlz~nl5S$#sEtaNoawks*H_=EDKh`CXQ}ixwfCbn4|xcE%ta13{l3{b zA>?JamM$fPdHFUvUr8CnEXmCS6Y+kv({zcyAWY2i0yBPk0s+;=!V4un?FKtc9-<{u zc4H2PM#)YJccuQsJN(;teLFY|%kbIFdOPmpdf)a#odT&*!ZfRJr4QlxXuENz%4pK| znVMdoQWU?pWR~pI2_+c(KBLt^#hg1W%=&nn?T{>`upQl#Jl1q%yr$X+oyz1Jmx94V zp&hS!C^tFEpz%nn)Y7{H+NjGM!W~u`7E^hC>~79Um51vuYUy<@(Bu=(ILeWA57(C> z-Gv-p_4JakklaxtvmALUAbpDkh@1HckhIPpjHc>-SmS%nF>wMtft}hi z>z`n+4hSrrR}O90`3;+HJ^Eg_oiF{HIl?h3`5{(D2?;ImN?va`Kp-E7uZjc}|4ph5 zYf8_(Ocsh%{P_?SC_n^F9h;oXM+704n@V_aUb$Xnj^eD*`_i6=bj0$6B&FA?q@R7I z5d|Nmkb#D2l_I6Fe<<1RggTP(X^0^b8m;SVv=L%Od$8WN^OwqZlh&7Jx`jy&1>l5L z1_koONl(x;IXZkv`>EDySNwct7uFcPf4{)_AWWihMTKnHU~!ca<5H0aCPRJjJi z@R6{fF5$PyWZx=skMJWU&%vk-uQE_Z^F1+hD!b^S)mlev$VjL<#b6>dcjf!|B+DIa zMjf+~a={vi@m!I%OT~+z8_ikzPelvnhoEAjLis@G_)3^Vvp?Z;)^#p|9|!Wj65cRH z&^2wBdulFS%sMET!O0$F)EQy(MUrQ!!Dhhj)EP)t9du-8=h8lw4gW`|@VEZ?_xk_O zyoS#Sbqdu6r8*_WRmg}epAr) zmz@`Ya)ZzduM+YZw=<;_dtu6_kA5^fWmGQxL8mZ~AEo-ptk>dR8oMkO%tAFrF_|2j zr(=x6o;BW^$1OKpu7!S-H3uf*U6G4hyoZa09qHZsK!YN=cly+D#*{3z9U>R`V)iQu_5?(GE#jvq;R;_^l_!ZIx0UO-M@#VT%!Xu zuIm+2$@59{sur{N?p$-Qw0uT~j8_5|Mv_{7ScE=S2@y_k+sH8fli@Ju^%ee3%EE+C ztD)AV2pPARs9Ww&`|vz>P!;2tWub(P0q^Q(!!U3YJPP>?0*%Q^SlcJ0pXD+KbkjKD<@- zk#8Zw4hbTOrPT)~K%!6ueX%al)6xW#W>1ayEyd~}H*HPuLW<1#_+VIYA{7_cdn)EX zE$lWj%xV>4x2d$_RH(#se8P0AAP~sx(f8S%R+p0q5Y^Xv0aM7R^mP1;w;G@9L^X}F ziyF-etpQS0II8IY%M#+RA++84*V+d+@{-W#Ow{_7>%|{@_fC9HwDvSoQnnA;H)A3x zQa0i(_~GKx27b)FlXE;Y(>mS{=2wd8D70(zJ|4!oRYf~%3$2-LcE$Whpa1WUI)8)w zuN>y@w*v6g4PD8saQ|}nz8;d55070>Z~||%5jXo?laT8_2SgoVtCeqfnQq%8V88Ow z3CJe>+=LMFqoc#A7KB@De)ydUP9iKFPXhYROV@CoE1~Nn0q7VzNvud^b@yz=CZU2d z6buUG7JNrl{b%&BRWZ>lCCK*@@xh`?Sm**e+89`s!7L*1`vxidu%s%lh#JOq58;(- zKj);4`JM)eK2SaolaMHE%eZDS&`!`4<$i=y5(kntJzuwI00s(8^5aw0(D?YYec`Wn z+dFY{)Djkq$hNi@1HMuU5c?CEIa=554-bRi!6MS-@&I{RF{xyON0rkv^<6*QjBm`4 zoWT-uET!qPe;*2=q!{p@AUE|<6`PATzK&wc=PO{%x%WI^MDNe*LJ{1dH~j00s9jyUXxb}vYXnQQ3J z7O{^^O41^0Z8FtkBfvYKru)(k^Bld{DZ9XoqN9VaO$LS257vX4uZ_@|V3)~6g2amt z!;anNeh2Cnnwn_!mW#S@%wsWebtq*3k+E~%g^;T$3_fg*RE^U@!hM=0&a)Dci879@ z_u5{=tYl=O6)7axh%&Equ?jy$62Snxy(Z?np#np*BB>8wrb~^h21h;23~yF7AL~4hj)NbHZ|^-@g)hOT z3qd1J`XBp)iT*U}cArIE4-BP3nUdzn|L;`9cTzb&3jJT}sP_$9wOri?Aj*IG$bbHB z-StYA_n{B1dGqf3&FV5AEAQt#R=J~RP*M5D9 z=6pLW{+IF2Xgv7qT~+xb_Zq5)?~lLBRW1UYpV2;%VRLdoC}6z#YpjVoow+n()Bts1E-uRm##s#1 z%P9kaR)h)ej)~_!TOV3n5;U7;P)L+q^y@VZN-(ocWHs%G!ApG1W%UM*xSCR$`7y$N zRdikElA?z;|0dSR6y470=5-I zwE+?BeT0@ckCEV`BjQyIrVgf7dIoKXxYwtGP9kEhBr0Q!Txff0U!%VYk4kF0{ba4B z4``+rZN7CDAqWAa3L+Rxd*<`UEY)W$jN#7 z8BjxD)D^aeJg3VP$FAh)ei#7f0ogH!EQij;1rQ$r-AzAWBZz#s+Am?A%JIx*c08;$ zXg<#k0~BVb{l8PysqMD_HL|#_ZYGuz1^`Rx?Xqflf40(aWr$zuH*)x=^9dP1#(`C< zbkF)xL0JBq;xz|VB8=?7Pv3~}d440REYRz6epGt9$LM&v79RYfgK~nx<-BH>R_ObT z|FvQ`-rNb9-0KC$^VupkT%$74*s-mY^7dKeI*KDA?xS$~g#`O{5dj|cOxoA4*&a`g zrqj7Nv2myg*(3t*6sS*xDU~B-@$9RehZW0*M`kRoy{mV@FM;&51=wYv##i_+5#KXi z5?As2w-(xd_b0y$hL#VcN{U<_SZGJl&~pPEnh7x%mv<;xSvUZ_32hDwuJ?~oM z0HN&#)!)=`Z8TQ18R!c*IM>SNe3{3>cX$g`y@8I)lp`C#HpS}pkhEE$9!_EsAR1#? zyU2VpvpP+?5Mo7L@(4yyNb~(yM0{?@13d>g?s`kVd;QOg6T_jK-z);kh9_VxIpN;;G~{l26a*wtL(?2 zy3*!^m@;`!{fVy=et3{o#ZXpd#fxMJceg?hv%A?@+p8A|`^QWOcNM{LP*vwM>PNo& z?8^6SIY0ia-``a<9k2ik_0 zCy!L<7&{sA4J;A8wR+pT*Uz71wXUZ)sV6I2_Hi3N3HE0TzXqA=mt9tmZiApf zxQZq_D4F`ANW(NgU$P3@9+}9XR|#KtEJ98lVx%u&C5B6eF%0Pzwes-==CqRH+m|fg zBEn9*x}vwpl-bv4=A8ThAnduXe~_vLl&4|uaI`{@Q~Rm#-R@!!{uS-r%N7Z5SxC`hs`RBYHYAZYHHx%l0&&SIk|X0fAz!8I zy37hpZeT}+O#vZm)Ql0xYp~r6R!R>a{{+ljs2*}*Y42Hbgd&^ zLdKa&3&Q2ax>i-5$Ubxk6K#-7_z=FHZ=Os~R*g0q{asE=If)r3YP=7`4`p=+*%+17XH8g4VwRVLEcXY+6#u8xZh6oAY#K0aZTTZ{6_$2_2%jXGZ= z1U)f832IC|BuFy&@auLIvfWr|ZzPKV&CGXxdyHxi>bL>ysqMw$>AdMKJpm9XnQpC- zBGgz{cC8sk;9FIn+;Z9ZRqOn{%Ng}^4L_RF*N6;;jRZU?gc#Bj&0I~U6_*RZ*Sp#2 z_IujAi@jW{>C2$8w|mk{mA6Q**P45sX1M*5)4Atq(}rg+Nf6<2zX+qtOon$up8$@i ziYp;xr0&VCWIBH*6?axoUO?<{8t{E^013}#kl@F&nI&DEYmwDZ4^7y&?SO#U3(t(iusVS6$96JDn3VrFPkQ@B3Ysx73O(d zB05N>MS50X8ID;!a5{B4q}$C|ah~P-*-rTwO&7}YP^CFB149#x)8}Og)W8cB%98h6 zcA9!I4$PVH3H~A2T_m*<{<2_~G2XC=6UR7+7hStN`J#ku#u2Gdd1`um=0x-ITHXdp zm|J`%7+~xT6Uliia(%ca{wVn6Fi2AA2u(h52(-dK6TTBO-2 zIYVYVhpsNkCxnU$>wjynBQv}MD~m!8mw zo#!ofO+*$x9ogavhGXEu-@$Fc7atd?zo7|^4PN zPdz%wSQ?XrhDB-deXI@4Z+=8^!XM1H0_TkNCsPW8)ab}Z3rhATlhOR4!Y7SqQ@Rtj z1Y4X{nk|q5?spj@#@~r0$hO$94I^;3Z_eTzdt)J*VQP@lSKB>}@_7r(;k4h6tr#u9 zR`R+1>A)Hw@S>dH^t4WQmghNba{BP9#vS!)ZB}D z%0Wpqc$x;pcdZeaWVv!8^Xd!KTg|Ha@82p1F6Gfgj)7UAPiY^j*uU|LOS7r`B+kfW zIb+P4HyH3PPF9+RYrw}-aPgflL*(ruVB+{ekg3H;AUE~~6<4Q9O~S^Y9EzF(OOm1o zW^RH9r_*huC@q?7?e()<+_!IBST5LE_ph}8W_4=b^Nlyv@ZrSs-#mYcRm$Hmc(3M^ z8pZ^J9t~CI+Oy}=WbqPR0n5Gq>?4?x`qyT_Kdz6skpGSi2l}o{1|Nc?YV3}pbcb?s zKETk>CAss*Shw-8!o;GYl~LX~f#o5j3sf9WS-v4Uty*$0D8pH)-Cl?j0XP9D>g;b8 zV*~aGh1+Rtqt%st>Zm0M@IuCq18)cjMO&+EqYAAo(GR6&bEafIs~6bD?FzpYmzP?! z7#xlkpmf^qL}tIyQODo7UnNV~6jmr7s!nu`v#b>myD} zHy6+o7%dwu(M{20wH-9+gu3g0{iYzK(`*zO?v5X`7BR=%R&Gr z8z1H&i$jHX07YQD7jr;$lBj>B&iJx$X@RhW94W9@=njGxjY~JB8`edTL0dznA&eTZ zCJp~Jb5)x-p27#U;r{Yom0pkB7N8*(unkXFMqWDBAGNJw8DDU3)OX{G+r~qs(a=SUkPM;;> z6^BD#{+A!(Rh@p*KYo6?{w;vr@fZ?kll3Y*)p2KqyYZtb2eqs1@#!OOV5SGGS#wjq z!Rvx$geb}E_m9)M7bmwCX<^fp>N@d3Mf-C7eFyEtuC(Co(G;YgOETHe}Y^h1BbKY=ZZ%QfQ zj@)OrD)-ML?|(XeCu~)^xA(>cj%tlO7C4qXzjMSpNqB$!*1q9k#qSjlKabCCBkX*P zO;llbA%U_Iw4d(B+97&-rU*nNIPO>727I>Nfk-_25sSX^RO>qISbE>+MHQATw(99V zh?6GQ8X)QFvO=WWwR4Vcb(|xyo)Wf zeRN6MN=B3Gw}J{HCh@_ve*TaYP;K_&+Mq4i-=S%fqo}rGdcp$hi7kGKq!TU>Y_-<9 zb1po%ne5kUB(WG_io$^w65|p~H|a|xst6l`C7%mdp=s)g5~TtpK%?q~s&9ya?h{FS z1rXNK==u!E(l&Q@ZhOzS+{ixRQRJ$Jq2C^m&7a55nr8JX5@Wn3dJ7xpjhqf!7Brrx zHgL7`>axE#uYHA&5{Jx%)IKp>RsZ2I1D{1Akla~bN@s#^{EcPl4zSgL%hl}=5?&Uh z5GH4<5`}1ob8yw^b%aBR8}Y-A4HCy0LrAEosE#S)z+3W8zGf2022akr3liyW7ABN3 zqx|(Uy$&*#Ukf+pz8({Y2=B1Q;3zd_YL!xfyd0#t7R%Z2ModP*5}i5tr+Onjokg_q z86Kl#Pf4#Uk5P8m8l|};FFJVjFQjNqL`G@Nd+2+0eRvZg5qKQb2E?ut_XSZcObD6F-Mn;(o+$b3q z8RfVM%#lo?hm~tF?;#J@J9r{DS6CYHV18(Z75W?nBaMsGN_z6g(jvkQd#`Fi^n(o= zQu{AQdqqk6Vfqpn#H7AbyEdx(3X8GDHJEsvwj3~mK!t~`O7tgD%ZcCXkd>DX^LNot ze{7;~zWkE5-7;R>{MGf0aiHUhG|_df$(Q+*R7Ud)i0cljqi;tw(QyDzbRJSWV(C5n z(01r|~&TWH~Us*4F?F{0P+6qEL;+up!f()P}; z?5dc%u1rX^$}6RB3l$s^Z9V81YzQ7RE6{EnTF~6 z2Gn$i2~j?qBy7_=YC5`snSiT{Wq<|pP((Q3e_>6=VUm|9SiptQcw@G#8M8vk1aBq} zv5q88!~_EyWf4*-n?#ILhZ5FsJ{Ucw4^na=B`;EQ6y*|A zgevp8iM4`pTSq0hA7CHm07(?n?$`f(%!RK_d4H{7H6k_R(=cQRhv7gw8K}YkvY?0{ zNgrPJam;yPrrHv^>I~4~gIlZLsL(=a0Mu)0c%l$VQ`^9Rzwr5%OxI(} zto>~PPpWUZzLPsev9dQ<;aLf?Qaxdj=_%n3Ezn<>3x|9!a1lL9W}G)1d=%IxaQ}Qb z-^LNiXQvmw#zJtWxKG;YPW~LzK>5+$qQF7J+S#&}m!1#8E8HE{*2;!AoYp^))?AJ_ zmduz|WOP&Jbd7`5d{P3DsFMOUPH_$%`DEU*5M+I=K2rq9e#_K5p3VY0#D0^VoIzmo zy9$KkvS5-8o>sl07~S>)4XnO%kK0~dvfJ)Mk3qvf3PycrVKGnP^Sorc__Mdivmd+F zQJ0m4RKa$sHh%~n^tkON3Bu2P z<@b0poZ9R@ZX!0@1B@wGLT&W?_vgZs2UFNULgnmDv*Ga9hfJnbC2m$gixYYIPp2x< z`z+{xF(glOhek$bU|*1t+aNFPS!z7bgcx?Ge3)p~eQ1Ty=QgPq;`i;kPYn_raB;DipCU>KgMRdmMNr!7z83iCTs zFT=(1vN_}4o!-Sh&E(c_(4QWAIezaS8_p1b9V!sD4MSd(PuUfZ2xEK?arRLJBzAC2 z0vp+vOd>nQ?tms-3r z851ki%Zhd1g*fuyRE{w5a=};XGs%hbO^sXwt(J-y75TVl!OH;h_#O>@j*bgnbZHbk zMAAGn1XlBD+;Oc&!BJJqDdiqO5|m^^!5sW^s-7D^EbnkH)d@EU_6RcoE|Rr39vW6Kb!ge8&ryAX>>G`v^e zriPPGmZb5UpcEm4#!Q5V7>~+lS!Ec|)P{Aomx5YaTrgfnU-K*wmFNc)tOl4Y=xS{U zV}AB98EWfHEqP2_fR73_faG2aQp%#(u>7|r%v+AtAYi!^x{uvBm=o;cuSp$RLVnYLd$6WBv91)YOoYazU>d) zOygH*HVFb=qlV9Y%KQxj#+9Pr85?)bMna*Lros*1nGJlF4kxy*7-bR{&V{|&TfoMI zGl<_nbW4yLt_pVr+#$$sY|dhCL@}|2kMri~l<18O+ML(_9N_L(h-!yZVh;;!gKZgu z*(5%W_57q41>&^%7#)U)Q@(3onfip;)4)5GpE-{*5nBQR`-iFY!!O zOtk)TQLVpaM4cQgAEfUDAVzZSV^6BVt?$%!{ZRR9j56PQ>dmo@j!g|+?{F*g0`dT_ z52tMU`ipW@+5`c*_J3DS&c7`-K{|+4?U$ka4!N}jDrKsr>DWw$(1c#kwhW@+-(7E> z*Qd+&VOBu1UH3a|&>2FV_*>=EI}a1#L94u*d%*BgZ0G3a6FQjF8(4yofWXlDK~38c zgZ_0?&*s#2Fvq&fQ|zGuX%p9JQxMjSOB~-NAM5GBkNK>$I3&1XGMTAVJ$zujH^}Jx zcbgjt6m`?O`->yPT=S-?(jSJbpluint_C(6AQSEewVZm41!WZ_K`B!tju=ps1@3&| z!aLA*zyLHD@W4P^9-}L8Oz2YjL%lN4@-%dRoPGkvnQiA|WOtkWMMMK8S?xh!gl{>? zc4fZPG{5K*ROlJ9#GOB6yIf%|{TN%vW@^Ssg~1|buUGV3N-#qKt=MRh0Im!adM{=4 zD||^5l2|WUKLk7S>g{n0nH9n3p1g9w``TyKs`03WcK2vv{D zcT5T*kW?|vp1Km36|KIhCOk1jAl*vSAAhna9spZu&-6v$j)8Np{L1E$>tF}aocEWQ zgueX>vmIH+GWd0Luyb9<0HE>HgW}`_fS6lX7-a5K35Ua9?|qiM6UW(Yct9iF0zv`> zQ5e5 z*oiJ=0-l|CmWlY2U3`4^!!4=C-66qB<3unaLD*$50T0BQ-a3ZEm* zyq-gGW<9aqtSN_BFqfX~))@3U(d!E3y2DGl3?An;YTTD&iyi%a5lWTy^$%iyn4-Hk z8+K}zE@yriPVTIAF1)>qgdTSM({+~#oO&fi8HMJGtdGMtla92wDJdz*0$!b1D>vt- zvvO{o1W=Vv?N$3PH$w_HO{P6;k#{`@8D9LA&6iRg2LfilI6JI&Q(sMt^jfOG?BzP% z?XthQ#Ef!;7q@E3-NNerry~&d+X_oAV)~b|v+Z58?}^gsq>mPA^OTkA7ti>)~~Ac^E7a9 zOcGy8H=w%ZDSeUtA5CW&6xY_Z+mqnIf;$9vcMlLOSa65n?hqV;yCyin9U6zm9U7P5 z?%KFJcc1rsmn!~HP{oh#wO7yiJY!@qC?pmGxUEA~vfvTQK|R&7$bxH{cT}`<`k^;O z!|}`~^z;#*$VK4o03{&f+g$uo0m-fKvFK6fVJH!s@1yGtFHec(>pU~~XC!2)nuZfA zPV^SPNIq?=-?Ar!JP)4g?n`ye4^Kbl$P_AfAFUH?!Q0yFpX6`?mZ>PcN$ST*Uslv zG{Gw9GH+RGC6hsu0_b+VrK3%}#lll?-0#0;bF)Q_Xp?$v;2^Se?6*f2+oCQ)U& z53M^cOwoR#=8myY4^X&NP*#5D?85W?Ft0yV&|6?{A}!X_#az}Si{X-4P4@JGLE`d| z-u*;FUhQ)jrP#d*R`r|T(?&2Qe7?m9PB{9Q^rz5eYWA8P3$KSs+skerv(0~+?9^rE z8fw4s2L|9f%|xk|8qzFMSfhp{Ilq`nC8`XIW5$|(xAXW!^P&|YrukpCZ9 z@-x$^?*T?Mego@QIk|c}*ATeorstlz8lNfPJt4sm#wzt#lu3oYcWYGDF1@ieQuRf; z89nzk>uQP&>)T&(t<0JN)zH6*DhbLR7{&$Y;-Nde{9-nEzd0?orP>~jMm(NwG^wi! znD=?4xS(P^m|){PH(aEVW_$v{IZ^;6w~<+Wax9QBMU}9)hv*$+oyjcR@9d}% zI~`vDadPA>v)U68M_#Ux!O2ToGOUVTo!>^Se2w*VoF)S(FZL$ux=|cV8MU0OFUw0Q zx+50T3GqE=OizEh&MGM5gfM~onK}WT;Di(LfrSnuWv9{t#C_!lqe%8WpfbC%IguE+ z!bYOm%_;=&Lt1-fqb@oHi4)-fGSfMWoWL-9)Fs%nkm93!H>r1AH|pCXcrfuN!F18q zod3#CH*Lmt8?nC$#FW&@(p!c9V45{CW1n}KOnko+zExSI=Z&CUw9(l9jTM*d=FyBu zkhn5B0;R-7AaVVqC~A-H`ZXhBVN#`3|FnUE7@a^)bXl5%xXL7PxoHm;h$f&z3nYpC zQBFKU>h1iRX_|2z+fB*hvGa8|BeLgyh_eGX)LJ5udj{mHj$08PJH29PQl+j+T;dPJ zX+XK%2xH&0E3*2vtojprw*MnJjo))t1%XP(U@vs@(#BqD|5Uipo@~t%s_w(-)V9d+ zZQ$ysL|pf~FcRv!Oj&@Op3$^F2dx&HOLm^jLp$4S>PYv*qc!nsU-6F-yy%PcPP2mp zf6J`*iojbE=y8s*)oO=-pwJB*?W6(eP#APX9Yvx!+mWv3rr<5T-k%4dpUZP&elVo) zyuN_AjjKa!syZU)4ZX*Z35cB!a+@}KklQCKL$-Ip{PRsGsD9|gzN74X&*7A=3KUJD zm+s>FpE<~7c`2o0XKpHJY*&EZt>_JQ$J?tnt2rcaeyzN!v(n~@OjLyV4sYGl;wUcW zQm{t;%)N|)t`kr7mleOw$T}8u2TVHOaukkwAD>7Z&+RtykPj#pVsXl?Pyv3b@g$cp zE+`$LdFPnz*!})QM%HHgf8%-U0f4-9F+`hva0S;IvNOj9Ob2~lANId~U-y4|Y5#AR z7WU>lb0XXL?~&b`9g8mdTpj3h1qfiFFdK$`50Y_YfLj{Z|M_1lmOq`kyBaA!;JuFh zycfA{L%sgd%xu?V`{j6S1$t(&**wp2u@hC!eo>Cfo#<-a(cIx$*l+WEXjnC~3yj^cF>wJF60v$2Y z2b&jjAbnF-umVJQ2tv5TBsrPQouVl1Ym9KhfQ$Kn!rMK>99O+8XxEXk0FvbaL{1#V zf^amJVd_!p7!w`B(>Tz}emMYfRzpevHC~&wjyjd|{<7VD{YE?{$dexm{n9}{&e~-W zCmJOfOB_ZdO&Z)9CyaWR?acDpypC}XN$owK>pbgg!C`ElX~_Si7CE%2tE5Txg>fwZ z1$G_Rezu5&Bb^%o%oOouI3YVFs4!}8JA)O-JV4GMoN=pRcv*gk*|Gk}QTr2#etQ}U zY9vG!-$#DW1?!e4VxCIv0tTQZs#V04|1(o-d&BRV|OXFN-sYEp| zRt0F$SLLDE(_&3hDp$_=jS{M|3wd!3J7-OsH0-80{V2~Y=%b=mpIrJdPs2drS>Oh* zV|+N78`Kg@B3QO9jE6H=?;~C)5(lVJPl^;N{e7z&e3rttn7Sj}R21iiOx8PmXCHy1 z&2G}5(sx)+6hu&OyQl)(>k@K$d8Qm>sp=oQS*H2vNg1WKSX!Hjd8*5=2Te&DO3=Y2|n;(}18FyYNiiDW;L^M?g1G+QA(~4LQXK#jE)@9>;lukL7Sub>?@7&$j4FvNC9bBv0 zh5m5d;JJcA6YHXVTsiCZ5GR4de%Xb|0*_U~%b0*>hDF0;3xV63Te7#C@0U}L>g7D3 znh8XLl;7OpQ5A_-RIgLDF~3PoK;M)}59=YP>hv*iRl=k$YXqMDhx!KYbTW%93>Lr;5g5pNnsyj_I zE;t=;N1On5o$C2~Z2$i7iB&m1yK1*CMjJS=y(6-pZ@$RC?s1w{nrFy-H1@u?dh9m7 z^6c-h!naH~F6SO;n@p~`zbo}P9q!zIY=>-#h7pG$DDo?Ha#pQ-`wMwI!rectUbK+f zqmEp;)Kq+b(pHRy2P06uD;9_qeD!Frw0X~br{38?>;KlC+)y6y0dk_yvFVNuS`~V@ zp8jeN-pP3U30*#MUyD%Am)5NCMBbYKW??Tyk*cro0PM)F^>N9D-I|CA$_3vt*v>e= z`%Rl&gSFfT$x8P;?O8GE6=X@`|0aCf!|?C|Mng`)^(y5>n3(_lwhOM~dIPkCCTl%Q zS6F&y9dBk>S)SBb*@{a)9sEbTQ`YVJbji%O`@!?ycdaq$z@q7m2Zw{aXm1W(AZ?OH z5q+<0KW1KAaT8SWYETk`%)q z1VxH}$_`7uke3$GgwSo@uDB=(oliY!4pj)ICpj8b-$M}R#n5EmG-*i zXpE{6_OG6y!mx7%8WECzrO`eAAe<5wjUOXL3n&wsqU9 z)DtY7wRDu3-QdK`ldM5q$OT(5K{r%B?vNyrr>3p05{(L-Gk*NN{_pII@o;Yuatg6w z6$&x*yZ=BmZvhqfOra2R%~bU@fo8O1*s{o+lp)h(BM#NL>u1NoEI%pz>n!3Y!%9(m zBFT`}p?;-A6PXI_MjlfCQReQQbpXCfKvcuUh>^P>B4f#p8396yBHg8CZ&7#Ign~d ztxP_O-cc`|En8O}(xa~dE2zsVg&YWs^GIIR}bgy0mTv2=CdB2KMQ z@%y@5<7-C}-QWb4b^+Z3+c=}Hk++U1mc;>5(sw#N`-)1-HzW^Je%l}tcT7D?_Cp>m>$nXt*w**j1j{@RGzvVmmUXi+e&+M;> zpJczt%+OfIhITPnCfBupU_RFFTi1wA&;(rk4ao!pHz>n`RQhV|})lZjZ znyuZ=WcKm;Q_1hRYT+{JtTL|_!qjA-Whuj<>lyro&|Z+*g5sD`TXd%-pL1DBJC%=z zT*o{XhItAQ+kGJ}3gYkFC+(fgHzD4ll-sdpNo)w<*Gi~YAI_mAj*z6AMC+h=8eDS5 z-qIxtyx+^mh=hiXW}4r7nqzdl2&4ZhPT7ou`#e{aqvs(uUg?nv3=C}iu3k5-+2zUsqEHPc@;F! zZ5sdMJI;>-U5X8EchIldL1-Q)+82pSwmv=^r<%|yWy-Zq2ra~ z#S4|})oa?i#M5!z|8&=^{f(RZ+5U4+j)~Q>9E*eitYq~=Pa~XR^p3EPt1bblh!3Bl z=*zW$E-^rB|8q-lmi>V8^G2jE{TnM@HwCTmBo=C`}Iz_c(WX&5LxTuNFOk7Yh zEnb1ZYdyes*{fyS>mwBBV)m*H_#@qhng2>K=bb-E-lB&7oiZ9_RJ)dXej^0&l`tMl zxFLjz!h}57)Yy;NvevtykfcU(Dq0qvwoNZ>1Wqr1f14tZ2`_$+c)tfx&`Q#NA_@Tf zdN>X!iLerrqxX*`%%x>P1!=q@gFVHD6_5d91`}V))xSF+WJ}N{){w4_M(l4>(E*Za zOlh*e#9^e9YRffG_Vnqod&B;Z?M4pz4To&7-A&l)BA4V3w|$qpBkWE+!3@i1T1>yV z4{zU|r9l`U)l%z0M$o+AzAt(Y^PL(WUrX?F9v*?}g>tVTa*52@|L~X%pUpN|fg?Ty zDYIN;_h)nX=JM~1B+=O(`7Z)Mh$;`7@S<%jQBW5$&(xmmw!)ty>Uee=0kHy?%%je z<4*-!GJlBlIhe6Syyf3eBlcQJ;(HG6H13p`fK>aAe+hfFplH~ZMJzZAaHjGKB!uI; zvAJ;a>x28cJ1TyCnjQ=IB!)e!xK(mNg2X&uk^u>2@ur626uMu#YhyrGc3*k~S$hz# zq1Oji(HF!l|09e;h{eU@$i((dN>+FIglH_FFi?wC+SuKv8oQd)hG+cj?oUm2y&q(2-BKHLEf=P1h- zjaSBob}T`t4m5bXpmV|ppnsmmfXYvSy>)9Y0z`Kr^pbWy4G(!RGVbQo?H|x0g%0B~ z$durllN_7e@=i~Q!+_z+E5BD?N`c$OrO>%UkaPm7zcAQ)_g@n1C0G3pf>lXYctB(n zy>hX&U4@mkl&9rZFCEFTUdYmfDmJ3`l@`*5aw|R)Lb&$YYT*0r7El5rcO5%0&0!h# za~g;x@CiKEmTA5|#_!g)TfdVU|1~HP#kqnTWus(mO&E%D6cl~W6frc_a@~?(?1BEJ zTt-CO`>TmgZ#FwFfqty?ofyQZYKnF{KA*M62x1udg2qqufDO{tR0HRq|35hk_g_78;9R#=A%4su@R((b{>@9D}9vgk>E0%9p6g#jfaC}4Mvj_ zn!jV5iaroCy_$?fcCFN6R#^A+3qU$q`@hLLIXsB$%tcHH+Mdz~p&E9x*U zCv519+Tli+-FVcP*jUaBRBpNNFVcbs`YjrOhV58J+L?04KbOlhOI1l(`o9=1vspW} zS^4r&2To1=z?iD$d!->WNB3sdEE*o2n$o9>u*D?v9}v#61F&K(1Gdp@0-8M5{J)$( z@DknJ?cR!i;(2E$hyr9$(UuXAahbXbWPknU>TNiR;axi)pFz>l&bT@%49hRNB=Zb6_A`nYrMNf)mW$UQ`wYLLwgjVmDM-|wp zHx$$u;qmrz$8A@S!`^6fd%UQ=G<*(xnE#n#;3Ye>KCkBzlhX2|+V++po9Nf`SG<@I zWW1y1CE^L`R!ffkG2ZoP|F@_0$7RTC2YEvHwqp+x?M6|C{Zh28_jU}gwb0Z2D~r*( zp<_4j4xdqV>P6)}xUK!Ky8kxv|93#J!d};t+rda!Y@U~YiccEcuywqkD<5u?)1B<|(~~><1bJ1glJMvI z07(0{vDEBVG4Sm|W&ELvib}L>w%^ZU(q`!h3Q^xTxXVI&2FGTthmyV+oj0Fr=@L5L zBPabyz7rt}XZ0T4%RYh-*L^@GSm^sfC6H+I4yW`2UPlShX&FOy(D^DVNULQaF71lf z=T-$w~-Vv(9L3vXXJ81~IL@xQvi*8PxyaO{_Kt7=g+}O>xpQ=QArO!HJ zl|+1qvi*iS5*)MtNv241CyK~9(- zLE>rqrF1)<12x1ZcKM-bCGQ&jiY!Fr{sET6i4yqce=0Hnr6Sa)X^g8PF7~?sQIScS zH5^1xX-l%EVvJbwE9A;`iX#=xEK`c!Dd62Qp~Be%DpHW}h=larcvj&HE(?=hllKO}f9TyDzs^UL?;fOt9q;#RS^$fN%dtoo5odb4! zZgbJ-B@0m$Jn&t~3%m1Zz=FlG*n&l8&4Ptt3k=oRJNz2-I0WOq1K%kJ@M@bEKd&rP zY2)jIj85qi*@{RcmH4o9vuCUywcJosQV;+eZcBD6w5ZCmod5br-KL_EuR|U;C1x_oCUqN?jA@WB zw*?AI=1`$1J#r;aY+7IYsPC=Y+rnGi%PI_abUZGold8ufI^*+jbvz)+CiuKKILO`u z<6G?LL(-kL+dHtU&+TQWQSTAAf&AD#d$|+XrUK1Asm-|m1FPxh#N}7FY97Alw}sXZ z|L{jv0DRL5hZW(E?lSMGs6J2Tgtd~Ly03KSA`nA1iBJFif{pulXIjUS|Mq0yb~0-J zqt`xq=k@W2P0RHx<6%}-WtCwJk)}f>reU~HmJ$*2X$O>L0&L&KoLBTOOV`)Fbr(0& z=dbL2Q^*7&BBr#9P?X`y(hqfA--J|$Zf44P+Q#^^cX_t`dcU!&1d$b=Uk35`Ub&h{ zB0r4YJ-Ul(&`nkIBZfU6tn(slL()#Lea;!&5F_f2n5%h z@Lgp@b}IWnyN#U!VGT+DHx1 zK0K=7xAVH+47+KX5P3SNA-C0iXw6!V&UTyACiI_G*W4^E&QkGLZ32GvdZErjNqDKc zADOi+=T0E)G@LSal8e-Cb*^TeiPUokgL-_@Ie}U{@wbHBm)sP6=Ch z?8&G^zq*~oY^yX6&q+qU1IcN<9kd0Za;%?qdMrr!2ohF=+8tJwJlWfyPk`DuXwBk$ zxs+!I2{;0*kMq~}(n08!OpzHL-qA%7%`vk<=t4QcnW(5fbl{U8%bvM0=-FJC8cn{F zH{Kg_+`f;uH{$R<(+~d>&Xk8)as+s)D>wvww&78Fz7pM-BPb67pZfiCgj6BtB2tK2@jWe|^w^<{_t8_YGc zjZgVD6JqBGlsZ9kdAkP*j-R5BdlbIS*dctHG1zv)FywF^i`d?glS&AoJ^;(2mr4(p zBz?G$5s+0Aij%1fhhQDi4h3m&$w#5o3pgZ2+;LqKGLmK`#eG5&3+?+nLi$ctRgNs0 zHbLUqHJVb56+=7_0qGwGfjaThDW<Z?sp*S7g@`;Z?}|N7m{p}_*BNDGdAz%ODF$)Vv7 zM#j_YD(YuRbh!VRne2d=T%6_lBO%=knGW0>6{$JNd9`I_o^(tI2FyilF{YHa?9&A1BrEBW z>#~h;oZSLU4`JhbMkG`#-&lHybz|`&&bT%wo*d?S1?Yl2?K*WJ&rH$_Kb9U$yli(x zYMl&znPu%5k0x&eDi_FBiAfwp*_oa({4 zgDSR}CV47D(sR84^*j+hW%Ewv4P_PzMVjzGAi+2ZMLz^t-u;rP?wKJQab+kPzMws= zo88h6aVCtuQ8;?}KflDyVtCyPMN~5ds5a!(bJ)s>gWmQn<+Ot9HD??*8a)l?gJLNGvk1 z&#G6<)~{1qWVqh1-o2=Nrwb+*mm{oIiF|bolkeYkx**y=Sb*1U5DgePz*PoKXrL#q zPziKlwK&e=b`Zo371Ij-hSyiDN8UukRs(MJ>#ziq!P}E%=rc`B|5$@r9Y$LbC|X3= z`CGh0W&X;5hkkd*!sbRbi_sAMyn#1})M7L>7uPBsX3cOafo|++9gsQ7fm$;?_tMh+ zrWJTM|G2Ly`_sI>ocTjXzP8z4fH|P2Q~6;<32I{&Wh*)nUp_w7ZXb1FIyNQElr4Qh z=5BM?Y6mk(-ih*GVP-+*Gv~9r2TkF_KbHl+6jfZxz$?yC1E3Gj%0Ty;>bSZWtp&{He?NIl ztMI!K`#E;jMz^jvBF7sbfqhCga;Df%;yaF2`2Ok!KHp}U95zT_+#yWKR5Vcyr=Age!bm?Y~d%&+9%koi&U)#mSgVP0MUIoi;)PvFSG5 zvQiH+xRPBLyS7?(nC>?cqwX(MBr3Y?o|9s&P$Rj@Nn&TyRP@|Mkqn4P<{o#vG^WIl zB`ex!Vt$n>YN{Z%81&4;`<(0tTTjMyOmVslO%qGy$>!!3gc zQAH_oGbdZ2=(UEVj2w@;qg)fjPrXl#K#@KFkkYiqD-e6HI~}t*e{Ak zyoXWoI|(SL87GJF8Jgj_y^UQP5~wzWXehHm4)JXsjbbiA2vdKL?DOpxp7>*yF9kk(VDRO%6G9NNgUx>Rae6XHg~XygbPf z!rWjC(3{6FohHQ)W)q%ujNyve^?Yw;-PWcdEpX`nAk1c zs!tl1^E6pqNI_)^R8Jo(CNNdfVRQniY{_`w6ZH@iXFaP%*U{Rfra8uzx_}eApi|V+ zDLgp@am~9fPFAJ!v<1q=f>qze`Mv9(hRWU)Z^Sj1Uq2-nv+A?{BVwI*qW#~|7XBG4 z%jdjlgr(Io)m-dfg#C-yLpK7WF2Uw9DFU(M&)0(;QlPgr?CbuJ6C;{;9~8brj1U$B z$JMK_vzH2&9-7MDszav30n$V_VJ=oem*^tbn7X%oY|QrZ{Mw~Yd0h6|6XKLQlMv2)dYG?2m503+6{ZtlOMwwQZWH{mYGVi-asigp zmF+BTSmyNnr3J~OBN-9A`+7!VXtfdz)-j>WuQA?NW zBSCSM-Skp_+^y{pjyejY`(DXG`&F`t-{dpr91`!}ft!tg*n1~s;79{fEHzr@LJpsn z@3uW10#USjGxI(KFW-?lR#jj*R5Sy;hAA+VKI!NN)z)IV>2WE^u1b|X*C>9tjZFJ4 zrGTlV-<*U7k;>OH;8@~07mza!q1JaqK@26Bupz}eKHTs1wpagB%So2Je3GaY>c>Kw z$R!R5vDA&-K@ZiY#iPEzWjLFaVcLXowRtI0$`-(pUCdf1&`aZ4J?Xh>gVXpXu> zicSfsjjTc*`HKR+;oIr%Qj8d~wjN3YOXoK8!Z`|vw{+vE$`_uBXZzP*Z+V6NXx33zjs^pDg)ao-??j`rQm8&4X zMCV^~sGF)-*FElq&k+ud!bpmuV07)9cNxagc!GTwPB*GsJoW;5g$xO&EHS~W4)SSn zWU9fNYd;jyO3D-VIy(-s=rNnrVo-n%n33zkfD!}Yg<0{ivXMv%l{ z>^-}?81v=Td%mrokHKN<5)hVNwjUXsH)8$Sar{!u;}xvH>q&>%9)o{z@nEKzvoYQV zL1ESd9A1-5+ia7Q8*+1b z6okwh9>;?2lFPzon0M~pX3V@HB*x}Kq2AB?G@3=%b}vL@U@=4COMQ0`aM?OU zUyaD>4fDu-v`oV3Hu4Si%1sV($=I2j2BHnXoP6;9b^EUavDi!`Yx6KK;jt34{zh`= z#j^Z>_P#;I9Ai_C-_?!g2CylTGV?5D;d%1eQc0ZGU8cq?&6!CI3Cx@0gU(3Q^oBd{ zP<4i_ZHw3prNMHIT3}44c%m=fwV_U!N>6S=`4jW~2eSYmH(z0#Ta2W&j zua6@s%>9S7#4(GU9e6cP7&u>s$uK-F%=bk;Pb5G@1GzK`SHQZz#)0nFWBfNNw}L#CEM#jD zQ^`v`ddHkFzp|hM4%?hYyV?++v|Wlt z{soupmzfW;ia%hN?S&0GI7jcYn0q^NVvm&`38Y_aNry*lVV+|A2Byjg!Ros_@ILVq zY@KooJVl(Wkf4_@(hqHGbybU^dS7Ui!(L>K(Pg2}S=&6YjjU+{UfOf9>}JZ+bKPtt zyW0Am^}Z87{`jvod%P|}zG*8LS-DzO8!GS#@}lPtL_>adQx?P=8|u(sQg%HCQISMl zxr}OuzH~o~x=4&?e#a*faO*D_ld@SAeK}`-^&Gd-Y7E|yClKXF@E|cV2oy+tMX+zW zv5#K0ZflHtkzh)Cih6mgXVhTQEqb8fhike>_x~>QR284}tWdVg&uC%t`BB!i-&l4= zY9MzyCqF@RMm56mOG}|j%^WkkDZaH8u!^$m@TfNB$hYY=@PQ#XCiCH;1u;x zK!GnQM_2ae9i>}EaTj?kwNIe4NVrCwkf>62j{f3Y(;s}|G}T!tsSIsYQQQ+_DhpPL zRW?dkth8Ip)CS6J2|61?iOoYS3N%(HQCF<74js=Zng*BXqv;o%TT}<+6n~-qnqj@# zKw>qj`t9{8PiA~JIgd*x$h%nSLY#5?k2hJ5i{{!!hz8k9BXJDYspVshF7!Z;i0y%wtj_Hjd+AOwC5}8#1n+nv%ucG z(m_6z55pqME%~unJ}vO-?E?MgjkKwMP;^`nou5GW+sl0~IOksHN z_9bW9KgCiK1-+shv|^8>r1!6L_nS;GcPADqUmxRk+Y2_{7*B89T$bXceBa!nyS#5z z@Y^;s=s5FnBrmhUJXqrn6nl}+o?@_;)kf)*FHd~Rg}ro!VaVuw$LX~Ea>aeN*Ne>d zqmGN-?y-WQ?Zpqtde_~F?V$Ikg7d}8#K7OlEJ3gYm}T$P+U{ra@Q;-zU|vtO?mXIU zWEW82ECSxRl1nT>@@DNzd2fYNOy1;s158GX{npUA;0$^_$rOa>I>XR`?AT2mlUeky z^`)5hlBULP<|L^&QjnicOD=V~ywKf>3!yZoheUbTgy>rv=6yt{oi8w1O;VF+yIb>K z@Pa0Rqn~b<9cCG5&dm0Q@2JmIA8O}-A5{6h(rmhf4LI&3NSECZ>y$PF9mckWqzk}3 ze>jru)BH=9G!aqhJt{N$1)Oq`vIdQ1Zi=qS)L)i}&rEW1{8T57^5zp+AdSWUuv)Jv z|Ho=4;y3Vraa(msi4yRAx&?VtZr*i)@sF23F)h#douMlGZ+3O(?rM>|SJd`=U)A1D z9F;7!iT)45@vPX`4-4Q%z4~x2uAfOLs$q(vIC6hI!r^lP^2EA0e-X&b37|h8nACee zuGFcq1wz*-c}tZLAQ!~!x=h43@UGK}gB^(_(=Bn3xQrR7s3!9lsi-UB#xtSGj8t5e z+Jshh^z`HD@AOxaMK9TM>N#$P7|@}zu&wzm+j)^}5$!T}hl+PSP>LB(6If&h81;sE zvok}|inA+`C)4gH)HM%(1Tnw!$IN`X>)ZxDv|Sp{p}^d(WBrlhQH(C7uj*Qd*zbqT zp-3Be^M{^PgYe4YR=(pyY+D|Emzmzj#@!M=hjvl>4w7l4M|l#xj$S?_;0*OU75|B8 zzZ3j|1dx{>kihF6I34#p!VfHa+>x~pRy%CJf2SvwvMsqE2Tm(3;4PyuOOg78u0xok zc7)_TW*-7mYr5i;I+zD~`l<2RTq%AmTw%MOCGn$)Bv@UmEX5WZM<#hTsHZ#!_pj?k z9(SoU`1JNW>`{_`ilrEhbBKFed!je+-le98z+HZwavo#8wCq|NMrK#35eDGOf21Yly)1dJc{=e^#_7b#|_e$3mj`H2bR_OX2<- zQA~bq9;W&%PPj&j_4Zh!;JZ=)AjgvTEA`9!SeczUwT|jsSx;Ev&KcQYN>6E<`P_uw(Up*3ji)>byPEzC-4wzf4HS33;zZC8NwyE zwvq4!V@_fVQTBawei9<4xaCl!G^S)~m>E-ZkaUJ97EjiOI9o3hKzG@cKd=(&Z7lP@1(1T>T)yu4&j#Eu`mu8(45H1M$i z+E#Ha$= zgSo^)BfiIe-n@UeBieH}u`u3_>n|mK2U8IjLDqY-3ZsGLvlL?bahGv3GI3{p0ugIu zKeToEMb&$2OS;B~zZ)9B?Y)}%8ZnwlgsnjDT!`q_Tfc?Tv>)Mc-h<5gwOpoa z^Fhi}ist0jQLu9Q?FZ6;1E=g$AZOwiQc;LpC7u~IozXC_;YPTLQa23@{3oh) z9OC86TIXjT69&?@I}M-f+j3_^?ZWxkB1AqQkpB*C!CzEZR5ucCcGtt${DnE4$OXfv4pT^*LV`C>62^{ z;$z|7qm4z2Y*5|zBzlXc=UeL1AY24lMXT_=fB#9^E0GM`PS)lf%$V&tHL9QS8)C?Y zP?+9O)M*=*Aud~Yn)|lf!{TfWWDYP-^~V(1uH1eX9b2l!(7RGHzx&*Qbs&Ssh@r=H z&lJ#y`)W|AP8fIxsXvl=kFuRQho3IjH55!eeXe~81WOM3D+w!t++KEB{kxMi4G#PN zqf|VfQC=O!{jcmHg=jC?#VZ|tI9*)j?64t!j*utmG6HPt&_^?MK~HP`*Pg&31IAYp z>QrN1r+bh()oUb~_oBW;WjBdk^ou-Lt?MW~8%0Q-wgA1@l`u6q-b`1idps{vf9*gD z^IfpY;Q6|-nGyY1uYPryyEqt$ohN}OL6uXOc!Qc~BQujd?R9O*?W6A@w*BWnjx4frDWwl3w*LObkts@C zD0ur!>~}1i+SF?b3@=qdLmzd5)HVpBzMUIc>y39}r~KYsxjJkV^E;2`nsXU7=GK>~ zp$(SI*LiI~N>u8Qd} zU>^AovH_7tf#%b%H*9iJowt7ns8TTmQ6#iyu`lQ%#E?u!21UMY;>_oHeA;gZTqE>qOVk$-xR+PqNZ1rM5H)a?{Ne(sLTqz2Om zGL@fXO1={v2j-*x8a0w7sYvlV5mXM9PPP!ysn}cw`*$sDv9wY^v!MN* zXkHB=z0ELV8;sEicQB~6GWw^JfKnS5i9db0DM4I)A77wA4bwDT_KER=z~1!bmIc3V zvh=Jj@jekVoD+GN?}*>FIQshIs(tIpHK}J$FcQ9~U)$}OqToq^uY9?Mp3rxLBDbR% zSwI@7xeV63-$*c;8)+%2n@xEc$o= zOdeUO{H$)4hUsxoR?a{TlK=ZvSyjEVvZeNYgqEHw#}&s0?=}eUBSw{}pjhvtonbAr zt1Z!XkI}SwMh3*P9$qYsG54p^&a|hC`0j|uBXpnkFEd`Xy+U=V^UH59%hkY>SctWx zyN<)wje@h2U!pH<^}N8;oDCjjnz0QV#<7jg33zj31JIL|!4btp~N)#}g@2{!acnh?MI%*h@XkoS? zx?O55vh*1*%zbH&oho)PJU(RZYQ&DQlehue``#VNK~$JJXwQb!>lO5tb|Cj`5rYyD z8C=m5fT5AzD&lltwAUY_J>B$YX(_v^ztHJrRrYQUq2J?n*R1I&0nTkF<6XwijCPY1 zO1<+m$R)WY_M~p7wbuthO^xb&bVTk3%!I@f6Oht~qax}L)wx6ktsQq-c-LFmbwm*p z^O!F%$5)sUA}2~ACMsF>J1TsBkH&5>PArW193x**+EAa|WzRf|pBuhIv~|~*-2$y_ z{Vjh5xHE9J*Ae}yPFeHD3%{&7 zAjbV4Yhd#YOT#a5@89iN^;Cevsm?ib*xpZId}^BfCVVaiav6Wg(rw%DZg8DWeG(qk z{T5Z#!Kf+6u3D^VG=*s|W_&wT{9q@7Xos@$A<}Z5COEL|(SZS+#ApBXrNZvLBHeF4 zzQ-lO{>Ss=Wu*oOqJdZMA6+!Qe~~v@%$Wz7rioq8>TvGih1O5sj;|)#7j6*Jc|`8J zU}jIQibXd|C}X=q_Oq*s3i#JnR5tzsy^<2;{5DLqF}SM!v#+9+XoR}KOUB0wvwq)| zY>4pmeJ*sgfsXGOu5b)_VoFp+W^!l$GX969LU6iGI2%}68(|}JK17p0exr8YFKjb2 zs;bX3MK8=>&zbv`#V_>DZ_3~CHso#KAw@sP<;^o`;6)-8jo{ zlw(;Zn45j8=9Lzz!o$>-r834jFD&~QmtZUYH;DRsJbpLaIn`GW^ltGbydo0kn|Vp^ zJ?dsUe6Hmy{6(7V0Fc6`DSpp~uWAC9_tQ?p+WT9;{yft6R`jE;11A!&iIJ%4c&V1{ z48Z4dL;$TBCt!e(~?H2A+CR6+@uRmxZ)G&)% z+OZ@;FY^L2>0F|mptp-6CMc>iO2iE>D`Oa&@Cfu{xm>zRzy zG-}zfc_kLVA16!d5rR}c=kEmE>Ta;Ee;pW2%f2@vykeIZ-L};ZwTh5L`kKcZ_ZuUw z-%LbuHd6NU1kP=E046CF`jxiDlvb+qEUV&^bZl~Uzn8HJ?LO>PZKo}ns%T^Xk#!vG zO_7O+9Ewq@X9e0^4N4r8LQ$YN3kUBPLNQn0O)*QuYc(z!Z`L8Dx@ zT9@T1rZ`i)RCWn1u50W8^O#w6sFA8!!`Kj>g@-RMV?K?VBruJIwQYJJfy@k40${Xh?9oK?UtxVi% zm6BV;a_7dQ8Z-lfL_5ESSDO{r)y|7^VenQ1UUr{uRr^m(Lyr&WU+?GM3?d}2EWVCY ziFmzn>-jD=H*F=lI1YLGch9~FC`Ir$G|XlVNSU|L9!Z2rit5C!bPa#Gl*g{O@o5cD z&O3MC=_{Wjq5redXpd*$nvg|S9@OEiVB6$2P@!En!?1d^(QJ`D`>^wktc{e|b4IxZ z4(II9lf>h&AJ1ug{WX-819%8RXBaEnFi8X(Y>8H9C3Tx2&^b_sUeH!5uggt@X1Tbw zww}NH-wW!+^-Ws2W#KwTS8ZR8A{##v82qJ`)VIG!8U0BIJ9bdHWQl z5!N(5A(Qf*QRW*>gq7j&4Gm4)wm6!({p8iO9l}HfCK(P28F&hQA9W8X2t4D<)Oleg zxexTvroCsE?OPT6MHkkIae>HIrO4Z^1HxKaD)d_KCh)CX(cZKUgdP!O)eO?_iGg6K+X zWZ| zSw=+}u3cD4KpK&52BcHEq@-Jr?v(Bv5Ri@mq*EFR>5d_!yJP51>8|hfob$~O{>@sm z7VCZ9`?>et*M1Y66WRMrx#+eRrJC0edkZheGlQ*gb5Q!bMBK}ZyClyKq*m)FmisNk z=PN^i*GB)?>qWdB%J@vkU`esa1Nro09r)R9ZK2UFK zm)aB0WoI~XDWO|UFM;M)dL8VU> zBH*~pA536sxA%>AkyvoJlJwb9vafO5s27?R$8_!5fR2nU`ltmHYU;QT{6DZ1}J zwkyYM$(YBGkE4nVge(p^_+|$<-Sx^9$QhFNlN`I9uVpfATT+tEqKzo&y=0x=X|FV5 zFAA!KQ1vc&cHMIuKtd|xQDa*2J)dyK+t+=I>}`?Bu70BTF7V8|t10VZ!G`%@udh)d zQ4Q9^4!|lVoZA&~svKQlr|SGT!(8;tDzkoU$h0q_(mByJo&yuq#;#C_Ss!_kmQ+Cg37 zJ?>*$oD7`;>=NQML(gJB=hA~c=(%!`GQiCqX9Sgf=_8=gY?C}t(#0RhKQo&yGfGJ+ z{c6K#X6x$=#rq`odsyDSqQ^yJ>(K2ZOkUm)=kvgm-arH{_mKqQ-QuJ7yUM4?osq8Y zo8^e1QNg##SuX^7eiI9xds*r14%Z(XY=l!A)aWSZR^!bhRq9Qg^wZHj^YdH}Co93G zB04c$mA;}g1lm|_(uFLEzfrv*I#(XYjq5arV2_HyOz%bOXulWU9VL-%yd}?zk;cae zrrEIRp}X06cbQUCq)<)#e^yVnt=RA&Op(S>Ih=;Sf)8x|6D$@@Ec*q?db#;NHsApK z?$PARw)WrhN1R^OH2GttZAxVd+dhgc+G!xrMg}$AdBIv%=d5A91u3jU%)$-?%@4-`xYhk6apIP}sI zZcmWVa~a`wqcZ}IyVtpO+n!hZQ*jC(vgvW7>444ej@|5;X#~5kOxAsRWOk9p`p8X0 z+xUs;(!6*SVa7=?abJ}7jOX3R_Q5W`nlC$yu*4?5@j@)m2Q&n+>udPx40-k;*A9yq zM0}0a-@~IjVbXn)r}*GU2<>h<5Z(X&HqCDPD|mykDP|s7-*Vt8pWi{-?RXZ07a*M9 zGchqajl&@q`-20}HvNSkj+&)ruEK2!pp6}I;fMB(IZ_V6?+6G=X>*5l?*aqimwaBH zn&%&-O_ih=vQjTf33Q0EMXrR%+txVQYP|`YhOYUJ2Ibqv2MK2i-}bug?EpS2)?)wD zPUL2XXTV(CrWJ@b=X9$Ylp83X;q(_;Ig+0l8(YObOEo;nOwiEeXj-q#p$XzM0L6}% zpwGEBuE{fD517HPf-jJM-_3cYh*}mFrjn8x4g@iSa5|`vPa=anj$>H)S7~DPKm#kd zt`XG%i;{$*&vZ|M1-K{;J(xeRI+NaB$MR1&W?BBGPvuXLqgBy;Cec)AL2i#2!(L3B%25 z98m%ZlH75wqUFD&KA%0Dteu5Y{FyfN#|3ZZlE@B~QBgkOC(+1q%HC>NN?@Y^Qrg#H zps;dhDXd>SdONo*(uM{OH?mO2b460B&BLjhZBIQ1I zv5nUkFqgUB8l_{0@S@eh%0DQ*3!L?>BMujiV$&h1y`106Y2KQ@d*^u^&3ksp23?y# zJ`tDF4mJa6cc&*)OSrKw9J*Gy;aVJW4Xl&d2|amn^7#C%5p8zej|hAevK2HI5^&%9 zDNuz~n~^+spddQ6P;_KC+ruZw`n?>;HY7+@9%Ee0JI{_CicF#O)-ZR2-YhuPY!UZ5 zE&al}a3p8Pn%buy+o`iN5rJU})UOAkJqPS&`F(EqSZzeSYf1M(X*4chdB;YsS8-ID ze>4B30Gvj5fk`#xel~EVrV}xYj@ZRd$mi-pda?U<`e5|(mngtOv+q1Fh%Dez;NOP# z(n!0P6@jyF+l50XX=>`NBAc0+DK7ujoAtxv<3a@PO#IxpDab0ugF^AA(jyao-d_Y` z13%wH_ZIl88-Eu(3gBtG5!bZuYZgFnJ;VbatT&~0WvsS$!q}E0h(!IrXX#gSSjdP7 z)FrxT_C+3VX^ERz=7Bg~ojj?0KeYE&`Hcf)T&kXglH2$Puh05lkuY8%ODtj1QFz_m zIr}FSBwi3xXEFyWlF0(FjexkbEC6A4&R7A zpCXJ3?~<~aRSp!UZ;04o$b^M{vAIgs4y+c^k&={p&h6f5%Aa#w5e!Os>nk`y*+7ts=uE@ zlEL&nPqqA90aNTpB)PxpC*wDnDp~`V z-C^aUxtORtzO2J6UH(|L9sG8SAJ`Ilf$+^g^DKchsnd568u$OqxsF;bTG23%e<cjuY7(z@$D$RX|Pac8$Zrr_I2Tl=Js7$C=pk5T}EBNQ5c0(@J;|DMH!D&yLKyc z$reejPx6lL&fbKFjqvknHx>y{w5^pOru1_=AQ}#)nD%{yXO*-&1k3QmeuD?*sgr-! z`EcUX4wNh^i)imtEvImpy280hd@RZk8hi6;bKV!CKVI+ig>Bk7_D^-U(@skngX;*( zsjm&i;>EexA(bKc8ZHaG0Vnjb736ugFMakng(ZJ0)_OYK?P;*&f~#EQ7w-T3EA(`d z3u2YEoBiP#5aQ7(pf_|SgH6KuHyxTWi^0t%cKCV8tV~j}=7^|URH>IXN}~vhiNjR> z=*xmgccNj%2|7_6)d7vHxDT;m zGbXc_+4$4$lpSN? zs2X$B9a^!_aX&oEOIZiIKQtHfB6+6dtby^Zoz1{`Ota0d|M2Az@vv6lTqZRMWO7wR zV@rl8t4xZ9o4=*LiK1JP=pc3;$RclcZ}-576K+ODZ)ch|(|urdRrT~~-d9LRw6oO~ zi|nxS>65<&Q3%OFM|%}`SfuVrj;OW4f}hnys|gXpgLP$^MvJ(>!#-N*BveN3I^69! zDtyhd$qdp_ff|1K6mox0lC5Ts^M^DbLG* z7FA6-wQ7EZU-A+vhJl)P^E{=Zad=+FI(xX4po(qLmq&!bA-V16n9cWRlRWXr>hbuP z$k=cGsMcMoe=fh(K2HfYpY7lp^Ch-iV41L@-5I^dxv)@{{x~`|dfY`nh!w%=KC0$0 zioihLFEu>(8Vx_$^?Em zcq_`gnf+xoBJy`5k$>CTn~duQ|BW>o<<383*W-t(rL)KR_7aj@l_D;+;02lFdP2Ld zrYr~Z%B)N!y*t{7B%?p0u!?x!xA96V;{&{ZUfmrJuGXZch}aP)vFPpur-k0E`ixx^ zRP`D7aC>Lh3;caxP(K(gjYbU$MW3+2KLbi4xaHcZ@Q1T2U~1ZCtVtDUJ%as9M=lWB(Naj1t7d~~mmi9QsEBJZqn&a86F6E=@ zyBRjWb;(Z6N#)zux%zua8*Hm@21;#^c1ucsPtr6=H`q9JaIV8C$mXAE*CXrC(KA z!|8vVV}~Ra?e~oT04-Pkz$Uc$3upQ2X#hy}gYRaZG=w}&>8SN$l<)a=)9q{xz|?dd zH>}1KWqH2={^>Q(ugtt`s;2=Hg2{DM5)SGt-jd1Jn1(03@@Zfz`#`r$2S(?&SdZ8F z{JFf%uDDFEU6$WLY!lW4zN_QNRO(U!TA<5TCD;?9S(l|tU#{j1rZz*u+>c>CB1Zd@ z0QRE0H~+Zd#`lmyS2<nT4ZOm~_VjD$t)6ML z5%O1^qDr%6bHdzmwx_>E?4dpg%v==iGt>AlUm)o}N^fcXrvoz3}#1lxs{UG1# zsq30)m&i?ACTQd8vW?S_mlpgKDrO1}@_~rhJq! z#X|kW7!m?GS2)^mUnQ;Sc-&7hYOJ9NoP>dPYFlk`)Sap;>;%h0N?RZm8}D9>RgSBr z_T~cHU7;9xim=d%<$ab`l&(hHtL{5mw|*g0uMrvwS2_i7l+v_hH}UQr34gVN=|l=H ze=*aQQ5zz}7VScZ43Oi`>a+J6wryeiW!cu3mW58}d~7M7_!UgSM+m*z`h;U=#xGiT z-;bqXCrPJfQ>mZWmuEXU6Ko(+yZjP19J1FH9ZWkp1|2_@e*2ZI)(^-}C?nh}rg%?( z{$hMxMwG(8`Gq-4l*H**vgOaD1Y2eYb8XKN^(Wa+xhu`W$+)5UqN)8t8+ZH3sanmg zdiRM>!)Msq&aoEWyKz`vowUU|kE|t{kBoB(2d+qNMk#ZVggc{;IHJB!JR96-9A;DS zwv#j@>pzF3c4Sm7XS5DtU1;a=hX!3Zz`a7LZ=L;$ktq3hQ~t_oK=`g-I;ip-AFX#c za)&Cq2P~h-eEznH_C}?Ljr7KJ1Fo=f|8eX~k`H*B^(**q8&-*sDZEHWTed{`UaAkP z=ANa0syD2hFaL2#5T7cZ^U$$*x=b>WDXo>7>aD!{+w${8)3i-xNM-yt%k}NhFN0#I zSo#)@Z@ZHzRaXxIE?H)AJAts+VY`pa>qATkuhCD%ZDMwGyywS_2;9Sgn7>bZZ(LKR zy!}dZrYJIncQLu8qW_mZA5#hDtdbh%sX`5z@_e1k<4l&hx0^3tfrr?m7-Dkt?OY@{n6L# z?RYbZL+TJOB@V;nUNxJqE4G4F=2m=C->%CI1)ACmSK?gH1F>SDhk{=_^)oRG5?z_qs zxW|)kkb>^Fe}Z9-KkV1&R$#phYYo~vIrN>o&7gBLV6#=XMiP~3eHQh>Wd5VQgOPpd zif03%e3I8J6{23n!)@ebb7*Bc7TZU42LT?*1_ND6Z1h7f<;eFW)K-%zb0mTI-Ukjd zHO7GgH-DEuc$w-4x$(AIuxVE#LZ25elN3{p4D1JD!!wrjzz9APT^+d^Y^?U2-gwv0 zJ<>W0z%T4Q8Ur;Y`e|rPg4kA`J&QEFQ7R_)B`4@~>P|)rwLcE+6z&RH2&zo_rPP`s z#IN_)455A*uVhfjVN+SK+g+>*ujOCTMb*|~@&xduRUw>;l#MjA8vx;rULsSJ089=2)Lstn~IIJBAsPUiG zP!T0SZ(ng)d@&kivo1wQ*p`n|Fh=1^`q@E4FsPnY@CE^9v(Lv`wrDXoJuSy8=O0Fj zR1CYF;CbS;uMN5G`ff{9wVBZIB#^;^vTWm8qJj3_9CB(|7uDc zY>+TL9Q#XJWLUoMIO%ZHMZDB4cS2mLqn<}7(jfd#6M?B%4~98-omp&1@k zDZ}zR*8{CU3GHX!kaK?JT<5zlGLm2Vdnil5pH4gcbX$#x+n;Z>nNuIgc=ofRJHgd) zC*^EE`e|NtLj0HfN~l-xp(CZ8%AziC5p5sgm2~Jj3F9rAul9mAm7dYumt72NPe7|R z&QAqdwZmGvHuZB6GqZzLpY+8qsl*t0*(jcnF*}`rEGhyf|7)pom|VI7i%#h5riNx{ z$a<3TM^%`HpRyAS+Fj9(r;mJnVUiY_(FIQm?)F!iH=bGT)UDNhVj-U6C8i;SK8y-x zo!m^MBz8J&_8k&dV2l$Vm*9Kynw{!cO_ck1jLq>0xE*ZWeJgNgYyPdGqE(D`)B5t$ zd?p$d#1JoZF&rtcs%qSh_6bs^EW_51mb*%~lY4V`$>@8PIh+|aG|<(f+WHhw#a# zmR~0xUO7B`)wwDxI1SyS1430RGfli_wf< z&oi`Z<6R?3=TDY~tyM7HGa@#_anL`Uk1!9?!%{Nn{Yub(Q|o+Xq92}Y{!=1q9E8~5 zku$LCwAnl3V``_dH&q0&*X^yPBu;( zE%wnwkAArR_@#kdEl>rlLQXb7AWy*dNzpA@FUXXT-I1Nnz5$Sl$s_ESeSVtmvi_^M zS*$zx4kQl4pj-m7ddc?7t~tJa`qv%(BYpHafuJ5v{YNwKzQEyuWu`OxB_)FXin3Qe z{zM`oy8N|~kEe*!k!&GlK!~wVJ{JgIVzzP%<3OB!_>dZv1o4S^$hDV4A(BRu{N$Kf zHq^SFRsQ*>kifm2K=*WFzk(&1CRW$1-3}mv(BsG)P{RexMoz=WV4|0=J1${x(7tsu z9=EaR~hLRgmqk! zJjIu>Vz9-=v0;Spn_@&kwy@uv$t~uE3P3-L>mL*qcB+3rHukT6G3Cfw<>4JFkzVT) z%w`_HFifL=GMeP`m}a|(^mbxmOz;nw+`q}Q{fk!2a7SKMau+s-Kjcq(hPMN^4VY92HHP2**!I zeopJ7xNXZ+79oc>Gcs}FyKQ=ddcrBcJ5=Z+AJQuLiogB-62bTR%xB{Tan<*Z!SBxc z&CYN}z{a+`2C%Fp5d7PW%tOSk@EZu_n#eVapmAX`^)(YPPTtMWzHu=Fg-!Z|dbfmnd*(HVRn2l8FRCCSE(;@ft}=W_KVEl#^KzOp z452+cu4;~r76<5+Z-=I?UGVbFeBMM8kI9zIQD#-!;6DK9-K+@EY#=Dins$@9M3YeL zFVO>dm1mzsTCY~_8jqim?jIn!SVQJ0n|*luC(sZ=-e#2YR+gx{+}<__%b&;!w(fr( zb#*pYF*ijuKf~9R7oet3kI%nWnO#qW4WJO<+@tlhTbo_@W8iaK&{tSF!ULPuKC}Ny z!e{__^X5$~+iED8fNRHmmFY|~+COE3*LuMmFb_-vE{rT)RVN?6l?FQiz0h1P+OPxN zh+w*0fsDz{;mg!l-4q~Jl!EYhke8Gqo;a+=DZ$2JcF%u&P!D@a9Hx&8QRNHQ(S&_j zTN&r=iaBKk|C?gMJVX|`<7l=}M*sgFN5m>EZUgYaXVAtzFGD(7J4-)u5+cQCOo~aN zc)9X~mWv#uuW**PYeG>Jx?2SwqUTmwW*ac>Z10ML1ZdvFAXW+o(2BbxA0CQSNEHoQ zn+mbZ&dgdSmb{9lsy~MS>AC6mTI-s1qo~`ir2g{h9-I_wybC4-6#jl(I445gF16te8#y^N4#+*K2 z-X?GS=?z@XX?SlS`kp%M{vt|z&z@{%9ifpP%Px?Ec|6ZUzelG&V^susiDV$kMJQwz zMzH9}-d0A)Hj@4~IPFty;cE(!bG&x1ZMWfv{V#S!Qir2t9A+)3^E+Wds?$|L1h5Yw zb$`EwlTGPz{$_3bsbu2t9Cf3=`77_!@xIW_LdMZCgh zV=;DQVzkeD8x5EJq7p3s{J@>`c}q6w=Ru0eP=4l@RmZnLAwebSkXzGotvM7)glK6 z-|RC{oTI(jUJ9e+Wh1cLTI_ZV+l{!~1h$YN4}Y5xR{bs#t?)ucrMjpem?`bn@BWM$ z!L}Y4%zuyNII@OBFX6t=bPv&+lKx3AI`=^zZ*yL&3yF*(-$i6xTkSQ4@09Z^RD3`~ zkh?cZ0lhASRjqaVB^hhWA61>(iRcncaSebpH7!K$Q!OBfn_O1~qBVXY<;;OzgM&<` z2k8#~s@=LG$AqHdO=|33^?krb8H&3QGm9WCMG$M6RVKu6rAvRFVlQ{z-s}Jv<`0-; zabyEsJev)YbFBJ@iwQ#z-uVKpZ3V=k&m%@+hx-vi{d443DK-7GKC8BPf5zyVn~dA(f%jrWij zD-DaW-=`igNj_QmyXt)M0X7%DwMbdiePkV#IQ}e|R6p}p3Wd$bWP!&8=TV|b?8w5y zg1S^Z`}RXPK=DGeV{$9fWnN_q{rm7fA*n1DJ|AaLY&7##iPKR#xN?TFBoU{r+@A|_v@wd^1I|HlD4t;>Nv77BPibfR6?0m^lS|27o zR7H^Ckww6{mbD$BOh zdOrf0pCy2bIMi4$Lw+tSeGXKw1-0QB0r=N1kz%!LE_d6>K2?fAl0`rZ8UgSwY>kg+ zR^s2rqrE1jS#&tlRLjBtsZd2DQ&OrxTZM^nP4`M~Pj+sVbjt$ya{X%_wl-R_q^b_F zv{0&Kdu@??5%UKR7(--EIz`~hQ+*#G*Y+5`oD;CQKW!wz?5B`LOW`RJmceuSrAyQ{ z64Yz9Ez9nFfY-HcoFbBIj1PgUaPECkhUcX0JP^%k9UuJ1TR0nwWV;3sPlR3%nH~qZ zJt1KPyGq?r&Zcru{$hrTj|1@q&D=76>9h1!Enm^#Qv0!jog7c7`p@xUbBH5UYkR0{ zMsFHK!?(5u>!^^u?vUueE|W`19jmB(&c{-<$*a?9wxW`gPs(YvMJiz`RnbrlKUkEb z<@d}*Z!MXmk+Tu-b24_Ky4;&U3ni}=q_ZRc#Ps5U0!o%k`i>Jv)rYNb)!F_2i2?O| ztWKL1?_k!@ApQ17?5qi)bQcD}j9aGRd4U?-Badi=E_rHY z0jY)ysBr1b{glFt*JEx9NOEbcd$%iH%M;Oqw!69ip1db=OgOTn5d`P`#ngXkkl|r`yi}4d+ z@ollY{%9I(&t$ikueE_`y5)|3KbA;pIJOid(e1ClhduwSafyCPVEEz2F2cn|cA>(n zi@f`8GZk{?uFE)BC!m6P!LgELPI>{TIOe*d7wispb{L}q7kI6Y8#SC?Y(S$?NX8f5 zVgda{J;@2vnYkh%-!?aWX9BI^F)Ktv%(}fjMPk3vTqL+Gy$2hk^2v{ zL5mtRL$qCoVT518ng?pFe6y0iagCfM7OJFQWwb)7=R2Bud(_RV(T-=asV$ko(EaVI z&`d%3{!rBEmg7CW*v$+5^D&2-8JDWPHZ@LK?6Gk{cOx&;rTV{jt zu|!V4Wwji_*Gf9gaL@g0E+MQCbxF!_I4sP1N6WEnpOT~+`DSw01865m(UnU(Y(%OE zjSFkEcqAV|Y$(~NSLar3DvGTpTMSXHBo-)tV<&jo*LXaVBm}Soh?n9av$|<$Ey0Es zL@nHfNEH{UH@PfQ*4Dp(Xs0k~wgVpi?*)&Wlbk9Z?%)tR+FMu-gQE>&^Nx<>?h{$V z8_VaA)#MtB5jC}vr;-0kJZqKL*o`u4cmIu4l9FnYtopfQeYKGTmc$*FZB6`eZaFGb zSbijdXaeKp3i_6AUyDN4(iVLGal>+b{8hT}&0^__ zt`iAy^X@wn9c_-U)+HrGC>FtSbIpmk4%M1xr&Uz&la?(WCpRrH18#zhhm6Ayb0c@@ zsI0zIlMw_T-Id7iFG&LRujeTM{v56CG_?&#+ z4Fay(zLh29_{tm@r&o8X#r!myTcP=a3L zwPDGp2ya*?JCv`Eu`^JQGWjqT7nfe#%4BNvDT_r zY^`k{b;x2LU43Pk++>=*iGCw;syo*I_MkjpFu*{t=HeXsAe*~aGQnk2iQ11YbF@?PG_IxPM`gSIs9xb z8~%~`ZPjv@7!{><)^tOgqEE>!Ii$}F#oFuZba9*;h)90RNS6=UHUlWixo);1fWIAI z9K|`XC!n)__x>V)hvHrxf9Oo63%OGOg+$pb9*mOy$t$&48(0ExU;$^9bUMU%HrFjY zZzh?o{T7|V|MqwMyLl!~b`c{j007qv|HV!UEOv38mSz5gbAZ?dEqTe#&W zwtbZM3XQ&$qbt&m&G^ua=$cGSlO@W%w=UFcWM(NRIHoui!f24 z+69+(+bQA8r-@PVw`%V42D(-0x=#7TW}MT}my-(J~;C?E?>LkAo zCm=$|NpzRya%(KG)eLTfIIyNbjfqxl%msY>>zda*xXW+rZRYHwp$+Lly^GU$#Px~x z8f#$2@*ms;t-MTthX&Yr7zs`N?|_>X$v`6gZzp{ycW=ZtbiM7%f$p}W7TEQ;35kcq zqg7;FbfdD{m1Ed=q!am`*T<*R0cEYLw@R9#obH*+>A<>ZU$-BF!|vd7T}Xo0!zi+= z#|pSXL3Z-VDXPP8#o{e+}eJ;@!Chl#}$R+K&yRfW49`6aKR ztJ~{H2*_a6Ezx0zerQ};8tSx^8-g#__^Oo~bIAw(wX0rW#ugT?dZ0>dWVhd+4cTH1 z5?qIb1k){c5hd!dJxR;AGP!H8rCL3la73vFJbc#ZjTuOU)7TGaZrLCte@oVSxt6p` z3M_HkxYMi4;RKV-LLxJrFgwc)=DWJ3;jmo1q2{G>Lo{Y~^OS_UGZKBBPoX}*Cophp z$K!5uNy3h@>~kq@AlA+ram7gMVohmhxx|cA842lI z_{~bshd!a}PNJA|P#orDpUEe)_5hUfZ$;UjGR`FH*1zfdQe7l^ z?@`k~fwueY{H~Wh3`u>4tM-;#8unDPYsI0*1epcrWA5g&#(jZjLY$*9iAg_N(P1K$ zVCBF7q?!M>De<^wr||D3Y*YKJLJ z^lgHv7!;2H(w~#aM7ua|SE!&*ifrl?(FPJIXvBCM&P+;EgY=H7MtN6sN@gbqi8KrO z=sb!c|9*0EhQ(tw)R=~MPGkeNZoxXYq1^H}EZ$sR3jZp>Nk%h#Y_H2M&pmY<)#qd! zRahWoqJ*A#4wvGq*YXdV7ZZ*FrekU$1HwB%-OP)Y|uB z*`ZdIY&!{8y=V@K-BV+&f$w^Tq(mM9?RJE4WK3&^_O^naWAvLhABTST^^aIb4?!H- zZ}G5JJ&=K87Zu1_*OrYEBzo!OYC^|5@;NS5)I`>;fI#N~Wyn{g^+aV0F@0snS)xx6Xxu#f-8PFx z`@gt;N_welL zX2oSIy$daP_p8|DT{uTm zF0aldMtt5@(xTix&YQFRa3Dt5jmZ>!+>#kT{|N2Ob3EU-%yWQ>p-cwKe_-9UOKg-& zNKD+D<*MVJ36mp@XE>XqCZ}l<-}%V*FZ0pC@jfF2^SC8U56bE}H==e{Nq&f;?_0zj z@tKsu?-Y*Q`;o<0u!xMYTep*7Kl~%Tu1lOkr<8rXgBHP%i)>bYpd)>8j9=mYMyn@~ zl;>dF*kz5`+~+0OjOp{2l6qJEjqtcE5s%g4LLK#0EvuM5L)2AR$Ng?vctsF~w=}LT zK1)gvLADp^OVcHFhUcX*-*F?2(;2_zTJ{Uy+n46ke+Ic4r+bF?8@G87AXWH?G$wRL zxigZLGs`k>s*^tLAgM#PPq^7*5tVHbOD;>thaZA1&Lo-iU5p({3!dj;sG`Q7splN_ zlrN^5F9LmZV&c4K;pn@L-nXQI?7Oz&YvG2LhdTL6%*6}YfJV>`a)2-^1gA}X0MrL4`bzFolI7F)nVt|-mNZO8nNvn4{eUz%9nEk# zLFUxpW)d}d(2y+~KCbBDy02Oja9J>)?Q3PWJls)*(N#W4p7yg}a6u9~tB-W4YYfXt zubZxPwbNLowE5v^CnJ9!s|#d{uc;Zy)9!>eIeHin#Y{U!AYqyd6ng5$C%}J zPn%Gt#mYI7qA@i43xS0Hf%vYXC0nC;r3@OE;v?K65mD#}2zW^1Mxcuf^p~AMP)dFPqC1EogOA z_02JYY><$ziN7l?jI37Y(e?ucu&1At+Np?JcD37m`3?N`X#qd1G=*Oy?p??{&`K(_ znzotM^7q^q(*{8|hNP&k0L|YKc&5Va+Zvp=NRUHU1KLDw!hHY*p>6Vin|@3tnoZQm z|2>luLpYE*qm`q3*dAY*2!PMdu?vO!FFt#(a%YYD2r$xa2J?_Athjwy7N>k`Zf<@% zSCE`r&G|(4C=Z~>fg!XLji^!)*dS#SES`$tjs~q&rxuxQCUC;rjN2KTidn`riRzPtZ!dfn756{+w z8-TH#yvxS{8nRmWlB?V5D4(=W!_#*wD@X;c?C-xO71cD@+~)Ko^)na_pdMiqDlZ3W=lr9g8RLm8l& zo1^b7Had6xCEPHQ+Z5Z<;;tU{qL?KlU*%?T<8*2Hp<4OLV^a+T_Z-%Ra+XPVWYm)4 zp$DrNXqF@~75Y9AwLcz7JYGIEXw`ehZ7Ik$QyEqIsSjc+eNX~_zZy{ea+o@`XELQg zQCUW1RVk_%Pj&TO3JVv}sxws6uJP(!0U<70`L92<-qms252F=!B1Ig~RL+F|7dbeFOeCG9wwq(L6z zsktMH@OVC&Y>?n6Z&HDXK*dbo#W=Qitw?#EX76`RBP|EHf%jfblgMJ%>HL<=S{1?f zwko46$1hQ>uX(zLzfflei@eQEO7iYzR1mgUDz=pP-c4o48%O&jw!DxHf@zPRV~ly( zM@r=gkpH4wdGzG?>ubv>lCBnFPRl83uEigmqU^2Vw&u<(X3ugkGvX!v7i0HrxJNDX zTWNCKbw7G6`{gc5HSitWf`PV8S zO5qYka9COR4~fFJyX4X~9uhof0Di~2T6@kvU1ci$XnoS=rh1yyaxyD5p>WhVrSva< z**e}EoGqWcp4W4sLc}{OrW5gV41!}PVB!iJML96JSww#D(a=@7Q=hR~EG3^g!f%+I_K7^^boTugP6@ny#p-Sv&tQWh8>)uh)7qKKD&fQB#j7N zb*ESPQEZ@Q#7f!h_Qtze*f{j%BZINbYrRJ0L9O7fULA#R---8mCGJm|oG5jM>_Q|F z%*h-%W2fAZLR2s;L$WW;*(AcM1h9#_8ca$BHB}FrV3$?AT+|c_1 z{e+LyC_{9T4)KyHqEwqh<(@KM)#O4Rr|wbuz<1{+Km^YJ^fbuh*PA4vZfAj2&(8xJ zGauqLT7~YLILm(H13rZ7MH`0<-$91GnNsBHYO@SU>G*(JHd+dnHq{pycgZP*7DfH< z_K?DAQ0xRn4)*SMYb;1vcFa=|BIhq#bx3 z6$%@2viWe0R^H|~M5|s=c-Q4DP{|^M#{W_vkuU6xu_k0Gi1R~RnKNV5;+N*AM!5Ov znQxt&^$QZX@$UBnhe-{`SENuQsD_4y3FP>F$}x_4hT6baVSkw}s>>e~c(ma0oH~jY zg`)twKKG9eN@80U4>)gbT~~gQ$0v`X|B8Z$f}SZ&e(6bq^;Mz`QVcVKAkdV6F9try z>P64gcV0X`Fh^BnnAD@yyaW8(?hDE&5rmL~q;ICZG13NNaid%VWiFjMd?uoF`HB{i zW#4O?Ub|Q-bw8Z61^}%(7zIp8H6Bu|vf@V)d!7befV9Zo`Lx0_XF1GsFx-)eq5vQ+s^OLx| z(o;5k4?m$vJ#W?_LT8(b5ari9%oq$=(kd(TchpRxY|0xo2?-MC;i6XcY1DAEg6W7w zc#MpU`E2~Z89r;wT7h#^RAhyvyhOHwZLl#xACypOCY3>J^b^v(wC{PpxGF_tFxJ{H zYqC(y`~lPdy3A>;#Ro2nA4Gh!x3JN;81ZNOv_gFS;y=uL(3NF_xIPG|qRXf)7>8!E zJ9Qzto=mjaW(tHhe$Z;D5Y(sVqs8;_Vd_=B*Ji*S(B#B;Xsj+#8~U8^<)twxCbe5mbJ8N>@0fH9qUV&w`QzAQp8QdM49KN zVq?%N6#Zz|R0971Ew66GHXT%Guhni(j&F>n_p16w2aMrp-?JFBqJ*A2yvHM8OXO=Z z0C~mGY4{uTl#!BOmC%vfbIjD~zk=D#V9+4fPgL12*T03QYSIK*G4$J#C7nxQEACLH z^-GxxQJ^K$0Ne{~jp4qTQ8*S>O?)|(qh7iYjibR+0y_2a-~4>iQir@Bs> z#u=2_{|Bcw#bxD=VC~z}jeZgA<0w5_r?mWziBzr5Llgg+$7XEqH6g4$lHdXwsw{ek znEY~RXi)4$X`K3JyDs=W(7KMb;t%~dgJih(63x5A?6x0jaM?uta{n`f@Z7UsF1iY` z{Vx;qPd2G+Uqj*h-v!0y`$36G>)qpOTv$;9g_D-BBjj0C_gVW%FHCql{|CGOvoD5V znTYr0UI37l?rcSZ1_aKkKRf+xO5wIiBAEKnxaavC3}D)dRSkxFA?I3n7bSz0Wrc5O zCv^VAqw4>}8c2zAouXqR(RV(d;ECT%)ViUB+ikm9QHNLR<~?>Z=F^DgvD4jbf4};% zfgJ2QlyAcdC9Dv+Db~X>mFb|F7{C19;Ak@&X&v_`)KL>tNobQ|{z(}b@W5bIK+lDK zzuequu{-?U8mg^}4SCw$DIX&V%Z}^@r4t6ed24-4L!$qGOr2Fg9L=^y1Hs+h87#O< za33UCaCdiicORS(+}$m>yF;+xE?-(KsNn@G3c+iaCK zZlhgF{OhYtQ;3R+N+9;2Y@N>v#>A^FOz~uTtSNnKN}{G&7*jx!ZjVeylsE&jfyGD~ zV_D+@1eBM8ag}p0HkgS&);1ynkRMo7=k=ESS zDHj{TmCC<0t#cIjTeD}I3kVpW*+J#Jd?`w4bP;oc#Ku?=q`F}7E`}y5BbONGS+5_{ zLN@&MNGcqJ;|>Tb{Cv`|h*RJ=;8%cN?j<{vhEwti7X~@UWNFJ1Fm^&fXOViaI|pZ1 zGf?-X>O7{#9A~>%Do0G-HDy8JlPjC!D zch-$WesaPWRhtR-rFj^5Ol-?c#ZGmW9m-PkSRRHrmdd7?wU8SXM1UTW6_umZI^h+CjQb9_*$C$_lpE!hOEcmpl&&X-2tP!Q z-&e(($jv!Spik3Yot@5dbti#|FDaSBmR|JD({W8cNqPOR=!`T zp`;cm5uIvuvT&Tv>Prx%UODp|i`CGXt@WT3t4R~@%KlAAJ&ar+)1?Lp8|05+SMP*? zHk!zq!Zjy@GF;W%tW_PlSXxP&>YS=wxKa-ziEwO`F(CXIbO=r=Q=D~gcAXADeiIXy z*vyehHB$4WlQ9MqjJg-b)hZlVehQr{W@>xF`@R4H{h`o2(7J!{e05n6??t{Y6Ac^aVth0%zA#q=ahqKJ}>KpO^2AmZ+T zg*}6fmh%&$AhBrSK6&tjbXbR{$<_UZ?2ib;bnyD3|Ir8TRX!W6L}Iccb-kTk_Kg?l zzzcT`Er#dWpl~dQ36+2bHwh84IL=MMNl|EYnV<{49r=O_0S~3+)#4JGbYI5lT^xC_ zrj*C2dllipCyu={+Xdi$BgMUaTr!-hK`>7w5PaSQKPW4&i*J2@H*+b|Q#(1fzibkv zz2#7s9=%KbGXz5GjjS#(ZUDkAPfQuY5T!k&+IeEYNhwjySXvx-9bPbWofHigj-V?% zZ=u3C_D{ALf>Q=Xu|r?bBQXIFSuSVWuG)&nOUhjgRO|`*B8~t=DBmWEcx52YmMAwo z`GUxpiAE1_7Ba3mnlI|6IoC)JgwyJay(R(~m#UIch@O~?WyWM#lRV2<3XqLjfU)x& ze4e-m6mS!U^*@lry$*zzmRBl@N^|s{N4<`qz$PZta~$j@Jz|?Gh3rcQeN(MRJV{EcOWOfM0OVVBb8e&r=FOzK=BI#JJ7ufZt6U%f8_v%Z0{t zJBv3>NH->tagEes^sJ4yBC?WJj3X6cfUNp*tZYA9LBZEzjj>9k3Q)Or$uIZh+IZt> z$4f#{NbBa@X+b?{OowHZT<70$%kC|8cr&KFuZ~(cQRA;b3J}%X7ruEu)RudMh_1$O zefRY`ayw}$3p+ojQ@7u0##~VFeWjOkIcefUk~BBJ^enVf4iQ|v7Z48q5xtCR|t$39s z^W@yf#QPRYLUKgad(`YrI&fgzqCBp;%@Qdt$e>$~_wr9Y^4NHqY<0*HIc%i5X#CN3 zfdt(}2YI^O%8A@}U0wbJGMs3FK51H$%Iz5nEbUQGYq)SCh22}P{=N;GY3KuXmbYcR zlf&9Pj?5_5oZ|2OpbnBNKEoPWoQ`aLkL^%1#PWPsg&s!@{MWd5u#tARg1P(FNDb!j zhQ#}yNXj^VhfzNA}z=`I7WEA+iCxNun(MCSy5Xhj830FpeWie z)jE=rrwQxqcaYj27MB|_CB=nB@qa^K{Dg?xR7+BM>igq6!;y)(~pUQJ9Fyu;OPT^cmgrC*5WGkJGtpi3?~y@S+pG$65( zhKwU0JHluQc>@V|!Q

        &A4a7h2c20XZofa2v{N$0WSKw0x<@hP(R z*hhAZRMU_~+jf&`?4pc}81w~8Dd+4#H0!wC3^wtE_Wl^yDJkW_kh`F+veX3d)ZkUTARfNsH8&K8N|tW0aF$Jy+Lt;`E&V>5 zALesAQz&z@V#~*No53kcm^e(N5t|eyn_A;R655-!v5R2G+lq3>)2I^wL}Wc$v3rc} zP>7I0(flRJ?sK-?_aSORmc3(ISC~SUsq}utktoCTi$!2P|&G>~6X0CV?-kRq0R z%L811);B$yha%F7i~7PjkWFZb$g|!YxkuET29;$apf#sWJfMKc)3Sa;CTYW^)iS-~ zrn_CqGPbw=$Ge1;HsvDM1wC7eUub@Su&;4+PsaaRtN%%^`)Gb zM^aucc^3Y1UQ<~N_Z>z?-LZ%EQkDo;yolMzK}EcarBxafqhBIR^3)__sYRrnuV#;< z1rfko(Bb3FCJ zK>erV#ZJfNYS8N3>;tUk*qQwEuyH!VO$c>{!JH5wd39HEu@fmpD$1`F3~mJd(z-ql z{q(7IAAxb#M8XMe^x$68PuIBkEnq{IrZ3^aw0>^%Ud88X(^IeJlcMqS z9V8%a1c57rqu+P>ZK~Yp2Yvz}+_OByH5X-DWwRkYZQ-DMq_DY+T}Ca-pDneU4ON zJG(fon>>vumE&7Q{?m~FrLSU+nB-fnOHns)iY{P*n@(*Ghc{>PWa(S)c5aDupKDV3USLG$_Qg2A7{bSCk_uY z&aq+T$)%k0RzyWA9NI{eNy|#7agL0rcT4NeAW6I_-{k@Yi9cso0N5_u#WB9IQ5h%1 zL@{7f#0?N)RGTa*)nbIefpVp@@}fsMM{GV0WUsW0tC>3vE?1L|4->yt<7G~R7TJCZ zbRQGsizE?BcnNaRxQi_?OX(kYV61ZAHSoSdY^@8tMo>C{L$f=ryYa(*FBkDi-vsg1 z^_`Kc+wQf%1eO0kI3L9l{Mi0QX8kwuKqMgbyJQSenKliP%VjT^OrNiX>$r?&kY+r2 zVy$Y*`%mk()9YRG?&bC`dxP1aHZU(}X;2@85(Ht)8k9=asz|CZps1@F*w#?8+g3t4 zq_6P8uIKx%^j$p_KLg;z(R{*Ci#R6_pr5ncIH^6#gCeHdPuLQU<_G+lQHE)m+v)SH zV#=h{WUQ7U>UUH~^%?V*Y556nMWiddr$ikpWt==(Wf~)aspS+UX)Uir1%ZbbTM6~j zc0JpJINECsgt56GT>j$H`R8*1+o_s=F;iv+6eORRUx6wGsI+em1&|c6Bw0kvinV7> zZyA#6K(Vr-oGM-csBc)_fO2wf9ZZq>hK4sz1NdYyLt7A&>GBq1QqS1W;#z2&6 z$(F%#w^X6~gN$`&xvQNqmtVIHulfzRf>E+!@l&d=7wr%=L7KYITIEcSin&g^)cl)U z>b>_jfUHh)^C&6Hz)!`9LSoB`5gK4fu7$+U;m`D@StQ4KcE_5-_sd)sUpZk_LL|vc`>haPt(%7#}`h@ag8*JKhg2= zcw*x!f^Cvynv}y8!bs;RrotyFA_ycBq`kxOGRDJZu&wj(ud?&+?X8AqWA|Dw?V+RNVPBxOUot*S zVdejtqW<-p8S=_=-&3T{)Vm~ZeR=h(W{a7II8f|i4cR=)1IzB?Le=AB_63aUiQg_d z%pQ=P=8rQc@kis7a_gcZOM0*YkJQejn$AjM7GG#1 z6W_G)sR?n$Rczp!=`gF@X7=#Wl;o>5S+|RINKT%dUSLn zp{TKdqgoe`Jf2iHCQ2bf0X;llA$Bre2=0}jHYfs#&6Q!?ta7k>opqPSG#ncTBT1a1 zB?!vV;?i)_pavQ+l^1B1#+o1F0N1A&$Ze&gHaKSkj+i8T)>r8ew;fWU_;p=3t}IRy zygHvfD%IH=yxQ3~2P10)1JjCkmC~eM&tQifZyOqv)YO8@SE0(S^R3QlW#QHRW^zI8gHf)?AbSr6HAqSLx0^3p={wk+m4W`1GI-C9F9-{VIuWitVOOR&b@ zJIro}7$^xl^Xp#ga42IULaQ1@%7trvn@!=!;x2+aRJ%m2Gp{($p{ANSVX zxVheF@pgA+p71sbkHz`VzW86SaT&oFmJ~yBC zWFWr8a3F5x=cE+Kvm}~j=w}UNnAEsUQhGT?liU9wr{a0En3Uo$^^1)Tww_@aKabyW z#BfqBEiDzExFOUWQsU}_;p!bYrTLIBcO^)h`UyWaDF=K=q?yMu3%W}eBWCTpcgjTR zc`qxEGIZ4Bit^p9WoUv<1vCq1_(Mg}Hz=wS3cD`ETTnz`r}zOH!i_@hk-ms(7XUU0 zO_fu9tzI_E4dU+%7D3{tO{Me~4@2L?aLlf9)I6;)R!R|W`=b`jXurjYdKx${n8Xi8 z?XfVF5yzZdS|mqw12`eacls3xH;_!blrTtQ%D;b2Bo1RvpzOy-7iz&pi1yLq8wHKU z-T*VFbIyy*K{7E4oGG3l8BlU!v8>|oE&tvt1r~DmPyvY(~>BKGmORPl;!fdyqf8XJ;Mg?q^I^hBWptH z&w^+ok$M;%>~SzgSxd)i{FCgi^s|#h8d_>9K#9sZw~{Yl9~+1t%pyatTpAm0`udh% zKpI)7?~?o4sCQq=$)+b3OGX*!dA{CQG|yO9>t{?yOMKn4ld-~B`q>pLVMJosZ<|-x zTKxS}%l9P5G(TxP?C(fb%a6)z(}@XnBe`>zxq6tpgEIJQFP5A!M1D*0`uG_j0$5WT zl|qP63Ci6g1&Um!ve=YO7Xiy!R5o4X5u)*f5%3~b1NrrtzK2nLT98nqc_RA1%i2f( zpd#7HPL_*EPy4f4rM@()lhL664s7tqRuL~y`s+jDdAptedk_}8t3XrT4f4PcZz5t( z^FThqF}qVweJYa}MeY|=Ut~l`|<5(s3Ao|%%SYK`sLC7VXve$ z7H-b`Z2Mhu&RUM6lD3hHcX=s@oWq+1_xB$!=Aqb}fWM8WM15YkOj+^sabFRfixouJ z(9=L7g^=igBGlG5v|c}?Ts5DV%O76Jdz2v8uY_V}(zH*M45kveB0V|z^4P#=Pd=v~ zM2^Y5=XtFHammUN?|>f(KE~1#>o~(2|J1pHbVLyap`qK3R@(%EM8*oT;RmeB(cqIQ z(Y4D>>-!BCKxtSfAtB7Lk*(y}4nIoToN=S$l$l$uK|EH~SWs2;$jD~5zwQfQiP`O6 zZCEGEcgOEx6LWInFGlJ za%r&6;5W;k-?e&GD!J(ER#9(b_|uGq9!wtXY@{tTNvsCtf2gBo@~_dy5b|Y*??=W* zMZmnC!39tZKuujeQp+!-(7uejg+tVa*JzflNoIhHSvyhKF{3fmxXd*o05Cj9c&M7I zmorvZts5Hv3~dv?%_Hxm}9EAWzuYyyMoI^A@pMIS| zwxM~V|F>ZI5wG+es^gWd7Hp{r=^ujpUs3M=t)(pjhTwQ$bQY)}!q;jYSkqIH15U^Wm#_0C5A!;0pOu@ zDobQ`S{sQI`~VQ)SBEZSZR-a?q(0+IhOp6yRB9Ov}hH#Xzu(O&0b*tog=n zc&ggcaAhj_AzJ(-7nSVPZ^{4z;0u*@j2PoJiz3;v-PgnqNkX2~+Nq^nOEIAMt4Af3A1woMZmat=6q zDo6?+Xc~g&AtD8>y1<;aS;Luy1te7`wzGrJ1cic>jGIALrR;0OEKpg0+(obIu|e!8 z-C5=kq?+cH@lH@S?7qpAeoGTiCZO~_yj>bOAfwtLo8d6U&H9W_v%Y|oNvgaTR8}Fz zL*chX%;bC6HUX0UYxDS!6cO+rT3gmY2W&Zf<@469cK~~E!(Bgh{TUAp#qPNOTPOJU zMGMYCD0TY#Gxr%9f64(He*WLp_(`XQGy3QiXqx7Z49@t)2gVmd|JoWyr4;Xn$?*Hk zn3EWeIJmTuX+x}Irj{R&W+qc~gKw{;)>(df9XYS+0Ne|dJ#6GC$T*g6gtNjB+oKb= z1}3BX_b@1{tE*EIA$SiEDxlKU?8N*I_TZSi%~^?~|7=5pDj6jDgPQL+rzEM^8V9)G z;sutIFD2H!*6b1dh`geX%|DXP2M+8?4`4XSkuhy+5INlf3D9H<0fM2ec5Q?Fj=&@z z$9p9?ukalOYKX~gpU2wDlukWf|DqIG2MZJ zx_z-+R)!?jTyHdqq7K*+8&$zi8p)K~L;_-%;1Ub75Cg?37sy3Ry9Cvh7cds+tq$Kh zWIO$06I&%mLLY1fQ1LY|7j-Y&lWYe|X@T;n$nSl1=8RW!=7xc%;#OfqpHEDr#be2R zcQJNcz&8iThqWINe5P73|Pc;AOI8cjfjfDFvJGrT)ff>8}u2GH}2#%vyZ z?CE>*cVpk{yfxXyCK}z<37?eJPsQePYRo?meRW^wSf%u=5 zCoRsU4xvZ6DvY-@h|Q|r}WxRP5Lb8GhN9Y*d?_|30TvT@WJi`aLNb#ILtDWsZcliI?C@rLh zQd#A|cZ;b{Vme7`h?K6@zuc5~J0GnLaRc!;S*pm-^6lRU1Tu+_v$fLz^aRVWLwoGR*kKdi2~0S6W=5_1SuGYMqIM3JzSNou|t z-G73lTM%xV5h+)wb;JBX_5(G?O3w z@wPs$bVn9}q707gt>u$@jhLjN>r#vrb*D>NqDUH?6XWHiQMhyUUCv{EvymDhf4TLG z{y5y9xT>%!dZ%bLDdsnvYUW9$6_mQ8W7lW+7SE${#?&(Yz>v{t4rhRP{#99mi_a?k zl`<3AO$z$D-uNmoO41l?kP@-8V=`(=;lq`-n57R)-oAI#OF3zTNjVmQ^m?oHWHV^Q zsSWrGKd?rMm-N%!Kw9P@v>&@nvW=t!+@vsV?XGhketpR|%m}M?2dE(d2or8 z{qpUh$Mv@-M0hO3{b=F;Tl)ozvF9RgbYayuIM>bZb=EC%eWk2X{mQ)fxnZQ2VVbK; zZfzN|LpNmlmK&y+_DUoRyEiyiedT(%Hc#Banqt=?MH08G$wy|C#0_0fB#^+oj6B&0 zrwRE{66MC)wzRw)s_G9~od!}8|xNMq52g6@3y61p7sJ#X@!XmdczWc=hfW!2RY4|_>G4$y)w#BcITU06@TQs|wh z-)NE@sp*VnI{(?L$K2lyiUu34A4sdR3ZHLje>7K)7jO9b3)${8ptz8+5vh>XCXFX4 zGco5}roN^zd8i`EV}80guHA mBb>Q>*6t-ZV%ox4M+>;5c)IIplYk3)c^O)yr#X zhzi(IzGGHa119>(dsW@e*q#`DFC<31Z^QV1Vu?-(u+TI#<@4$|QkEk8)Jk0Nr=Zvg z<)r8MIb*bl=no#U9-l1Z@DIx(6&)ls@viY0hw#R^0qDwh08kO2-GhPr3If=omcXwV zDVMP@D7sSxbJwdeWy{{(#+VB2yoPbFRjBRF%0OB{Ae$t*@>*bWV(GGYoyl~`pOLx3 zFYZ-|EVul~K3<75n*5K?-!+klJo07Ehesfi!}j*u1K8Br0r%g&kq^hqjfY@VB=k=5 z>h>t=lFoqsu(;cK)c-sI8~#Cug^RljZXz3u{di+0Y5nkfy`5L6&{=S?AaR*he`X~@ zF+R0*AMyk%Rnzo+5#t1pZIDRnpufmkCW^CZg&}ojTcfCPO5WkVvlnXB!1$7^P=^5O z2P6_MC2mXKzpqlM7)ByS-I$C8%5D)TdrDd$Gh0fPp=$G8OZ@0C-w8wLSgbV(P_%7e(_8cdh`0!X;(_z)E;%^EkJHK8Gd+(Y^*;~ zqxS*F`pv@_lrdOi6R%Hl`N7GFeg-6V;}WL~L{2C3dw5o6GJB5^BxM1=KNf}?BfnMk zb0p`rABB$ss^c&X`<-g1{LDn>_kvgC!7!TacBUPr(|aA6QPnvqHTR#t&&0&g>%J-P zZB8X3c?8j^FiOJDIcpf4UiUaEP~)fa^G(ljvMiE3rA0Q5JYP*psqD*jWT4`E)ld`U z5Z>)uohHYCvN7+)RJVGp6|X(6CrXY+6ks|S#I^XwX-xJ^1L;CoL6x{1ob9McWR`g&AAZ!b0I zeQ=ob0Et4#=R@}b^?y$ob_Qvae)seXPwgRvBS(Yt&P!2J)hvr{L17eA^jp@r?)iZ9 zdw(+5ak?5TO@2y<>=g^!Dopw&ddQ>;&H)Ue#Y$dncwcOT$K5c9O148ID7w`VN`;fw zW)T7R?S zNPE&9*T_KFv(P?6jGEv$B8fAenZgeWM@Kpw(XpIR6VM)6l~!YHbZQgD&+!w#r)iAt zhX4_i7gu^f!)3Ox##pF03J?t_uc90=mT%`If1AY7Q|rSbfY0uCa%S9~tp2tl*kGF! zIFfu#7ZC@RY3jIeOZ{3*;ucqqxiiyY2d!7r6-;@}l?D%Zgkp}8VaW6t+B@$Rx^>_F z76!*0E&<6+5pn-II@EGYs*3g~^O| z#l$e`X0dM{;@gQ0t*WVes%Df{u0BR|m7^I29)yz%0BfjB|0y)-vZ`-nFCgak$Y0ba zl>&$FFf}sBy-JpqFbZi zzQY&0UEx>DmLG{}X|l}n&}Nf76VcPgh=@>lo{Lb%*L14-`q772_tEu|Us^f?;Nc*= z^3WOWo#uaQ)RG?`$o4)D1s|{1OBgrR1wNR@>gvCDQ=GQ$qIo?UGMk{S`TH+`DTugi zkDV{K9+i^Mi#lRNnW%mrP+}{3BmWuZ!M)qzpC2|ap!td1@EkUM^?D4&!v4!|ai7S( z67+jLQ4%k>i-bU#{7jnccFv2_KTHxT9Dq0m^H*wM*ZS@S4!n*;J6h0zfqXFy@7K8C z?95Q~3Xg~^H?FQjpdIuA-u3m3V{a&KzP>TFJTVrSnSzCdv-3Ls5l!s2qKk{z7NDzb zEDa%>#@O5E>CC!+%6!@TV!s`3-z7|8hcl_}u9+ybeiqLS?t9_U`lS>NfWRB)@O#`( z2j>?_I=ynuNok)ic~>CFxp@I3R#5Hv+NMi!3Y z128I>rceT)K&{?OPi;b=ez7uZyoqu8X8_(zChGVT5D&z$DAK0`C>cZ+o4NFoxK$TL zTI*ww`9wh{elp7yxo#pa$p3P3k!mY_-A^AuMCc{!d4a}X5yo7e*p>We;bnO#y~?n6LN1dLyWYbZo9C;f zfo{4*>+(63cRfA^>5KGm#J)+~Vq&_Sowj8BhDPRj^+`(!>+&;a+CfU&A$n>0(05Re z^4xEv#6}Tt&~=xAh4-XDB#9t^O(SJd)|#aY2AchbgL-~|6SUO};NF03wm(645Rdl) z5DJv^OV8w|>>)2CI>&Sr-f|u?&1*2hWfWvmzwJ+>=SX?YKVxEy^U4^-l5%g{@Nlg; z5s8W<=CB}w&u|$B1;O#OC~Rj<DE?;$R_YWo31F;s1uX>2ni{+rZ|Q!H+*o?B9X= zyxEJZ?-QtP*A73P#{6JJ6fvythp&k&orxPy5?e#4(Y@Vdx;K)@vs>Aa!2D2$V@h>% zxi8g{FITOJQV|XgsnkBH(U5hIB;NcV(}N4Imx`O++zdVCGYoK zR${c#;R&V~j!aDr`B%3i{Q2enVDygXFzaFH3VooKYUpW;En{VkE=$EBc=SLilpM;X zxpD+binnWnhMUJ2_7YYBhm}>O<>2#iG!x<6R(<`?+QA?>uuY-SY7wTcRSNDBEN~cB z)YS|H69=}^a=M05H+`eyg**sv%oW(Jw=?TDM0$#DIDYn+%%>RK;m*I;r=Y8HG`@10+;i4(}0hR=k77<03Z+17h?%6bj;aMxljD>Qpj#b0}$h=a2Z~ z!aBKWpAkz{ai;TwX(-=(r2>cS88&N~!E1NZSnPz9t>Z21`C4rCG?RH7YWd4jcns4u z5j>-?pZXYcEM#tSVnn{*`=Z@Awep0lgoG?Clr7D?+g!OrWjO*o}2WB zEHxnIcC!EwQU@gmNo~h8y>f^N7{gEYaN2(Qa!#Y`chanYoT7xH-*Q9jx=G@0U&x$Q z##m!n0Zmuy+dMBS5U&s5518A!_+rW?@w@P+{UWMm+u?IXRW^NqhqE#^j)gH^Znz0~ zHaow$FD(N@PlVxTRvT&3+ka+BY_&(5Xt*OP6Lh3}9A^W6d)u|(h&6I>u&%waV4H0 zlti7kI2*#eqIzV^thKb!H|$8-?(pdMCxySbGep~0vg3o0-8gFy-rEO$eAhKXy#QqH zAo=xft`XM`w!$AR7ty!YPLXP5 zNkp1JURfX&QPH!Q-y^+V?>;>46+B$-y6YD-y5PI` zn^$h&r6r}s2Y!Y%=u`V)cog7v^!!nkOGJWA@xyu?p$ZVpf`%@6x!IcS4`L1Va zOjGam$x?a~ZDhRA3p&`xhMvl#OYtQUOH`I<2m>A*=}P62gwPr)6=6x}!{*)yk6crb z1f|-27aUEMbv)aKHT=h3D3h_Y73&{#hXsQ00P#;4Feh4P(E&IX9K2L_PCw`^srq$} zXy8Q{YiPk`WF)O#)??Q_vU9pv^fz&Pt-{1yEtqRKF1{}^1d;t|CdBJdvTU<`Q5Xp6 z!(*&0LO;sPMU(UPiH1hQV}2;W^FR>yCC6|^O33up{ZxWwk4jE@uOu~>T$Qy~%(4VP zFU-QlKyrB#mxg1&cX&_*S;T~O6eRZB!97mua9ZN`4OEav9`JL~?HGG^+E|53ua?(y zOrVnoMne&SB;|b1c$tzj?^$h}DilJLq_ls{N_f$nw zZ5v^=Qn#CBCf4xSM%hzY8rnya7qK{^7kasB72w&6!Ab%uLJS8FJ5O-}vjk5|2I0{* zk)5R5Hr|{S?xE)-UT*2lL}yWW9tOH|_{%J~QO=0BEMe(!N58SQp9nic-Z=vrZD#00 zka4I~<7r0mqhIseT>?Y)GJ7@F7$wOS^y5NxyqzePeHzG@&0eLEHX5;4_fjdpwn7G) zl#y$-Q-I@gBA$KjwKbDG3Ta{61KrvNp$LFMs+d zfO4%C-vk<`#)cBq&RJVae}Xi)0e>6UJT3!aJ7&sf>r`mgeQqYp0^3b^_iuWE{``H)}cE6gpt0 z8Htuixxm2Xe;=xR%ts8Cv-;ng|DCSrqfFO6J*PFD2Tw#xSP~Kvgp5zc?d=52{2v{- zGR6-A_dSnQE%&096F9}4-vQ~Qh>t6mvdNfX4@*z-LJ+4}<0q>Pmc?t4sdY`pmsz`qXz5~% z&H7;Y>+LW&kIXAp!so^*Xqd;tgLH%t>V0V^faF5)dogI>jVcIh(H9&|B z{5p9a4swbadLA!nyzfNl1EeIx?5NwG=e88J~S3h^$CrUj%mRr?4;FzMlZ zrVPy`CeDc?9+yGE=g{id_PKg7wGkzU3KpT_uN5e-P+#7?i3r~vtXh>mgU?l;w&S@@ z_~ZDxjamD4^y#_r9okk@h>V7lIB(AfN=0@6dmO(G(ojD#89?U%U+;U9c##uF;S)*H zmSecygU#c#Im@%XEXD#xRF{n>L>-+OSGfEj2v#`IgmBw@`IO~;tjcpr`q9^F>n@@v zV%Aw+e4^A#|BCIbCEP_GWnFQ# zk-ySv{_KA3+cpvXwp-`0Ez1ACY^+Bcdw;&R3&vF?+;nv{B}srjz#W?pqJ-R!osS2E z_8#QnW`@{@>R`FD04a<2s(1FZq5Sp(Ec(>gjp%<*Il(m39tp_lzfR)6SM4{Eac;yz zzw=P=r2HKA1`jQv%j&zz!GC{LpjX+SX#}>!^hrW=XNht4~oDgF)&|A`CQslt(63oXd%< zFLOwWFXJd|jEltEIei%wy$JL-4%#$%aw zMlW)F!GNC9sfoix6c;4UKWJPo{3)7bo<1b#V(>I_X4)B>A@i;liUz|uWR9USO59rX zN|8I}U+fS<>)8sE)i zrOm32MjQ(m&gHK{f{>DYjQ2pO1>(pDh0mjadQo9Twh|K`USALpWVhUXCbg6#{G;y^ zwe1Ra{|mO^V}KeSYb~eO!&%7t+jE|G%hYnA0yh%L3~Z;DOJ9IrCyR+9DH!PqLsf(g z?yX5Z{Z4~K(g+`hauz7>wO3$XLgwWjYcQYvbhPxo8qQdCg4EdYmrC(C*8_xMmn*mC_O7}4*6tFFej;<~4?*mIQ1_Vid*-BlI<9lC=r1Z8)?T`=4KVD&P z4yVBgs4A@%@P@QQxkVn(mBS_xj{`VAYrL7_8zN-ydOxA>xE`a|8_6R_$>LkQDY`l; z{^8Y?Qa7CKebT8Q?@CwfLB`FA~POjO9iv&33*KwS~O7l_smGpAg?+ zr7olrHAG2yc{zzlADTl9C-(b_skTsQvZV{oxCTVR?0M$BW>AyS{%Y z^v&UE{#RUk%T7u>B=YWDw4Z$LDSTh9?hZ){Iw~9MR1E^vz{#|t`&y#Uc>Eq{_bbj{ zV@MN2;}Z4JdTl~{Qb2SNO+kGU?sU5)MTlh@Eyn0lS5`m63}p_Kp4qmd`*Rq?+)A;k zqA8BneQRm81Hh$NcI{>9iWR3&DJ;0hq-D%tVe>I$sP{r{)-5r*bp1yd{S{~^CUy{4XM~&7x{4@j^P}DqUM`Odq>#gcJIK7 zOSB6xI9vCc)ltsehPPfo64^3-GOV$G=Dn&87%zH@&g~+s9fLQc6=%!h90cJ7Cs{tG|}P!r3d(KIA%@84K@lC`v}nRr$r=Xqyrn^lH;a zeV8Y<2AN1K@_-_I=%$JBn_ygR!RR?=#Y@jIn#xKH@6Q}d@3V2D+p(dQMm3d1xlO?p zM$t_SkVI)H!DcV_{Bp!}q5_J@`5%@zOS26XxM`{4s}Y4%_CikiL*9PgvO}^K7dCO6 z$Yd}tLf}F0lkJ+jBC&BD9%SGrE9>&B0b^8hEmbq;FSoBrZ2bOVsKgPUA68(DVW4NZ ztOHlC^ysCHkZwvyt7hLU16*1m%IGPA$j?e89r*VMc1flv*!jEt(HF2CH)JJMq@ zAO1L_9!&l?3?(ASr-CBVEBN;H&4qWk;cBhM-e9zkv=b|wb8t%umYi9?3oP&c_r*oT z134v$cyV0z?}Op~b_w7WgDZ+P>>n@NP+_u=%uE8GOK_UkU#uqp;`2;RrtE>GVix+{a{;n7Ximd`((xhS!P9-g2kJk2B$U`3zh6qfOxNS`RzoM zS=}S{V1kB^78pJZpa{gkdiL+7wlz1-(H%DE3vrBaM(?an33*hJ^p7(CrHPAsr3qX1 zS*P|Or|z4POx>q90<-;Wl8oB(Nd}YWWrlRZwljK=E{EoPQ!K&l*cV{9r?kNg)F_oF zTLb}h-~gl+Lf+;Gu*gW6UqJuV1!Qs#t1sPme8pBi1YqoEixdLDg2FoLU2FYFj+ccd z`gxia1k1ugahb+Y^Yy3UB#}n?Bi=pnmY8AtU-t9-FLau4=4;GRVC+EQew~yUD7o>i z^4|O7I>%wJeM@YDhGpMwQB3kwf8677mC|q#ehdo8aZxWl;H#kxFB?%qA5N-5&R41~4S~EaC>^zE*hB&UOc?I|U z7m|o=IU4=iGXh>ee6M_#EFQxDe?Cxbm<&-x$vjar*UiSmTV(puPQX$ z2{Oy{8=0Cf`Ck|{pjjMxsCgVVZCRX>pb&hz$r3bZ4`r%MxNbD2{WAy~J&b#;l~_is zL)xYk85lY17#Fmwb^rx%)M>dh50qi|8gby(_^{amsj<80yUh0a)tVR!TV%75Cby}H zP4R5@}BK>d_DFbj+kr)@mg0pDIuJ zf3b6};nnD`xG^tPZ2>C-W4x{Ir%P>mQ{$}>&&G!;IqW*`mhc39T5*FgGTb&i&B4Gq z?~AU}C$4Xm8g-ERK2Jq|xehjhU^T(F9Zh!cAz11;!`Q^1^91K#@nye*+pr;hR)Qah zz!URq+;m*+BRg=nH%Ik1^c&naH%O!>rg}eFSo{R z-I9jL{q^c`*z<5ZCru}RScue}Xvn_PHG1RqAb+tZ@U!DUqSQ`}|I3fD=W+dy^5VV8 z{#zlEe+jbI9xwm-dg0N(?09 zNK~BZ#dEGDuCtvsrl7S@bqH5ho$CZ8ZB#T>>K>*%PN3-#W2JXieZ_WKxSZb#RzSeu;7My(hVChg z5l4;PuvoVr%V$$($KIIkrD=Y@(F)((+1MV;@{!vT#DoDXr00YjLU8~>L z@X=wJW}7y@4$sPJx3r8E@w`_NDzLJ72cgK%E}qKve|S2}hBmi^U2j^X6f5qbxLa}8 z;uNR2I|O$v#oe8v#oeI|?(Q1g9fA|=WWO_WenLKEJ!{=|p_)+=SjUvFFbz92W6D$6 zsxX_2!;#fD{QNh0WUbA`P;R4497RcsCHW1H83|%67Fv#v@(vEeJCbN9OyeZ(4_@c!o!Z`CS?$i)}DwVuHB9 zUfA16RjQtXLu6VjogFQbeyeJNJ$p;5fJNk1m6Xs_6>SM{SC?SFPiuUgm0cbSUuD1@ z$M+Y3NU1GYkt>(URMw7aGUJuax!}t>Tn-YAl?6x3uPX#)<@himnz+HzSMo;mNy(+} zm729OZL=VQPDHbBh|f||Y;*@@>is7av$Fd;>C;%Tb)gc@u?P3EzBUNXY9gkNan7gB zvv@E%QJ&1fY7-U7EG@h(2iH4XTysyzvb572vx zFO4o{VLPNvZI7t)?#3Rym3e;*QP*(Bdstwnn6?Pp0cjci#qD09JaQjPu+I zIQs=sT}hw|;e?U;^SUoNNwYRv!{qsQur8`n6e%;qE9R2_)7fpS>y}a}lVPQQ7?(6` z`E|6-vXd2tz(NOjACmjEg-oLGyPuYJVh+R*hv_=B&yOY`R{g#`Sya-0dwrRYNjw>Y zQL;itS^ieaGMd1+rHm`hz$kgv_PHo)5+$MAoNqZ!2lO)1iK&{`|LdYVCT8JAp`m zDgW`2kr~M51y@I@3mDkq#W%zI_I%xBc)w(d!8-6CM?JsD(PQzy3dadage1GUN9^?MHY$^$Tn*mjs9Lv6wDJ&XzM1K6$LCU;Xz& zGjZ@D5W}as{hVLVzaMw$L@8h<%pv(J)})FwS&YCrNR6!aC1LY@WtC)23?`MMV?sH3 zCQ()py08{Aso6FxL(>;c$no#cM%tr6hDhOZszYJ~)&AQTT#@#B%#MH)p)u&4k7R}Q ze32LI^Q55Ox44e?J%+N~Q#&9d{*pW)`sBSL3!4jZ@(a2!QOPeqIN1IT35nxU-IDj; zUsHc4i=m&=A8l;P*?sn16&}wS)ipKdbYF`mL&tht{^=GaDC8jvsgiP&3R~s79Nh1& zk;Lp_ne&P2Kfb2SiO%C!2~RwJm%Ol>&tMR4^#wmdT@;>!44Hxcq3K6sAbhqYDx4vo zGaK&9p9Q1)VK5~vtu%GHX5!*u+83&D_?ArByyj+27v*w&sumer%WhYGYzJSda#?nG zVlY+`!%;y+#1;uG0f5P*`}Wksw4a!`Iqre0VSCr*N}-mTZK!knm1_QuUWob|H}A# zac1FRniYS;vvCd*@ZOJJeL8QyZs&ll?dZgI&0&WrJvHBQW!L}CPQ=n0=&Q%6+JC^x z4wAyq34?GQm=X?@W8H8Dy<9LKW`+3QHVqBzdai~Il#-=zkyo;y8|`_M$yHF4R!8ME zvtw(x5tf#Yi^{qoj!Fh@tfz8e-@gxFQ&_?VSvUf#fuX(}d{vkaX1nmd# z3QPB*W_zw;3X)X6{qG7}mL@1Y=o00BjD63MR%J3DoAu?elHArYB{YOjMB3rUcl8GwI6#9qVDRfHnMMR@`bqrikn4ILz6#2GA z6;}R!Lg+UC@F+tNL0=Zibq(!yhD+#m+QQ2~HpC;s*58B9zDFBAKaQhyF|!Y*A{#Wc zfRhb`lOX=$Mzc%8AW!eGbKS&kSG6Lwh$0HS8}$9fyQ7mO}9|36RITQjiK~% zFY<6d-Z?lpTVl-*mOjy2J!klQU9TG_9!=cI`i<{ePtSE(;{npNxK+;>5b=V+{|-SP z1ubyuHREHZK(FX=^SnKe=7PG(fTosX1q*X;Jz)deQ%p;pBeZ0x)wxM=S&(~f(Zm~) zdT@c-X#Nsp)J1zlmPY{o-_i9oRNL8#b&KgEA+Sma^?^~jDp8BW%(XU z?Sp;D^UFnmAu{_>I!sQ*W7hd?ztt0REW_({-ga<#V)#ZBgoL5_PS*A^Os1%)h`W(K zGBVQf_3>Z_wT7y7&XcP2sbq4~cjcDHeu$yub*C!o!SoIF!%Uxh=8{kDN`JG@ed za`az-UYMo9N_dKG%PGQc549Wf?pUTFP>nmziZf!;LSrj%FzRyQY0vW@=wl`G$`yX@ zEgCZDO%?&*Tkydlz-S~b#p9X6-L~719*gmN^;{aAz{f^AF-Ni3PW~(&2Y~R?jT*J} zWf5vZQdU%j|Fh|uT%HgKY)sr zb<*-Qh*`#Fx6zRCqN8aVYU^mo469;|pxL~_hN}p~SYZ^)FM7e=zoI196T+cS5qb`` z1Pk9NVh!>0tc|JC>7-kxR8LzhSx^67cv8{p;_if5^Tg?G?k|Xzg`Ar;P=5v{b4Po7 zF*knI?ZQG~O4iH642?G;k&m!@+2x9yU`cYh6_#b>D<=3QML$hR2PpnT5hqDF&KQuH zW(^04-zE1dicV0d{}vg%Bb$ec_Q<1pb< zjo|f-AaEow zbk@c*!ce}a!?0#%) z9gG*@JAr3scn+lSZ~kXe4Jm0>78)hhc?g(%oc-J3154kI@U8i)9G#-ddW8LUb;#yU zgb%`7KJ_4c;7=hB=bnyK3YsV~Xn!g&d(s~&1;z0g%qdX0URHi|uOblhc!Ed`QcS91ElAPbUwjrcIsRLtPZWKnY(cW?0oS?>8q(|$}`Q37!rxvhHmcSOI;c7wa? zQfEP!h)#6%)_i*Fch=~QEWFkwaV$(P3nEy{jpwEON26>9(uiCXWDk^~)oIbBH|hK3 zJ5in4beiX0|3R(E5e4TE$?l<<`2ijIRo<{Po%Yp8?knDR{cBwkr!o4Wu`#*Zpp2Vw zD=%~h0h5^tk4WxLA;#PE$CWJTuLp4Nw=R*%H^BK5gw^q>NTlyg;1%`xb!nFUcH*fy zyq3Sh?!6q5d-h(R>sYc+QjvV>Qas#6gVkfL(4|2oSMgafSb6-H06y$gZpbGM0)Ygn z`&RuAe%aI|;#IwVciL5vrZ=uBtCN~IJEJsLe5)+)Z=hHkRg;H|jS@q0r5AR#N+Q{O zgj@I&1R!9zfKtfST%rY^L;FS@SB011d~>OX%XyFz18|r$2+%$_(p38wjgQw(#K3b4 zVbvLyROvj(@wpL*?)wCgz2SX**x{;Tp3-5FrFNyN6MQ;tNauAbSf@=C6)zY`{h6x& zK=~QV<0A?Ru+pogt`O4o9z)CUsTJ0}O@Tq$^?c5n6_`sNI z_ZW4Zefp2LJ4VHcW>>#nLv2HIDJCmO=ckf|`f~P}=}}}V$|w1>#fs?IE@mx@$%^jx zN|l3yx!?24tWW$2zcLEt`l^H=k+JqvwsD0I^1Su9>wfwmHRZ7RdK_Siq|-_MAbxPq zvmWk{>%&t0@OlraFnkv86=^$W(DNRqhK&|I-qPb2$mCc%h}A3Q3jg`6tfm$OcKC}1 zBS!+NACHtEQMNT2ZxuBl6BnXUCg2N$w`CWHZKuGtkO1D1l`SSCsb!Ae9gQisAJi46 zYU9dq+XLR-1u{G^&MK%FaK)!D`g~beqN2N=C@CpPoW=IGb`QCCVI9C;e8F^*f3?9_ z9SG{Y+JLb6NhgZgi}9QWT&g@Qd`&Z5eeiP)3|}Dl<8cuI`v;R_4JW&N4j+K>GwI*p z8u;GHKA)tDY?B3a0F;D%d4wM?nJe`h#78)tirkXS^&3Q$R24q?oN*zVhFXw=TktwO zoAznxLs?bIurca9|4DJv)@tPsjCO($~Wb{or02B}sSp=4y!s0859DF5bg?;U*JI zRD>H}9>_pB0$5@YsM~17A;WZ~iY#mDbMx7I=y|T$_KTmdaSp@eP4L{#ZF-_OrxGI; z-1Ss_%zTP!3@*t8^)VGvRWLmqB(#5&xtQwPY-^K7Qkh|e+>^g@26;S5N^!>X>~T^` zjX71WPB(c*;FkKi>+f7x6p370k!tdLtO{FVT+geI=_MekpEMY*7o)2yA!#b$feMwx zDZWp!=TpQ5kD17>2PxG-be(8Qanq1OK}R(p-w_{`$cqh%!LbL$SR)I0Pa{KO9zpE& z8Bt}S_Wh?3I!Q0{AaYIXH&qIs+*GUQQit7UE!lMD$#m*`GZyiK(6J3XG#tlhle+Xo z=Lga)ZRHt0=Ga}*X5B&6(fV&#QYJQHA-jqzGAksR2jWCJV+op<+wHbgaaA>GI_pq@ zpZmtzDPkh+s+zxKXGL%)Uw5^Qslm?7VlIlBNT*@ z^PXT86_HS{wR}qUgZQAk{!L-zV4>~Y4G%0eyz{4+!V2x2&EQRf{Qky={Xh zo^gN>g1?Kxymz|}n^T3c61)oH_AUt9s%%_9qRyuD?;R>Fp~oLIsEb-}e~w;u&3CF+ zIF9!Xa3)t81f{)sh54tkJef4d0EwwW{Tl1ess#CoC!6cW2kQn&!(iq=@e0l=MZ@hv zhF8P_gz2!&ZxHexwW^)IGw-w8bT&7n(Mtn&>_l)^`bQU1Rt7l6NCWxT8{3M zxddrI*{jB=uyTREqi;8wn`>+^8c)SdMqsFlrJu<&%Xp46TkT3lzp{E^ciECb+v+x{IH2)zz4;$S zTrrA?HII!Lu^>e2^vyUM|JUo>9T??$#)lUse7;lwggkegW@KrP@HCG$@zhQYTjrDh z&m56B=4@7~h+&?pxxj_@z- z5ZsED78x~N{O|SX?5@hifQs@RIu>AnE|JcH*I@*O!c*(J+goHmLIJC;R9$iH+TY(I zcyj$!iX^iu$NqudFSDnr%XA=zesQZCqwG4Riw_rz;sG*yC#R)skp;X7FffkSe0lt7 z*VPqx><|+M@cqQv{yIKS;dby#>#uuNXdCV0qVYnG=GV|T0%M84 z_}g^^!f&S>#4v*I@qRO4GfLsLfQ{6beAsZ<4G~X0HP4*`EY=RK`J1ec4LtOOOWZ7A z8|L@$y_XIz8qaTLYpC2~ed8zo^Nr!nVXQJr<6~L#R9`W5F0-wQ6ydS-?~#e+{~%sC(b14X6r-0ilEEb;ENvMHG$ zRDEX)l|bvQlO!>nHKgIASs#_*M~vpJL1ee^-0+)!3X6 zsVsgHM{n`_DZ*6$MMIM}vB(=Sh|tCaKJ09{PQ+iNII}LK2G@Ulzj2Jp;!>@Ptp`_#> z)BlTW@&LeQv%aEVvYaUk4?*0VeT;c9`i5G;9hwk-Jw6LQVf>bmS3}g+O%V-Pz%7(I zBZr(a=2#}CA5+Z-n$Ii!I!vHz7^0z;VM=uI*aEeszrN~v-a(L@1~=Y*biO=Ffgs1% z&KKVc_sS%sq?%zXtdGFZv61F0dQWzXNt-erWEWEHPI9Yh^PUF?w^^4@KVfcwy~JN6t9h82 z3*PYe@acX!=a>*|Sa#ki2tk328a}^^d%f=@T31!q&^YS3+1JZhz4z&}Z$29@Q=9K> zs68<7Il?pV8=;=PSt2}CBe3^B7d#*iX}tjnKQs#l++7e)yV`5qP9Ko!=4pd^1ZmL- z)5#anZja+cR(cb{T)Qz?j~4TvUPJtDy%G->2M_BhKgI6md2}Lk?`}@;xnG~N zHsgcVot~&oY?(IW!|T0oZL&Sqy|@RAq+w$W@#Hez$KyVpnS##Pe;4eQ9@!k)|K~Wnf6`>~9)vcd`8sgq z86tiY>Ogu2ca3Ga0J>{wR5{_1?by9Hz6wP6^P><#3i`13N6}4@L=O!1u|sF!{fjRZ zx9N_r8|ukarmGYp;ZMRwPIe&w82H|OY*f|ZsVuHoX)$fzkk+c{^GgVNfbjxetFqg@ zzDJX-b_i?tx;)sR3tVnvX)=;bztHkzJh2Mf#RFPH%uko4o20KcgB1hCf=FN;QR)a9qy4**=bTENJOy#7a@ioe~`OROs=-z~$&dS6bPg zE6YnR7k*O}N`{g>m`%!}+g;_j^6a-w_>lWfy|{oiU&clEL`grBcdz^-3soi?@2Yom{*`SQ zJ#$49O~8Sig#LyIy&*G}CDMuDe?|C7Q8Q|_d&39F|M~J;*k$@Rk>1>XvpQVBJHkL` z*U4&C6hW#VpUU$eWP7%5VcWHo`FKnwIzhwIxz;h#04wBT9~t?3SVO5h#1XrDeM-=P zo3*{|$M2IRAJ)a$-6tlokPxpeOF+|4>@)%_WWg^#c}H%Y1Q@UcKP(VpTQYAgLD6K) zK9_~Y24nGAH8D|MHKD5#!KYSIQV#y$9cccPifEG}r`CBmKezOwpsAwHK+n&wT~Ffc zpBpabwj+082yY}0j`7iU2y6*EiBs2LAmR(J0UDa3l~rV6aWN4J{#b84b<~vdMxOPm ze>C6xJ5|9z1Vg`wJ^4;?H@6I53}RrD*WD1?2}W2DKP?}PAdf3ChYE`r3VmYUwHW_E zyfd9hHOk42i*XLT0)TLmug_EvphgIPZEe1SnA@0i#`Pk1z5=w&UT$FthiXB9=jJozs-D4A zf&ZPZ%TL|}79Qbj?A7y8umMY{X}=2t)pb{V8!Uzr9oSA8{va2h%)S-xnc5PKI>g08 z)?FP&Q8Q^~ws)Ii8&x;d&B>1i{^QQt*Y`fI@Aok6=R`1)VO98cL(R69h5{iRH3i~s zkj?P|t8)iJQqkdj5pr)B+LSG7jmmgCd048xUG=A8DWBwk+1~YCMG8s|;uj>e-pehY zLp;kZWvvw^>f1j?EB&3x*^1pKv?49Iwzd_@xWHUrxf6%`=S@pG!%nwgRh(@OS?+>kKL0Dxhmrnc zk6CBY?@GKPynBF{RW*W>*7zn4=6Ek$>riZOIbV`S-os?w#H_&&y&vxi7IJZ1Cv0~b zf`GuX<*#7?UwXV@8??0@v2}x`Dg;6UTAYwB1WFyI6#!?Ssg~j5 zYtCJa+pXt$ac4%zHn3|@NhofQ1H55DnW|vqHXch`I{i*^v3e~&Ee!*U5(~o1Fe1;s z(-3z#<@fK+tPS&i-5mus11dZA{7h-LTB}(dHSkkTSN^Zwl%l>6s9)ddPtU1DXNS;~ z5NoJWy&Pb7tOwORo(?l^`dH?leq1;v1C^M>nJ+NHD$Wy$BZ)T-IvyrfPUE}1$ZMpY z@Le>qZx_9Rj$|}4t}~9xyQL`C5Ja;FZli~(4y$ly%xr%4wNKw#O#p>^N$GW(1%2i)N`;C>z!k)r)ug%D_FwgDHF$H`RM;wOtHfp=+sw@`*#=$aapFHn^ZeMjW{VOxC~)<7_H26&|BL& zGYADI7blTwaEh@}_{aP_!vW!s)jLl2=~kwNSa1{xsKGtPO`=%n(!VF-AA*QzmIuHV zqQgAKvM8CJpn5#TbZz-y0%;#nmIv?s!mGReHxHK0c*WUm&%F1pliAditZ)ez^Z(wn-*@V<)`;*Zr-Uxg03xLk{9IM_a_4R)%vi zAdqA!mx$K+-#4~$daiNeJS;iKPS!T~!7S`#Q$GH|Qm2fHBuTrvjhyPs07c8?KV}yA za)2C^Vr~o?*mAHv+<;Pgu#@Q^C6S`ZRy`4u0pVA-s*DSr9z4^vS2Hx{UX8=WlB`vv zJ?k|Cu%IV-O&OIHyJiHZru0OaL~PE_YnDInzQ5iqw(dq&I1TXO8`U5`Q7~Prj}G5v z{BCly)r>%OVdj|8U1+iPJgKWJHZ3@Ldh^4w?a;B3&)>ReI=YZvt^bA>*$T>?obbxrFW#=-k^94-=wEfZdp&Q8}=i>7v z(HUm5?8Cl0wE#AZ^ge#y#F%!fb&?D4L#3 znExj20FTj=kflr@=)WgaGwHr!-2W1M=v{v_atrJ7U%oz6eRWT5bKBxp0=DyPu_7$m zUpD7{iK1VRni?4)kUM3?(G5CbL{en3THl8?U{RrtQ?HLhW2<#7n(xDAZ~iJV51$Sh zw%OA=J3A+LiCrRK8qxq6=|+1enol{bXQx&w<6|zvn`m(bO)uSy{lnE9f6Y!SC+ePVk%cSoUk^h>1^X zogcA4k5Kv6+fO>;yocxc*@G2_UsQExrP8_UV{ zEHP?TAt6OUTabcWTo%)r+%`Oiw>dmWHaNQ-uwPcf{?dD- zRcAsiCogNiOJd#jiQvNs0kw&hja?te%g}hga@iB|cyRf%l@{QKsw8|zVBod)Rq*;o zEnUEpr6ZjSV_K_l3~gEyY>l8DkBWzkkU)rBrco>@NCO=iD&?OuEB`qsL#e2TpCG)aZ|bdAh0Y<*^mo zx01V=W_S`?oycimmg~gtf${gfM6_i4LrPiSVG}JoJRECJ97g;#n9pW@ z9Y$~3-P}5)SIey0xO}axPMPl~jp@Y@(d)!6nD(yJZ#ojXh!y{4alBquR(5v1)=At3L$gYh7hLEM4%a*{ayh$`s40Co|A0>~NJ^?A zhT=^$?@sNe*Qj|wx<@mF~sqP@4?P&>}m~(JT`bCOqxlRdr=1!kAI~HsI@ed;IA~r z5PM?=LOxl*H}1c}eSqZ!U`1-CF`SGB%ke(g6v*YHWvWh!NAI~Pd~*(D9Af~rQ@}*MVTaMQmUjhMGQAkODJW|Fcj+3XjZHvt@U+`5CC> zXx8HsA_mb9$Ip>7S47F`eP$i;tro`%%=z%bxi_UX==xU_bf+40avbwX2eSr@#3R+K%o&L@J5g2QM7g`J=h(qGK^164eZk#@+Np^xO#UHQ1SOV zR$%2>*kQ8C%|Udq@do%+sPXIF*$1HZ6Ivs6>q1968HbSduk_dUqnM^~n3$M6lB26($E5jm<8`i)__cxeJ=e=$}_<%2x7iZ(FWYjrcC-Oao^WD@%Yh2TK_STfW5uVQH^=iRNTj~C&_{|6k6hs;%Ur)X z8`Kt}7!D$+{|C68p5>hq+k1T08c&BzcORrX3s{L}- z-HRajcV`yR5OX4IykHA$v9B2JJsm!JWKtcsst#J*mQ@A^fo?CrLM8xl#Sn4&=w%j>P@i{XBM{1q@pM^wy8N&NDGv*DVHvK^;)Cax-E#;!*z*xwBwnMwXC zaeXm$*`j^y?Z8D7Qw%i(fQ2YHN**4s*9d0^pef~oDlYicJ$+NKU+?os_wp&g%_G< zpsLTkUo+MdD#!9bEow`cGaoPIV_Ap&7F>gDyMVj3g|At_PGg#9D#=JK zdvml9T){#R^Gsr0NH?2)7zk(jP29p?gmaE357hXu6pO+v)gPZiDE9Um#AdXq?0U8?!Ccf&ypZ3qi_OWUUQp@ukAb%b zmx1@KK70|Qo8a>I6}efDb-qOY0JW`!D7mWZPryBSB+HNTP6mT}dgcK#@(LtRvE#jgK6~VhCNjcQZqp1HU;qZ%Ku%nv!WQDOtPM~0>{-$cv_d^IJ z!53f7fpb1MpYsM07=**qj@f>J4krpQsSHQZzG!@(X0NHU`L*rSRN)6OaGVq4<^S=UMf?TA}MQ3La zU$d9;x@E3^Bq4`IWBi(Sc)y9~{V$K3j?I&<{4mncTs^-g=)qV<(8lxe_u~ysN6bf` zjkgY{q35d?^{NMVPQVd0?829ftu(iDiAj06nB}1PCQ$Q?mttOqaCFwaGl^g5X^M?_ zJJ}^W_&bMC=yKrza==a39ZHpcJ+XT82x-vPczC#G2o@LCyQ&htda>T$yP0HQH+63s zQ`_uuxLY8LwWHtn)egEZ{%*DGkfRxXuJ2V->-TwipxfA|wtaELV>eRhThf$08PQ6_iJLRV+iJ17WW|B+Xc*8Q1B_@{_m&^riD>lru&Ogv5oHvx;X13x`?#9~ z0qH&cU;d^;s`2);;eC!N2|t;y;r}44Q%72D4{P6i>h#rD!|@HkrMtu(yV+BreD?Mt zP1QqoB3x#*kGKU$7vCfHaM_bnO8m!L1-ik7Z?j6m%VoR7uxg?Izi{ZeUr$vIW%Qnj z4y~=1bJ$8o=h;9*5HfsFE7VfN)<5H}Zzt}8^9rq-8O;FpD}J5-yWB~w3JC$4{kWef!xRV`ga$nVcyg1bLEu#A5DQRF%$vugCx zx*@$UkdK1g5>`;(EaSf~$EbO8{>}AqpFK9O*cDLf!w~cQ&w@nckJK3|mWGBJ(BSvD z+U@y@+^b1;BVj3JygdSOiH{5#uh#5g@ZocmbqUroeCsG^LWfAB5q1GGBMG9t++R{P zV}GMpjs7@W6rS>(8@>sQRDA~@fx{&60wl9uuN_w^b)=LZl~YV?CubPsWjc7IA*2pr4&3L2!k{CZKmS=##jyggFx*C{mO-I=W2S40+|Zx+ zv!LnMItf(-72RHsvpxnTR{7un?uF6(^Ff`-wCkLvgQ&a3I|)SB!KH*3b_?}@Xo7X6 z76;vS8|vc|o9T9+@2G$|{9Z&nqd8GBsrwq~`)Carb-&2tCN-7%o3F_=xiOi=dUH>q zh2$!E&;}s=lu}HzKR__RaxJY9AvU2Z16OBIYXLZ*Jgb2_P=6t7R$t~WTyj;sVj<_e zKC03W>78&J?{THyL*QC#wRnuiC&-Opclog=NtS_~EdYDWsj%l74seqo%jdLC7`o@T z^plLz?5>aD4<$Q~naVW}rVc7Femb>}{NsX_3`;)&y4syM5TGpxNQp|wBKMyTBa+^J(q%bu4nVEN+q(leYq$w#W->2#O zx1j;~TBmr;hCaa}3=4!P_$-b2Rnl&5T>g&zxDNrHZ$bt>xAWW=lg*3mxBFR!#E-=d z-99(7m3sxAOvUiozhYpQPMtVhb4LCc-v++9xdF&=R?+wZ5Phixn7Ec`KJW$Hk(3$B)S* zy=0>QMg%=!8Sa}uZ-XMQb&s#^9{=PHhM|*|zuo{#Utb&~BF(|vVXi1mx_`KCR+?;Y zd5yaM5o!*hj1$C)6M5w|NVyPuC5U(!R`M^9{?A5l*hJ91X8(UDDD!8#5Vkc&n`5*t z=eKo0P|dPGmWIo)r61imTEnGMi;hR<>!sem!1*7Pq|=&?X1p{#Z+fX% zk~05SqQ}RB9JRMMgm|l)3tfk=icMb29ZmnLI7odCZF+G+O}=<-1jEgkERMS z(P2E;fuvssVLH+IdW`jD^yN_;ayc@i2fyORF48#dtCD3Baj?^#b;WtjymXP>;HtjK zyhV6ciC5IQ$-En{Yt#Q5HJ81 z)Cokw5=7nlF+G>$E=L)wO~Z{Iq#RJ=7^Nx!Vn=JN!Wjil0u z=A+J#KqPwOri3kRj=xPtALX3Y1dgCd%(1p{CVx`L>$SU=p&x@NzHXk zkr~(W><&)UBNf^ut>dg$2HCwE%Y`_Bk@$*81Rr~km{JW7K`)pq?8D?RYXm-a72r+UflN$ z?Xd3~x?zj!`hf=qP#h(ZdvpWOTT0Nwilyi6S)1p5AuN=+?5yzQN?0851>bg|Qo>D< zYoS^MtJ($m&n&k<&BG|cA1dp|io@5Y8#0K(7@A;oHq_EZHB=G zt6DDChmA)?ucBJckeO+w7^WxShjqggxJ5*@>RNZs=9+Pd{c^8|e{L?r7UJ)7a5UY$ z6@c9M3QO9>mF9x!CbM{yUXDInhv3<~-nDen%N``Fed`X#q_jIe4~b&=BNKPO=8+3% zL&L8r>PxjNO8M4hygY8)ABj5-)^wBXf^?mg0{kD0Z&|f!MSuNAqLVlXbYTBqM1vpq ztF1+Ten(GeGrDhv>=(4POt+ZQ>aBN-Y^4D-6Z}oIh)ooWo|~yEk{3C~X5h3Oz|8%Q zVLfiA&ePshfq&_HsdbsSExge7=Z9Hb9b#8`DU&4>M zyn=zg499VC^G^ z`pV^m(*~7RR!eAb)%50YDrqumA!LYONrB2fc1ZrpiGpLPmydj;e5477(&R0%^kjrM z**lryjR;8_D{wSH=;D4+y=Tkm3)X~ZmgvfFu%e+<#&gS?97!m27dB_h1#m_E$Q){A zO!#_rBr+?jDT|5P_#>5k_=hCXU$^+KIjOc&TgvnT)WduL)w!eX=hSN~ZKRgIh%Dhx z={WwX?#jNWNHNJ)sZ`5hRQSgh*t*g+qMN>QrE@v(F)*}I7tE2r)oJ0tJd@3aWyZ_B8991O&iN}Q+j}01+fDb2#>Y1l zpzAGh5ajM49g4nYx&4OY0J^1L_qtF^PEL-RfNQd2x4jcoc-rIu-EZlE9=AS%z5q!L za0hqfDK7dw7B-7o@V4f8M0#!2HU@Ps{DX@|zpvb>VIG_4@n;V9(kyM#T+X!Mtdo@N z2%-#mB6e3L9D*KAPZ|Ttut+E!CY)f{TDn*E`LQ}2v9N?@lHM-{0Jume19}NSelGci zZ@snZ`W&z;KK0uPaiXKl_SL9Y4J0#JeN;z7qp84LQXWz-D$Y4<9rz=-Os-Pz+gF!0 znF=XTj+DWuHX~^=iJGo%p%Z8@pJ_s1K`Fx@S&fw%PcDE{Dyh`LN+#)Zy&4?CNjU9x zX*ts%ey(4%WiFKU{B?1B`!#wH0K&fLyk=Oa(ysPC_KY%hD$Kgy>PGp^0D(sB>6op_ z1TIU?)1?hRmll?QSqc(GS-*Mm044p=)2{0Xu)p!edy(SZK z5B}H7jBBLW1x7USp#lV#peum?(gwnSVO~4`U!9B4s@oMh0ei<=aaecyx+P&Sbva49 z^?yCM>y{mKolVOJ=2r^`Hl2)9h}ZP6m6w}jwXV01jgnybK2-FtA?ST3Vw*cfejOlo zIF!GvA=dj{xR(M``Tyzc+zQy#wwfQV7U0<=|EKp-=um*3QV7I-O$Vt868Fi0Hg-dmVnd(I#RuFAXc5Q7y%^XjX z_*y#Z%dX36Jj$4E*rA(zlSuTwp$aEpZJnf0qML@e7Cq6?lM~3TtMwHq#ALZ*D)WwN zhG3NY&+g=eIRMKKYi2|4L3U}S^e>?_^|oW3!3r*_IR)ik0SZEdOC+rpa=NMM%nwzY zj^7^M7k6q8;2UYjqO?>cYCRq-ITF`7QlUV8kI~NeGu6ZTcDDQxdO6gTKhH+TMx^Ny z8J)zOPI-V4;#DlNLQYOphkY3=ZnQ7Y>)fVdZO^gc;d+U|rAa(W9|{43vQU+g!6J;z zL}Mq+zTae6D;UoQ>BPU>P$+I^x1*6lVI%1Uw{4@2C#_XqPpezXQqw*&ZtTOarBHz4+;h+->;NBYSAXO^Nz3?csIs@sNAG%1ZmotOtEH| zZ^lSA)6>rmI4NOMIm$XZlrOo3F7ks4+gVl9Y!0*DeaBII-V)*&13HU%OZUj?$yL%` z!`=zl5(e)72>l(&M$Lc~>)2lyzwPUC0>m^Faj1#gxRO-HqW>RLZxt8y`hI_lv@|H) z3?b6pNO!8#&_j23NOuj5bR!^LN_Tf7-Q8W!XaDy8{$CF#bHJS5_uSXI)_SkzdU-LR zKIL%sS2yBmOAz9#Bmc?MZr1slPQyllDQVZ=)GSI|&fBoUK-XV&aGpIb@j){NIF)GF z6?`^=(wHM_O$+G33V#8wB}Ny`iKVyoX7wd=H>2+(7{zre>-F!>tq1souL;rWP+2c`|K;U#m*hVaZS>{Is{g z=-(UMO*57u_e1xZs}#dly9^6Yj8%bA>!VoI#fmus{{DFLKv!;T*I$}qUkG?BuO?Wt=PR?#@oG(1$yW3RY zHn`fGIB44`5}xs1=jo-&c|I+!hvGRB-^^kix7sOfj&CSF3(WI=+&6u9_X`#Z}Y{{;DpLX*H z_tRi7S5Nnex1Ii25{fGrwzbUbwB^=r=9_vQA+yeb#GBe~ebRzPa_iqZLQWsjBl>F> zV}a@bABB-UX%o^>-dE4N*`QU422#Pq$jkQS*KYnVdLo)KRa@*4%=>F>J^}<-nj+e6 z9o+UeRo)ZKp6LEzXu(!Fvy>Xlm{B1tzV4W|zG?xSLPG#=2-$z_xgA;HJr^;zHQzXo8; z;q}YdkWe8XM$E2X$h8I}$|djRHVb#a7Y9OB%tk2D&A&{>s@EpUYM8yJT_wp?^?%-t zkgnb`&_ID2QB)`7cPJWT%McjYgE%m0vaoFuK8vYFhN-iKLakM|;2c|}zhmv^6OFX9 zC5!|)i1B5+QH^y z<1hVdf3<-d0plQIagh&>>M5vgB5+pH!O?L#9O<#JzEF3^uWEFXnmIH)+`>!9k!gcf zOke+_1fYqtz!wgBojFqUM51lGSCCCUKW+OuKC{*Ph}Q{eIpoez-+VNls*W6$gT@;P zv2i~pHP&BvNYAwhRyNKu-#Z=1x*WqlIHw=~E&P=( zY=IocCR0H1G5j*&xDbLZqg7kkt(^{mGC597cigX-?eb5#SL+(`p4Rql zrBGZ_g)W_X;y)_!X$)b3=GD}bHn$+?V$R>9BGLM2qlW-xCf(Ud{XK$kf@71ck+LlT zPUdBuW6z6aH%i1r5;r)8v}mrUAfi=N$JuyDg3%?& zW4I{w(~k6^UW*6DczKpIYALX2ZPKH*R!Xr7m*xH~JqMmt$J%|D>~J^iRq1@sI6S5{)DnX=tm2M~X|zXvBP) zF?z!(RdP^UB%7#hKeZ2hZy8tJwuo$aFAnvd4=nG$9VbAdJI>;$Se@o8GfvQjH;_st z-huxxih^ft(Rt3=N0>ZL7_LSKMY2;dt3LLUd4e9I79BcOECVSGDKMw;%Ugj*hiny74iBu33jzZr+PB%Pb3_S?)Z5w!A^MVKvy6R?_ZyYpt$bu zegS945f$TJklRH>0)ihei)mD{hg`&fTF9MS#uumog+ms@9`A9(>ceY=(R=@l;-?~Z z8JC(GcCY6{Jr^D0REno#ZgU-JldB;H)M~*K4w+J@{866XtXJFN`-O5B$n5`H9D_l# z_ma~@8b)hYV`$AeD`G~dO|Kj^_PwF*yI6D)!KOW1qmnvw`%Hv)8O$q5iWeU*BB#Cv z#dYBgmNXfc<&6LIGvYWR4NJ&l)(>TYiYcMI%S|MpUXWfMp7d&+_xU=Binll-XE~#N zL1Y;4F;CfjmbD_`Qu7n1>`SGZwQ7=9vwtr4p)w`rA+Vu^2z?oi{f?U2JJfN0JjqFx zCw0?7Dt4h9Yv}~?7lD*ZGNuMb857H*$R-I1*07qyi1ZJvGaHPgQ}7m9CTkyY{w9+| zAKgXzNsNt!1ZC0C;~<=?ilUvjMUKRuB*_y`YUoKsoSAZ}-nT5zII9ILXFHb>* zm?4~dR7>#5(9EjhKI{Iu@6!euGip{7&nURFiPh986f%|Og`#C6PlOYg72jcpX_O}! zTaVCdu@J{_8*ESVrU*a6CM3T9SY>I~#;~=koVk@P4Jd_GWcGTvKZzWxOuULvVgl(5}EF2z)0+5&nJWSyTu2%X#RUtFS%cRyE+%JM~>}A)C>7t zP6o1rH@SLheJE>vdiTIc#ub~tNO~WuO=zBzCkaZ zb<|q9@b)hJ9b|uxYQ}^f#BzWb=Yq!C@55hRnVu&lMkzQ-0u#L__{1K2IrF}+&(=uR z*uGq**Sl4Hq?R;y>FztJ9&Jj`0GZ$J_%Q2fi&nOEefA6RDs+kv0<8ykKmHRHeav{a z2Xy-b`;G1}*;WdXqL%aja-Z`qM-NI%|7Gm|pf$2oS?oV@)jGE0r5%Pxrb4vpnt)8! z@o)RQ$PYiFs8u*IT1%;j2SiSNOiDAa^gzcJdsE!TIuJ3H$2O#G=A<_7759VP`Y&zG zH;Wb473V-H)#QVV5Dl3}@pVDFUZ;Ct2&2fM-YC}6pXaZpz*O4NbPR?kmkF4)>?Bw+ zAvoB|(hd9N?XfUk*pCV~;mRKIV+n<+%f!fJBVnp7Dofjw%ExKsx>1%mM*Zc8@9C_l zttV0VnZ)NJLU^rj?nPw7X1dYVch_@ovhI&I^N8E+p)lsEz^P&SRg`0_-uO582JMY) zN}fxaN~eW)Wgnw+C>C@wx7Z4(ntoa({r(v3NGJR$yh;p;&&}Z9yGZH9a?CmWv>`S< zt5&Kl%Pxh149ZP3W61I=gu1RPsiitQi;x4Vot?E%xOT$KHsmIqIWeK@XCeoAs(E{$ zLsS09DNIcP)}>uemi^>gD0;%h^?wFGN)eVP(nX*mGkG^Nzm&(|Oy?GbL_9D*tR28+c`!>5lCq2h9>(v`?BZmHdJK8)lglh&*~ z703x_BA75?GH!zNtS7_6AZav93?Ac^6LaLtS#Pa3=7$LtDa!K)Z8KJc_$ak%6)hQO zOGEBeon;BGWr>_xQ+OcP^qduu&S`2D=5$58G4H2wria9IQY7znTO78ulj!nFcir?s zhb-RalM1~4572B0)nsn=k1i{Jn>6&G;?t{OaYsuw1vWTF!CP#kZuPuhX7mTLy93j- z6AQB+&kiD_h=4SUmzTgXFN2S*ux6@$Q;{>Tpuh}w+12#t-@qRi^n43wC%R>O0CkH3j)&#`%~2Kghq z3S%UmZrme%mJ8L1*6}WPANV2l3;qq@Il!1_=DSon+TL!k6GDQH&W~NI?|4vB^wSrh zBgvBIB;sL<`v9A}%?JQqYaQdtQC(A0_v;^<8h{5 z)UNo1&lAIh;M(0Cy-sDld_`7-yY>ZC_lfcGY&ECUdZ+zKg%!lu$gW%IqIpJ&1+o}` zoK4D03Ocp3(z3nX`_~Iw`D}J=()ZuwX|SZy>_d8B@nu%o1tIBI*&N=F?obNN{?NN6 z=dO@^T?-G-TO0;G?aArRZ)!zId^2_DxaM^(F+Lbo8o+N!MnjCSisnqUm$#TjRXG(Z zz5~k>jLp4D4voL7#8KVt3O<`r=)?VFk>DpmQ{T%UBTMis7z5mga}{%EqrE9rkha-m z`Ld-$c8tH_mOx<^*EFlNmR7S_92&va?k>`PEhqABf5ccH z#cm;P$YN))|4Bym=S3m$dd;S9rAiCDO#lu@L`@N$t)?2_GlfJBqehJlkIw4RLd$Rl zhE+@7Z!}MGFWT6j0X0&^6%r4IYHy{DFvePCygMi~BGl?U zzmUr`@sCg!UjLBq1r6#)&|k88cNwn?SyI5icuT>XAm8N?`GG9H^Asyd#ybn2CBr#3 zP|RPsw9g^VQd(kK#R)+Dm<-@m;Mx-v$XOU2%`>Y;JaJ3>7@wcd&WE)L=w!{71r5f2 zevkeTn~_*jM>y%H)C#_9!Ix~eZGam3$`WWb$ql4KA)kBIYpQ*&-36_+Eri_7G#iSF8unJS zPRlhTZ7W7dzfygWA}I;G=jdh{gJLW}`c#A$nBp_vPVr=#*nDb`oN_;5C*MzclgAh5 zMrFP)nCGbb*xRjw-oaXswfpnd(mb>8BOBcS56xvT+99ju%Db;U2;t%Is>w|^DVN$7 zKC@IM#~ARg>x?XRo$xHziH}h@E}u3 zodW(W1PbQ1KU%xF0!eJ9etx`ZT$67J%F~Sdofk1eOE!{fK96c^(om9ATikOO#9Cwc-DTJM$dnHI*R^K_U*d6G z0uOM81xxjYz?>pxE~cTIAWp3bkn;D z;j$@9?Z~ESJBcf+%NMXjS-t?C+J#;#f)$@fYam5l*Yy1UFtX&^=*==P8yPy<@=JT< zoH#pMgEe0ORjG9UNhp^y?f;O(g;RAaKJ+BM_d|MDQu4Kw;w>^Z^z`(Tha6LlB+lS9 zT#YfoTVkLFkc%MZhixl?_k)!MV+=U7N^kk*%fC;drRXbe{{NAOmVy%HR_aLY>|!H-Nu zfb&T|_GfAcoX@DYp#Oz0xZ!ykY};Cbi|#^wmaNrB>PqYbMCK1DvGnK!?Ova`>Zn`Y zM|pW}!K*-4VC!k~)OU`J!}V|GrO$F5RlDG5n@w%q+0-m^?UE=sLh*^38&A=d8g=mF z=UY@8&ncl^QXeFryS0oxL9gN{bFu}UcW33ox*_pC4na}oMA{m}tL5H@JWD9QkUc~D zaORb3Nr#dcIuAa40s>2_=gjY4*~&EP-P} ztAsmoXTjH&9o9b*VzY-jNi{{EYLzK}<>a8Vx26OHecCLRyOCrdP+@u-#^(3gqDs3V z_kf@e>(O|l|Cw!^vza);RLF0EOgNm{QLiU>CM(yXi-9A->-!?-Sgy$o;Jo$yIMZEg z0(GC>&#lvD?`lzA;Xs-aN)H;PGA$N`wYRImu6sjHd-1yE`Gv7E<_Uk zC>^?uZO2sH*^Bj(ELbSJXIZs2k49vYHIcQA+cD|{ciJB zSbZmj=tf%9*sRpkMkYq&V%k0;tCrsZ!_kh$M&)+fbX)20p^3J`o)?}rz4*#{km@8>%j%disv&SupT~9~ZyiW>>dQhhG#8?ryhl|{`H&&j8Oe*N@Jm|y z*EeUqY@g#V#hRCt7TiAmgSn|1HG3ppoSWvu&wCWp$zJ{{0r5OeZ8r0kF~nQj$|zG9 z9_CnyILPNiP46#nyALJ>ydHW)%fJn4*Ax_T>3a4Y(; zTH{fp(T)O0Eb5CPSYzchAXc>9q^08U6Et(}Zf(`tHA{Mu$JIM~fFs&SryoW%O&2iF z0GN-~>Rf`XYM zH(0j$WjH3Mt$9_JgOl2BH{fvE_y0Bk+Q87JDCI3ieEZ_sGCiP&wzJ;;y!cvI5z?^2 z+?5QF1$y@3O>ZS_6yGSQl)S=xc}>!9LvG^H7q#%rn7p8Sd2|{|ek57%7yE5^)gP@_ z>2%CW93OLE*E-(zR6SH_vz&A|r+EiJpu5PBvTO6j%jwV5b-Y-`9fq?z0)FUSeCgvq zZG^38y$BDU>PWsH6L>5GEO1Fon*Lc&cYR#b?!c?7_ZdT=QuE6gKOu*!_kIsvgGQyn z>dWqm=eNF_&y=$Tz#bW(?Gi!Ss|bY*1JRE8G{EXnMQUEgV#fgyjqG|q!kKkb!>O}; zqI>yj+B@#2e1}QrFN?ca_lLj4#r?Ur?D}_;aNJ8Ma3mD zaj!^)B@{S%n8@Oo1O1&PMd{ybqRE0`+)-lvz99jFQ-63Lb>4K3gvAWt7p3+uw!O-$ z=JNZwn6j4;_G?nAi5JTV{wJ0#J@&FRreCc{dctllCLWjf3%Oyx)CZciXLo|T!_^Z} z35h06Q1V;t?j8K)iwb_0`!lM#j7<1+XUn;@M?9VH+e1nCEpR{|=tC43LH3cF-VYPI z_HBIrHOj;f@psfa9D^#Ya-iXD7p*lJP?Rx2B9;3Ly)x7zo@-F%2~gl~g`UE_UbzmmDddIY zG%R{M0%E+y9k3kDz^G|>Z|X)A7E!{C2C-wc9#z;9kK1-UKpBD5H+lVXX0L+(TIq>eNB}1(|zf9nKY6pqxzlciANah!l|9^qc=Yc*=#(R z`gwCC!4=S`eBae!E?a*Zg=ikq5;ab3wmVm`@Q%No6B%r{gTCX z7S%orvK?M9-{@1G8lmc|V*dVA{uL>&_vquUGA71fV58e~P1CX>u}%MpHnhBl9DAVs z^w%GB(+u}ut%G?|ff@%GwYfBjyJ+R#CL}^$Pv*nEyRh#oG)gulwp;|;bEoC)f&d>4PtUC*SZkv=FQylxqFMDh0+*?K z%;(|D^{JV_>!jRlGD7Mqnfx=3ESJ>_sRQ`z?y`q&Wj;{kncZ%Zb=mr8=X}1VXI^75 zFjKIT=P@CZtKOSIODkk<_2ZYKx@TJ4 z+tWYdQd=H1S{?q!Tf>}p#bngaf+umY=6M_apJ}Z~|NJSL)prMntJZmKSsD_rx%>|P zUao-4hH2?d7&mAPb3I!RFNPbD2~G;Kb3;qahD$YhxQY$eG~>UwZ(unD%+)XS)l`wf zXNJ!O8-IZv450WA_MT|}LlL!311Tcat-qu>?`lwT_{nMS%c=Wj1kW+!z)_9}k z#p~OOM&PxZ8)5ekVPL%Q?koV~3_zY#Q^3AJf$yyX*eB8z?FQn@PxUsw&kqL{0He~$ zpvt|<2c?}+aFjp*K}3srUa?lHecge10AB>ZQ-o5nT7p03>(`cYP;UWegotj0SxX4U zTsf4p3}q6OOCHz}5VH2elsJTn)+ATTjnqHP@Xk9of=T;}csOc1&$Ue8zFf`tNRX{b zbWJ3&44pD|WWG7U1U2E9xR^eMmnH|ktMC<{(90gxr@8OjUVd+0-1`K1+%61MGu3S9 zn8Tn^M0N`jc>4Pr5|m@HF=i#=$UHJy>=f3$vGCH(`kFtB%GE_N@fNm!)7#5V%LH?h zaZY=Igr&m)GgX-Z{IHb_Pg?SCwzTtiadYXbx-~LimD!?9JNkw!A9|2tpFq6QaF=E> zbsA!{)+Tk4RPq#J=yAUz>(FP1f$I?t`hCk(PGJRC-~FRp1i36ZreIygR^ur?ww*`L zYCG%a6LBL~lCTc3kVEFLyg;8$X-*EQ#Nn*|NO(~3N4+3ppu=@h3gv93(^v~0IdroR zt?yha^1HA~m``4-pBWo0qCB7UpCAyamZ$-^sqyK)kF5AZ+GO2Sm74@7smBun3dk@ZB6 zSE29-s!7^hn?o%Gs_P2Y_jqU;J|eslf7kpeqN=d_CXH7qHa(tRAzze_Y-SQGj5(6U zdiO8eMu84=)Y1Qz3$Eb4U{xklWq@tsN?ZAD^fUu}lVGaSDBg|81E>GB3jG*PrlXJC z`1;>XUOc5xA#D3wv6!{*0q7I;Qx|A41w;|{y#syO)w!zTDXJEGk}qz@_b&yz`jf?y zTQsJFnqPi8e<6c5T)ilSfUY~|A?F`8cN~mE%z{t9DGH~e^ zg$M$_t%P#HBKouozY1%KQ}3I=Em4~)-UzlX5&b$?fKl{4sn;3|5nD>-n2>BB0Cd$2 zFfxVq3)*Ea)7;8?Kit%@E+N|3UMCB`E(E(U@x_1dIz?ZR^SFKf$NQC0|7;D0OJ6)N zl=nU{-MAb*8->pzbJtnB#LpV4e~%WmW7ug)lBLOws4LoH+C4iK<3)OnG)Q2e%P{jt zOnKgwnb_@437En=ayWaVNlL-|)@VKemG@v)>EC&m|NX<--*-2>%La3jYkaMo|GTi} z6^9@0bU8Td|E8JCb$H6O#sV*)vn0xvbe+{D2D-MU$d)jLYa}T3dZ9me!xVF#z_VGzfYfT(hnEpcu*bBSPGs6WQE71F z^XjYGA@BY_qJ7(pwuxvuX=UJMl_pLH1O-qiC3=G#(gYL4vgC4Fx@5O!XZ-U@7l zAHNBRm=L%HYC|}e@+86yk!p4=}?Q@y26iHrc~r_bl;y|J614CsMmwcxO9*v zS%5C_6k3?rq^3}8)bH*$3>Em1c)D2;K>QQD(WHE`-9W1MhBniI9s!-O%m}SMthl1Q zD`HGI;$4#sK64T6W26Bbgyh{Srs}@5TG-`ib2|(0|tW7A}(r9fJ1K76(HhgD!5ds*93S2r>D&j&dC=mioL0)=sy*9XvKfl9rOa z`#j2JNr?}P_r2|(;{9h+3RQoeFp613*QqEPFPzuj3*d`}W%J4kfL88Ap)toe1&zD z5G4ewm>S>Ynn4j8v*86?57wWz4KH%*Kf|#UTQc;QS8C1vR zJ-<06cux88a=^El9#NUkJ-aFQ`ypm#X0a;zz78)1?Ux&sT^M~Sta)Io`x?gn1kaXc zWjMK?L)ODP9p{7n1GA3qmMp)s`O){Po^dx?(PQy1F65Z^1+JC9e$5Bl?QGXs!^G!j zG&$}9XX>9E=H$nsdEjUSCe4Dij~UKh($xGGf5+I2jl{p09k#YqsxvRo#=4t~q=%J! zDOyY*iE&(PT-Ed1X{B45zaN7kmCjygUr2h{>k7DKXlNo+bz5^TxxcUYMlg6b$<<*pw2QL+Bk-XT^I!tqJ4=S#UUz3)4bo2kckAqZ)%I<<&hMDub3x%j z;rUOGTZ)3Bp`3M03opiY-58Enc2(ZOtcoZ&bGACJ2U&!589cI@jgvoZ&VsG?4iS+_ zlf7^Ml$Vvh!P9dD&Ito~(r)AIAXW691L=_^-&iGHQqQ*E4WCvd3 z4#OW|C9{2Rb{cY)RGo}qLQr=9`VT6@H}`xFZcMSlt(vLG!o8`AFyB8nG01Q~&TS!2 z%-aq}b+ltm!DaGaXCQWK7f<)u07a6ig*>&3!eLWS;{E-NnEin$iOUP&qp7cPdBoYp zSP(gr+K+N4P}?@^c&Bt{R)pj#Im4&p5WE$w$Xz`*lDaxhX+8c82xv~^xr5xMZC8lc z?aZi-tzE*V@B?0X-*&Qgps^et6;o%^8zq})Y$j~9oqmr3T8K=IG5Yq>ulRRn@I^9% zRlW;UA|E@fi~XT7-PG|4ogrBu3=u3 z{8K1W2vthu98$W^lP+ZgdY|{D2S=|oGN)zHtVrMQ*FI@!!J*)`oExOJC?#M{ArDfqFFaF5Gnkbn>$y z7RjS9&BNqDL`l4IE=J5O>qu#Jxz7r*s@=E@8yQBGQKiBTRgyUU^b=*(5Sa zo2LO;=61>=p4S!CAc`Fth%-tu$}!64c;dLCY}3yC{0o#{oV3}z%jL}1@YNuis9|s8 z-o&XOGN1ViU<~y)Ux8H!l zUvm9$@f=~~F-vD3vHfvKW90%jy`Y)I_ouPbOlGXxxta9m!*4HM9CyJ66Tza*S2vW+ z4~zUjW9F<2J_?V=EV5PVPAu`aRu1_<6C)!E{)#tE_d2XrDPG*D#6WpSh~Zta{oYiO zaJA#5IJfYDg~eHqDcL$x6L;e|GdH9?+W<*QwDI-V5|AW%i5$Fe=+1AuN;5p9we?O!y&6r=T5`HB6h6XC6Jhz;XSTAHXC|7Y6*nTRt?aXVx%QWqXECxcG?_N`aiu2 zsQxC(F5l(8eX0Uy-`5rVI~fIZ)f;X@UCYOE*jemS?x|<^Pn$RUxidl`(SoxNE@)?X zSG1W*7CJZ*6Z55%dX=eGyA#a&n;*%6~eZzCCqrrbl}{CTX` z`W2~HtehUFt;i75u5zX=6;B z$|HAH7+p>_Wc{8SZ?kDvPfS69b8>(iZf-8>#Kfmsz&C0v$R#*&jmmepz*$;jm8c)F zJZ(<}I`cD9OT^&wDJP(0VS4}j$_k>@q0*Bx+L0& zocOX8f0lP$i!i0BI2cRU@sfxS6-fYf|E3G;##F#^bGFchI!)r836@g-O&i*2ke>V2 zVNu@t5=q+Me;fnw3nhlI${9t)X0)cim5W(#YjFVl;SvL?v@H#0bAe#ks6DON(#@_Q z*THviu>AuAK)|bC9Os~v3t#<9;KRXnafwEZmVMNW1f?s<0X}Wtu-#kD1x-phlSt#w zA4_Dz=rZLHAG@Rf=*QP%?Mv|BNmpZL@boE=*$YS;RvXCGQ{D$}h<|VzK*=?oL**xR z5=hBI6nl|wsvqYo=WTncqhU1rvuEH_L7bsb6NWm_R`u4Xos}D+#1fK;!6&TB;+S!) zxJ@+@cA3bsK^+AGl_y=M>~BO8j<`3o_ZzVr(NU=w4K~S6%5o5jK_HNt52as)QwU3f z<`{MW#Ab=xK@bKj!~p4o^F35JFnjpZl!9t5pCt+VGLV{_5T_uH zd3h^p?7*;7ei(qasufvc+gh|mq}9S|1e(Iz*LTk=@lq9Lrco6F(Oy&T_$*ucQmy|njDa86`GK>Qx4b<6{#oJVDmZI2cm$*I zS}|X|d&rTy%{lP>r@n8m@);?lE5&OshpYB*ZGJOatl?xCIPoZw+$(mlvQza)ZX4%) zRZjb=L~Qy$MtLsfi59O#utygHBq2^B7(_MCfYmC>F(guCwM?66>fX%PeuROP$WCR- z(PTYUN^G*~qYs(KEm7!808m==DiTUZ5cY9+KgU@|QjxDQ(k2vHrF&Dw3t;lOomI`9 z%@$p2sPPhh3#$T(e<;_-;)X#!chieOnsD4~bbbckrcR|g@x&>|;jjG+=J82l2!?*I zubT>WIF7YhFs$Yaa{iQ59e0Y@V}7l2lV{{(%|v<7UgLH*Ow$9GfYAI=wt^!K4N*(_ zt!l*1;?0Lmr8#NH_7Q^vbJUou%5qbcAzP|CV)`sgPi7I$>%4$Lw2v&w?Iuo2E0)bd zrZ0gaZOOdgAwgaYI~vb~-#jSrcY)YD*}$at%NohFVnJF%)UwsFmDqe%Z3H?BT(fHf zXd%^csmo}7MjtF@TLP+$$8x-SBIva4P{VNr0-)4mId11QbXr#&Tnt`>)I++Gxh^o( z)uIk9+0;bl00o?YmWs;1`7e^kt~#VVK}YD(zU=P$YAw?&WV<2M5?+ZJW8dIl1)C;aNJx@l^NTs( zPI@x5*dXH%D925@ps0&#jYTcqsC9zx!xz*mhNNs-8H*$*L0h`zo0c8(Us2{8AcZje zi!sOK1x06X&s=Fg&fREZ3(e_&1A%h)}cB5^@P#rFuk{@OX@TkK#6*kEm|@~}6FqoK%I^-1o_w9Q6Yox` zV%F9}NIM}hLKa_CdDa7QxF}AK4v-$6d47-Sr*qlG99IX&e?ToM_+En$BdJSg2yx|7 zjc{AZwX=v@Ax7J7|Bfe(}9cfKv$vnO~fLHB+Z-V#HbiQ5QzgNKyZ{RZe< zE{HAG_9bHVys;8E>vwcJ>S?+&Gk{4_KM5P$;^BZt$YWi=nJ|LcXcd@HdH9v0@^Ov=8CG^NV$O{S+OfZ%(TXui7mR9spL&$wDU8!S#*^Vxb5+g_`l1?ApJ zgn*36|EC1@&F8}+MY4uL83_*~*kjaVOg{g>fb4xdznx7rj>RSIx7^o1j$o!}NIAo+ z#ZCOn-e`5P4&4N*1N||eH8WnZjPbbq#1C?vGMXH0CG_AhOoJIMiONW9R|Z%=dsXot z5ZIr|)Q|Y7@*IJbNv6K;f$*JR(9H%uO-aWt#@lmx4z*!Pu>p?hGG8L+!&Om*i66xp z&wM}C+QNUj_>YbyYqBM@&p^u>aD9A2$CG$1c;n~xS{tLN5fxM-)d zO>jnMpX>}&h~%b0P}5@sZCj`HhR+4=tv_w28%25@xPXbJOJTzxd}BRB3|d)pHcCns zrv2QKzdjE+Dh{cj$Y$mzOTBO?Ztc0~TvX)Z+xBzH=I3lSvKASUvqo%jWsdob)^Oy{ z$+4j@Vo>AQdvQ5po%kG~2)qmu4yWivTvOX~aM=sNIhE26Cd*|_%jx8s#1YAvP@bFy zyP08HR3grDA4Rzz2CoIVM%a%9Ft0~(uZT*xm(=pmZxYven>=*Z*Ak$5+K>47R339# z>5D$e_2z2uoTB`_924G*2EY1q>v_WzQ1|@)mT9i%fo2`>Y_wB0QOZ8S%#X2)K@@Vn z>>=~WT_NX*pZ?{$EgDG(GUcu>@~Y6Q*Rzm9UmB;S-Lv!DdY!snPu-k$K(emaL}5OQ zL6$dgV5~53nKZsvSF;g0*v)fJl|;Vp z!7jq6{i9tC!I3=!&ry>nX+YpKlVvtIa4UF*zcZZ4$e9A~Q4?$Hr2qVPk-p`Vbn{vgV~)Nwqh4%i7nj{9 zJW`oXR_w+%W7vU#(}q!rpL}JL&XM3VFYh_YWMG4RC{&Va4KK9(wEVn^3sM14ygNaK zQ3yyTH#k%uTc9#q0Nb*u66C(AKUm46^-1Q#WOyW%NQcy?55Z?*_sBL;(`7`Cslu?l zvVtD|GDZ65No&)&^d*V{yUZbe9SkUQ7?Jmtp96DU8@W-vncER!L0qMkC14yvK;?+ z-voZcX~WDIxHe12n-iB=x6B~K8oro*46BOX(j)do#-$8 zbRIJ=ws_sZ9`C5VS@$b@8Ck`SfAf!!OvOb+vKtqn>=WcDEsCYZMy@Ii3w~od(84 zUDU)IMnWYlG0SyB2RAAzEp$HMR+RN63~X108B{O4hOdV)}i+V5@}8E|ew|7d}a z^7A;$zqiP-Vq_UP``ZZvy^YftnIJe3h_OgFq5&0cHpuS>`ag?_Q5E`fz{(|;Px_1v z54Sf~QL(yD!lh!cA+U`*I|Dr%lPb; z&KyxBYm#G2j}gZF9c=A|_>e3Gky3S}`KQahblF3q#3JwBCK1Do+CJ0XE-QCQOU=Uk zR51lMe%`VBG3%{PHmS)m#8KUyb%DHS(4Kfg_Vx%fA<&yFh++6DgJ`KOkU4H$EE^GF zzcbL6)7<=ZuyE~KB0^nyWBcz_eB}<6Ib-yRjwn7KIapiB!)4^Njf?V*0se~}HwWmQ z%0z6)MmP_E$PFowOE!R;;rmxg^I2y*-+){6H>oJ~0;E-EusGj}`bcIYI$Q9J%u%Z(O;R^xbYEru3h^GPrf zi^r82(G+i}WZpjx0R88OYpz}c@cEM*v!>p=F+r!+YhJ5Q)sCJUp*XMPV`xt{|L-Q4 zXPlUIw0dA~>S98XYX5KUowxb=t*j%tCR5aTo39C(BjPJMI9i_$r{z(pz2Ba8$eR=I zCmQ{yPv`C4w+29Mv5U%*f#v5zG)Qk`$Ng?rO!{AKqCbbZ0L|s~?s4_}T#9TVMWG|8 zgG|?*`k$0bl>NNQ84{1Wj`N4`hzM(jj=my%f3pP0+m%`N-=T_>{txjN0`gf~iB2`- zY2q$6>Q8&7Z5{TsS>T}fL<_@~zw(Y5^ABLtz05w0tch~U z5NF1-T$-inU2%ZNQtXI*pnA1v+9^95UdqIH=EI!DO*%LIeZ6j_L!K;aV$!2EKVH3y zh6kvoDc@YezZJ1!&)f?QO}O-5JoRGgjdGrseZm#fSq@W7GNxL!U9M z;P0C~`!_;tb58>vyt8uEaYV7_F>|htxb9_!8Ymxc}?{(Q%TV0R0A~#9!yb1QeiN3PsG2Q;8emcP!f}mb?L@V z?`kS8i`vZCmph+aDpl4d=Bj*47_NIE5`%H919PQW|>X`Cga+eI52V2G=Jj)1=`dS&*yaC$| zbzp!z_6rQ6RJTn~3NnywCQpeqMCd>~HB!b2c1*n#-HE?xDCrO7$lB3= z0*kfpBdxewm3%$Ih3ShYyq92)#_3}Vk_N%H{fUN4XOGLuGKG-1&`3wNoCgzC0zqA( znvabNyPR{{HC;$U&D?HlFOO9KKLNC{^QYHfsKav+5SsdWl65U0sws~PU39v_dJl=K z13=@U&9(ZtGbXU=!AV_MwkrEi#|`MR39HZaoXP}7VV(bHd;$L1#T4ke;zKkh@XP^p z?HEH)fnM43sjO#ID#_?tRv_bYjAPfxK{V5ItUn&2>y1dx&AiG`GZaw8v_pgQTX_V2 z`Aq{oHpt0n9VUw4wGkM>Akl)0|dS z0H%}GN6Xos@Lrlkc~inDh*JLYa9*T+!JHhWe=xXDcha-rj*RWo_+H zPx+?+Ge$WVHbL^oe63S+oxEHOA}>)Tq6SAEw=pyzQIeT-f4L^!Teb1&Sx9MaC;*Un;&$o16ob7sk`R$Yy?r8(mu||;CY>>=4`W_5~V-9Syz~2 zURApiU1#e?^dmg7^K5)6!vjAd5bTds%ObsRz83x`Evgg@ldkeXxj(Z>N!nu<29n4t zauywdgL8~qEo!;2M71>#n~`R9^@l-3HDwi*(#M;ZM&(Cq>)S}v;mT^)zPave(OCH$13wbCw^rki;V{{!-@8dHbDhH|w|rwE zYu8^j?=LjMFI&Ml*PILt$TB4E*pm=({D%LiF>bhrn1T$%0`T9LJ-F{(rOju511B!v zUt=K1ej_@t^$4QG>d#!L`bPjE?Du3ezFdEibh}ljHk}Ad1QrGU8W|fKP+$5T0179L zlpKOFn*8wL{RSi{_J#2~4uJRT`fQoXsHK@?LIfc@YE7SHFQy`OLQYQjdZ%E2i99V) z@96#*#NYpYfFpi0{Aw0cO{U87Oo3#zbBK4OT${?O+AW>cZ$6n-hMC=!Z3QgQ)YjBz z+46%;Zkjp|Bv0&)pVeE#EM+Wkrc(zU99wy`d8+x7N64{EIU z=0oJA7)c{H2QgpniMPsMQGoz#doV#`mo~66H5RP3R@5ujY@tuHqe!|vcB`jUr?;j_jDGAj}=1^NfJg9(1y( znmi<#Sn-r7X}l`t2|zTx4TS{H_uXZ&L0I`ikqIwnbMr+4&plfA1?m|5m~6fjEL-v9 zM>I3RsRGL^gI5?;oFShn`_So%Z4yC4g7Vi9gvD2qNdRRnWTxZ;9(U>mSq!Gzy3WK2 zwgX;Ome2CTzBix_Yc=43A6y*o*@tYWaloJGG=q0MQh!1C{m<&Fj`Qh$o9l`i^6j&? z8`rPtEYw_4#Oy9NXuYRbz8l8L1dnOWp)FcR+&ZP7%8_Vne^c>$VT=* zUiKmJM%lf~%$MYcm=k23R#rLBvdQF^c8rcD*$8c0PxCoMT9U9$?ooKfxc=61wP7B4 zOZF}Gv#6dpW4*XylNWJ!%&mQD_ww|1aIn)YtkH>qI}nt`a1wl!{nfq=m+gLlKkNY$ zUrQ`?x@6iD1Z!nyC%NhW%4)aF+T65Xmz7_0-5hKCUy9>DmHwUYKWE|~_TPk`|CE1d zW)f5aP6T*T7lb&zJFS>CS0$OBEBguauxAb%$TMZv(iW@=IYvgv4bDBn?LSW0I4(8%e1C(zcT;*bZ{2JX6J@ zi-{D#e5jBBq0RU9%OO5nkJ3i|8YH-;j8%1Hpa>V5E;9RPT@*DUGFHdbgl=+c?q5k2 zw+IBbfb3_?eAI6^Lg4spzOA`rTA|w2I)Ehe#_=gCLMWb^EeD3aJi(ahMWEM+y}2{e z>YB@v2+h*?nNm=NQ+=QVUXW#kYv`M`)I|eGnNF3Pbe2_mBWjdHV)X{iq<462RLK=Z zI%u8_S^5ILOYy$;`#B94cc~~R&>Ujcbb7)tsfkEAA>E!4^e0O^0Uv)Kfe$5k8E@g_ ze|oY9i7q1C;CU0k#S5$6M3E)Wz;=ZZ1!C+f^^s$RZ}s;*QHrc-70u8YV`F#AbONL0 zC9d&wS>c&3i>=F9nM#wi;wYcR#$<_xR1XP{sbdoT%>>-f%sK6d>D8`5%%3iTbL^gy zjfD8ie2FL{r!NmZvs%2ST`9%DU^scbOd=8m5dcQgbqauA2@Q;ZMZtv=PuPog%1JSs z-w52Aa5P;R;+>H>Y$P9G%gaas{JwbEZqW)eEB0=PA<{MMi+NF?|BG#>Lu$*xg-LDJ zd$7!|Pu{b5-M4)zQTw~=AH?qTb#}Sll=yM*zbe-MJhp9NHy8iAC;RWV4CAb@il|Lg zUsE%@Ba;9UfR^9VLh$Jp^FU>1Y;25k9TEsB?d*Qr4A!7Dw^3nU;5m9NrT&9c=Xy#4ko_gc(r7 z+ARY{PjJfD;EFNFRY>5UKS65!rfL!-X(LFL^x+pbj9XT&1v~U@VKc$BjzVRen@#8w zXkA4Wfi$ava0Ef2(BO+NK%6y=Za+{GJ`d9$h+6Qar9>spF8<-O0kPYcWc#uKbcx;> zY^u-o`s0a<@bcW_NS|z+cdAFkPGHqgi{j@U-jqKe2CN#se6mIm37wi;NfUr|Qe#8ZFZC<|yW)$ZRd?sag?I?VY zpqy#G_vdxe6ISFkNjM^JGp1lN(&hpWEg5m< zuG0?f02E6fE|ao*IfcThOgp`Pd)IlF?`LuPeZkGm612pt;<6S706PnsnMN%S6vS?I zZe_EaiOF;3=W%qf`~*F3?R3D8__m{5V`=$MYqbBOSN{dEF1`^uAk+UJEE+ysV|g9t zix?*vB?p!asR#ey-{w|kE!#>WNJ-)VKr*e`(kGZI+AIj;2LN$6QUO|mVdi6+I}2$B zV%pjnIEW8B5io5=3MSB|Er05n)T4wOo#ervT8p>E+XE*`;2#t0niPAoh4bn&lXP}) zV~ZJEyNrMMzM;SQ-G8e)e@j9~fy-p#ve)Xy*?gYl)B5qkV9kSjx}VpNo!SUMa}e7P zG{bT*Hp96`Tr_R1C&v#weTYe&%>Rrjg8R4LePA6*t9hXm!HKj^U`$Qk+U)Q{1zwG)oOd2z{lQIuUdg#7ydUPo z68En{J$AC2*^McfybzB;s!4cvq|CryhZ6kaZ0#Xv3=}6S`Y;qN2}qr@kK;wtmNqd% zZSj3c(@I@>nkcP|C{=y$Z z?a%*-5mNl4s6J%e>$pG?=I2>GZRJVip}`}{xl&$e^&5fqwIs1U0-lEpawutf^ztY+?nXxq)KYD zUs>HXd-FcNOnPxs-HDANUF4yLIT7KESnJ(v$GC>Zng4>+Nl7TaP8EAeG0C?uPf5t+ z?B;$YMk($g@_=xc;hCS?+7!}vYG6Ggo$dXC{Y6vVT6%G6rDUSP{b4@p)0(vPOR`t# z9vwJ(JX`KWkNrB?xOPA=k86EBjk?4Owd8(c38Cmyt$)Uj(vMu^HrRz*p5GB1N+SBL z6c8@oGHR3iha2X2B(KdW;ZGkgj|L1D^GgU?(rH@nO z=2Ymn2MkRUdGtUdyl+4LC=zi#vVsmxx=25Liv7pY^mCd)KuWYFWky1S4vXd$2#*y2 z>ykJg^i%SgN*(vq`Y}`zw_*ZJ5R*azCgaq}!n&wu1;GK}XOt#Dc3U_iVIihQtLDEt zid$3g`tFuFbr3+5Rdz@f`tG)>#OZxXkEtO^g*e5*<|y^zhv9>XoMKR6*4>)l2QKRJ zq`H$+C}d5Zt+fXdKFAx^E3Np?GE0gQRERxC!Jy_SN&j@fSb%F1x=Oqltx9?Vwam0M zkjCnXGc{NlYGWpn>3^Fjdm2JVq;~2L6mq^w^kd8SfDr>Bhe26I4XSLWi@HnTH29E& zl}a*0h`Iy1a~8%=Lyaoh+Dxw0QE#EfL_R{=R4x z9ng0@KpABPihn6d5M=)=TdA_5g9*xD3A?d4oenN$s1I|U#jG{U-ao@NRGy-#33H9u zBaCZLEizji@dc>VXCKjCi$~hA`xB8ix9yH$`|){r8jP&;z7-(!1i$-1JT*){_jxam`c(AQL6MnL=qUieVGen!vp;uPrq_gPyx1$NYu=LVx%|9Us13CY%OLRb zyJig{?=i&6dj*4)s|3qQt1L3s%xvq4km%!3Pl4L>;-lS^`~Q^J@b@{V`_UgvogU=> ziopN#)P;I}soKLZ#1zhqNC-D!Mw)YuCYWNYBC+Q+ik~>X!@HqL`O+I|t%FvOCy6|I zSk!!|6O26jyU(fnj4IOujd2=0`1hS8oe0*^iFSYffxZE+g|T`QHU z?MR6o8pMbxugs!Gt)9qK=FJwz?`8H;B0$+wmX=n8q9bv6cRv9M6CgPamUXS*jJUJL zag3p*E0RQRsgQ!5xR?ow$SbB~ejuzv14gMdBu-*fDAnX8B=>P=*0aC%+NYxMMNvgs zr051-hgtJG5SV&r^OudvJxjLOWbG{{EcZQ9)?f_1$QCy!YuM&vwfuU6RvAqbKEy~>|M5f2Am6{7u7) zRMvg#w{1LGFIpfI7|K{msNwYhu$(SF?P4Bi)u9YUT&KGR_>%xy_pVO`S(`JxdcD2= zf{2DPROFMz1*dg1O-+lyjysoaB-)0&W{gC11+wgO-nhE9lbgvu&jfUG* zuoiMOI>g2r*Opj&hA&^)HWS3P!d^vf8LMTEQ6X#{*a!pJ)l0@1)>y#DQAe=gIExWy zPLMlrEkzj{oKS#pbSEMkS8tyAJSl#f#I8!}&OxCT0#o}<4F)P}NC_&AoTZ+bOS0&8 z8Y(&&RNL3vM8!A@T4rTylI&;7pQiv1M)*=0nMH_D2w{VBDewohw8`;HTnEM| z=$=g~gKH*Eye~-L5D-cTq)RN}!;R0j1l**rD!h&-QCJ^4fgg&@n9gIauQ->=S^4V% z_L6!aCVK;BaG~O|xzU4rdI_f(wji-dh$?noC%y?V@+gm~EIFcTA$viT;x$pz3JkJU z`CYYi^D*fR+wS8@@6ipQ3ul=x?eG28{!)XrxbE07O7V$R#sA#T|9%L+;nDbiE8vI5 zNjce2ePsvu8rDOF}xm zEt=zB37P;Z{9uul5F>UZ2YoEjq7cG>5MD51Ce@=Tlp+NP6K;f?k$DyjQOHb5SvTs( z?a2WWB52OUxp0p`!bZqK{eX#K?r%`)@qdi{F@gP4Fo^|g%T96t+x<{&H6s`hbFMm} z@Q$olyfP(!rnmMecBu~i=G2Qd4D3nr1>;Rq5WBHfuDcfudC(uuR443Ji=?IJxfg$( zQ?~d`S%09UdlpqZYd-%-I4<|D*^`14uoFzM%nX|G$H{4PPmU`Cn*+a^yu&u-X(``w z2I5@oXcOj)n4EC?g9D%{p+|TD8O2z_@?KMpy;qS&tU;jX^I*03HTcjCcJ$amWnJ86 z7^eJ6=AgfQKO^6Y6eTUb;xbKncia)h7@JZT7@j+%v$l}l5ebM#>LvK=s%8ITn2WkR zkRhzIxh24^eZw{<#EB3DYid;`_OeB&f0x_#sD z0H)7)NmNwFgfK|BP{?sb|QxN z*?cT3C@?^j6AXU^N0xXpAqBt)nFfa2Z!c>6{%TX1Q_0;l^ql z>{iqCZT8uU11MrB=%owA;Sp<#d~AJi(p2H5VE(GB-uUmU_rITg@36(cS^qD(94~JZ zvi_+$MOZ+%D0(~WMq)}%v{6L#jBq3E`cAFA=VeV=0KNmUOcQY}Qu7s?p-p|3+)O(i87#E!mrt44TYUZ0H*V*FFD`fu#q1C{Q;_UL$BY` z;E56glc2cG!USJ}o)rk>!!$#A{6$vdF1yTzBO%Z4*EDH5Op|p}1qT#llZ1zkM=?gg zV3M^W;h&L1L@Q;IMh7v+s*=`378}jt_qi~d-f&z3fSeIU{!kWJLqC;ZAw>K!&xYC6 zVjN|8#`x9nlg2gB%B4xRj`(&upm5@mJ9Ide{?DWpKgqFGv}gX~e(+GT+?1smflJWH zsrHibGVNiX@N>-2HvD;Pu0C|c5O3=XKfK8$j7?GdkPidll?@=KOBNXnn|d*pc?x$~*vO!4;R9^?|3nnTF~CI01Mb!B6U^Ka=p z;P{CH)rwSVHs;;M-_`#AnX|X134Ujh{ZAwK59@0pVC;JbAPeTorNQ}8U1TWFu?u%7 z&l|Pl_6RypBp-QMZ(NaywhYHf;Ikg9QqsA)CD91?`XFskItw(LS&%Lg6VY1=|!{Z-9p16OZ$td|aXad+hBebqFB%INO(OlwMXL6UL zC3tQRFu7&dOR>_r7Pd+I3E&?@N0}u+cbBKYM5Vw+%4f@n91N0}_IoEST#D#pbC~L4 zwf1$)c7CEm2<5n4XI+b#=|H~ae#&s|nbXi^AmMn&*GTX+1+f$Cg-;qf(+~AqcTVbK z*7Cm7Z0nL9j(=pju$rcy}MuNc|)j57e%D62!uQiP4zHoIi?5zLgnd_58XeG zxrx~JVK}+wP4*kiACCI0)9)s;9?pW7w$VcDBIhk_?bhr}=^DvuU_N9tCgxC9 z1~_&hOl7N%;-+y=&m!Zl{wegDO^_JB)3o^b+iJp%Ikiy;%uMl`oMk6IO*&xc=z|VV z;tOM?9<1SHV`~eUPQ%U(-N-d+w8BF4w={dj3dKsSk$sz1FlGmQb3H7^2(<*G#i~;=~5uB0g{!XR&#Cr+vyjpt?*D#MAU3ff-!v>O)h*kU;Lt zX!@&@DL20aZ6Qjb_nAA%MRv!?PkxE^w4SU$Ob-l01NV50EcdRf8q74*0W2j?t}go1 zprKf-;Q(#6YTlB4rBmux7Asp&)5a9|lR3dfgG#CcTftEpGx*7Dr_d4Qmv9jWz>p}m z(8aGBUE=-+-Ud7o*&)oXS_49y>;9FJGWRJ7VAO(wNWQR*Iwt%#b6+?zec}y`ipm1* z{iiQfk^YdW{F{~InSjPm_~6hZfd?&=A4E*xuglY|+1MM;~(-_g}vW*XF+OsQ-sFbPVAj!!l-H3u4}BZlLPM z{|zmwdp8ylr%kpt4Tu+cLV(0+GT2mB*~j!P7AkH2d|0Uc77O_oD|q4WRsRnisN^>u zl$B`O3)IV9>9_5pUBww#yKez|X#o1Mv3k2p@y@qV=1Oozm{$56fv}}v0FUk7O~+?6)NEhg7vXOlkF{-{LjD&U(e*CJnEH4{ zih3?QlCaFnS+EYwCqqeqM40XSR=qvyWR!w_EXuU~HrTj&QLrK_FnqXq-|du0qt9Oj zGSlJPBc-wdh#Y?qpOh9u8HR<7&k9GPjc2`KD?mYwUC!uOez?|xl5`dJv+n&cf_Xzw zMLurSkYI)`uE$i6{-!PtF1DQl!L;TSrVvXEU#yZnLQJF21+D+|_`H-gV-*%HeKa7z z6-WWjNE^h?cslbds-T>c4z?;0L88)T2&!Bm^8Hw2E@LP9@9t-Zkgc!qMsTrZRqe?m{!| zhDM#W4N}yl(>2ft;)oN$Q{ShWpn^p3eO6IQ#r5laB$F`+oM*@WjBaKY!sdBlbaO89 zVZ+Bw#zML@Mgc1JlY;EDZo3U^DzknRB;I9&$$VK!){_EJW>tPCK7z+GsLaC#(20jO zPlks=*=@`7B{_|Pq(q7$c+smB+k%LnY-`;KdXjh7ZBGDdQUh|}k(OTndT4c+MaHgR z!;|{5`rlpWtxdn9{?6wA?6K*d26iG+{jb%(nxf#$la9$n0{O$Oqkr(A3*)Py;f9mP*NB;#uwrwR(J&;1~8UNPF^-_Am`?~&j|3{kMj=_ls)Eyod63^@76!%_T(M)=TsgyhH;=FoM zaRE+>LM*}1zy^>kV%-Q&pA!ElD<`~%?{WB(Hh36y@Boqbw&TM4mc_Am#4_u96*ZH)Lp9PM}O7K7e09Nfw4L(b0Oh$?dT;DMrr7!nwo{r z61~PDhzy8QxZ4muJwljx+rFX4)-MTEH3n5S>u(gfl9z*@+Fo{$=joNB>_+z8zQ>gg!Abqvf60VeJ9arMnf>K#CI5^CblA+(3)!X%% z!H^98%|NE$*?&`ty{HWH3rfEPIlIG5l(yEzWq18g2fWe=+5yUUKWWuZ`2FLsCuRo$ zsaUV$yjhpmgL>+k?AVB0MDN&5$on0oizaTu4Umm~J-2R+b1o1EL;NtUUG9evppdmp z9xxNJX5;+VMezw;*&%lLOEiBNW0{wi!9#`Zv(e9h`Rm$elELC&nk?Qf?hl{Msd)dS zcd6)W)6@&@_OCn+bOlX9nW8Lw1gb_)EV^yPfTn*X9%;d$4!>G%}coW<{TBRtp4YUDfBEBw$it(dl{(1|G<=ZG)T zusemsPnsVQ!a^JkY@$DDo}-K0i}f*_XP*BV=?2v=WKn*4>B zyI)-XK!>L;6F{NXzrQ{2rggtHKY4v)yM=i2|NJiBhq@LwUj04YWp(1}73}~1KNHqP zb7768fN-0@*%g8wO`ZRLr>t<|xJN_5xRcRl$T<}PQe)zAzBt`>KaDaxyj)K$oY(n5 zRPF=XmU%VE*{A}jC9$`j-}-Di+a36D)KiY3OcfZT(si;~Bci*RNftU8Z0K1V?VuMI z)hRjfB-5ORkjK}Mbwae-U8w%?d1+owK-KZd7fQEM!?KvjjD$6ukkOD11FNueG;UqP z?|bpm$&g-M{V+O;NKE%#R!R5muRmIBiKTBKip-6o8$?-9A!1aY(O<8WMxOjEZc=-9z&&m{k$aW7ArME} zhR3NQi<*=;_XVZQVf(f=td8}1 zgg8qP>*!&3lhSGuId{fHd zEb0da7=HKQ@_Z@y0gzXXKccq3Dmgytf$>8Ke@S=Sg3)tcS>Zj8fo3z7#0=Gr#;|_U zTbFPDJuY2m%^Vbajb5G??BvGGjwLtERYfH6bhsS=O>I(piB*!zDl0pxyfjVrR5zs^ z$miI#=mlKr&+2P;smXEaJzlna53W1!hju! z#B3koGR35W_sUZb#aQurjl)U9W{PCUCBAnFKsnF2`VUBV);r(}GiZk|G^>|e*@zbT z^037k$rZXx)I@R9^I3|S(;bX@$VpIy{Y_*HS*@eLbKePkJ|B9XD_v0@dbp~pb$UUh z8O~mBUahO~JQ<<6+)p!HO_1Q9)NUGnQuVa!M>t)>hRER_29L|CzHL-aL0Zn#3A*q& zjOazvt!W8#B+E6tf038)TH+-`M+8ah#M$rX_LMvFb5a}anB$P7-(b6f)h>tAPg%@@LulO5(b1KKzbr=*p zc2p@sS!GpK`U;CnH4v}PH&wF)Ucg5~QCyiaA|Jsp6vDXl8|@&Uw}}3*4xP@Ibu5U| zO5G2C35CfPh#pg-jww-&ao7lhHQ_K;9{S1I#q1w8ZzFLC4(lVArYozFIh$c7H4(O4 z3|l^9;E5FbClGdNOknZ?Kd5)h#J3R;N?r`iWR8iRGl3YaB2f^rCev0OU7{;qjnfdOgDOnv6PMZOlOr zNJ-gv1?aMJVTl5=QfIsaqAGb8ahLLy&h;J$QcZTlDE7YoiLcIvI?>YA>D8G z|H5rvV7U47D2Ii;mk)?T659L9qCUoBG5$r$JyJ_ZR^w;Drn)dA*XN#M0nn-#;Up+}&nI_h=5-Q;AA!dOFi{Wv; zGDgO(z*KOq{S#Is*J>8H-!(zwdyE}Fj>--W(-v!O2%nOtWm^ z+Qs#Hz}K5KMm-tc*$E{tyn}~A!XHE&3Dm%mjv* zH*e~WU6tsKpY?Y=_f6lkPV>W!SR+QlNut<_Akp+i*CY93w)7V-l~S_h6=~<=H6KCM zrzbYa5q)28!RI3rIi~{9V`)rtJ_|Rt=sh)~{=T;h4>xm47_nEK?2yi0X31fL)%W3V zHx=qg#kcph&E&mzUWf2miOLl)$4X$!)naR>+r>c1|?{-eNA z`1C20hCu+DkFOn%)e0ew|4vfxK3w-=>Idn7lK&(88Q(Tp2xW$}KSQ|`j=m@t@?eL8 z3Oj%u8n1oGO7H7&tMgxwkCA7OJT_ocqQ4bM>{~E1F$YhyiyUS5X1LLGZColdR3R;{ z1gISG(I(+@US#f19_NSODlaFQa**&zQ}k#mNpXaFi&MguKOkm+wEGVt=D#iqDQ4N@ zE8th@!(@?^z=wR*yJu(oz3KroERbsbTbu?8Fb6(y22zbQ+72P5S+2QLLS!2tH2WUpp_1!Tj z{Gz#yh#QQGD^95HugUP7&y=?xcXRjU@&Ls3T;g@1cJ@vNYb6_dn6Dp^M3|RYN&UyU$@bX|OGGwm#g0A`gk_Jf! z+mx2J05+uwC${Gpgdx?VP<>~#=~b&`9002~)9T){{q#I#PX3-9*};`p=)X`kEdO0b zv2^^ft^P&g>eEz;Cwqj^Hoz>N4{f`*D?yzV;q{&uT0&Z>XD{+Suj~3lOcC$eg^xm) zc7xei*F9=W&)`kmF_-8OT}Xl`FaVGMRSZr@_)rjr0|kT0pC0#7ZQX~(MYC~XZQ?UR|`k!N2%1Fz&9N)Qwjgdb+%Og6$)o4*)W$J7B- zMHIaRukgd5Fm;>?&8eb#zxeJp`@z?KcBin|%QQ+C(V3aqf^N%?!{1Pv) zdFnsWqO+TGRtS*Xn7y=Nv^~P7?c5ak6k3i#J)8;$^EBz(kkej{5~rCBW@qGL%eT}0Dv_U{4}h!Cu3p34TnY=8eRK>L*jX3*mmluv{j8bMend&So;s|=0T+nn2u3ZsdZcv-qGg5ux}-G$%JIP~ckXW59n_7Xd4YnddpFWH4! zhAR?kN}}t43z-x9`RchJ8h%DbTy#m1macxFCU@=PJ_kRNBEGA2r4eV)PyCfQ+o3I; zUtYVhJo8X-iZ|SSkuHkhAsRC;dA47W;yaj*h;=*KIVCbs!{dh*jWaGG;YSPxgA-E8 z{l?_B190i+Du$=d!+IoS%AL$d3cbo}Di%Q-`ZQnpU?;xBIE5y?nGVMF3>XT)&JDsP zoaTg!dIs-RfeO>+`6!jr&(meb`l#I93WW(4glMFW2OFG~7(V~jB34z7tL9{ZL&-si z7a@cQP!=(5-E8QBjoUbOa*xaMqW=o{fQaP#E#SW6pDSkiICXn7(50XMr4^I!@p zKG-S<=*ik+6WY_i`?c?+gS7=$lY)jLfYXqVAS#Wb^VT%~Yp@Q`I76E|FInNaROaP2 zJM2sam$JgB2|H6mzY~~x-xX8s0KDWOn=_=KldNlQQ=GjgW86L=%uE2MM)vv#Pj7+5 z{5LNVoJJUEL;wWe2PO+W>P-J64J%fKPvIus&zTilx`~7>Z!Pqal(bM{mVqXLTh09AcK8i4$l!0^6+15n#VQ z`U>JG?F_O-+^231)tAAIvx$ zqo7{WWKEztSMs{g56kCo_yJTwcQofnhMK|uDO^4yEKov*0z1xF#*40ZyWih#XV1?< z(zE)T$+{Ps6Jli|rSvH8Z#Fq)XF9r{GA^LOxMFVXeuBuP^TZr;HV36nNGhJ^Yx7bz z2lU#X!|n%IB%hn<>o;h)tv{`s8e=@n&CShtd@g_vkMqB6zFd#beP~6H0AjwzCJRHx ztqa%r``T`Ud)u@rQLkhA!>D~xe2z<#;t~({Nyh)4ctfOW*z8)y=eyYK|5gD1h9bAm zHkH*Wsd0rtk34bCXb0g3 z2y+_asGP+&LYX7KXBVpX&){ys(4^%SrexBN%C&Cw-5U(lI=p`T-gRQ~a+fADFz#WI z-{DfG6MFIV0#urkge1CJiAgi5l(Uv_WtW!vp$wk(U10P%Pi72lPbZS>J>gK$wR|>k z#1rnuu{$0ea*}|Lou-(sB(>~2Fw*%l0WucywbVg0vD)>ez&F1jJ zGo9AI#>l-zS%U~k8L_dJoYX%jD8tI`MfK#_+50lH3Sa2(_&Ca)*r8evdo3?VGYF2N`v`$bHoV&a ziCB~E;qo2pc-<8u(5EpJJQdyLXR-HPy*EOL`NjYT>#-My(6*=5Q#P}H;PG4&1;Cy; zZI*+>>4mOrcRjj0FuCc=M4Gja102tBotdecHJ;$i2E8LI{0l78>NUG zPfGcPGqml#XVZ^>UD_Zf0CF#%+UOaOHe5Xw+17%NAX}7D(gmy`B_>g6q-R+efv;b7 zy3h`Hi@dT_Rz5IhzOtX3w#8&t{Lm_g6NvsTwNg2huveoRh;Z7;mL251$!kYDHROl( zPPo=$FBKwAR=T3MsalJHB(K%VNO&5qVW&mY>3E#tex90ni0uZ1 z_X#Fn4;ie4yqe2?zqv0V+}(L(6*C_q794ycfj*R>9em+-{zD2z@03dhm4|$L@nCTd zrRq|FvgA-=LK9DXMrnP7Nk2cMfVcp2pQi>dmp_M` z2Np!c4a5qHdpgtIcJ4FaQYPl1cB9y)Zq`0tbX_hm+16KlUv)m#vMKR<({Fd^zU?btOr$3)twL}*W_*`+e)-S@eQ z>F#j;-4JL#wr`2K6J6wOMCl@2Uy@Lb(pB`v5Kcr*u z0$ryB(0G2kVfnv@i*OFPj@7hQKBr0DxU63e3CN_znaHR?8*FxHq~V>&qFr)WEBu^+mWiRbr>`V{3K{M{jJ>+X+Q&M>b~Y2k8s4xP#C%B17z4Cq8=S z~EJm z37Lrw{KT%JVi>z_g(VNs+dTGY+pjAEmy2g6f>(po$Vsh$EpgWR~+% zKzh8$bjqLB)CA(Uaa`rAZ}?ETE;qCnyTyG!wv&rGD0w)7tN;;z2FyKAH>NI+*WJr2 zzYkPOIZ`Ztp%SxIu74Cd(|hJ^m?KQcHA#I&l2%nY#1B3F75kT0!y{1 z#G%N!qHW!_wZ6;Nsf6&el*$G9EaAdf-)59$7k^0TF)gAK0Yr+}sKk2C`161Z$uIy) zRHyHfob1?zXwS+xwG4ckOHeGOX{79rsL1EfJ{V8R^7m}FS|o|CRqw~0K9X;cl})*f zy&tSiB|}N~s20PccD)_j!NePiz?j^vYowC!Zk^-7!M^DZ`JB^Z>-PcZ_;+}b_X#21 zy^Gz1LOH008cquZhTL2=G8z&1QJ=Nwx{4OpG+LX4uioZ!HqA}fQdisK8OuNYez;l; zkB;^(v9$L?YQp@C%=v67c815|;W|rD>u+DR^JtbRl_HtlFw!?=5y!l5J+N`7Z!=QD zyGogY_?Ed|r7cTTX$F*jpB^A}k_Ox6SI`uRGj;RV(8)24rNSn`wlNJ|+>dE2KoDC}n~#K_1a{Tp0@qMt z@}89J)$ec`buME@L-la`0cu|z8($M!4=3Sr$yr_MZH=0Wp^i_VXxH#1UBGC^);_4+ zt!{s~iGsuO%7-ASnxym${D;U#i15TAhA&rXPY~m;-(87mX=O>&*c;PNza9{=oFEwH z5zB_=cdhM^)zAJa@8LiG_NLdH&Xg&Ux|MwBi7d06%02Oq>QBl{4UI@;=(}VG$uuwT=b=6Y2uwn}fUg1?sHG3{N z%R`EVLnNv@QV+yRd=889k_z7JxRNeJN&ws3&fvo7z3~agkm>YvB7gf2{|Wl>91i%o zIN^`D26s$)U-vy&Z!d~emK$+r=N^&&ribkIJD}J?!s9GSyTVs9WjSh3ji|r1^H3ny zvIG>x38IvdaKQNesFq>p?m3L)RMJtsDGJ9-NE#nE=1dJiV4ucLVFEK>0^~$+m2%6I zIjZ0Ab8&p+{k8m8hQtv(2@^7Bh%5M@*<@Bj?|bfMU ztf=WZt^FBPIf{h;9NQK;rdjbBN$65#Y+F>0RX7J=ImoxKz*22Va;mDXr#j-y^|(O! zSSE$hUTuOi$F1WzfLP?O(7w)!jZhvT&HYq*ixR7OWxS&~CF{x?JJmnMfn^}hu^Gcc z9z#*~-L6+_O+}Y_C*F83stGNWIZkGw77sEMK8HoFt=RH+h>d*2!Q%XLs?>(BGQXnM<_HruvqyDi17xI=OG;#S-pibH|oQi3}z?%ERE zy|}x(1$RwwcMb66dhYl87iKbH1}6J?9Bbd!T81wj=jJC5m&0uit7yi z`;X81ZQk9LIaGqU;RiK^mXiAqiufayncBKDqy1*Y2+0bjmTa#BHuFTb!hyS}rm#cq z8NRfaboZQY*$PU5mr=Zo3&9F1FOj{@LKD10Ie#}Z zsbl}T=^xZz(bC;&xZ$EIM(c2>ugGcfW9fQQlzcYsD5_Ha-&Ra=&ydBjYX-pOZ13*} zsk;#xDG{P@&)P!Q)T^w|7Kz79qUQb#lV)-@d>$ueq=pKhFoYjJ@IHf?yKC|6uO@GoEvI8ie@*%2^#H{LjJSF?BB z()!nNDL6EZ_y>XOypOBumr+j>dh>_wakf~+{oc-tFrjlPH#fyGQC#D=q?$q=n=1jQ z<(WbT#%*jDgwFk&(^Z|ODq`FX=q@NgrsJk~(sC+C{9yx@XP6hop6t__?Z2^?DVO`& z+0AJ_`iJq!>!IvlW$(5uX|4m0*^V6EtcyYG4`g14m7QRIr#p9KCN^pJkevuGL&0;R z$M*WSG4Bdy+jy(?B79KBT3H$O(#74k}-CF zBX&{~f>+VRi0B2V{#4v91gFRs?)BZK2W#?Vkhzb7g2MGag5pr$F2;Rv?4z-Px_a(; z-+yPd$3#<@$92?9>=LHGz3RcLq_5ijJnzN<;X&k=ldCEr z?GxmBEk%{mq^Q6Jew{ldBcqQL<7NF~SWO$U&=Xnj`dkscQ zP}M?vrJ+Hbz_s1QI4Z5Dm1T&3?kd&|nQQRbV!3e)`tjm1z)HhFGvA~U1l@vbe_1d{ z;kLrC?T?|MrQNO_W7naa%-WJ#xUv|#m=2==PY`i)JYR!qT=rEu2H7LlOqO1ow%Ds| zI{Ib+PBsks-OD%zIu$+Ci?2vxneJ5N4|lhod;493T>-a<(3fYvZQxK=tXP%@5q?+Q zz6C>Xjdd}rG+yy-w31bqkIoKaB#1ou=c=6D8Zz|g&bV#V$Cz7`l_8~^p@7Z*;VEZ6lC-&=)q)0eIpb#&Y zAGQ4@C84}HzzqZ6aeQbc&F1311%pV^QQ|3wqG$HSz*l0A+c@B84N586(}fq^PgG1pZSM7Sh9urGT(evb6A&H~w{nmpU^gW33foW)={Y zGD3XsY zbndqg$7D0HVCimlGabd%v=gDj&$Dr2M#=%Q#;!G%Uau^NrJl$oJ3Bg4cuBWg(WpD4c&s%*k2GK%g<<+##933s(KGE(* zS6WpmW&_?x8*5J4UjCQge88~NJcm>Uq6F&O#oDUcSEaV=Rzb$Scngo!#Bhp+a)^IJ z(x=aqv_W@YmKD8QVhIIB;JHACB9`w)LnePN(sv^iekjrNb7cda5fO{?D@zH(FdcONBIzZ;xoh zUR05f485i-hQ@Ti$c7a+f-kx5lmvD@k-h1L)f*S)74%=xlG-NIs+O%LL5hmveJB4o zBlIyaFUJ;Miw$hP-N`~>9qvxow>pppf^1nMhXxhVN9cPR#Q+tM++uqQp}X|)Xu%KC zyCj&@ig^zfVJ1a0+rt5EH9|n$=b&~ZRp`Mt=susvc4;;g``*yKq0>V&U?{VMZ9mcO zw647tZT0B>)#dW{#d2}B+1TF1WGbbINXI%TT9(wSzy&ufTdXT`Je?17cXxMEZ~yCW zsIu5=4a&L=>(SSoPcK$tZ!LqcjuNL15E9VoUs>XQF4%0HIBmeogr#0%M3{$HEAPiD z_K@3KN?S?MKwVzjgy&DhEWaAuIN=86?DvwnBAXBkAqmg>{7C%E6I8svlzu9{2NbIp z<59Gp5F@WQXRuy<`@-eCm+LtX24ktfWa_|7jqvT9reKyDt^^iYb_1r+3CCK%+e>U5 zKS=CN7)F7XtyY`%xe6WR1lZM7jR>fuj$JFe>5xU~3BSC6s? z0CW}p-z(UJ|H51OJSDKgZR7$+I47pvv>}p|a0)%Ds%47y5ZeK!`!wFwS_Y+Fcy#g& zKIILHOeTEck>Rv+FO2j{E-#snnCd8OW(nUnVVgB!@%HQfC0d%oA&6rx^W%V>VI-2r z?O`hku1O0=PC+tm1M%<@R_k2)JQ)biqA&~)Ve34gg5J=J^%w;}sm~sdO#njJ_$>PR)e8ONsoY{w!nc6#scdp+@Fckq1HLD1C-!SIEQGGF#X;)Fzh zb5HV1(!YBpA@v*QoJ=UB-s%Uhk+A|ZtcTDu;lbktPIkQP2DxS# zVVy2;#CA9p(zoB|TJipR>Q6r&oGZ})Yz$FP zQkff78K%Y_5<3o@{Y2xsdg?uKez3H*BvZ1zTu<>>BGwo`Za!URRHX>r=i=`)&aE-B zj@jl@4iDPHgzW0z06mvun11}ky_f3)DfV*K(4Oz zXt|9wf-ZrunJ6v!L^c+3D$4~`ACb5+Dk=O|sTFGCYelwZ8won4Kj6t~&j>;A2Lf}f z;e4A*ktsj>V%;Dx1`4nK$9Vo7)wMZ^*hnYBNkjE%1bBkPqRT$v;eR`EB5cH-gFv94~&j0_`=|u*1OVnFeB#%Pad^m=zMX ziKSNhC?&w7)#?VUpT5mxbp(GE$!f_8H`-_5`XvE}7~`Hk_@WONF2RAf8ssrpuLbr} z8iU_&?^uNIKswbm*7-LEjc{)%k{f^%kCS|Rmswk;C1;k+6pS%q7t_-I?8r<*PV}m= z!PlxhhD-CnR1rwgE=gl?7B>bp+U)DVYyMfVDXl8`2I6==>gp={Vw#9xy(m3hfMHS0 zkUboV6=5=!Zf95>D`SaEzRTFqlkjVJF5yZA+Q!AV(l?n)^WN(7+A13OX#OI$HS``> zdoJIN5Cf?WH}V8Hl{zPrkE;VswJhPh-4#!Oa@@l8f+C{nx5MJu;jlI&?|SD zoEsp{N=GJ4D$rs?D^_HobUJulyrE~Z7u{fC+s#O^I^RKRTPCZlOdA@L8k`>|f<-+T zEp6-F`efeH;762}fQ`QY(S2)aufXZ6(_z1eUN|%JO0W>nvta#lsmNSeRRd~~il=9I(6 zTFcRXRIqu>vw$CD1#|b#{?@-OdrG48d2P8%73FG2;E%bQxhC#4{`^54v*#MQ-C~pP zSwW6vn7vP5USY$-et^QQ04HIhDzZQ3)pg=jn=Fj$9R@jgvAZIiVG6M%$L@uaICc+k zxtANZXk-HzPCnOJPV~;}m{bI&Na3^U2hac0Ic~I_XIkF_WycYi_+mA!Iio(^pU2T> z`_5dFg?$@zKUwN{_qVr4k*($9euhh|Xz_)txUb`}+}>#OLk}W_^@f+y`>_oqjy^6& zO~ZQ6OEdJbbC1zceYR31F_ukOFfu8S|38Prq|muAi(akN7>~^ijoaHv9q6J1whfJ= z_XWWU46il-!<1oL5%gJKZEQ+gr&l;3-(ML&rwMy;;SWDo{ZD9l>3g9A{ZFGU)GS%5 zd9N*Wzdb5Iu{f7apLW3SX6!%QU-ofz6kOegzl*@`LBO22))j|=_-x#n3H$-4&|#b?ZQhzzE)WDL$YP?jn7B$d4mkocwKa1G{D8TRJz=D!om2y>%=H zqDynP8Ib?Ncl}nbn=A2q;R3ZVKurQ05HgY%R)AEHR}9Ddgc5a z^m5gd0@&=cl{WpU%X@7Oy-oa?TUzrZsQ#=OCj-D>F&2HO`*G_%&XK6S~JqHAaQ~&7tX9a4GMq?+lmH11T-7IvxIhfM$1H)yEKqa1wi;=o*HvYaz>rYVQnPIRr(r(M;Ht7{b=z$l9=@J_XD6}=o9sv ze4+^CDx4xYE7=kZ4r>0{i|jtAm>X1skcV@Tk)tV&F3s$m3XtE{{paY3C!`jhzrAZ1 z!a1JA?X|!~2?r~D#5X^b{gC>Fp=4TKTsc|?m->W5F?^aT9tHl!Sqb>TOm}vMC1OX) zIJ!Q_%KrHqzDk-jzlsqJjTHu?n$wJi>>VnO4CL=kjM(4T@N@w_s?V6t*H^9)^@HE3 zkB*OBmrG^IAGjL{fS=>jVxq?@bsK#JULSWhYrF@z=Crg&d?auZH8m6dWH3E0emMD% z=^8krzH85F(=U4+S<^ukJt19J<8{gsObqF|D<00bhZHY$g1tW4B`XHlOEKVzt8EmM z6s{~dR1Vou*bjxdD5xvK@iPg7pDW~riIZW=2BC{9A?C}o;zEY1#OII8);BS|M-D`u z;6uJ@i);6W*u43?%Obb@y;Hfkc6vdS#fMSjHu7drMiP~hx^VE+qx`8h2QG(jOT(|d(s1# zt`LV)l7v3WGYVWF7N|ZXS|G_KiYA7b<`;j5QWod7=MrqB;tU?Kz7M8q&!%CWXp#;2 zu0)MrDUoJHf^a|4-^`gm@VjBmrYdgO@; zdf3aXUYk1%u%YPW6ZKx7cz}lJkO3Q)HFRQT2JZ&S5l3eV72U4BVCjG5w|H{hFL!uA zeT$god>tYFVpX?-dV#L(%K4eKuN&?(W%O3Be-mR*_rmRO*3qn;pv=;UxXucxZ z?1p91-#qlCas$xmhjy<8fMEM$fvu>$oFL4FLOU;ZNBvCzNbJ$;_ul^G;gH8bh?QI4 zE&;yT@Mm+Izy$|OKjXroHuF=2>r~f+@5m4|2I!btv!Zvob{VQz~5c-OjKpN{!oZf0-w?HDjx?^f(?QzRJJ7>7B^ zk0;XkAa|=j7w_#F38V#m#p?b~#Hl@R-URFYZ^!P6Lb6ESy!_D4_CCYij6CtfUj7&u zuPytFZd>mA8p8ODoq;*|3TS}$D#+cJ>@1isaq2Du;E0gE}^3y*e`*n-N^W?XfSg3I%EP z2u$g8_dFj{3R2&Lk>N?!IXk+$;0SZ%^V?!7TAxo`KAC}XD^gMn9Pzd4(LJ=fu2+Ki zp_|l~7CPo@{MW~dPo`4Q%%m~h=lRuA&PVyTXvl?!fTJw_Lk-gWUcBTm9sa-MiP*Ij zgsBGJPle52p&IQuY%;%c7M$j=V+8FuVlv%wlbIQM!wu4MJJ6`F05jI8McX_Q$S64V zp)9qwNB?Dv!-|NfOJ)IzXnpFJ;k@n;m`FVVd5?*cH85!+bCfbL)RFrb1r`S zlj+hKMV9?Vl6~Qh%lNw0f?VKMWrm3pOGRnSn?`_~Plcx64i;yxiSDAo|ym|t7LxIr%8 zZFHoEyem;M8O?Z}%;3aG!i~oQ+`2vBzXzFB6?lFb-Cm0X2HuEa{%RW^kyjpboQ;=u zgxk(bUCoRTSXDHc-J(lxk5YGav2Avd4H-(cmTzB1E#f2Abf-0#cUSH!I9y;M+H<15 z;|9|xFXkm^*MrT5V!vf|k50yc;%Qx44N_3hOLFH2*+g>1ehSv?V&#@OVDsZvs4*}+ zC^U~`mk;s5MQ&A8tLdC8i-}YPPgWMS^I70c z%Jon{`AOlo*6$WRG^J&GM#e)z9&f6r8;Y0)1FDn;n(zq=4UoG26bi}v_zgY{oGhe7 zVeNxtoc^5O9iKD+@mO2ddIg>=xe36&bE&UAo_R|o~`vr>jIyjaW2ee*@_PxH}w z^XWPdiXVz5dx@I3zZbsgY$e5Q_L-bNp=Sj=0p?0+c?PY(_P>+FlCEB18-0}9Q{ArI zl)YR#$FF|c4Uk%o>b1A0-Jdl!BU~`q;hWZ(S4$b(Z*a^4X+STskHxOj(Ol`IdIm`B zd0gPh_F{7N=Rc>CI);r-GMD}Fp4vi103^;oc=P41X{pg6-NkM5Kd*YM$epf8QA3c} zx*HJXv`dN9V-3*CzTS!E#xtldX_b%$9zd4e$*U$2t9tiuVd2=t%;3){QeN#!{q=$A zAp;AC=>mSkTQp3CGvBnQJ|W`#g1(=j|4Xz(W5)$3=x2IE#;*)(edbpmdqcIJ4#{wx zk#D{lWxie7t)Ertv#aU|t%G&;0G9FeB_J~YSnA^y#pSbMW@3GVF`d)cp8?OSPo1!- zS|1FVnZ|d*1`IJ5wa}CM-Kei`dO~7aHwo4Rvv?hdJFhd(4{A`4Gn0dw`?aW`>VMjV z7eM}Z+-n}2elQlLDJ#ji!@IO0*JHy=_Bcz??&UHrz_n8U|EB6P!AY_G|2CJIGBj(! ztkT&+R){kCWtbh_DeOERCu=Xk@bLTvCfT@nb52CewUxt2E-QJ}23$pCiTMlebkQTh zpr&&iro+Qd%NkX?RyUqUx&}8(jh_L-Bgb(khUOM~6-^s6F99U_XOv>GtbY zR)ePa|^q>@P?BcIf^SMmwo@69Bf9{B+xT?8Lv3@AR=DiJ;v$lL@_rn@Bwuo zC|qSt)^)}JSUcU|Zx${sA$WM6tT-k<9f_iI5O&zyOZ)_RIC!$ah(-$QCBvJOOYOjo zQw!fhqEDOtenWj(rWBoJw^YAT#2)~G!W>7cO|n!Q55Ck}t<#Y(g3 z;_!;>>&CUMVQ=*dZs_Mwd2=y!O(T5%GgnHUE;`T_Y6`|F);Q~b1(SMO7Y<@=66)Mp z-l5(ZP-qm0NOBpci&9@Im~3^NWTlr#5c2TjET>}6Sk3SSirsG%D`HbI<|i!s)naYd z6T4vB{i4?sFyip-m%CwM>0SU6mouT{HBJ|Qvt8mtg8yas%8XwsVd;$LeSZ*n!Y07N zST$;SCC48#IMD)`Dzu}-NOc!RKqD=imwB%O%JSp1e;{;aKZ*UJPmj~2R*ii8jeQ9A zl*1N#*}lJMGg*rUzTJLobTp*THZ|CYizulcD$Rc>w8lJFKYw|lVA!l55Lo4F&VXEZ zJ(;(86{t1TF)%Up20mVAa>I$SXL+yKOzJ&Pt&FgZsmc4A@Tw1=eedXco)m)V)Z)40 zs{T;(az_grYm;rM3TAzugWrgPZf4#A2Q!7J7|zLqE6wgjXF_Bxk6{>J7SyP@*uH5E zZZ2X2vV|T=mqf&f;GWYcs4w&y^2q)bUjw!N?N+lb`;+oCM9p=%Y{R}cqHsk5L->kA zz4!0)vXuqjMT)NhzQd49=r(46+CMgvx2Hui0!gb_7fg|x_%p_MFBs@>+srBoy^u6w zip=mnDuvBKUK;2p+n)f|y{WuI_JEdWih4DqW0Yduu*!M!|IIcZ)!rtd{|9uDjV0%S zK4CPxp?3RG(hm5#ZnHP8rfHUx#^lsT(V zPCMld(r&H3eK9=dBZ-QvwxsCvJYs3x+2duG?Sr072<|(GzaRg&kIEDIbD>f%f5-$E zI!_1`u689|opbI!OT8WM(hhd{-2UwJ+{Lt}NsfU#^auN;ZXtB6^uZTMi58Zvy&sdQyIC^2YlwtLg?Oc16h56^{29nbwu#g~|m zep!H^Qqe$K66rgAtH+pxJCH4rE(8IMNV5A}XFW=PGF--Ow$OwDMPB!Au={KMRnLfa z)!rr~_fs$4ur+O}GW#IwwkM7FLRMHFj(%G1LC+=eP_Vip)!I#7KT&?kuS?D9UjB@) zEAc8cxJsUk&VV7CM(n;5TjZf`4zLb9G49~7z_sdo*?tz;fyUgVBKfMca``b9`9h4u zyt&jOb15RJ3Tn;(;&9GtL))75caX(t*h$IIl2O|@cIAv*)YSVSwlQq52KXXbuJA2fO@hq=O#!Cy!%L2pW zM|lewyyXTFr>nfwxMn`6iK)N%BBz76ohBnX0J{P~P6I9ZoL&-Q1)34mkGBe0x>h|- zxFk(HTM#eYZI=E}TGd?VKJM`Os>DQIIW1ohPTosW~HE zQn%@`MwXX*40>#Fg4U;hw<#*h%b{cb4SaAi|{BJ>uhMRM+Hc} zi993DPID;f7~6ylA&u*1AIZl~WFOk$9!)7E;>ZNauUZSLP-w_H21m&2Y30Z)MXYs7 zKE?<2J6wIAD$p+2UDKHWT=^>`$GrT084llTZW-fL)6M7W?3XvyE$c!SK}noPNjU66 z8-S~;$s(a9k~WWKEBg zBts0AWrLVrDB8^-3@2*6OluxDMe`4M=ZA>aw^-GV-?Rpxuk6?^CKPZd^|SVcUe9o) z{;4bYL1NkY%=>!NwhA~#*MT*t_{S|%bVW@ZFXpt`7T4G8NK4wHAp5|b!{MPcxNgul zHeQqCVIXi`ms(}ky#(PqEle0~Wt=L|0#odUK7fAzSAf{RI<@WeSgx(6ww2L9+!Nw`UU)tez{7vMQ3ou?YRQ8K` zNh|2oKp&+|5a+%nDOlUOnc0r?{p2svt9C|6&)5COr1~bb`KK5eC0=i-(CAb|j(E~{ zk0I3YSuGy-1p~EJXhd96_uQ7_-Q{|9HxFL{z^J|bxsF|!$m$fUKa&ar)Ai0yPV7Y- zK`0o&Y$`(p+kh?Xm7RQ8;(Zj4PvCj}8+2dn_CK^@#?Pnu11TH)ownCo!+)3H-LYU< z^2k;H$m;)b4FX?9GXNy+$yF|s?wAwaVi&=j>7owK7=tmBQ;>!B3vZ%EdpimDMw5#9 zddnWLzOQf_wtp9*j?o(2`{hMGsmoz8TF1wJZc|sfA{Abf&=X|+ajzFL^Q^a$K4%VF z-Bqs@66;oI1?G5FsEPRzNYj(qJSOij^%a^S`9yMKlg@_vGt45WR`;;e;i(Wb(Rpt?wfU^| z*u7>{N<2brA)MuqkM9-gLCEjQzvq9)xDjxS_XqE%q{Y0-+&7(4C+XsFH^;(Va{|yo zd$A3HehU&caw#KG^ChB=*;B6gk3syteVeJrTcRrq6o#A z9%SBkxpI}6S{Xy)nfn-vxt%9)bCoZsA4E~K$N%{AD^Ug!#2m!ly2*mAy8MV?28NJD zlE0jc$N?>Hrb;4EBv!4IZ`AF^e;hXh|FL&{N{{+h#t~>1+Wa{*JU^0vK`;U+4s_M% zL8tGGX1!U`L9{m1*&@vj~jzX@#(?vT7MhU@7Or`@F&L|*#`P4yI+0qu$&8!wTJFxn(yQm0Tkwr@Lq5*m$C*U@Bj zEH@XgeDvcaRc8BI<;d8|@?$(HVkXqsbMJ4VZfm<-Um9&&bal}AGTd{)_71hT z+023Ak3#u#Ak}oQ0zY_Qq4tyU^LG-_G=tc(mGD2|4hM5pU$>(daYA)gL8-dACDPA0 ztG`nDZqFO}?IQCCQEaT=hwT^r7}0ot5>+IcukmKfIE;LFtFWrR2ELKS34L8wRq{tV z9-qT&@(h^cAeIB~YiP5ez9WM+{Rw9k}f|pIVk56?mIvn%vNIMIZf=v zW}DVFy8R_CV|LV`ULBlk_rqcwUZbW=CEyg<`;`^j4Da!TlG2Jl&{3<(0vYJ*UJ$3L zXIVW~2wS^qrYjA=(G6BRDcKnj-Hyf7Z9{^*)t$dmrqTWg-n=+V2T`#O1lb_E_4Fqk za@~E5krt0wTx-;bETGi=#)W?`@`MjNbBHwP ze8lGpm?;$S=Hm;UmYrNC7{ih!kD%bknXK=0f+6u`Lv8s!_h+8nH4EKVsG=}4pn%xs z{mHT>E7qmUE6m~K+QJ-*LpGsU)pouv{eB#^>*P4J>-Z(sXXE#U-5;r9sxzG?#5%x@HO%m~hto-)(;vb-?S~_I>s)bRHoJhtU_zxH-k% z$=-FsHMihe=@uvT052Tir!X@+dmEL4MJ;5*=;YH|FohJ2rhvFz=vx^jekTPugo%|&HQgiC+oT%Y+n3LR< zvq@n1e)7KS&F^&ojG!??aQ9C+Xg2tl*e}!kLHX1?2KMF3Z+K?vD#IjQzEfO788p0B zd)s5pm)da|vbCPXY#B0`2jA4x!YK@WC}T-XBIbrQ9;ONaoF$?6G^Q?kC>t;Jx`S1x zumBfVC9!>k9RiFgPknQZKg=pCHxdboFbr0Ur3LQ2N#-6saqj1@cVPBC=I({5%jWA> zkIPpdXdx{;|NFJ;txZnARW32|5d5Ci>VonE20TBBj(n!t$FIMC*BK`5g~3n<@&Y#P z@83V-FcqoyNEx1B6VOg6AOmf=@J*s~zJd#HKV^RYX{2%~2?&cMmzc2F{ox(0c)=09 z;AI$V3f`r&;s2(k6-4RwwI*yRyJ`fo~W2camTpG6w{uD3Lex=#dvO6L$$4tS@Vk7 z{t|$@Fl=#pjKN2?@_8x;3BwX)( zzhJZBbpU98+JD#qzxLkCcB-Dm;(){a?Oe#n5@@mHC`j>iz(ng(~bIj44ftKEU

        u?nCeS5R%WV)#VYdLgT>0z~UBfn9 zx-CWT@%~0Y5E$vr(g{XVoaX#7eu zdpzwnB=V=+eXm4@-=simrss@2p^#&SO0A3Y_RIZ-q?cYQq|Wc*n2#?@vq*K(qL`s` z8>mI$_pl9|Iq9%?yFk!a;ib_q(O#znlV})O(s8U%m4IU>d;I1K;p6@)5`2Hm^I}-; z)PCZkhd}rQ;`paepD;uE1UbjAn*5DbGV1qe>jwIqOPS~4JeyCHaj_<6xWnz+!tBCHqbcDvJH%s;s3PS?+j z;o*nC?u_>9r5;S_*#-)drM1epl)l@N6OAHKTR#R9 zaY;mR2;=6dea*eip(IVIWwy-a?=2|zvN0AMe$cp~dP%8gXjHc&C$^Cq_%vv%YDOi@ zyKmbQj4wm@?P?606CK4~_=LpKXqKJNEB9CMf*S*!jh+r*TiOL>@_mJC3BN3BJ%=#6 zoRLlD<;!3xUu%>JPBEfr0I>#_kD^~OHF0e3@pbpPgH&kON4QqLtsV0r(}Vc;Ob2ob zSO26FqS3s%wBZw@_6mrS8RP#%vw6YGfkw5*X!8-Qz{4Z!Q~%O$3axdYs92YzXeK@- zLdg&FXMj8^nvzAjxQ4@iB$1}4MF{QJHbnSUWzv#UaTTn0Lnfu8 zaTd2hS`b5c?!zFfPzYs_@w%v~dyxv-U?lpnqOD<7-OrW}1eN@~g%wDWDR)ubvbk}0 zWOuk;ZvA|fNaLqgE1fI&MGn?6GP8@G>rO@Nb?3J4CWy_QLiEOo5`03ai0RRvI8DcS z(EFY>eM@&qBIj;Uu2nCUYcu-$xL6&8Oun8Q=(jin;~*U;;z9O%*L@!RC>x@>#m8|~pK4P=rTsJQv#yn*M2ixWkRi`eY|DL$y z5NE>#2dGYFQSBu3_|DS#7{vhA5|3EdNmUqaXvYi$+Dr|TGrRk=aW}1989nof1hrPLibw|({XhMtZx-j+S#F* zHo*7ed)I@@fuL1HnG`WGBwN+S6o&g{*mu4D3I>%!dyv8!Zm*0VpkuJ0(TAfO`Y2i~ zHd86U$OwIQ`F{PC1T#NwqSJE0T~1EO>a40*g#@0CujICJ-oxHlw1H!!pT0|+`F4y% z1{}=X!PdK<9S{q9ml4PYFYKGsU^G$PSgjT;uz5~o=%E8^^OHUWbwx$b|63Gs!~O~X z|0W)3T8=QC?iG!<|Cm&5=eY+TD@J{{u(C%@LfB)-}W%eJg+Kg?rq?3t)8o{O&LycMP z%gpo5==6X)A?Ox;llk0IgdB>~%tk?t5Wj#j)pWT2hX`q9|7P{fvjXzhM{*2TWg-&1t)_ggrvUqGh-4~Nv(d5g| z1-(=e(y!Xhy~qK0T`5B<5%R|TrR?dNY=b#@h?o0p>yiYp1NfjfZ)GqxoRPa+2p+g7 zwLqFwr`l{~U|oqH#k{|(sK+IlH;;-`KS8~VuAse@k&^&dSdI|6DpzZb(kqc8I&|6& zyS)r+3i#*mp&CQ(W=$Sssb?Cq=xFi@^PfXF-N5f~-PzT~`071n zQ0a>*l)y#fbShwSdiCI0T8fuv_r3y7k%VkXK(wK`XG1x*G=Fkr#jZN81Cz9oUw(a! zOc8*?-GxFs=-r_muV>a7T#F6&`9lUP6H$*G6VEa-H&0I=FAKn>1 z0`SN_n~iHZAn*l0_#j(?9mQw|Wwt11#K>KNB(yWLGuO)^8uzJM8D@)Dc#C})RQ_tM zqR7|SVI!O8mvRrkx{5W>9I(f9{o{&`eWk+lr*%p{7j2Gq@piNY`QFMYHDHX-v67S~ z9t5Io9cLV1H*NvVHzS?XGgj>lm)fatxX9D*$x~U*GD63#KAIP)+$9gfklw{b`POJf zeeppw6%-p=;wFRp$w6HH1%BYX;s?X0633<^^GVa88rDJX)BMRMbK&Gf`O_aF99%1 zXQ}-MSHSnHWhj$Kqi$#9RPWe->up%*1}1@_)9+TmV}2i|7-?0b=}RPwNvC1Oh*O)| zAcanW^YsKD#FQwilWEEpEq8z?@`s_Z=QjMyHdert>rR5KVC6HY834HeN3nxppU^)* zU{daA_#yhk;D1&DZxv@37dKE%2L8ld=;>7bMT^7hvA6>~-&dj(pH9 z#O9M3#mn0$wwZ|Nrzh`*&>oZiGx^}Y+rD*AN7!ZyFkk`P?nPzmHaY7g!NbE7yp$0K z{pU_bHhnC^uH5XHVvSFXzF}))qihn}aXsH7JyqbMpAo`~+t|zqbt?u7uq*4UR$K|= z+V)ptnRC39S8Zoh8O6?m9*H$HG`CR*n?2$VH`l)ydsS4H$(WnVNyE3EL|xn2gk5}E+^r1V{GWI$QO->8?9`% z>%`>b+(6Wzwz$6bbm&kn5S(g?medNI0 zoF6esEgE6i=!%xfL`l#nNe;rk$lC_b)4tP`h8$9%f7IY4GisD7hVERQVt{6T{oF>7P&fbe7CU(n+`d=rEL!AB*d-8o8tc@+R_|8AdcT-w{nr`NL_4+%~ z5P55{Bm(c8i%^p1%7~2{!8?5Y>TPVDauS@udd_ExbMzR)*9l7rWZWV(wIVZ$!M+q< zXXYDyxZC{lat80+Zn1*3s%g_t<^}N~@zxz&cMnv5 zX95_49sjCuJF2wQu;rIjE`?_98WhIKc@)yrUFcRWN_-1Rn(A@nP~I7O;c_OM3E z?#Gi^)zw3*wy>^^>`adLwwwi{`=5YAtqrRFSICu`q0Au+n$!Rw2eeeJo%b+GR5x5X1<36u>=LZK^s$?($hCF+?5s_RIYLa>F_y35Yt+oE!gB z=fbWoSG&Z$Miln#K^J2xui$vJqwF#hZ|5rp+JUH>FBB+OiCg2RjmTX~zR=}UL98!k z*2JM`N*WK4B_q>Kv|5 z@{dRl>BSy*$Z)GlFx@;3VpJVSkIzDnbqy>Jd67OVp zO8qCc>DQ$4@j^#W#|QxLeztaKcuHE?xtGSiL(u+4vHZ!g8@zQU?Flo_;g1KrIPBZM z4G*6Nu3B|s=o{NaiR&3TDOB}LE_e3%3%l$o!5H_3Wd{^VU+X|1&I7BXgVoG>kJ71N zCD+$XzisX2y{GhP+A3y+#-Du@0e;M)-aiqDNsb3(?Ff_I^{q#!^?1c9yY8Gb{9Kt@ zp9mCJ<^}fv8K!B5PsL@Fcogg?;8}Q~Pmu^5HlqAM4LbasEY%}QknA>*lgQSTerU7*UM}Fgi zE_J$bce)MGE;XC7nnCA%$8||Lll73sb`gO&X2^y;n8yo7_~C@&@F5tL?B*DU(hQ=B0xyq45jh~0tkF>6Q*)sL*7r+ zTz4Z+jwpss?-py-i_@qY%hqqRI7mfL4)o{wpt#XQ>&+-laS2FZwpL&0W6)bP$Wg(N zOfRL5!lI|CHV#B1XH>P>t-jEhfs)cv;Jvn3DB4kwIVMT8cnJDMND~z+>#tBX!N`Bt zFnrvgrlMYbMOxE#@^4asi~W;}UA=Pf$rsE)H2J=*EM+;xG9bT3O+F_Dst%voWFR^N zb5;BaZ*GnvnxA*U@iQ!qAgE|{ilL$;BDG#Qqx}3`o(5+9pqUiciCqOtRrQOm>RF=Y zc>WyvG4KNp_wh)l*-92C7M_mHb5vA+)t!00@17t$oozyd-z*>|>ZdOgxq3ECmGfpG zk=Cb+Cdu9rzak*mEMecz?$Eg^ei=um1~z0{6QV@+hea53*vv5D05h*zcDaZWrs{Pq z`uRvn&@4gq49*uluJbFZi}AiLy|v#@gXNTbU8(7IO7`ESx9HirXMiU<72f- z>7Mf6sm%hNFH0yF$n@a4BBBFFE*@8FH)b*bFg>(1_k)X=FERI~H%g&}1;em%;)4rk zxk;Ig&PX~+H;q3^ewuF|hfm+vwU=&G-A1iJvHy>#w`_$=YKIEZ|n-}7*Q9Sptiyg&Sr zw+g!oX9mC$I3EKs62ZLC5zf4_0?Q1)EIO{~**`zaBg9D*X*Q>Jt}hyxlsUSHbO_f%2v=hj_6>!M-b`vPp%gfR? z(~bv1_=KWc5)IT^=>u;rF3Cg&ulMFB`2^TYfqZs__p|%%(BIMY$A|l43I*YiT^#1u zPi125lUUaEqEQ5Fy5U+r4=O?{WCa<{#H9~CyjORpQG&jSx}Hi=i`fO$`(C%JWxds* zXUESPn#C--7M-X)`;!Hm3K!b!dVgOPL$5LMN8KhGCcuJ^%0=NqqFYWVdP7o|OG#;4 zDwcnAF5#M@WPh$mkK zwlnpckpi}3qDVzQ(^|Ioa-zPB_a9%hdJeMGK}x^nWP%Y`(ZpjEB-^(u%_@RuW@gKL zo-LnLd-U@MP2aF~avO9Zw@5H?l@ji6Mu~iRjj`@f!1RmKWl*DUSBZ6*+vCQnx5f*Y z2Da_nL;c-ye*K&YYH~jQZ4IOW%yefgT@k5|j*G807MY`kfcJskh|t~I@htmeT-4ay*!QKUF-h!i z??uZEDz>;Lo(^58yVgEcQ|K$Oe*SE!s6H4%9Vc+oB8>Wmil0$IY&|;Eb_mq+q2hHn zE{Kmy#Fu{%u?QlLiw&5^DO2d1BSc*0DL5JBeU`eg5D3tzcR}p+3AU=y9j;n`+3DCo z7WHoWZsyDWG9le|GLkf;;<&oJFV?I{U&gMDvR%e*vdp?F{0&({4X2QqlSFE4CrRhJ zx1z2;WTA}b1ut=od;EC^$}=M_4of1?ae#xE*b9&Fl?sdqHj>B-I5R{Fdy=|e?S=N_ zzx`4=AI`f1jWib5t?^e;N)5kQfE!AI27b%CMxlyok)-EJ!kYhmV4%@hicKODI|gF< z;8jeIUuy9;?fy_nvk@?4pnQDD*L#QoB+S*;knJ;T$l=@y#MOwEV>Z&vc!g3>noJA)Kv^FiI0BU@y7(gA8@|Ap;itojoty@disdx+4d~@o zH50w&73wo5*K?5?xi!cDe0;}Y2y%ib5pl^Onh?ikgvdo-xJTScY<_$FY_`t@RFRvw zK%28q$&VfW-|$wXwDwNRwvuy8KwWO^O&YqwvdQHD(y2IxBA_ zT(Ywa7(3)ZBPrm)BD^5i2knhgvujf3uXmIKE=Q`Aigimype;n2Z#|4c&>m3FFd@X6 z%YPDhi=w86hVEtW*C7nXWh4g}%JaWjeQsAce9BlI<8+mz9gIq3!*$(XQ9ymYD z6Kp(%m34?GLL)3oU%;hp`@44!KWDR7*J6N+`}Zl2*?91yy!Yo6hiWFB$1AZ+B@w_@NAZJ=Za2M1}?n&{u4vR{;yC!XfNFbf#^bR#L zxw~qZ)OnxuMdp^Kb-sc#7Z{*_A-A|}n8aIsD_lSq8}lx=$l92UKBhXpzU|o!>g=}O zFOyQ2mstM%JD=yZ;Pd-`d7^pA z&>3Z#iF4>wb??G;6Z9mX1*aQA)-R#i>c%VT>0kgDR*$=B9%>9g%$PWSo4Kb4PA7AVY)2h7a`Ghcfy)Ny6 zmXv$mX{MTQORpcWn9ZW@F&Mz^)n8De-zcY6_&Y@%nRpB@o8pd6r@)7(5(T=YmXCi% zA>_A5pDEFaxTsXtIWS%ljkE3ME$fc&RQRCjZju_;YVx4X(@@<~Pby&fCivZ(bz~z> zTz&tX(p3_P%oB3-!^FUFF1GgrVc^?KmvX%mB(vf&e36~ewcPGW4fJt6gcRoy@nZdm zeDQktcWvx94-Di|Vz?I-)`lUPQ?}3SaAl(f34aI^Keg1|^6RmNEJjv7s_BSe^9~y=BdHox z^hUintJg8EI@}mE<0svzfx)qFYe+^zPp_|+DND+e#T1AoB_6dTan(2fqiEB?cB;Cf zZ+KW#MMZIiw{9~%YF4k`U4-ZKC@^a0r(tKpXWMzYh=_Ck^Ct7ID6NTwh+}0XvUcBT zIgM&zluYK|UCrGjikht|1LR%E{j=vP7l2#>|KUbT^wheakelI+3hii1qa9y-m%F|e z(RoB}=>(1n(h;xHJgy2ff7Nw*Bch19fTiBhN3{a9m|Wf}>!DmOHiwqPaj0ex!Mdw|hz|IqgwiC5JcS~gR$K42Cp0MtSI55G}$dE9umP7)L zCUr>!Cy+<;YQ*GX0;&2`@jJEo-kzunJqXH8C(TK0K0#XuGJS4lN5V&WtFP9t>m`$3 zs-Yh6o4AC`&NOXFwz&9|CNsXyofXJyQ3Cnudi1MK_cgjQobw$gw2HOK*$TH#Vn%n6 zP~J1rt(>GY;vnNWSPW%H{;D(eN24ufE$DP=6h*#hPn=F%oZff zIB>+Z^}#^y1QoYmL;dR2N~g!v)nTb~;+@;KI?Osem7F8OXfC`qt5ML;# z^|BdbMO;Q^<}P47<_K3!UCZaNdth%3<*ucZ^*)t`!uTeRhBzb`1Dn@a0M?sxGrz+p11r}WS(`FREt3AG%l?dG?E0e#x*cDbN8QO7y?MCZoTyd==MXFW>z zp^py^Q}|AA7x}Io%lp^kZiWZuY3pMtc^v}FTcL-&9CuFuUwxtu`%m}e{$(Wb#eDHU zFWo_PL`|%@X75$+pYFe=X2cbhOJm@W8zZQfgWZw7gYqpB zgS;_>?#>E5`}9Dj*H(|BMtP#~msZrc`_qh;%|2{Uio#UL&f6TQ`+WUu^5SIod!t&*z52W{i08+ZW3^4Swg7Bf8}*p1z75E^+q8Xey!( zqQo@f1~u_V8e)kr7H$n_2eV-8!e%CP$tQ5`daFzkD;*-g$wd`GgDX)w zp&ars2{9Kfpp|$>O!1nUAL{LgOv()Gt6{ z^-HVC`AT;C-H7qo0<2Xjpd|=yuIDL;Vk60rPZzUuGUK$ z1SX?7WNO&VS}GykOtm@9&7Tj=%wAMU!C)+EBvUGZ<*=<+kBL*^>MH_h%HuU?iNCnO z=0cW_idXHfjP+T_A*tAP<+q=vCf+WtY-O^`w{UZz(}U+rmpJ1|>MYGej{lSnuM3e= zV;X8u-$dJL|CUT7y|j4hDKkf^k$?BC2#)m|MZOHh$%ToP%w#Dmx`8fH;Ik%mOhiMz zZP@dITwjZXhQLm%l733n5Psqs$9{QK3P*(sM9wgK{m0EY9Um6;n&}IUi1MqI!*R2x z73233uXfufrhm?9F60i56B$@wNN&yq)7Hh5m@y>(cpwYQJ)AD$WV1xx599vXo%Awq z>3VuCSz&Ze4`dM&Zf*>(qGhiRlhNB0l(~`}7gD)5KF&=diq$6?;|oHG1>TgO}L4r9Fq+=APm zqmL)oa;dzBtyPdG!-sR&fT(Z|`=#(Kd>P=hlMw@eJ z%vx$B6b3kEX2Ay2nuh6x&@xq`rmM5>`vQBmyL|@xg7s6_nK9l#A|tD~c*u_XACAcd zX#SBq>@#Q@n-9OFyxI+ADjjQSD#lOz&A%1>@oLT(S^`sCi>J%Hw`n@&(ZONIWz{z$P# zE2)5s{e6g6kc@l;khh7tXWFiLWUr_!3(sVKjevkKlAKpXIGy**KXN$zMjf_&D>d5h ztbKz{uP|D_?=B0ucLj=;63+c1ze2`8;m{A^u9t6KK91Y`eHTvT@>U{}C`ieWUN7E3 z(7B`C-utaY*kbVbX4f}Ci3swt-i8LZlr|~m(A;>{@C5cCa%T`ALerG%O2ReVr~cih z3T<^K8L)J~zTWw~lD6$`HZ0adVZrB_!QSYCVsMZ|BTJGQaMEC}@a-$`pmir_6LMiQ zX?|kBXS+i_oM9Fnf5>B)=OUR-g?=>b|MS6?(=)R2`+1`{mU!&g_tzRN6_`xh!ltb$ z0dL3Y(yMRX8M)YBcVv}omYF>VlqN{_R1+rJD`$O|4oi>-|KOWSBEbq7Jgtu^0e!q< zfCLB7(#Jp#hGYaj^wgL@Aq>|^o~(;T zHh$l>;hmvcSCKO<@g*f;fBcf;_=15IsLqv2txuYHpr|7CVQPw=pDc4JQh^qAX&sa!&_b>tLZY-xee z@>~jZrB8J0bCOfOVc64zG+r!q*sJW;x?w%J@_9q(CKqO&xHDA^E*r=F?4XZDXQ5QQ zFwQo?ot}?CRPq`&;P z13o%um|sXwM_q}_gl`F&9~W{oXf_q()cD+86gqOpkFd<8W}{5ym)XB0#Idc&P6aj^ zZa-Ks>(q)Zaf#0_J#dsW6D9LOF6LC&&HC7%^PJ_>5KM+Wv3wo}DQstLY&s3GR)dVg z2nzoOpVCrzow33^cgYS~jn)OZczF5<(;}#>7esBShb=$-m-ownnLU@_c0^{p3;U z>(CRi+S^``v6XgA7Vr^qgX9*l;1o5z$fnV3UPqS&zY40Zx$1uOXkcbq4HJgl8SXNV zRCfx<2Y&#MJzO8ASC!#ML_`e7b!hvBW*)lqUQNn7M1EJewIeF`q7@R->B*C@n!jt< zyx7*06qm|CyI*;Qeo*&lyd||^|K%`LQ}cHc`@+)We?V}XsBSM|QRX!@*v;oBm|Q&l z0#UPm(zqPyOh^(EUnuP_Z*7Y7!i=H63hC5V{H$B=O}ut8-i@w69~Wk)aL{;Jq3M~K zQEe~Jr}DuGj=42I0Y?z2eJ))hKO^59~5CM>2}sV*D78F81b1$5m@P><3amKS+;!~^E& zF_Pp(VnYCEg6R7CdO-pp&^15&9{~aaP5p22rGgYfGV8rY>Sb3yDD4C+rUe$CQfyru z2NfhF0`JA>&l7{QY#kG89!*E1*n+BU&A)|NGR-7GX&T2KBB~ZbVFu^v$#@Ul`zJiN z1QExZqM5IIj$m2<)D0II%H{oR?70Xa+BZ6YWXyFW(WVrnd68{=AuI?Qn(nrfd^bPp zQyTXz4cYT9D`?0_pME{1rp}R7Xp+MzB2V;a&@kdbM|Gma zcWd7vz$eYZ`4`*0zN*ROAQ5*28$Oko-3O*zya1B;Sd3(lp-PXt5hTjT$gCAB5}Kit z12L+m=p~Dd?CdGXanZ$iU+W!8Tb0>4F-qS1fDn~!(TQue0ORsCws|*GFFH}6hUQ|x zm)}esv2aY1PKE|7g80cS=`*Hd^Ct7q;6%mGR_Bq_?SGVjH+~|*jwIbP=^$j{DK-@I0oB2G zmHDf`lxp+eF?`|if zHj?SdyP&7dWR~h>iXsgSI%hZG>StG*SZgayCx0(!(W-?}J#IScQR1T0#9qrZf5RE) z!o^)xpmRQ6C#}IqyluLxYy10Eq~W#s*W^gcMMYJ|JwDU5#sYFt`MMi~azlHx=;A>u zFYdK1V@tE?z|$NLgZ+uTLNi)S3U<9$?$-y~X=D%^SYq+2ZGYhpKg623MyD_z*gCxH z;oloefv)T?3tuHm?qbS`x+K5Mwt1rThj$nLaB5$B5_de2qFtp&# zudr+TKjC77iX#$ow?2zU5`_QOp%c7*WqH%DxUVDHa#%u95OZADP^z}Z{mv6)ehia;Ck>R6f zYyQAehSNQB`_>d(mIDAb(!}M=KlRo=hnj%P(HK-Epi{qwv;*2}m;E>0(eMeh+6-H; zbYCGlLn~?%xk*asoVbtYnORT19>mU!UKO(39qN6WUF}F2-OaAd1&!OnC%ZN5ak|s= zkb1!PWICqZqzZvcv}|Pim>frLC~hphvE7!PX7}w0>>#h1y$B3PP zD@b>zVud)tKkOEZDH{oSW*}$dV3jDco7WiRP%?f#%POS|OnG29ATcyUmxzwt64ykH zj@$oeQQ1X?^5@21X5bUGl3~E7iL1vavrv<4)VQ;gX5^EG7nCCgw!{l~T3%3%RMK|} zAGfowvKj92fwS9|{>NH%YbiF`Kjg#@tB+W~&p%E;tc2j#0k7c1;Xz+)8z}HtllYYf z=_Bg{VBtyK=Q0(3f!ycHxq4mfAf+)m-D!#dgnVo5>LOV^dUOPmVuubch9PN?UwvOg z>#7pS0G^AEI0Sl;cZ|nPg`A&7g@Dm{q1gPX0=xSYx^V}Mre~H*9FoIO_0WWhT{~j; zI}r2^62t0-F0-ig_UF&!K)+tB4(vGh>~{_YMisJ&?%6+69~2RJj*mj!2LDu;hiMyj z3KW4e=?=Q4v|{J#vdB}eCd0?1-jDMSUg}d0Miv1_{iWK2YdKyu? zYBQGEvJ6gheueVdw%y`ncU1Y6^yKQCGANDRONGvmrB@?oyc*PSq9HJ`3D2e5T8;(r zntB&G5hx+`@f<^EOX1-A3gb+uUHH1tn!bk0;E`z$N0h?z<%}uC8aJ8G)k;_&VY_{W zd{U(UWVXjy9X-tNBc^~@6yJ{0ca;hUq!Gb$vnkbCc6`oSDYAT;0K4<6jQX>9a)!NZ z?%&Hn`ujok<|?Xqs2)lx^qcZ=o)T6YcQg&x;xRD?;?98z3mLE_e$I6w4Bo(k?^dR+ z%qE^I45y0#M)T$yPFr{u{|);y1bx}%@7tx9yUV`QnKxRzHeFmYrLBodYsB9A%2!l;vHEA_2%Z_;5@tVfdz;xdB=IfLfn;Ui_LKp z5@_fPHfk4bI{8d9Su&Y!p608BbmyB94=vxPRV}MP)gt)VS|Vvrhd=EHMikCh;Pw;k z_Z`l^=`0`%4Jk+uw|=wHcCt!lenIZo{}(KkuXw@Kg)s|l3v=osv1vq6!QwQyUOs^VPwh5hb|Tpkz+#kK*_Iy;+8C zH+jnO2?%QM91c)Ml$AW%MKajF3>N+aJRa?P)aEyMQztU8&Tdi{?C4#c-Ep!8?TX7- zR@i=x5T0yQbnWz%%ZQ%V-ykXT%;#S(7NO+J^ZKKOFC*Dm5o5@U@C3v^fqLV}&)O^> zP3w7e3k!>@Afb|V*V;n|DH;BO4b01t(d;K!F3XK7&#hN3iwHARqROn5_UY*#aI>V3*C=gw06*L(_r{(eu_paUp)$Yau7Vf+XV1Ow{Uc*wt&P3hzFpGM6znv zzg74wcsS!ULU7D#n&w8ws&I#pl6QGuZ^XHCY}UZzWjZdz{bu)uq%`g?(!dI`Eko{p z>@40s(bo<9L^9jcIKeaNuD$Ob;pO7`;Iv-u zP(%jcTlnd{S<~85obA&Vv!l${zz@Y5OP%M^wun>Zf`*?3W8#Oc8aNp#CZ#hp;s;@h zOO)%L_Bxn_Oyel-K6DmfIGMVep694mgM^~saX87ioxrpAW zQ2%9*njO;rz!SJ$DSYu;RL)g}Vu)a{!<|bX(qER1!ARiMLyO2P^08`3LaH5f(L|&F zA(M1Vnj-wZNpG{3xOlZ3kDL3tuTQFd%P(*}xW7d)NrzH=Atdk@1?@CnQdKiKN!`q6 zVM5-+?%Z+W+C0W6KKU*un}~iFCe>o9XR%sqH)%p42BJ6a{xLDiz??L^hQ#vx{ONP? z+!&49RrW7SR>Uio53{62>58p<=_D>`OZr)CV#3>S z0*r5-6#9vI-weW%xNmBOAgAy^^mz3~;R!8BR!EyAgo~TI2m+vuIMO^0#tTbx%QYN| zy#f*(+?~+Yni9i%v5|J)aTa|p?bG;WJV`Zx_G}*>-Ms%iEST&O)FDiSAQ!%o?De@5 zlJr1{Gn4AaKPol!H7=kx(@ni6!%ew?l)gT>f*w16$`rUIFV8sl=9}1RtynwQe4gG6 zy*#~%nB3~}s}8qX^4|4=Jlw@8LACs3Mno_U)mdgLPE-C}lREZz921;p2Qs6Zw{8D+ z*1r)E$o7F5s{DU_;KA3OQMfj3cOR!_lc9HC zF~f6n9n)-Yme20t?ykvP)-FdyTuMDF(rh&0>UzFvkuwH6|jft^`m+j@j8UfNJ+b1Ik{;bB}`AhKwN0HO+ zN7;cQ4^2M(SLeO70cHrDjN$&$vHT{fRh|IjWe=o_fDBrNP$CcCmQ?gD+1}C5yFE1+mo(l9dpIK#f{MvLRohe%_By1&qSOZUz3SCE z__~Ndt-ifFDW4M7HzHKW-e}@sdnf7!G168yGEUjfuZ^c)uR_o|yKh!2EcqiT{{<0~ zm={@+e1haFW5nE-1%F!0gK}pT?vCI3whq-Ea}+q{&)1@dhq*Nr-RC|0Ckd&(DAbi> zO_tO=-&nf;v1;wTs1N*f9s5Vxvv7k92JSo^M~mVtmP6zgoi{r9@-)h`@gpcRbNhLW z9{Hr~Wyh~*4e#^6+GfLYSsAlqdGw*#(VtF*LK|sbt_FvXXNU5nsihaju5ed4tt%L8 z*X_TN*A34La3`5N+~CHQwok?2YCPgS=3-|P>JxUeqi?F5V;n}AgOgU`aQ;*zbZ+Ok zieegW5KP?WS(W~c>N_sDSFz-cyp!lQLziTW91GeYNjPuseF^cy;)|#K@*4AWwQ}NH z{aSUWlFD!%)N>=#yuasBZ6aAPON8}hflF#uEZ>LP6U;i#xGCj-{cYeN^c}bK?)PQg z%hN5jLtP$~FEd3%xNCzFIW~|4oBm!-w&Ct3;KRr8V|q0_g5?O|IBMh7-ZVkoGt35J zc9C`AR*h*h>WW9vdP)4*n0dqAM+dD@e{D?ZZh=-kyWG^qYFX7^W;B(RG6%A;w`n&r z%i8;wvXkaiSMa>=+4aiCC0k6m;M0fKnBt%80HLqlW0`k=!-%l$Ys`5Kt$;+{vKjB0 zWYT!`;Lb)bZjm?B(y6+3^Trl-bTLh^D|#KxA{K_ZEL-}Rj|H;r!+>|f!Fg@zDu+UU zd*J6kG((qkoFikqm%i~IV-3xZgGh073Nyxy^^P)rQ@1zY7TIl1mUNikI)T2S*y4|R z;~c6x!8p`kppdIQifpYYFI>z2wJbDR;US|lEPGqK5;DDd2$26?Gnh%SC1Gd#k1l+s z32%(o$~VCeYhkKO_S<;sdu)>|NSL#nFUO}or)ghXrBbM{pFB2EuFulPDTr{3-)q{QhOj(?@m>0px8l*mDMav1 z; zN~xi>Kvve$hRD`-LHGO5`)(`*YB@S<+;mji6Yn!9#ApE=`$cuQ-ht@PMWun~Wo4P6 z$~dBQSxq-;!k{JdDWpJGhlio~o>%4Cm)bMygJ=NCh3P@Y%*QkcBi&ge9O>pKs3wx5 z?I%d%tZTBJx@_m&zS0x;`=eR$2C}68ro`vAQe#|x^Cw@A;&aKh5M`QnuI*K9BUdh= z+V6~h*c?fmI`UHDIF;tgLz%hl_5xIq_)$kg`BRJaS;>%>Tru>6ZFNhd>WOi};s4-l zcH`ud+RVr-EDoY$GD5-BkA`P|$r)J6K928@A#)V*v?A(J*v>DOp@e^@I;p$n)0h4V znVqJ8E@cvRo?x$}N=1k)E0+MIlO ze;U{b1No+!`+o#x(K3d5x{4$dcE1^)*;+DV_R|u zLmdlU?KJ+pFz7_VE5@yUQ9o0LF9f^md36aJC3Pb4qhi~!9NoMUt_60NedcfLR!w%d zHlAckd+=6atg$MSG%srJE3;hRy}vc~7IgvL?3IX-N?h#xVcQ_!)%6?4rQ6(XYef@s zzqW&y>b_fMvuW==Z3}$pp);=mg`_)?(K9k4xI6)JQHPnY-&ox$M2ZWUdlwgZs*7_l zjWnFeBTxCt8(^)WOD}b8>k+e1ml1R%GRL>xH(^kSsa@^29N|VTtD49{2wj*?6r|?VRsmw2%CNo|f+cOv5))BRA_e zqg*1HpzFOw#AB7*NGy%a8U48dAF%Ng1AH{me z6j}b^Vna3}6}KOrzRWy1baG)`14nEnqwqYkGdtqm6?Wa71l|-?~DT+3m@l)-)j%p*B(IIi?L{I;285-grtCRj9 z1tNFHq8{wHhqYf7elcmF4^9zRakM1t9_uE>tIfFW<^7Uc9`U zn~iR7V(tLb@}misQ5y{gy0YH4?l0F6zdrgPdyslwKvO`;TSmgc;lR~Q znZasVnRnNdD+!jRkvPYHL_ZuyR+%HW0$5221~|ak{8EYSDa|LVBuhe==E%i@LjOXF z#mSyh0Dpr26xn6gaYIoffCRps41g=Mm?dnyu1%Y%F?& zJ1iBWV3s1JsCb!6#&uOA`~MzizoCW6?%Auv7FSpsPki~KAy4e+=y057kpfmg?Py&oybkZ}$Yyng z)daYnK7R#1J1Namz@v97LN(mnN%tp~Ng}tL{=T9{CdP(m;P3A)Nrm`A9CJ>duu*8GU6--yzT!@W~;lr;r?4+wEw`x zqnc%OD7HIf|I4wTx*0$;5JmrNF;Ijq zkNk|KSvT`*iSZvtQ_EAN;BS(_wI6G8?l=0DFQtbZW>yZ@)ZC<(l(Ke_wN?GNk5Lr{o$S_u!x?3uGsW-O zVq85r>T?u~x%!LT1j>_RuGin61Mtmd+w>JI@K+1jnaM{2#K`hDQ5BLBc9_~PB09LZ z9R%&VIr3MN1R>@{XA%RyuRAS^+4|!gRaAH<$YTmC@;`;CZH#a&s~^WHBeIJ2Hev?( z-d#=3yKc&c)TnbnKJdhKJj!|-lufVczR}~#%~rYJu*v!od#d{BxrOG4(5jRq zq(=5UtOP(^huYW;l_ zGYhLv=KVbXe58V&s}$hdDlA$XeWK0JfQyI>pDihH^m1it4iuiE~Qn z?-WL*I`h=M2qs4bv4HudxObh{bN6#?NvdOQL&^Poe6_6SVUtJ)5Rd-23iDgTf>%_k zz|G2+IJbe3x_u5qQE6=0jdv@QL$O-}x{LFeRx6r;WNJ$AF<8*gSgvq7z@n;sQx1&# ztXt)YBaWiPTC_1NHk29`UH8_h0>)su7nYZ*d_E&da^AC;S>%+SpYM+Mm_(a7WK`XR zoe(v{5-D&m%YsIK(?TxaESWcAakd~cn$wsq`<&cw&r36!hwrqpRDYgk@XAFw-5_X( z$U4+tP@6sI8;f4{9_^p4(Mq5pEs^6V1%2c)v}9Y38{mn_YqZ# zw!LD|7Q z{@l_^;U)>s2FF#UYk6mZ*|_FNB?2?#+e|$QH27n3;#BtO-?n~6e8c^*L@%GJ!eBNq zz}chkZ!>K0_P9K9n%d4ukiSq>wo~y4pb7S)blT1r(Od&h7{3rKRA<$_95I2Nurd%x zsT!AH_3UQ{uLD+6HDS-z&oU6g`HD;8Bvn4SES~}7_^2!kcrdb$yt17E&8gbGwQ(6+KR*(;-)s)0S&uVb~hWr%uqMG!|-rVnr2c=IFy) z;N6R`SO?lCG|^)rqEx2>2(i6=yP?>fLDYQ7Uiq6+arKf;jEd*ziQmu%>l@4Na)p7+ zS?`supHdRtw{wv$z>VTa^xKu>HINHQ;&mxyU4Hocd|TJx-v=0I0dJllP-e4DkRj$= zaqR?-Co)v4Wq~iW>Y}(}Bxd^q0|RNm>yJ?mBmez-)nJD5dEd+IzI)Adc=!4LJyC-X z23Y2RDGr(MXlA%yzBU3Nm0noT{I_cy!2{0swM(lXP^Q=&x>yaw4ezXM`i(%6*&CLk z_%_SGzqTXiv9Q9wS?WAWN(|B-2Oy&BEcx1~?kA>hOw z=A?#aFXiUu25udaP@Y76t*?aJ+~$R7PU6(4V}wi}`n0|W*QFkL{Gyz}oz4=ApKJ#n+oD0PI48CS8#G65KUPTi?tshYkX}xHr^)`GCjBt*G)lX`s!6 zH~j@LWG2EQ1_qS-sRFPz8h(xi*u%SMLIW_LCZ(P1@}}R03{D|-zmXXEduCFa?q>fn z^~ro`_pf&dHb=-1Bo3fu(hMOAodX&2)+s4W za$)UzW~_=d21Y~@=vfWfu3{~h-N{?C!Aq6mF)45$$6>KV*7;x4(TWVdfq@cJQ{0r% zX^}@q%y%u-wv+G&Dq09$X@C6KXron!jFkS)TNC zY27=8NM|v?kbya<>?IYS9&`Q_5~q@C!Vd-flQHA!-@h%lQ=kWwxc6@RQgWg1<}_^R zHn=VF*Aq90EhUSM;&64dAhH`j8-D@gB*qcEnMQ@uQIE z2yo*t-=Cn~AdE`A5B)8*xy3p1F|+keHEiCRnXOxU^yTu@%))G9i!ipnEIi1GF=oF- z@vB;d6A6$0WCGcoF1f^4wa{=Ox8OSus)NJG!ZxIi6)~>v#vIlKGVXQVx$!wPk^y@# zv?l{gc+tOZB{S%2=1_aWFvrbUY+QVIFTWoD@P4BkJA2tl{_ey38ir?mNjLBpR-NFV zg9!t*$d|j`p`*gESDB;k6k2sw@x@i8a-{9RpH3BFYS_%@qQe1~YNKr-pL&zu##9B)PCfaXDlNE92(Us^ISIB<5-1Wc-6soBKrFK+u2T^fP)MJrL#{#yWMgYyn(<{F8Nf67<{EQ>1zixxv_A)>5_q>w zeYIwFzdrhLvfLys%o&sZGqie&CcQovFXrHYA5gN#RI2F>&U|Z}QuPuFkcg+W-SqeF zl2w(FNQ*}h!X9cEJ?*4;xdGA13E{jJq5s_-l&kcm8ABZk;|7&LBa^BNG|RKN(dSd6 zV?&$JF-B>yQBj7t1iE=6VtKl$W&7z_L2`tzeKnb51npxp1~I{-js=SCz#eSoqky6; zr9SpHyvU|$inr-L1ND+3JwbYL0fRqP_%G_eS-hwuX8rzfC{d_{;Z08=^fk!2PEs-? zLpj=s7n13DQIH~=;xcwIUeR-UPmBn2s-zvUcv{mN*pFJL z8TSzT1NLyTG+&Sc-@!pAL&-?jMhynTf~KD>O~pGq?Qt=*3R$?O$CU3dXM&zQr@0yP zhQcby_|NOHs&{0Yfw?(0b#%Eh(B(!>42lsZ^>Ykya-w~6Lg8Ej2@J*$Uo5CC-iK8f zL|BnnC{F&>$bGKH8Z!ualHQ#F(dwXTHk02F?9W%wn7^56>;Dd2db1K;4SJNTw34t| zpG>b7T8uhwuT>>*abs#*QCRS14mz6p9cPU#H>wd9<5|8^oe58aDcz*DY`)Bn{z&^M z(#d}5zM9mkU@4@@+KBePdE87aMRND|Q@`skDr(J)^=GPaDd-e!fd(cDJppYo0hZu3 z4rU6Mnz*d>qv{cJw_5>e=(o}1fEOj z$NYz zX5xY4?A5+|o#Ro4vd4Re%opZUZf#`+*q#7V_LnlAIQIlEU)-FJL73fNO*135j9C5j zD~^N!o^Ag~|CiSz74)*RyHHfBC-2Nqi+cD0zgrmgY1=h1@xkwH{sM=VzM+xs%aG@ccU>WNIJ!&5 zIb-yEv~ndpXY1+rIor`aJ&5O)%=(4f=zKi5YeP&?+y);FObWSd^9#I$*-pIgpa4Hs z>AmYa(lY0SpKAw$Y|-u-MR24TC+E}$S$*BeU-sB6vd2$B40K~CF2k;Ip{PsfNqJSV zTSFR`iiZ^Z(l-9@=|sZ+29v5vQwZ_RrZ7b5v(kp^FMtb4=-|k2_kw5q@isCeEou|% zFmUO}sHll~DxgWPe?g-8rJuN1r%i4mBujm?6k^oz3Vk0a!#%u9C@m5npRw?-Nv}52 z%wrA7My#`T-koVY!CA)XtQI$z)9LIEpvh0jo&BuiII7UOC;GK-NUGBp&-l(0MtoFU zC1WmN8a^k0m9cNKxp3Z|@SgMAdHwqm?eOY*5G17k*!{WmCU>vmF=q%zDx!r(|L*$`se6&vZNo@UH%2t(J^h`U0qM=ZsI63D@eX0aAo5z7+$+(`FL1DtP z^(mOUQQ)=wd+V2JU}s#+8Izp6U$5CJWwsA&gzqsDSif%6AAMeJ^|ITP<8`XP>j`jM zv#$^r7moyz+h>oSfT@dXgnyT`mv$s2uPnRRC}62=N51+KvovY}dctq)EfZW@Edt8hc{fw%xd~t;WX0HX7TWG`5|*^XzBuwf^s?d+xRFZ*yIz z&)?AqmHppD_JeoTE5`PnsQ21*2;Sj;F)>zT5oYzLgSHd!WUXb{?lGV@6b*{&VYdan zB=Q5Lyn^m-g^QO88)yNQ8OZ?(@c#IPyy*k&dbhyCTe;)whlukX@t@sn=Do{;c<>?u z7#qa2elxtLP-mN1Y*4J=CVwMBAcl231J-@jA&EgvNIP;SYM-Xkop9mtt@tKZk`-;= z$DfPEZU#ugH(xoy%wE2Sd3~JwEN^@qKRhFqdY&)&+em_@%k{`}xxp}GJ|ukUFZh~7 zQQ%0$GXZ>PO$?xC!virfzbdqlT6%WS(lVz=Q2Q{G5|9VA!x9qt>UJg9#BnSRD;S{P_t+EIfp4P<~9?K+Dq-~`reH7)@~f_jD?!zjA$6=Qqa zC~}QsJZJ>wq{;okB+FmPUX~y|;uj+mh3)Rt53)AH-s5kZPY&#h*tSbN7n=;oWMN;Y zTR3bt%2Mnb=CvBV=4Gu(`p&!19Nrq;H#$>r%(dUw+N(9chk=j}b8;CL2!_hp#i-X5 z%Vavgp6dT1Lp}-velC!FNS4-Tfh-NB6f~Qx8tgX1Ai>$M11N#_l_oSuK#Ce#?2P#= z{9Bl^QufzQQ)>A=W47+_bIUMtymLGV)Qne@BbeO{HJR2@iV1~r!B=H*!6{|~srR4Y zL?Zbvl`f5+Lsw)q*^wJO$e)x?zRSw!MQ=y>j+TIM+UDr&vE?MH27_IWXqt8CMWR68 z&a{i=Sp@C4sRs;Wj;uhJpv~c&VG`xodFR}zFiEb!x;k4f|7Q#pbv531xtI;qo&it{ zq#4_ENP(2kT;#-CW=mJPzk7!xG?ybT=?%csQ{W90uzzVdM(n2=RM6SJ=2`!J~;Q<9iH6pg;qF6a_b1d!f)X-f5(N*B0*u^VV?brAKrq zm5M+FqOMObXvFWBrHm=E1U?o#hUDX-=fvp1NA=;6Z5pogJe}LfrUF^$tI}~Q$eqGX zl^ns^#~3gJ&W9=LyW2{tw9|QU0W}S7eIxqtB!^Rv3rPb(#YLou-HvnCX5pl|W-@b5 zAoptL+=Pti!Uo7-<1*T=aLIsz9Uk(*2$qgm7-gz^iJF|J1PUg%)5_l2L74N|a* zJo#0tHXYhpO{KBHnkvto(ya=dx_1CLTYukOB)@&@|EGYv9>fT!sxi*XF^eZ!_ReLiuFV%2b<@9_NS`AX*dD&A1@8W;NU@by-Z zOpY#C-PPk3IP4{wvk>@4L6uO+&@7>}C5H zj99)R81%c7=Y2jz$MlM@pxO|+E7lDm;;_Ij*n>Kp6;+wVmknDy-G6ZdrVv5ZENOt4 zftL##t0gNX9f!r$SDn4GGT!r62vn`yB=%5nW}wYv=!P6wJMO#6qlRlxjuX-9#RC}z zd|45ad%m{uw3HQkI}u(Y8b~-#IFZ1)PTwt}INwi>U_Hu1DAhB8jf_73um=_yrz|{W zi6-hYyqyjTMUXbaaS&yFM6ch1dY95L$`vhw8TMo>Sk+M$-$Jr6SU4~K2!{630x$*a z5jGDI(3lga{;LILD5!7+eInw+yD}GjS_+?Eic@Mgo}`h83NJB@fe6+_`VwG46MA>I zyAAZ6snR9_uRzBqWH1`a*^M)jz$leeiNS`GB7oag6d*n4{iTvKJ}p%BReC%bT|>q5Q>pzm~TEP8NuznbN_+3S@6yLU<4?bNFH*7yd zf^PD9z`8;+r#yz%lY4;VwFP6!Jl83>6Y3`W)le`R@e`Y#9|XH9<}ruCG>Xq|`_k^f z++_b_xH7ZVx~OcH6FH?UAJh>puGiYdvSN$_bt&+oAHxyhyZoeh#?+n|Cx7hlq;qP@ z@ctA*rZaZR0#}>2XX&li&dt-pwVZP{&Q?MO+{9o2&Vby8Y~S2<7;sytp?sGpYXa7U zdWa;;NIjB2r#1^mhU<9qbP8xzP-By*Mw%6T-Ht=YBUOj%h*(wXkk0ZG?6CEi_gFpW zi=w~F{^-D;2{KFeYb8iY33qI)9=B#%e+cAa@zXal!tbHNB;))+| zVdo#t%^Cp`;bp|~gL5AtCuvsUJn`>~OC&h(WEjO36qF1Z5edfxF z6mR}E@rSTf8mGi##X>6i#~g|`!E)Ln=$W@Gt_#y~*r@is_i&^%adc|jRLdw?njOin zW`po0YE5+r0%8lxbS3AOA}1psReNJB-HU4i3D3e#hi|7EOqLLhIr8x^pG&bLrpO5! z$375V%LZuF3 zUbLZhU;)8$PNpzdqVAN+eUsWeq@zxVb5x&W7SR13OS|YOCJ4yF3pE98qEc9Ba6;~n z0({CNEQp8MQSl=1%pO0GO-zfW;&9ZeR-)VmHN)7~5>T$)Qg4+|V?1V1Mtc^o zKSean=QYLTM|FBP*lTu!YZL=H)$POH{d!NzOzp+y>qg6(im{j{$3R!}w(mZSKAYsh z#$ajDqd-lBlgs@V8N~)id`JkvHq5_9%iDT5EL_NM@QHEppn-lL$t{I3Ru<)pVr&-2 zd-Rm(YQv+%Q)N59!(pbS!e|Pld)AVYbh(b1wn)wMiL>t8gL@IUi-AFh0a$n0?)cCWiRKx_E+AH*@ime}7bzpxvwo$vw{p^Nw9-%+Nc zNwcUukf|08vj+Gs_+O5<{#&H`HyHbHul#f{Hd?OQGZ5Yr>j#yT%pLRZ$$QuDn}X!r zgeCB)eTo7fwfB?5;5IPf&_lErjw+1XRJ+dfGg0ful*dVQs$z#PzPbMlMKhgvO#06t zr1U_Neu-}s?3mHfUo|=$825di1*~X#9L+}_0ye@ac`(Ae_U2nrNm0(z1sKd7NCj~a zxzS(FT{@I$kdE~qczml#31W>WC>iY?c36nDY0C4K2V+Yk2%;zm>>5~2j(@BZ%5a%! z(ozl6mP=ynG^nbB=1_MO6bhaUvaK{CC~!Dfvb^a%Zz#udWN>DZnHtVT#whF52LpBN zSgzz{=>1x)f`vV~rMPT-h#0xbV5<4dVHpLiA&X`4LOa&!p+rb3H5zf*1lN8pXm^w% z9FYFMIKy>Opkx72M+9g>h8gGRp@w=oF}4_t8S)YKdx~ck)9Lp@ z1)u(|KMtq(9h6VXS7~q}I$OnpgM*xSiFz(#I;SE@jniy5jDCgPJWd3@(Zg87>r4sG z5|;hmsrb-bh`V=#{S8a%vY8Y^Q@grz*3sehMO(VNRtT+(LbzJZIM@rumPM6lYMk69 zg72-Ta{gP`vK$Xd>i>pU|20$}#Q)eRvRofX0x#-X58&>DN;w_`M5d zH3!A5*x#51N<@w}KRj6Ymnb(0ac;^+o#R)cjt54*m%kz!O&$=mv~Iu4@*s8$VCCeZ zOUugp0=aW{T1$u|#GU|fJC3)US0hGjie2`J!&Ut)2W{N`l&Ri1KkNwAZyK7o(s8JN z#LG?ULLj}p_~?0@rz0-oQEiCdEkOoXJnl}ry}?r`N3 zW3noE3ek~||7?-aj&wjX^s>wFqmir|FeFNDtj-ujuAUa2_A>;JIDY7v!_m2-V;>=y z!F@|4+GX)%F(ilZ%%dKNbtG#8rHQl~&i9zyPF4*}=dg2K{p#ZK8HL68>mJ{Q)|X#| zfB9Y_rqM_NhwpA;eAM>EW>qgpp%9Gb)An!AbNz4=L#g%#0cEtW+Wpq8y+xN9N!FQqU7D}VK8|9Z;CL_ZFZkG>lZa1tE}5>3P=mh5+ad;6o& zW%we#C+`&&VX-XO=|#-;Pz*17;;c!}sJPF_Y4-au)KGRy@gsvAdD*yd%Cegsgn!r1 z6Mua;tL$WxMI++)To$~r%ueLVqR3vLKA7HIrFHIfuFWWfi4=yK0+j7{l=%jnSnVS> zo&`u&<2K7TEHSyo;ujCxEz`d2-_`lH? zPy>x+i&m?P?^6A2uH-W&W=zn()e{-Wva*qu@B-9+g_IwHSI^F|Dp|k% zha@@{$LUgQBjnw9&$R?&Lhu_u8G-g$f6(?RVh=M_<&?6cUDd>Pf~tkTFw!ifz)EBt zg}~7ENX}aN7XPkp&_LT`{W;F^p@S2c`B(%S76{)tS|`(`!bNgqi5n#;IaZv<*9N6o zL$nc}olbg(CC0T5t6vBOePo*ErT|eqiw4l+=p#9@uHZD@FTrQF-sGsnUBai*XmY~;mT#8A3BB3tabIqg%lw6aslfBTm`Y@ z>wgOPBmQW#U}0eq=XLkn+>q!C@;Ospku7=jfSPd%&8DQzVz|Xx*|$)&r1d29JmiSh zz_wt#8a6#$HF`=zqkTH8;zG;A^uIlrTcrl$(T(8Qwm||GwL~n=dt3AfCv?U}Q3xbc zswmy-URKH1N@?e%nGGFwd=?sOer9JUv`eZo@a~2PqsX8@*+Y%amam{x6emEty6R>8 ze0LrF$^&P09@)Bg9yJwt&UAp!DF@~4y<~}~J!RwnI=RRY52LE?ufW#_*e?@x%C?$a zS1$nwjGq`grXP=17h3-pN5T7jUju$lV}p4-5DYNSf#_?c?b^89Wm^ESI1#~;b9cB_ z7a1IohvoL%h)YkeQgfyqZ92h(7l8F;&GI}WSWnB8+2unzw+rOC@;cE0%0hSoo=(W7 z3}=%H=F8<1qNHxyeb*>`4n`w^o^MVAq^J&-IH?|TJOku*m>p1sqvNWLHt{&2N1O*@ zdepymW)))6hGYj}RI-erID@MdEny<;#<{FUg$w}+g*0b>hmJa~WmBV-%;C+o;NAGz z$m3D((`qR@!UOW5LyJ%XjSz~bxCkTpWaTG|crv76N{>;aj>$oHpHSaIH3Gi5LC zps(oSh2s$0`3&VA2|Cd~V1($gvo9!NTc+_Dq6{I+3E5e}C3H0Yku0JheR?P|@-`*X zd#lB;_pkkfnx3}2o~DY39{*g7A~7k8XGhH1HQ(9lH<%0W+A^L9bSp}+N2{Ev)pQY} zzKMk$EAxv+86!K;az8E5Igb)17C-A~yR(8~KCjbI+$0S=l8|M>Glh&A1lzn^;|nL} z@}qXw%00C2XhVbF)8v_mUJu4__`#rUd$_qRMZG|_Sp3-4V=sOxyAFUXq%O$U;Ng9M zfrL2x{3Qs#J73d4_j)>dZC+}O;FK88K8hp80yR>&%OeX+fo$1T@9tYM&!*V*4BfQ? zYTP53zgh(F+Wl8DLxcV!7nqyeUDvWDtJQ`0y2oT2X&;KnlIS2W0GH*GfVuUb53jos z1vPFub1t5IE=vBG9V#3cLF&XDPx-q6=&@wXK>)_)(7BDTt_#a8e(W5Tx-p=$%#1fD zp0uzbrw~uBV%PB1^6cfNR#?ov!F|62C-!Fvu4o&dX1^?s#A{o9XUCdB&LK07#%ZBQ z{5Hq(&0j()uVhb>hzI$@84`)SA~O2)_T)yRIIvJr(*d+lfO`pU)Evo*+E=#l2FW16 zJR|$mT4px4g8%IloFkZ@>h~>4SfRrxnCVN(SR-p+w4r7!#-HyahJk3}yWjOJEG16F zp^-79riH^vuuQp%`|DT;pLh2|3n2SZkACrv{U#;R_4)(uQ+Bx`aD)I2t@$G=SZ8oX z5}cHmcNK-y={wN5M|fErW!<9)HirgW8C}P5WIg7{$N?iBCw>_o=l8ky%lLxf z4S*Vk)lqCqCi?amZ4OROyU1F5ijqRo?%$vK!*2VQ^N#+=Gl|qS>s1d;liw|(-2R5s zRa8q1U_XiW03@=hQf782#1&yh%M!CQkl7ZiMWJ<3qSh40UZ>^bsK<#(z!j*aP%pC> zez($N`vCRd%8(_n^r4XbG3o~8bfIxn`J)egmKqbG<5hBNtn6=CuJMrNyrS9z>)*)g z0x?dBC^`8O<=7~e_^)1OFb`VJ`u9qf?;A`8zqPNoAyHx&t~(wQbq^WO8JT6RxUT0- zPp&gLu5+PnWS~k=jlq!@{~$@wj2NBBq!G>po_$8^GF2p$-Q4A$|NpGtVBFa8HZlf1PK_hk6vDwE#i`MPKU;;CEgxH&DaPbObcmvU|UF^=4f& zIAzy~$<%#|c6`FEXnO>kkf6kT_iLBssMdJee;eiRU$>Chv1ZW%p7aSzFLNzDeO;F$ z{09wvZC&>!(e?1_7IlEZ7!4;k8$MOYMAG*`4%A0e86^ay^)Ta+wky7IXDF8fK{i)H z`31S5=x$sp;Qk4pQIk!xU&2>#9%y* zp)1>4A8en?#Up20)Buh+G`o&?_|oBdVgmtc`n^c;`OsNXzoTu8GRLB_Q6t(N&C+4& zhhnR~?hb*N{wh^8r1Z?SLyb15f_wIRhI3D66h8~Dyb*yq*N~*QWT!YEfiq}VUS*xa zbR`oQmQWzN{(V(=P(-V%so!D+s_VL?vt?C8X0;8H&|`wW-kcj{e=5%(i?T}S6;x)qB44VeH4O-}k z(DQW~QPb$p1p0mDP~NMn)l5K&Q&rjBI|sOOb!M-R&q;@&i6ule*kao74l5z%25+lH zR(wW&?RNRG*~2t|m_+nzFH0(!Iuk04!WG&Jx6&K3BT^xXHp2=Ro|H0Zgkv8`w5A0i zgm0s0U#lX1>7&&H!qD^-e)e`OvTzzK7{a-6J=q^DjA2T(GxQ1vp#kRn;D_%Q7NO{pg5K*)zOtha~;pufuf?B5aX*idZ0&fs`z2!iF9J-rpqW#e4=~> zI+&@o(OU4lEK6l^oHewv*>049&^7g>iOFR}dVkIcbt^Zm_)9#tbk+zoUird<>upgb zF&Viw2pq2J(#{^8O_^t)irA7OaHoFE`!#48&Fh5-dTLzVf*N^Fidi8VS}V(-W5dPJ zzhXm>I0MqCK~^zufOYfD;L5XuAIcv#yqUUkIj17RSB6jJ3noH=Xq6s$he9 z4VZBdzx3;gtY1ujN#GM?IrYVXnB43W!-kL-u!N?c}96Q+|;Fy;68a7%|}*4L5#jEyNK4p^26NHJ6)e^FFcj?4$K zVqmA{w-qBTEHsu@RK;(QsN%&c%0+2UG*I2Gz<2IJbRXuQmXY0JE%aC zq*2e7S5Q6B@Jz|oE=^)j*>t535->WJLP~%Mc-Op%Qw3{w^b5$3qKPH-kwoYorgEjM z8L*2kRo5wt=A{rN>?Xm&Q{A!(FDCq;6R-S<%<=uVK(Md;6E1KO8pH)Wava zHbcz_qeWrfe+vo}WJXiGPTN{leFcOezIH2DN$IZ0vB=Kn)ll&A*Z4A46vD~K7enLk z?==p{Hc0Npe`gFY!2w`W)FQScEB_^XQki%)*Iy!{Fi@n61rkcn_xoY;n$t&-WOJgn z>#myT0#crqZ|se4Tf&bCZoC6_^)xM60Q^RLR@U?oF}{F#ecjm2Iu4!~ULxFf8rgUt z6&rfGrRAUcp&TT_x+G{SEOf+>1r22-r3g@hlZxuXuL^Npeunxhyy9K%X=8C~!^|wk zR2>mb*pU9xa{8q}3X(2@=kz9a)05r5R7c9gIJsjdGQCw`Q19G*+^1ot;XfDBsaYz1 z5n+}>~i*5JyB&fx02y=O*38{$7-`4QM`@Dc0#dNpIRp2B8hVHwPB z2{Z{~^@o;u!*(fpuN0-?&Ar+F_-B&k;_X2@&o_2-R9eULY0qknAZs~)*<$_uMVrMt zbo4iI1?^aESuxt+yOs(xP0X)&kQ3QdYQ(u^`e9~zG-Fx2d0jm>0#`%mjvAIj-4%Fb za1gu|p`5s+voAizmtR_4-t*jO&2q73f4RBFWUSr$Wqx5Xuew?*ob5Z0tFj%w}2OL3mqACd6XZQ%_41s~u2DY<&bMM|t+(Np}wA|l0Ui1L30G|{lDAJ6T`*iSZjMe?e%;0%hEwU(U&@14zI7cRBVbXU&jEi6n7B=RHitkF4#J@ zjzjQx%L!*HXsz{T=c*+>F+2S8@YlYXusabuX^5lohYWbQm|spzKmHLR?{vMI z#4@{gEiIUO1)L11DiWgC@BFGirTH@?G6lS^MsSA#`m?;702~$wYlC*17}?pZJk=ra zJhcQlZ;#1uiS)=D8YbI#c8+QqvRKu)G4!%}$~lkFn?g__nL->itvMWzP&K!I3NxC& zTe$XBQV!@_wMv3MPLf;*^(_k;4tt$O!~E5SWFChlIup69oWWneb|p| ze5AzKIm>#pKcTGVa6h1gjBiDICAFjF(`6d;NT)zlD)Cz=4UG&Vnp$ykf0dS=k*O~N z9+1x)e;}ib9(x9zYP3VX^K#M6l!{x$Ht>574uGWWFqbES1ZEf}?_u-zo}x*}FcbZC zKaWr}9@>ecnPYKSws=&UTM*@>Iugl%*KYJ9pkxWjut)REGG^{9t~L{ z{Hb03%YnOB5|hsiq#`cEMOmV=V>Dg-_o>RD45cy5nnNH77W<20U5NPiq4rkm z2RP9t=G%x5-}By&KgwU6D~2R3>EE7X#TS@9V)%~`T~2231#;!#JX#xMXH1F2e| z7(YlIBjeF@LlE5|cuW@!403g%w)`!^T_}Byj}ag&6df}=WAN(K^Y1Pa84k@UzRejt{Td!F&8q;zv;Ins+pk6W+ywtVZg{j zpIj5mJd;cC=7e#K;ue+Q7d@YM&q^JsF`ZD+Nj+fS^`J){u1r$Hr0Zx|3GGL5V?EGv zV`p)ClvtiGhtCZWF?$>?NI2lsL5| zf+u^=-a8{V?bn zvQVd-pw<|DWg|F+zSaYVUe@~ruOumBNuN?w5IEtC%bZXId{Inh=s}6Kverz-_j3{9 zN{BF^4qR>f1{r|DH&cbPJP~VLjMN_&z@L;hwkxM<1jQlM3sM~fod(79pBL~wG#OB6 zc2itgYKi!Gj*K?!X0FPEcG1UVTnbfflM1ygir!qZN~cCfgzW5)zTBV01P!~1q_lsU zQ79vi+eD9{9+L;?n?q%9phmRpIhz|^hpmOuk|}lT+um_P(CvbWP=mFs`D~?T<$?)n z3- zwXzDVZMkgAnYFu&mgo;OY$@nb=XsTw|G3;Yo;<*yzyp~o4wu!kk{CZUDxzSJa}1FoxKOh8pwN?M94#%}sTWX#lU6Wpu8&cOkwa^lKmX;Yy88Mm z96484_J8({=^E^JA6}Bh_(j&H+uiNQU@G-ZC#|)6UqW-ulF?KPHy`)|*0{381MobV z=y=SCso8)Ri_J>Ifg8QY<*aYI8$;QOUxHyn<0LMvI7c1}hTz1T zySicI=6+;zm8?fy7h0W~x8J`)eKU=qXnyXkj(+Mb7vI)n0D#cctzg#jM3FFdOJVos z(KL|YqdYcUvw}zo;oYeFfcW+Wf%hdsLSGp4FK^;Boc&-ugZnCIbicTE$rc$j^?UlMMb85sQ*-Zf8*tzC8KH;uON~ zM)L~`6&}r0(2c!_HdTMX{Og(@atwoNj!!E{jGc?$7L~3Uj>sDB`~3Qhm1Y*Nj*JWA z#2LO84H&6eD*E|p6%LBjPK9p{e;*(A5>{&JVp5XfSrH~aSzb0zeiXl>vxFE+@TkBV zV;PD_t~*-}?Y3&p7TtjoXkJ?|xEo@WNbOr6ubF}#1oVg94YR9f z1t=q5M4!_jY*%M~hBDzpTB1Ra2b2_=E7~MFv7Sp7F{TofKyeX~kS@7peDK;vKb>GzJ6H%kjrZ-x}~@G?(?bLM_VzkumHjj26V*K_ z9|~=lQ#G2EmAj`>%gsbS+Yl!@!-relg71$df_dgsIW31&fFVIBUxt*2Oz)4u)XOjU7t z3{T*Qm?76teWx({&A?wj2n$glo24IqaN9|X0}Kp{Lr1QekRbMTX%7cBnF+0Mbbtl# zUak6?Z4Dw1FtE3SCMp`C6E}Y51jnEf=PzL6bvm@_TJ<^ZJZ$ak_`iK-6MR7lfzCvM zecZtw4u6cvZUg-eD%oz^S`YSrJ%P(|-r4&zazs7+S7BHTn@)SFe1DJzFWjpTsRnH; z%k?=vt;wIZ&13%?dmWUWc{KU#!Se2olg7BzPIMBzt#WR?ss=fpBIw&>kTdJ%5o{ke z!w)qJO7Xk(;K<3GK(g4ZFU_3LJJbw{4x~EGw0fC+#uQCGKlhZ<2CAazl%mai8wS#}K#E>ab&5TpImiK}1X1C3GxxxqTm2L~hV#VoY zxM)oX!}=L)@4~~*<{YID3o7?(-;~UVt>x)2m=#mtcaK)$W ztI9mbjh1V5yns79`d^b?ct=p5ww-2aWiav_@FHX&m(^4lmw;LLsqg7_OPCj0`FXap zDIQC!9nUyM-_`AXRtJ2-4QF*UugHt*-$q7lezqq$mr_K5vtm)9GVNzum{ueu1$AO! zu`29ASN_Z1ak8KE|?WK|NMF-8O)c9)LprS(N>}T!zfkAP*j{aw2n)1K0{>UrxxFD$ za{7Y^lC>-38r6G`yV#X8QWF_q^xB@{+a$x5KawT67&lMNym)MK8kS{CR?6CLuU|pv zHg;;(Pm!UPINbEl5)RQijINb>+!6NFm&$kqju`hX{Ag~D9dL93NP_b31*W8o4||c- z65^K#r%NSJ*tyf&Pf+^NS;xxTMN9F^M98OPG> z9Ka6`KE2y>PLz^tR{^`Xm$#M&AhyGzn7YB`AGkjt)^i>ItM_i)y-a z`o_F(dYa8DU}^`NR`knO8-*3_Fh4ZIip_e<47_EF&2Hn8?h>;&k<($`;d*QR^;%L& z3T^yTS4^wCJ#UN2ap6c}vi}CWmXA$X{kE$|UWtf02&0jjp&>cZjoYQPN4_|@@xJ+?5Q z&S$+;X}RP#u*WRGptEE*M?OX;eQDU6;YK5<2m1qb@@uQ#gFTM`LI;UThlsP>y5jP- z;9++b0nmF<(~UO8_x=sb=i}?>o^w7<82UV8EVl16a^LT~{v8>)nGoBsBs$E)GLKl5 z)4n*8AjhGyu-%@WA8Ia)Iy-U+p^48~uf?oCu}Hw8i#mlvRt6%xM+di!V@ILda02tFKTPU(g^Po+hSzz`Qgvs;mNIBw-Z6PVieWhgWorY%z3N`VHr`Jbb% zsI&MK6Zi-mNl@;4i0?`NP?VDcw5p`>LCLLh0=r{hNLU_w{`fOTb9 zAyoJ=#PW{Oi|GT^5Bh!b+PfPK5Ov=#rx9Yy3V`tv>2yV4%)ET*A8gkG-a zV_~k;*5AFJ*g53Y$Behb2D-=rcOrW37!i(4HRz1i;*ku9H+-XuJZ|uAEwaf?DJK5Q z7+Z%YtL35wPZ;+OBV6!{I8$^%ccn_Mb)i+0<_DBc#q%j;mYvceE(I8s5nIp%ksW%m zDpSrfGf`NR7HO%Co`un;2S~RUOP>YXFL9!dmBZ$zk)0m37aXs$j`o(R&v&mz7lagJ zlS(S>rD!l-xlG3mJFI^GJ{1e+9Cb!#2w`G|`OH(@Up6d1@OK2J%rO{YVMMZEmWnDO z;~2i<<@u)N{Qw)Z)ZK&z>g?aYj%t8s-Kt|tnPx%?OppyYC?OKem)TZ|FRUX|^>wc-K zg$fetcpjxwqy7Tj%kOpHAnX)A>M6K0fL^5#HI+aQmfiz`o1yf&ZS(NBZkX_mO3KQn zvT%lTZ7XV(hUz1uN8zXI0&0K$)7JSXh&`oUL>K>0G>aH|Z@N)FMW35jWyy5&>eIt- zI*RcMO6?xldVhC+Js6?7I=z{yVCWZYeKfi~ntKjw^cnM9y*+vaYeL3`5qpXz-_5g4 zZEwC@sJliHu?BBS5x8U{=E*gY9J9Dxt$j_d2yuy!5}Q`co+#y30brul{K z-M~h*(zoBR2kjtXx_LJne?USm8K8ewjCwuJzoAm-1U1VTaOVkh*i`p8)py@+%gqfx z$nk>0+$*v&(x6DtHwC0h$oZ`8O|#FF6Fpmsg)-I{OAxTUeTyOnfv+-Ae(wZq2$v$$ zUTL~BAUHCSnX0SN^&327R^3*SC?{=B3UyN2Pp)KkEIK}RC}du~Tjp4COj~NBQk~Zq!-|HwRu>SQ-=LJQ`wfgXT0kh;hmp0Z&_?pzBstO~J&G}-kU&yOKGhSNt6%+;Z!Rw)frmyT-My=oj-Hg+-+*9m){cbq|81^Lxu!@&oY~nvzo;7wB97*}`lXtxn z_D&Alc96LdUOD1Dp9#ozb3MuTN?D41BKEKUdNS%|Z0pGB(^&h3*pEZ~x#F{4EX?PZ zhaQRpf{3fnZ#c_kC}F3m5pR0vR+Zgi49)pOT#NAG-%2oqB4nu+F<6`4O(@3ThJT5SWHfO z<$d}4Xxl&y1({N8bD{(pORO`f5ho7+qKX8MC7{z^mQJn5OG_(>pIX+y7+kEN`1e=xuqj>)>yhb zB8myv+iHZj>FTUnNjyCk#40E$8HId*MT%^mGTc>C?xpl&Fx(Ux7~c%dX2M&dp^j3A*pz5&g)5 zI<^QL<00LCQ<|>Nz!~!%!<7GIr2k1%8=%AGS-ygQPEQgz{UO2Oaxkda0OOsKM(hL> z#>U3_jbr)Ek{kHJl=*H|ykgr3WP!&|#zRp;T3UESK9@ptiv||@knglME3ZMAt3-g= z@%JVp-iNaeT6zto=n3stE7p=m6}2$DWMvh!hWmybhPBs68#Qi$Y|WTJ2A}p$Pd^Qn zjnc_t9p)BqqP}KmuxeJ%!jfKvC`}LyvRaBExb-@pV%XIwdo?cae_wAlOvvgm{q6N6 z0OqoyqPhb87{L<3yNljOs zFkS@7KU7n?`LslNe%JP!4zC4TAFvn^rWJl*JnZILgR~q$b0{b}^YU)Ye)|oEsK5Qg z2S=ap1#OW@BdRoM4zG)LwLyF9vN<+F`)o-joB78HUc>$N)l=LI2{PF*QE;xlJ9>`C zmGSG}1pRL{#$AQZ-_RmPTTsxbb_uA~RJmDh`D#QGtgfQh&U%yjk%mZi+w%(C+4*Kj zTWEX~g&|7FU1=jZo-Go}`+EA#vZFj&=lajt{@*r<)rq2t zLw6}l*FO&QgWJ`~TyIInMN@^OczaMS{6eErzJSV;sj$9mN%Dx*Rh|_x2~xRfvY`7~ zIhz!#3It^gQ-DO%U>;X5Tm`{V1z7pc8oV5!lRC4VLes=}S@4x&}^`B^8zbURpiA zDK>U@B~5*@T|#r~blaFPOvTRS0LCm5h}8K;Su-Nfya~;6a1kTk!$5PWB*=4J(seG+)KS{_hx5hXr6b z&~Q4zV#P^=vSUT+i1ZJ)TFh5|6!?(jZy~nZR}OIe@ORX1a5CM6pQvaLehxeI;)WUY zO*7Auu`-6yCO^jX5#r4#$(W6#97K|7ih}>VlUGz+ZvtHu7dNqi6*wgI;=-Gmi z^Old3Q}vsKSpeL77*8=*nt3=KR0Qo?erl5FamMdf_g$7pADK(*os-t&uX~kR+U94L8GTjn;;x)~9GH()1ZQDmdqPuPFj^%41}Oj7 zFsx;H&wtX3+RRdLvAbNgLhJ0Y$qZa@c04LdEqA^2zscMxZ4t$JC=q;RM~ff$H|n%AUvF87bep z4#d8ne#qi@Ka;-VQYnFei7f+#sZhs_A>8|e87dZI)lk0a0yTrZ=FfT;F}VVsOedcg zZ++vrq3Flg`l-uj>zbWb^ITQ?8!Rj<8L}*k-2{k{O_L@t77O9s>1N`eTnfGhjQ*Sw zd?5Iz=D~OOH!+Rfxj3VcWOq1rIJx_^==#F0nAq=;C{txwwd?tqj-oF-ERl&@j=p42 zs=6RXU=@DQgJOggwY{%-5V{nxiO;jv=AN_VWjuF#vEcu)be2(Vb#1q9DHMm|4lNd( z(iXSkR@^nk-Q8QMn?9?+H1}GnsX`*UB%T{lW(a)YfX*z_q_(AE5Lb^{NJ5RM?EHs)pw;GhpDp(%L~Rp4vSGe{5b z24joQ3-Qg8s92FJ?IA7IY$4Am8nXDb$NaxYFJ=M!pcUOv$~*jTq%%a}R35eII@>l%|rxV6B;oA-f+d>otsTomIbmb;b(D>14xR8LLe;c0Md68xt@?g}%XS z5+Xw3C!F4|*Dzwx+90(LK9yfiL)9A-b?)0$sVD?U9KZ5yy5cou;i2N zcl|<0nNOkpp$=O=1?Grzi5YG4=(`YFYK;Yy&0DX8Lrgk=If3*|{KmfZ;|ETFg1?qI zk){r~{1w9`9A7J+Q8Ux!76OWJROmPlectW8pdTDclj}Z7nlfmO{F2I{yEK-X;g=Iq z)s_F`Tw8Mw|B#ZZ@qR9&IE2{$(QRl65G%76gTyDUzmtr^iWdf<5%Z@f==vv;qzruH zY^n2-+C`q)^;HH_{_yGCC+|m;f-G0;1Kq_)ADpmErN8JgU3{dZWx!}UwoY~Q5__gh z2;Y(ho73KYPWr}2>Ug$n6%-APyuTKCHm_+`zjQ+}|5gNx+nWWRX$QTIDg19j6uzY5^9rG%>Kw(xP925)xneZUGN86uVgXD98>qVE5Qs6d^ubjQ1abB~xYZtC zULU-9K?VZjg!l5kd_i*W`DT7UO3d1})3(thCYtuzH7wffSU2>dKwvXBn2-P8k>o;N zf?MoEa8uoiLSu`{;dzTHXSctI*Nvt@;5|QVskLNly?ZT67w8wXWgqH-^<-Cw#vg{W z#J|7dm^)&rk88_m6>D+JLpG$J3$Dj-eBRE1!FT8`&L?Vmjy%_+<7s^H&sOi=XSZ#} z!?yEewl9Eia(%64w(7h^OGEb~WWn|k5}@DD{Cry0!o0=%2)g)2@fFv<#w+?;8^Zft zXrWU?L_}Jp{-j(k^rsz191JFB3pF`J?N@dyU`6!$3|D#jX4Kj$jd=}{Jg=i__M;{@ z^AnHmsa-!{k$k$L-2^b^jYQ4Ck9nGlvm3b005W_d_+(S%87vSoN2&k)~yhPGLZUg<;mU=ZRy~ z$jCd9r%J+!&Nd=jp2nwL6Lq)K{eg%NWQqdKqc*c5uR=eO7GHZNrx| zs;3yu>Pn)-{d;0~{|$g9N};9$)hu5mQuLy&`$l&a~ddDC*#Mpc>XFx6dO&F2HD zlklHpg&p`EsV!BeLsMJ@TZM4d&ufT_`oGH_YR>cdMU*lW@MV9>-Xi5E0ZHNKqhMjH z->?u(b?Ke~zI+B8Y$CSpG;i4b=BdPoHX0L)Qhkba)zm41C*j*Tx6vwJ5~-vauc z-S2l{@{5XnMhT)p=HXZGV~>BgWGu+hb!_%g)4(H3Ih5-Bug(HjH{HYSNo0dkc8DGD zHLd$m5lP6qLKMPglDPmtdGA`Cb;Y&zoD99IK`P2ZE$icYXsPDCTY0!F{S7b6d;JQtrJA9)O~BC57C2k@ z7FDR7rpMAjl4#6clLDUG`~7gv0aOl}At5}=@@q$x1 zGj+Vecvhp{h%t)6I_v&^(8IN9qUfPCnQuVYDI7=I;aSDZlRRS8!F1AoGLk8hI;gec zN>vBM;VnGP$iAU!@}4NkN~fU$r^bC25fyR5H@2 zqB$UQObd% z5xT4Cd?+W1np%a^{^oPe*F)mYMuhnz4qLMrCxU*k&2Uf+;nmgSu84E z!9}f5J@}=wm57^r3|LTsAK*ESe*{jNN4M;7futVa<(~*ZRo|_4T~p^yRP@xgBWgk` zp2n@7i=t>SDLGkLS*s@FdeV6RJIx}btM*b${{LPr`a4~+Pc5B~Ig2F3c-{u+CA8ek z>!-e44AE#i5-zhDb&&oSFntMV2yjJINHSyc8Mu@eGlIW_<86?7pbqG#<(23E!D#vh z$u8rw@k^3^H(s4G`TLZ7AK5u(%vxA^`i#DOR?6B{SJx}*qvVG7Z z9HClo*GoT4|B=};Ev7+RdovVERb9NG%pNPGD4}Q9F~q~=)UKl~*9nguaTpJ|f<$QGLeT{!x%3x?^ADmCdSf~?Bo7y{eba8w1qOOo< z;C{dln+WzaUMc3j%=%V=$TJ8RAKSI!!e|!uz3DyATbtyrKs&XHOh?uZCN7CECqP$! zwVun!1++m;6@7cvx^Zjvp=5=A2fGs~FUA^8hL4$C)xPNYNAi&a zhs^dl9eW!R+^5jwe9~AA^(gt%4i7CpPWdB|QudXxK$gh-yWXU)Idt;KUK4roaYGWX zk@Pn`!ZzLC_M>ci>_6uZaLcp2kE|MYi>#Z#Nh?80D^Q!4sN7c5vVnaR)tb1~S1P*d zih=+Ha=-$;XIR2`??&xQ=1w&16E5dmH1II|DGwLDR#~b-`tm-CJlK7ZhYPDvoW2eG ziyoiZ?IS9x&(HaDO!n@6s!2h{%)(4Bhh}t2W>N3gx`&x1fcAGySx1a=rKL>mRbvWo zUEJ<+3YMUwUl;6h7FdDaK|Qn6US4iTK)K0saHiV&mg%i&U@G+nSp>ro9n5Kv*DfMP z)qtF>{B~wJn)t7ZRq;{n0572(v#lbM{?{QEs_Ev;Y2dGL=)Ttyop&QFY#XVHMUF-T ziArxiQG=!7G*62})mOhQe0Emu|TFKhW|C8b@&8MZ5)Ch?q!l|aZM zEtORGm~Qt6zs;RL!8i!n$A|>tN4EeKK?eLHI2&8WUssNy%gP_>#($XLYdlx#AUbm z5!$^K#X1XGd`4)0#Fkm^pi9Jm3nviy`DstI+2o7#57R}e<3n;dz3^D5X~|wsTE3$p zh)wzV?MGc};qz~b?pr_Vs5bHim%-M&1o^$e_G|ctTo7VSF?0G%SRCnE8Yx| zecHib$D;2=7kE^(z;NQ@pC!C-4CgvI?dP%W=Db{6ZMC6g%&s#XDo4#^cSewN;+SYA zPD!@ggP^p2tH>gv0T3rYjmRa<&ERvKT3hS8m(E+y@)z!b!F2iAkmUwk=Lhoh2Q}yG z3(M^s0oAQBQvTzW79w-^*VyK$Y0W62_#4Z8%?> zv;Ez;6t^Vhr8#%5h0&*C(D6N(E7%BGoesWsi{>(}3Rl~>$yfBl;CIQ(IwhE@{LuLs)^d;SZOIHFEiU;s`MpWj$`q=7H19&ibpuh z_P0*;Qy3_UqtCj<&<74xX(LZ^&%a(W8NaH!{uqaZ)~z8`hrIF)AgCc=yTtOSl7bdI zo&WCBr)e%T*+7^dA@06F_wV+1H64#{=2JZ+Qbn~zX!PE=oYxhnRjBsv9DATGpH1j)tK?F53M1;x>((xp`i998 z{V=y!n}atO+iauB&z8D!v>m4f@+t+PmTjEVOR{G!E^+|Dc>ma1$iR(ol#$8rFXb_Do(mjy({+ppv)=I#tX?c(9Rq9ZKWQLWtt(m(hv zYe;Y7c#%B80x36Ghu}nTRFCWhF7%hNl$mvip!BY#T!2dpy*bs0_L z)OJAh;&>tY%P+!3pTtg4AGQuka=>asxkMlJP#iHt2s$@{FrAjIOUfYQ9lTaYmie{| z)dQuf1t~Yq^Sp@0cJrdlQBTp^MN__pNb~mY=LcIX(vPpY@5da^5ua4PN1G+!t~Sc| z>7Of~^>m>$@n4t=Lwwp$7TQr8f&rNGM49;gzhx?H4L9e1z<@Dl9>Z&#dqjzPIk?fs z^$a03HcQyq@_DX0hc7d_^kMVTXGK6MvfoPh;$zL`e=jhSw%5M!$=YAij5e`?7Bg$< z;tD<9$cGMXM+gfUYL_rpCrvR=L>CnAZgqSXFrEC-*m=uuX7v1hwE6CC(HjI@Wa!>rGDYoC06 zY|!(i+3{~JZgXw^8QxEUXe!dUs-@=_x3!TIk~j{uJ9Y&Dja)>k+jc0Q?l#-&n!b1X zL0q>C`@k+DhN1kj3|JaA-7czb;}c?9dcv7g@*xthiIg#kubEh>@kn@x_-nr}X-QHZ z>`z&eQpy)j6B1(7IiPkNtR>D}IU!Tst9fYXx^8~9#;~&*0N~^Np<0URf&1p>s|~8# z_NFVeOIjUBEcb*j`PH7@w#fj|2hiqu+M-jG2;*O@MSu@K}<#Yv_M7I>ayDF7)br%_^NXEpbzEI`=+JiLk z?(i7%_0neAuAG2%PFAYP2X>e-IeP0GK5Kc;)rTX~iBg7svY-46FsrnOo&HyBb$3srz(dq0|YYg_LJvSO_*x@>%_xq)zDq9qDxF=vI01Br^U_n8P zR5j~CgFuva{*(G4-f+Q7^o&+5t!k8=S`k*1B~!6n6EZimT9UH-#d|jEUe#OeR&dH! z*{8;qJ}^t2%9GZu)V2G!MAFCV^oXRk&iagn3`|78xH0UHL1B@s;7;?KjPfulXG+hA zzSN*x$1g5zC-Jk_cK($0(bh!R)R_G99EQHR`U^^nwayf~oHf##S(%X$F@naeVXe>E zgnys~y*=_~UaV6kmLdXXP@O$Gi`O!-9QfaTHAEBrLrjzOaYB&9n}?$F`ee3Zt^$I( z;NkDt*(FL+aVxY250moQVaLgy7wt#Y{hWb5#6|%Rc(Yozm|PENHxN=n4(p5U@%pYd z>k9InzVMu{<`?6UW?uhlo^EKyqOup7x7A_|dfkST21n(mmtUdqRT=*ac(e!1Zid)( zFf4SEJr8DI3j_r}iHJZdi$My$ z-Cw4&U1sM{3191HM5{*!W4AKk+pk>7Zo+Am+!;OU0GP44TzD@P$EM}X{DdTD+deHr zdY(>L?+3k(O^{Zwb(N5AhBcS{a-+3Qr%#g)hx2wUuSs7RHVZDw7a@l(JAU8W&On!CUl@Ec>S2@n7t$Qrp|9@?Z4*2w+SvE{KioL@+_SIfLfwD%i<}mkyLGX;S zs3BszYS|xwHv-X%L7|lJZE!weijL@yF?B*Z1d2>t^XT@f;syp-^>r67u|WxeZknPS7)H^Y%dKM z=djjZ@o{YLY`od46^j7D<4Cm}|LAl}!v;`U7q>TMdJK};(0-y0c#Gh!>cj<=j18|8 z^#281Xd)kaj$!<@R2Fu;Pg0*0r|=-oX6A1FXAL9^H*ko5eg;u-#G^KGr~bOSN%PuR zZ+99{9`DJiZpU)9ocQYQPS(4r((A@PI;G#4SeyQJex`HTx&C*P)D(j#iEi2JkYMgZ z*JAg#B7ZEXn@1xbR4_0Uf=a7y=tR2-T&@J{@0J)t2y6)@)i#b!tvD{*k12&hDQUV=AY^&DQ;NFjn=l?tW4|7U0`acv*N{ z@Wc`5tQ3(tWe}@uS^Z~v%zIH|9p!Tu$Ddt$_i5BZG-kxK(7s7EryaUAbx`R+|3Q~J z!_1ptI|-`DHZyLzXFH;t1XZ{O&;(@I~|HZ*k!2HSylgLk$r2s9QW z+y6lQ9%m-Mvtt#Jpb&FFy3|g6ka#x9)j-(y=Rztyz|QasJDzyPte+T1m~#kcmJy>rO^qx{IX%534+^wtJ>PKOre83P+brO^Z+; ztZ7_Lb@r2c*(v$XUJ-BWEW?nAVdI;!-%EUEht9CIv6nxMba7fx zZv%(IhaF12G|G&>=EYVgyTe1&{hXZbue!S~{rsLzS(%twG)$Y6{(feUJh|u*kN;ff z+WMJrmb){PrJKg`<;`^eQ7He7mCe{Vq^oE92Y+T-L-6kzj9VnTA%oLJ3aO%kf)vf`9u(Cr zm-0;(_qjd6&W~B1JZ!I}rex|PGj7cut`9(t5Yx?ksg=$f>7N7(F^=qCw(Yxh?fRNu zpQW6Ucj;#BpLW1KR=z*K{VwZJd^D=s3fHTkqBinZisMBonK^%``f!6e=SroSZ_0)ic+xD(U^43-H zd%88uoOT=sZIxKt4##sZCbSL71k5>iB|G*qDR1+ls4E{Pjt_O|6sALh8a`1hayiVwzH+9!Gve5t5l7-KAV&Wi7Kf*Wb1`!$H@i95&$X72vn|P|0m$*kRx>c) z-!KX$D8}toond^>K2X63C*d><;}!iC9&h0&saj;9J+h3ZN~9l0(HTpUYzHuTw{>@h zb>XcW;78@bC*mM;7_FR9Nl77SXp)YI63Czr+pgPoUlPc2dFV_1>@dgtSaH+``@W0O zagONI)6!sp^RSp&vWyGcV}xCohViyZx8bLKkIn~IQwz6wiq&MVZMyjueY+KD*YJ;J z6-&LQxSg;{fv4o~LM`l$q{5 zP_Ky ztBs$!U%v2;mstD1D88KlhWa^v8MxGi9M4XxN3uO!D~zUPuAFtFE*QBg20y~j0@AJp zg@3mr%oEA$bWggc*aTIObKlMWWTkrXD!Shc-Tvle<+!4-KbI%IPUtCe$pF*d{zy_b z$W4c~jcBTnG#?MtxXsuly&ajPxvh`^zcT=pAMtFEJ77oSGKa8OJS{L=a0M(?Em+5@Ka8~N-)EOW$GzZuck<`UK}^lcWDBj>U>zYdr)Z_O)|nAWt_0hU2c~w zw_EqJ)t~3TzrZ?Az$@qN5V+Dkb{M$0(u-Rp@Wq04R_NzfWL#0r+$U7!e}lgg$wp`< zcEv@Fe4Azch2v;4BHs*p)ZX@cJuC$~hEd;L^HGOG?k(WeiRn_7(?Q9$GM`v1w7s{_rEA@PkBYVMeu*KiwB8drAm?d! zq1)lhMGGsI2vo-{hi@K(J50gUfY-vMLBX^U#F_)+eXFzz!Qd_qUI>qVOAoxPzwzV4dvSRAiVHWduQ(HrR%3D310)7J+0kYffIQndvQon`fUd)5G-Q|84Ek1~9Wew=aeNM6w!!a*xr+R7YX*q`*c zc?bGf$+F5r+`G>?$iHMF$@_;9vmIs*gvthGV9R*4=BD>}^5C^3KPj60v4xD`YsM;= z!cDC(Td?v+pwL2wlq7qRs^r^*%tw_PWUVjae;AtOE2v7{aRy>)csBdUT=CGP5JLm) z!lL4%5yCdWdzJf_WM)63ba?Y>fvU*u{YqIWwp#(O6Kkvvd z>m^dO*s>aaI86%pD#xk@jf(8;ZWrD|`HlhHY9AohQ$AjWD}}{v@1lI(UB~o`Qa@rS zfE*JiG9hA z1D$oRmg0RNpVCeY6A`pa%_Hw|JMO#$n|Q?Yet|Q-sIm~vlJfIw zO-§}$Rr}uqgq^m=i@vOAlSq9B6RO%um7&3)tzAAfyq*-qbBN}l!HCxMx9j<9A z)Y_|pB(*gOH~X5Yd-rIBf;Aiow`HK4Kc=V>w(^QTQkPIeGz$FQ)aJWUQu{n$`knWL zyM&0fm|?|nCY$cu1a`bpkLQyhslp)Ja-m?frjH)Tw9& zF;6onV0&;wTbbK%JSlDc59qAXJ?M4^0fO|WB9$YHj*X|QIZLZ#PKQXv zvv?h;jr{M;n#3Mhlr7~fS_2T^qr}TSpK!LTZG7A86WQvj zbQIHJ7v)FsIZ&0m3ntLoq#WfB)A#sy{*5fd6oPIqCvSsF>3k`C=sScMTs+@4cb74w z!hC}i_FS!tK`=V0?B?}yBiQEjW26DVlrpU;{gXL{#lHx4IU)B$4Znwjk`^dP{~Vzc z_CzVh!8>1el9kJ$mCG0yAy!1Nt!U1{?RZg#0Um7j*;T)*F`F`B4yh)(Z`nd*4Hjc+ z#34qYi{C>%42Y-l&HtTXktHTl2MMIVlFx90qE^C*mNh8U8N zX5>>gTm)Rkc>c;g-a_Tvn)P;L=PJj>Nl?MipA<7~cH<;oeim+S5vCxV@U5_e7CayD zVzi9a5)0R&rO79DSh?YiN={5X71sjk^Mj{O=6U}neylC~Q`0X*VASXVL$}F=f!cp3agC+x zgMmvhZT{Mc#aLz;GAE}HA4o!p^uAxfndOQ3TB zXFwiY=jwWC6wv03lnvt6kRRo|kpH{u_JKUlJoBTU2=3EQ@>z|QWI;BGwCqZ1K_xxx za8@EE?XdFT(V0mWwD?f1Pkhi*kbY_kp&sc>QE8-?HHj2&)=qFsUfh;P?{^C5S`a=+$Ct$lDq(9Si!9?0chQQMNaRS7uMf-1XYJn6J~K zlByaN=4vWqCh;S#QF*?m(Q;J#U8w(&JfhH0EcZJWl~3q9BeH1xq)^dqs1|?u*9p1z z0N-QOl3FY)hCykTcBYPa27vwNS7PvFfiEw=wt+O0NFbKKQPq#{fq~17gcgGK3*`7$ zXB=Bc_VyI%g4MetRvpTZ6usC3Tx?3ZrFjg@@#%$pJGtx|yw9=! z%3-anN5cjo?b+?EZ@CyH?u$_OkAa5<*y6H(V!lW_jb2vuqPvH-#R_!RbD|_NHT&o? zSA4;qnTk>@q{eBp63$eM2OrZf#Lnic&s?NWEfB+##K4s@w`I>ID>j1cY6UQ+!nE%x zt~&}BBX{)*>|#=?zXgbUPVz%3`L*%2f=Hbk{|s~*#XnPfw#`5jI@qK~@*9MC+Sodk zeIuWY9`(F;yy)90 zCEn?S?FLcLx_)-A`4DgjpLsp)<+azkTnHh23bdslp!|B887!h=;C7&>!1K|rs<`N^ zwe~h5hDjA*{GlRsj(P(;3+P=#c5O6{&T6`je9-(LOYK`J3MiWu6M*5zp*4 zv>99miKPr@R9t*6!o`WNU>_}q`wW1xXm8Jy>f0jCOFKj?`_81>yz;OEX95IkFgQEF zO+6UO`ZEy|Bp~_bCoMuq!h(_SScK#MHi(Ou5o?mZf zn~*5G#Ke_E?#-H@89zNTdunU0PHHj&|jaHrRCIHH&O=*vP%p!12}~WqFqR`=7`dOvs7uB5Nvh8UamwjaVf$96iq{{ z&H56TkUB%K)aqY3c^dABss2&??j)1{@I<={d$jK87a~UlcZaj(ytgn}hbMF6@n9k# ztYLzGC<>8zf4!1t_UF$}uk+1tXBF1a}PHua+sSEy4hBzFD zU2(SL8Y{vL8G4sy8D)oM9lv2g0h%3~#LYgif*$*!^=mR&e=$kb?;)0Vz|ob%s#qw-Kts8?1| zk-2=EhTXD8MDLh^IN-ElQnNqt-3M${B+{moSoOd-{F44J<)j!cuL3)>Ta^AyfX~Ii zT{V&DOtX+Mvxi@rN*CpHpqImQ6yd5GD)sVNHJr5GJk#HuZN(cqeeGL&mNz|-GnbPE zpIz&IE<3zsk5ifazPB)MzqlJFPg>Slj&u^KLijogk7;ld=RPF$Rd0leb!+M9uSKJ1R9|4~ZwPlq{bexCyH~zdqq|((`jMe)I zj?=m1=mH@kqw1%lY(Oy9UbepnooCr<0|a&i+|EO#>0fTL)f5QGF?^cIDTkJMpc;TZ zp1eArP9HRL%Ix(U$|fP_?N@b{mEnt6TA=s)3&;pq%>Q zgAHkixaX6F*-si0sKwk*4u#u}gRC5V$%g7w- zU8;;&@+>`RI@Skqqqi2e_omg_FWS~65KKa#6|p=9|VB4ZbK-1{%(1fzT?65+CD|V2<3dMltTLv2=v*$q%8Y10h~?aYBboM9(j;07#Jk1)iAtar=Uy(RHl2 zt1$jGj+~1|>zRZ)0tK6Xf*Ad15xlga;D2#-3|k(ds}6>2klVtR>m8X#T2sYUCsSVn zlvmgM26zT;!$h#L9LJ%v=S$vif``aWUoyb|Xqj8;p+YTm!Y*i_1HBvJafv3*&v-zDszM2t9V! z)LNVnn;%3H>kppr5?bcCyi-bFr|@qV*l>2H)q2Rjw&nBN+7k|+9qzKw94(#}NG9Hx z)JyiqSp-N-_Y_TpSf7MxIp|RP3dO7XVTTV3)$<-|#3>j^X?Qm_78*(#@EuAprPDsD z7b!C1=g_7ZkmoCrxtb}+*lL$qADnv$`yB8^ITzBVWz08Tx0*L`yQ^v}=z(%~y1@Yi zn!Qv_&=x$VR3Z0=_ss>)l=1D=VEiL(|L9(9g@o)wHF4-HA?mc+O_HO072QD!n(VXc zwM29T*h@T?G)dCGn&sOO(;RHSv-x}vViZjg=#Bn-buL=#w&__~UY6)L&6C>mJjQU} zR6a>NFAYr=wUep5MoyAELF*#!%1M88Si#d{0q87!CY9m0U#Jd))<&8!tUO!moo2;tK!l-N_+U+u0T zTF$m}G*!?MRM^^~nNshq3b#J8MF2ZX_&Yn$Jl~0RzJqJm$toEjAC$br9fQ%vpx7`x zyBPN^ytJ}hLa~!%Qx+p150%!f@mo)%i3}+}Rp#Gso}+giBt5kR5Wg#Si-{-F*P@U= z#e83r%EkEyzF8LZZGOjoO0^xJ_*oAwF!}uxdiMam>U3y1GEVrHDfEZLMs$LZ^+g!5F_z6ZqB7ukXr?IF&>XzGnuG$WnTLXNeP~CrHcWLZd^ql!fg1 zzfBWOWY0Ht*!L`m;?ry*kqN3mp*sCvNRcWMlIr zU%Sdb0eEbs&*BI&0bso9bHVCyB4@GfT?AJ}Fx2wdQdCs5l~dAmUVRere&Hr`Fe+g? zayy)UQ^x!o+r8qU$O#OL=ZYO&%r3s=O)D`Maygw|ThX7Z-Sjj&dUTq>5^lNo4HA6u z`@HUTRCTg?#o3W?-7fswH;6NYew9^-{q7y%_3~YSphC7E5Qkc55yRR_%=jW-N~`qd zoO-#d8cXo)P~;G`x1??#9sKbQVqGCEh=j6f)_3@OI*bZ-(fGz~{Ep}8ROqI~FVjqrM>t6S^2{H(EhPro?8b+OT#uuJUny;kc;WBjm#y)9#XGTQU~JiuB2O zOY*HfB>McbOudAq8@qe&FXAyi>tVUUf4rjo!YFd}@AH4b6wv>V zrCM@*u0v91xgH>h7(8k$hB-FQw2hCXvTFWH zzB{o;Dbc?>^@5M_CMyXwHE;Jz31xn>vG#{awqWUOO=}{8Hzbvv?O%uH8Me7CjjQI) zkS{a@2W;0cGiJI~LRY*I7lQ_ZlzZkAe*S*zmBqQrB0BbW?i*PPz=1Z+=?R9TTD$`1 z>EC;F1rneTUE%>cpP<5i_)*+ey{>{WKW$BUmX5U~?%WOp5_3l~CYW z^6(I*_@^wZ&vO|R?8dchKj(>`{*jx!8Wh%hWbBVSi7@e12!MsmHUQg z+D$JPDR(SdHTZw3yi0U?r+a`$$&*)bd=_P72+J}~V@@rF7P|SkXSaS+l2lR(AaAR z%bg5CVsS5OQH#rJPP|DGAK)+i7KS#Vu0U{PXZs{sN2LVf$mg7V~s^t>#UG-_js=;)xnaJB6FE8)kjNNMG$t(V~%x zKf~wmf>+$T`3+HlgHxiNc{<~l*;k=^v(kdk$EZSIFm>TWLy=Ea(~edpKHNkOGNt>_ znk_3YUw&Kwr7X*-&y65hkq<^w>1IR;Ej)9zCXQD)O!#3`>1*>+_ z#9A6#&{*$3WurgE*sK~WpQk(aSLg`5mk3#>FycKLzZ5!o;YAb|e7EJFuPlPan-30R z_uBsQKD0#`^s|0>{9|r`I=&1-PW_RC!{g^=PTY+90|+kC1Ybf~YueF=vV5oqsXh|5 z-V3X!lYu&3GdxV?WQnNXLQWE0D|rPK_hyUJevce1qr4f6ZxRngmn7TnGb zxYcF&3a>NKAE+B198suBoAYO1s`YuCsIHQ|;im}j^f=l|Jqu`#v7R4iTtomL z0p*QsDc7ERxX~uW%J#PWfm$0ZQ6SvC3HdWndX=QoN4@l~X#w}CE2xU(JE7GO#wwR#{6oh&=uE#E1*;fgRpA^`nbsfPVCKzm^gzZ>HdRN9o-w zVee12yWeikeH}yQTkT+z0O}~kWAth7tKGcHm}J+LK0n9q8xRrF14D$yaynfcUw)op zJ4O1eatP>$M~KuR+1i$)v7`_bP*qju&+%Aiw)AJzrZI1YP0gt7Zr% zs9gm>%5X?BL6Z{v++q&l=B&mX){PEO{EpjcS0?6lM#umMrR!4}-x)xgwnkmsRv-;} z5FnRR&A+>1P>aow%7ILE&}R1&Av5!{0KfcL&!Qsb{)kQGD#X&^y)Ex|ecIr4cLPwZ zcYi}kn7eqhD1|6!xQ|w8aOVlq9L2+Ui>R0W0|k1)%KgGgo}GBKYM2x1Kp?J`!sM98 z%t73vNG2n7zxPT#@2h-Ei`-}Lx4DM#>PhcQ$~91qgr5rf2|eVA${MCuD)cepGN!SU z2R$UUq%jW7`KmA_3#sRO>L68YTa+IK-V9Nthj$r5Ge@24sp0ot1Ip1f2y240L{fY{ zsy|2N;j9*V`VMKmYdxX~syt4(vJzXa?K_u13CTtb!JzT#uMbID%c>NADjh)^(fqb5 z2D{o?+!|u5I@Ld=e-17}^4RmnlQot69$;ShKqJHj2CAJ|HlN|vmiB9dIVsSCNN61F z$*L3=KD7n93>P_e0b|)$Snx2UHWEdgS5;AsU-Et&WA#(5p=JYX9PH0}F>VANNf! zXzF&Xi{mRs3y2NpWtFRMr7VVz8kF%w0Ko&_vqR zo^~>1t-Ux;TRTTDOrD(KfO&W3e&4g@lZs|eBz8s=)Tbhul%2Q!Wrb?F@x>)BCG}%P&MB7gOvX!`z-c;b>Q@`f-z<>CgC(lU z$y+z&QH|}jb(}MM{2Kd}C=*-VMknI}1_4<}06fJO5je7w{5Cp4RI5d!OfmmgR~7%$ zdEXq^>*$k)=3$Y|9q};*G0 z+SQt|-e!)4P2OZFW&*F}_*wXFwIGBIknLp>{M{TFGy%M4TX?P#aozpa#9+_x=YzpR zl;6bw$zf~l{{f!DqvJ2>|7~$3GN#DI{^h(pSvCnD*Y+iKO`RjOB17Grjh$PX=W|q6 zt-j`Ow~)XF(}sI6T{X@9#gx^YXmgXNfTXYa*9HGM0pkV8c*b5i806W|9tG z07J)Tn>#KrouQV~Mxb`ikkL{ZdvRG=t=Eu+blTJ`0Aye#z`Mitx=#Y1I_h|Z<7&R6 zNsn(E^6vEWD6VOP33(<;nR#BCFk5?sH+CIs5H1f%DB6SGQ0EzQc{4emKQ4~G9lK3< zR0R+3>`X##VUy`)kbRqu)*2rwd^g5jpQjw|wp_Vi-}%O$klM9K+`eFSv^_9?O><&B ze5VbEICvNvr8M6BL2c!n=GgZywwn^ibfCj?ZBB-DbkRwP%2AcQ)(1axnm}^8^-HB= znXluj6Z)d2(!}D|QTne22m1@0I-4T%wFaoB-naA_KF6l5ue(_4{Jyxel^T>6GS$`x z4fnedYSm7=Z3u~8Z(?LlF}73O=dm}6O!V`PKlcXNsLM3_GWO z9q7S4=T&8X5bsZ+ny+#}R1NjLjl?@&9K_ZdX4VXX(0z)LyRAIeOhMGUYanEz)mpfwLM@w7Ru2ec1@)fD zAarXOIlCqysaww}mw~TmMU!#F)$N)Z#NErJ*AMyk!MFylNxgW6!!onQ)idBN&7;Kx zn0IjMg8EYhvPmp(nRd{W^QW7$j(ek>EA?(XWvk!`uYNq()(zgulkp`L^npY?YwCFGqUnEiUDkSnU@; zz;LaY^T&f}(2I!2%j3)w24Tuo7Z3`wL6>Z-rR&p8rJf?ZAot3>&Hc*z?2iU1BkGc_p?yHcBDiDo~{76ZCRKv$RCcEQL zfl)qZ+0EOu)puwK9cWaR8qH3{(aR&?N5HwyuCyI;*0DDB7LP{Cy8pC6uLm%gN9ocZ(!$qWt@#r!J0t{Uv$xI>!23rk&4+NCVuXTk4aVxEj z)TKrw%%1nU+b(l2g`94RUf{FnUs|;p9PDNTK?1VXFFkwe^IJED*HA3Bll?8Wmm)04 zwteAx(bl)FT8fwfWqTA-_v0b(Z5{{f%YFhR@A#M3yz;}?DRmPu#8Y5@o{m&08jMSm z?h@^Vx7U|Q^6S!>o&gWL(WWlV)3L)WKVTY{VjgA-{(0-$=f}Nd5o2q*>f0b!XCI(@-~P} zu)l2-xt!q8^EuVb%(S%sfh%~-WnZ>SbddBhhfEF`S(?ET;7&;gwgr5MHM$!z6O$1l z;pxD5<=W0yGlaaJ?l0yuOiqF;j<#k`>;(AbnrD#|H>HvWm}4jz>?97Qz7px#8n(9C znN^KgmOR(%n=KA<0iCu^gJWNkql@=r72za`6vL=;(V9x`z0bx(#HtwD(>pL`W@f#E zN|IZx37b3A0sE^#7O4q3_R z!3n#-qT`b^^x*dIxSK8A4~kYFx-=t!w2$GCpIkEYxXz6V@`v5aeJVw$=Z|sqbW|u; zd@5QzaQ0~qvz38`hu&qcP_ovm&2qQhYN3rL8rvSeN`Y`5J?{eQbpNh5>{G<}(@P-x&00R5fk)e4MwdfYd`w^34@H zbDXAw&Pt)`f{(%UEKAboo#ICkxN8d!0-njb-*^_qkJX+zH#1CPFa){6=kQ=^5smBI z{4{sulJiZgrETtfFA6sh_&HXa6RiOj7?J-aYXEpu_%7)6`;-J;Fn!cep6>$f5YRo_ z#Ege&cQS@2Z%=h zIw6qV0MMkol2X9aY0G%H#i&JLdci8YQL2Sh5_9#x9JC5=^F250-gssu$tUi;QFIOw ztt#7@y(GK4YRf2}teMo~0->9v(=r-KOjcbtosd$ijkUvnwUx6{jYR zkB9tOs9<&N!mX9!GUEJ3%NUJ~O-srFg|yei*qFW=j!6iT^AnPjqPp+E=b||GD;2My zs?9@Dpp3er@f#*>3rbjG-}t89}Ls z^cE2r(}f5UsE|#55~kpdUTRnqP3^4k1vDyzSbn*M{hI6QnqJA?{P5!`CRB-Ur{VTJ z4iim#qE19!)DF#20Sr_`1jO*!dsPXstM-hRFLFFCA3yp&`>}Gqb4X+Uy2zq+=_;Dc zpEQcdTt5&+n|zb)jG@BKkPjyRUi*U<04YLR9-6@NN<^Ilncgv#cyrmKYw!HB>aTm6 zyA{xfErDY|y+Tln!@qVDa*oK~XL$F~ffM>0;=kSm1eUF91+VKxhhXd{mIogtw;5$LRsE3HzoYhq0 zOZTShPBqa1y= zfZsKmoVUI{I1C;)s*Bo+25}rYGLS{X!$=6u;+Sk4*(GPSmWlR9R`DjYQKEBI#jU&{v z6Z3*)L7duP&C6AZ%+KVtcPa}azXONudCrz;l-GbHOW%f#P@$5ri)zeTFbF=Li;OgQ z9ti2b5sx958oW828CgU&9&VG|gho5qWg_VHhUw`J2iqs03*x^v?vbFxIf~y4e}0ay zJ{bz;{Jou#=R8a1ipNln2L?lLPU>EGB0_ZP_3W4?7gVu7t8n%Oq%JtppHIKmug4W4 zosSQ2Z5S-HpD(J8#@~DRiZTtkPEHU{6dNru37N21S+gE9-;<*a#POZAVu^`~sg?z^ zApF~nhlQLEr^QtrZEiVX#!$JJvohu!q`F1T`<|Jsj=$D+-Y%^{Rc+`P^T7kUsUyMN zM1n`e0v?~*Uy^b*cin*i<8-e3Wdnh@^YT(*B!OhHlS z9bB*HUAx|ftu;MA{rBS?^|B8GF=M?|UFBN51qIZR$!innj{VVty@Li!drvO9I7wxb zn}mY%+waEoX~Xw)ZJ;(eZsO=8ohcY>GF)C*mkY@a{;&y)qBGwZ^bCyyQ$}ncs9s}OACd|4Bw}Op^|LsM*FKrk(dr7) zi2%TayEr}!LTK1*cR5ORzTXJ=R(1KSiFU0S^-BjSj}C9{-g!1Y=L;)J8osAi6;FZl zNdyLuY-Z1Fx8Uo;UglOwX@#_#`6%LMtmZ8h0|OSo$>2cazh|Y=+<2euUDWDA0BLes zQ#BYmGSy4gdZitZmTP1H-TSO^yWMAWz3bNl1Fpa&dWFZEWiBDrZ_LPst zOhJ5&(sdzoXnU0wDcwVBxX)*hV#Lel&)Co`ktRqAu5HeFqln};`_4UQ+AcJjgljuY zdqp|gGA0qADTtncT_{5-rsLI>c$gs|K11;*FF2QshXn7`^O)*u8o$`)jWbTHk4~#I z2Xn{0wzXyh%0%#x`%?XD?TP4^T)}dVEBtraNLmnGL zTs0UA{$vhO1pf9-t4?)!nqfqudc9#eFHQQ@Z~ILJEH>NF+DhBHG<4>^#F+68hW=e9 zPDPp+hG3|q(OZP4Jr|jTo3Mk_;ki^N7j5#P#lMRlSQfI)y)MV*#FT#N$%WQ>)pPrsG9dIT8l3yp}TIe;N;Wayc-Xip>(vO9%>vJl_fALr7M_;-` zraP*D$6dmf)5Zk+*?=!;I}whHK$jjJ8BZ3 z@@E$y0{dDwfu8<_8HYln180e}bR6~C7wp}?^vfv}g=8F+CZ$|INm!Wog`~$iPJN${ zI-XAK67zq$`8eOq{Ao`UhF^xLj_$#S|Np8TC78>24*rlX8%P{b#b z;kICC`6E#AsNO(kYLf`z=@=t!!~gUVM+7df6r#1^;BG%%eAl&QvuYXB^>;RJNWFWl z@?V0qXT2+++F?f;kPx3&WE7;%R@sie);`J}tqy=3QC8i7&`!Mx?RIu3;Iy}07;|tl zHKm3_CCppwW{aHdl*$zJo)+ZQ9Q5W}aGRDsZ9Zatew^!2g^~z(6dCPYC?Qy~@Hqob zXB+?WRhI)j$!wKLXP=0Wg6MQ}5Q-bs*C@^jQ2Gk%KRR4)57B!K5WBAT6WJ--1Mr(P zAZ|K5?)~*YGZF6};^Xfbk3-;t+XyK-7qnRM;{NHJxAwT>o)`?ttyV!$UtzMCHByBH zNjgEA){OMb<*fT)^0c2EW}6j!XSIf|9d8P?8Vc6NcJtnmI<(z)BQG%tBn|?ekn`U% zEH>8=CJaFY&r85Y=jynp$!0VD(=0v6aZF$i=|sc!^+@mHMomwH?9WhPn*V?N%C!P# z?N@03FwzWp1iVhPr}s;1Wq(%(mN$h*7wbKfOtbpZu{=@hsZCs?lHP-D?-LV)Pum`| zMdX-s6Yqs(FQt(*tMo;z>EO1SC{dXhApY7b2QqLbI3iFr6_qT=6fc3u;f-LIAet>t z(3pv(`Av>h!zp-gbj$uaPuuB|Igp_SQGwoSn;Uk@;caHZVp+l#2F>`5sNj||`;4Gm zMycDWV!{myUm{g_*72Tbt3)EJTbP=d6i{b zOEZ%dcW3=k8;`qz8F`Pi%y$ttFSg-(sgawR5YxGAnqU0#RV{B;N@nxUu zkw5QF5FfHcF5?aD_OrCsc}3-7@x*c7iHO^TVV_#g>ZijGms}#AZ)A#m^_Kt6vX?a6 zwD*9ejMY7OE(TfO|C;9D_ASrxCxROMwD@JUM+7=cn;?QWP``iA1$fw?KS%;@nExh|Moz%pm2=Ed#^YdWqGT;pJ~W77@ofs6vU=*m*k3UkD_ z&L;En>jN@pHChw@0&Wp<{Q9WhdFvGxSS^#E8hsmiIPe zWV13$mnz6@?>Ki>`uI>6MBR}M)JZbuD)OKa7`biKU~_$cRatWL{!Ox3%jl%=L-GPO zCemQVHaZH$eu0nKbmx3KyPt>9QO#uI!fdtg?y5c62thL9B)`?L$}769?Fp?P(B5-J zKON1LciUAqy=A~XLKG~eraI<%@gK48IfK5foC~>Ib%W(zfe=W`l%7LJ-S?+_V>NA0 zt3zJHUir^msXoimcS=e1F*U3PD}7sVhLQ6I2ky->3aeDTFnOOl3g+MGUrXAp3XiQ0 zN|1U7`mXqP;7tA{+*-L?wF;^?+XC$SJBe!2uag4b<;`#JeW3xz$Ggd|mP}`Z-VYQG z9j!FxRxol(=lt!rhovb%@kZ2`iB{ZkgRI2_z1IcwkLvya;(&LD-f4rsL&uKupq+#d zw>sZaitY=w(eamLb+Q11yD!L#-ffuD!q(=DCw8;K_x?4`lQH6Acm+uOaGnX{6z<6%hXpF}gcy)tA!GDtq1-ckxYNwTNa0y9+ne^(vCN5+^gwM$|Z>neY z)}|OWYY{pczRE3~YYRQzZ&?CdGO(|GAI^NM`){1wrrYKt$i6{{Ms^$e>O?yL4^vf3 zJP38k0Wy^wPiSf~@^!F4q`oLO0eI19DqkHGe+n|w^k{jV%z4&2O6P^k)2UPhKl$+K z8UbAo4&95enqBr_Z+tE<@EE@{A==7#1ZYke>>m_QPmbu^=4FvS(p_{bkDn{8-}-}M z2&^*}<{|f{k9r6(=uO)6-fY+nEDS&NQq${Rh3e2>P^BK(faiUC6LBzrr|KYiCG97M zRQ<>flBnIS&DVd&+;;vI+gjbvJf#k~c9iV(haMC{6lFQWT?-eVm{|Uvhcl51e9_66 z=4p=RvF))jMBsN#X4XCDO%Aesxvghr3yYfr4_;h(b?^!{bhwMZ&*TU^Imfm*%)# zO)=eX|5E%BuBY=_Gl09c-`;H%KSxxFu9-05z~`OVuW$QgUWXv@K$#J}$*sGGy=L!D zduoQJWBY0NR&qhXCM@DLO#zR@?GYz3omHy;EmMY3JJ4ATe%Ze$D#=Mi)+wmz#JL%q z^?MPI>88R<|8D>8FqY&2hD72g=Kc9^c~uB)4uwsy>3Blun&1WFi6FK*4&ve&Y*rIqjZ-`#Bq zp)bA#X~Jw?YP;BI<5Ivjtct^o(X}vkl4%{5Tns;&AQU_P^#Lt6(e&@05Z`^~LrUg- zIr!!?Syfj2$EIN|8iPVyJ-dI|_pEJ+36>qOZD@O+)Tx@!HHn{M0Jm(TAQu+wH3-2R zu|aulT~<~nV06nj82p<({PunF-)*> z)fck?TK=m37B|5*r;Bx^nk9{Nsl2*Go{0Uslm8J6StJC&lHY|2P(A zeKHRFF@1nID8#@>P7S@CrDYrQ=Dg3;6$#?=58nyr+q8qrQ0odgnNhQ&;pc@0Vx4n5 zEMxs+y_}B+Hgs6fKULFY$lE!c{Rzy)XstGY<(jRHk!0yP=_~dQ{*G zTWZ3uI5!pT_Tl__=5Qe8#_2QYTNsfqMSxkLWHLf37diDA)i=6vJ4Wf!Uh1d*pdYH1 zzuV4Bl-tu46K&~*Ggz`t|Vy>eHE!_#&yev*or>3tT2f0K+Ug1 zLw+co$Y1h7g;ER*d(_@vkYCxY(EzfbL&H{ke{sM~m2z>TijDh#5hiU#{2a;8Pe5;W zM$&Zu;J(HBQBQD9vb;8d{7shNzR2JdGV(0=;#6YIXy@?8AfX|dfXXEq(OPLh|v+;ysa}RW#+4yoA zJ%%BQ(IpjC;ahe2?{)rsQUNp*$eS526hsmAD+1+0WtYd9WWlvtl_~riSsLJhvz4d+=#f!HAS1h~woG;|#;h=Ii z5$6MwJ2((B`D#~byd7|pjocF6O6V4ujp6TQZFAlE*4r=X4r05SgDdmtl4)ZL5Im=XzZ z(mK6)_Q}fX4G3+BNuyX0??xD8bJOv0%l*Y#)IzF+P7;-N%(%U~J9KgJTvYaUWO~OT zP1UFlXXb-x)kZ64zZ_O(5~a)%;U*AO{L0wE1mshSw`v#S>M0o**nG8S=LqXdzdbK3 z@ZfV;;-d*<33==$lC3CF<2>c-HsR()%)na67BkG+h2=C;e|%CFPt?(*@!biJcu(~q zR-M;oMNF@$+a<(oCvjz1qAQA5JY7O&k+uvmJmJ!~^ra(nDUXSHIJ2W5QE@}wn?Mv*EG@oLbZGa!1XnSoLE>IuN1JM7$_t-Xn)#o-m>NI)wv;F(7{dY)pWwHHdss;RL z5w($J3$JIa7Y^3RH`?nO96TyqGb`497&nEf<*$(vnxNn2Aq z`LyM+lErK;qKpYs7pgp#r6ZfYE#bMDv)t1pGL%_|hP=>x9MW*R<^8EbJ~;skBs7vG zL;)o({m=by*MG`G#)(x8KRP2Y(rSn351|(UZPAblq=BuAg3gm6QH7uH^t`kJ@62#> zz9-oc{^_WxGk`RK>Wgc02s!r3x`*GA<|H8uoVd_q$f>AMeP9$5mwx|{emPwO(#BTo3|D3XJY{%*x+@HHhhjjvXMDy?MR>{s^Pt-XGy$?(Cd^ll|69S+W#Lae#o^J(l1J`D z>}^%UpQ$7@Pw%n7<0HYztEmNi?;zP=g%uK=OHr>(BXiDJOg**u2`*ei04}p0O<}}j zQ(H6HA-RIdwW}hl!k}!(3{F&&%DDD`e&fizuM=;1E+pt&$%lIPcvI5ggld_ ze!W5N#dfFfi&x;=!TTcm)@LFN<!?^joB`6#+X@1YM#^%6wI(6;G$1sfDgJKFS5M<(xCG0fp+;%!yR7rPZ?6X6 z!+Ryxm!d6TT?xNGtV>MF@P;?I%nqRd%)5C~EltN#&OCh-7^Nqh(`4#C_Vspr_p!-D z#mP47wGc4&7Yhy8Svy+Mje5=Z#Kao_U=Ad$zsMc|hX85&XSU^RX=ksltlEXtDs+2x zAxzO}y>NLO9?+_F;}qYBpQQW7n{Y0c-e(@W%_|nOtq41A`U_N=`wVank{u`@XW3<85Oc2sy&)RE(#Ja6 z*~=MApk_-8Z4+XPkyV1ucJtr5O)5k0FM=s$@G_~ZWiOm#dtbul-CY6;7Uw6c7o6+3 zy!p$eM2;`tb$u9SI9$InktB`y*he#0r|nudaeD95M9N{x+_mdZZZZ@mT%jufWU|ay zyed4VpXfeB5a+g+SP+EIrAh$QrQjSKU00`CMx&6O=5<9S`cW(C%aVdC^pV<_fH?sj zbx@`6joRjd51t(FiIda8td2&<26(_eyS)OJMc|3{E%ZBmmmrnG#kuA5&d{B*djI*R zgY~>}C@O5?ceVb;G(Sk8i$rf6o$S}R<~$pP-9T~ z+iTn1wL=K5HoLG#flkZdu$`afr-P51=b@o#WW*ta?qPq?RI zRsR1QVs`G{tgSDxkX8W)XV;eOfI{Iaa`H$76F`DFo|GvUU|V&2vKhhK>fMU|4XpRZ zSG`w7^vPRQ=-s4@+wMVOx%>zU0WY?1+lvdQMKg;M4vM~o7@Mj}Qch!gy#XdCfd&cb zqp2yw1)3QD2`bIC;On!aw)2b%Ej@jWA!1>r2qagx9;3h;Y?GPARWJxRRE%I}pI2xof%{JdF7^yaE$+cd%VrJc?fpi&DS z#IG`pQi^C7o-8fXusL}(-q~L_(v_c1s~ird#XKhm*=KvkWPlA1VZghwwu3{LWTjW? z#-`38zDL5!jK0XHsricVLDJYrZ{+Ob%-?G-_8$y?23w)92WJHT7!y%wv_QlibteLn zS_GzlbRwAgeCm2pHx#y=&-FKpv?B@Q1Ikdihv}bFI$ALu@zk>O-kv|S;tSTIM`!SY z1RUt)H5ACbe^Z$HG{_>l3medhE!y3E%ZLh|!n!)dRwe7034kD#9XlsM483fuyF z2bOAUg))*3?TWqPQ@Gi_d3h;83(RFxjaf;bM0|AV(TI~n1a(A0n;kA*0Kp7;g9Mxh zVo_A@9&b9g!vZD*)?i5Mf$}~Sjy+t%i4y7icZ^;6AiTI7NF=Udqf=(Rh7mFM3+6!8 z?e8|rknL*5eMpR^Vbq*`pl{GRHA$MwD+%*&Jhd1nUxJU8hIU*Sgv&PZ&#_qynP z{$%fkt=;J@pKY7!4^58g`X+IRsw`)C0erj0VOgwIx|v^+A1z_d0Z7HBj6isEFJFZ4 z)S*RZf3^+1c^EuJMuT2_nXaIxmRoj+jcwiA?_64TS*A$!4WQgYrczTyRiybWtxAkR z2FPBA_%`aUmYRgNO~7@~V|Zw|Ti3H|OH)lH+Jv3jrl{ClHByAZab=QyMlmLUce`80 zel`Xh2}0tPb<-i>_Ih{Mauz(dM*p}g40c=@2@88&Yc+E zFW)qD80;qNX_7@@tRI5`Z){IxMf)PsN&0zGT7nd5>uWpC)Te`kgT_0ca9$Bbi28Zs zL->nx5yEt?AP5eqQPjbs}F0j$Nq-A})SZ{FMh_dz%RX&ieirk#70OUF@M1OM-ZGVP|DBbhhXVZZVNYm7Z zTeaMRbx&ZqVs+)%ZHU!Pi&^n0me%&|#NYCyA&BNNH9ci_&mqgGG4+ftI9}Y`{gPM4 zjeVTg%^-mH(uKbzN)1XVy!+fBr|Txb{9XhD8yB9Gqqigll-r z@6UTCG0T>;v#Hl{6gzk+tb=bg)StFO(_2pN>R^X_x@l$;=Yw|_vGsJHp|d0sR+F4F z8E!!7)7K`hi;Hrp-@o_SX)z;mB=%5HNT(GLTibs&U=ksR&(uhId%E_;g+z7whX)l&_d6Qb)KM)herr8PFt(kQ@9JHT0S6FZcg?QKWr^*bOcGcT?R7UpEO z$WJQC4egV%k8Y-&kJ^dB-4IPD;fIcn;B$HiH450?zxYsPF)*wI|NfQ|8D4{=lEJK} z_pO)LrbH0Q;|KU#n0?y$gJNuYLWDJeXU%Vp391eXUgu#k55nZ#cZY|E3aYw6Oj;2N z+KR!$!}L_*CFSLD-L#F_=8|?QsAZyRR(A1*oKh39V(uX6BI#^n`TpxruW`|0xZ1k` zgXD2@@A{@hd(NM4XgEh{!~4g~wdC;o=_!jpP^H<3x^N?ClpvGd8Tzj!{0=3~qxBZ(OZ*ysr{0#L~pR=eBX5PC2ZYmSA+I3MVuQ{-Sv87Bg2Dq5?|~;tT7gKCa)#t)Q0cT;k-OKOX%7%Bh@D{kbR4scW*#y z2z}zm^yxT>gyd0eUiHn*Y1$7(PcJRjUYvX^r&}_Wh$hqU+}w&kq2VL!pxDRELjgMT zmXDpV@sjnYc7{`=pZDP~n|l759ok*V9fqCBtJs#7`G9FwCngh)42# z#(*z$@v#ZI-HdQZ^~*f}s0<5T)I_6Bj%J@wWdhaLIg(k1CDSBENKs1?I{a~*`Hvrf_trVnPJ z!f9BQMg|uibHPMsvtdWB0HcZ&9>)Tl-vSikk)6)m%ipyLrk38V(zHH}@c}je&Ixxm z0Ln;UVt*pnejWg?eT|H=GBwiL5Ekub8~GkQ+qDDhc=?z!o<+yrf2w=Y{J*7>9VKAxauS3HWxXEz)+eaD~SV_u$^v2B>lKZSiw{Uxa?w1?Rb8*W!?f^-6g z{f77JYr|w|m>s#+MG@j-QO5Ng?x*7<2ze%1GIoMtBAtQMmdm?4p?f`$(;&7eWmAm{ z#Rb(;{pKECW{|9v+QE=j2+_;qZMTAiTsKUv!-RmN0Eq70U-xr@b5p0}%d`^IvN)T~ zOO6{8BKek6tb1;+Q2iZEPWN$d3_2^ZF9>>-X!;9DA64zjy6fXTifLSSukB%YG?+m? z@-!e{b?z|a636l47YJ?m=Rv>ne6rE!iub?>F`GKYzqOSgFeOWk1^=G5jDM-Mm0mU| zTv51?usSj?c}_2H;QXX^J2p*}IdGeB5Aky6QyQo+YLJ;5;*t+l)71@@Bj&L0CF`kr zl_zyjY=GI2t}`b3h4+P*D`{uzC%3Bp7<%c3!z4ZG)o)N!H)v8V_lu5YkMpoVvtCVP zuu@KRGC7E;b&C8GO_AEvK^-RuFWFgfuEskf&F#E+4xsCOk^U$N15+8({f7uL8wQ_U zlJ*uvCldv$7-IQ8NFXV>x`dc9=E>b=!U7{&u8(zs=eW6Ph9aKC%1yi$LB7!XXgq%B z#9X5pmYK(qZj$%O?Nj@-^0LQ>%`B!eF!C;3-+O#Ks@$qm)BPeAR6pN4?%w$w27G$I zWj~mW9enwl<9LR$g{z#c^MCT8{=IKhliI2oTZia>^FP3sR9mQ^_v8AZRYh0C>k}!7 z&o;)g_qc%D;ZL*kUu)3WP`g{gYvYQ!J&{bG7fNg~4GTJ5kK2y>?Uy+~WcH!Ba=mPx zkzw0A(g+Rg2^A$*uQ7)qdAbwoT?z1)JyNl-)O$uZ_fUz&n!fmSYz`+-TwbpGzH8@) z_IbowqW-PgaMqgz=jpoMV< z>j{_l`@8<5WNPD zG^V!8tSgb@Epr1pS~7fT!&|%2;_jt2W&PDlLTiTPZ=Vkhv~sFIOH>tOXPuA!ywpn9g#dz>DbbnQQNVs(;Bg9)eCcWlFy3ScZV>!O1Oq6?+eJY(TU_&7hAXqA4t=@a4A>e#4>cEx&+nb zEnNt%HMoD@K4dG3#1#zJH(((lv;<0e++Hr4R1W*&6U{eV;j`PU6E%^kT-FvW@a}17 zh$b`gmH&Yf`m!F-xYz!4-Yvtjapt-f)l=}5ZIkH#DbfIc6JxYe;s1UcumoaB0OS#| zSD1IPaR#eZYb}4LDzz(uWXb|5Fs7%K4R$W65FDGpR;Tl+(&8FYVc}bsY`T?rYvV6S zzuQy%hKC*GYYo3~9UW*t{!DSEglhl3?aLO0Ps)6n7BXS$aanu}%GjSxShMsOw6q~R z$)EWZEM-|dwV{f2qscGw1vyzS&fzCD{Q0r$#Wuzlr{v<&}pe6%~y zprkX|%t>;sPh&T15uF=p-;vOltO~cMFbBG&#Eh8h_NiEoO^_R3w6F#kFCzSRRZ(YH zcg@GcLpuDwH=-6WqC5?~6G$OIev*h`_UWQ;8Pl2xQHofuSc{Z7xxWOxQGsaGAIO`{ z{j{bNulbc7J$I=^84kwmDK{~@S|}RV(I)59GPSxok!;rCX&1$e0cI*|1e%sso6vrP zm2n$o$;HI@_~66TkJ7_EMa8Z;tE6JA+n>{~2WlSqNA-4klO1REM`kgl>=Nnb=wA+?huBF?lixtw9*}S&|%kPhO7TM$IP_;w`n;Z zt{8KqJZr2jPi5dw6+I9;)Jx1VNEyiT#@_mC|C~KFqJIDu5X49-kNAyLXI?tq!1N?- zw3z#~XY8|#gMi2N=MJBj?M0bt!~fey{!Q-YIq+ek|8GncI^*`|8fd)eifJpu zH-81;+#A}`)h9v-=zY)}+KDyhH78&q=HAOIGuJiIx>cEj{ZQF#09X1OCdhnydoO?3 z!Lhe&9~A?K27ix>j_l6wFuQN$e|BV4D~RP7r+}d}4VyJqCf9<`(>#!dvo(_}OPI|M zm$tfCiI=vf9TU|7Bm2doH$H}*$;>sbAs&%l*cP=VIOL(J-PtPk?Mho<<;Y4sBk47ll% zZxmr}0w!>M^~cX?eIRe^W6~N0o4+UWp>u-e_SHyy`6t#+mw~|p=|W4%Zn~~P^~^HA zSBC!ExT(RYyu4p@ScC>#K8>cONNOg)6`5`IFg^_g(&e|zn5w(_dS^G z;)u?XSHQmPWvKeD_$3WX^{P9{aeg8S)W=X?heA~{VF+TfBulF*6a!hY>ylfjNN98_ z9MJkt(1lsjpi90?=BY~zN5B7o2Fqr4`nL7{@vB!|Z`kDeXE49}xqG^#qfLPCQAiQ} z^IJ0CpW9n;N9=T6bPTJZDl$Sn@th-URvV_HdNsHzDmXRYhE+HH-#D;?@P+t^fRIt- z7WzpfR^d(Wgi^46hr+wq)TH2=VOmp`qE5UkX$5kq{3qhR8RGLEBq1)FatYdF#hYSF zqmZe27GQgb593{Y=d7D>BSt3J&Us={l2%YP66wn2(qfJG&8ykXSB7%7nt{?vP3co2 zbG1OZWo8N9yt=v{PXv8cGb<`p-Gh4dPy|cIN+{I`cUD0?8u3*PoBQU6G^gGVY5e6x zav7`dB)$;`cLjLRA!}iGEyyTi)GLfk;{RoywQiC9YVbtci#WVf)aU%@rA`hiln5JB z=H(&LJgXVUD;J%p!Jdw{tqttq>RrsX+PqnjZ}Pvms9;m9e~!SgGU30V)8rrbMBuVI zv;Hr@@BiKa0YHWMfA0gF$lK~L^YAa2p@&0izHOu&f?nwP`F#-2R(uZIx6ChnfcdqA z=;Er>CqTy6nPRNz9P@gALBfP~xfSDTcT~BXSWa{a>!=po<(r02lg5tjc&R1(eW~}E z>6^5pFJqKI_8+EnrsJ@a?3mX^>_nTD{(4C66xbYfU}(sV`9c)tt(E?x2jS%Rfh}9G zS&4Uil#DqY-FM9U_cQNbm(Ot5>l(~9o)QIrguqd3j*8HN{Aij9;%Z_P)IJdz_%>}% zj$BMD+x9j0of*tb65QKfziItic{65Nc6iVxeE4DNz510k5+%{ju}fB zk)NJ>dmK%CGcKU%WNdbZI$`rSeSAcGX=Q(y;?$FLf{8QLZ4DnqG4E)Cw?-Pm?zn?= ze6?cdsiOj^Y(>6M?J`#MAB(|wU7VOQ>bAqw)j1E24D~~e;PfYb-1h zpQFxsjJDW>l`o5f4x6M)`@HzXXW0DkHTFf-BJTKfM9dGOR$%Nh1!EC=vOBjANmk?a zqdQfMB5Zz2{eGeUA5&))76sgGeQ9aw1`$v~Ku}<42}$W5N=oVO7^IP|p}V`gLl_vk zW9aVg{KogZ=Q-aMcXPorv;TYVwf1jW*7Z_0v|qb5vCr5tWOX4YrCusD|@q(nfP@U_Nf=vt;6nOb8^|?s`w8!6rc=dudjuz3nDuHTN(VAH!k`v9@l9vZJ%3g^q1Sc zECx`I*_-%Xj&)Mp98UUq9U>NZ%1fr+sPds)*Q-%#qX)I+oXe#e+a1skShOUrH?#J; zw3tnQ$Yg!3CG!ec1;Nayzz}BD_PG&G3%z4WV?4hR%M+H1NF%U*;Z{9-retW@d8erM zO8=XXbLj&)oKoi#AY9(J$e=Zsrc(6LfpNa!p6&>mEmw?|w%`^;coG0p!nws*Lq8Uc zyv_rdTDnkv%8j%?h*kN@kZL%jrQ@qck&E5og*-Q!uX4kyk`l;_BtEz@*KBxX@ueGP zZSEz<&?>xkFdiIV(FF-{Qq$P!yk26^tas<(wjL32b0b=)AMR`%f8sC`f6te{g|G}a zBAVDD%S7$6Nwi?$!U+Spa_LE>h50r*xF^zAd>28r!zfDzc76mPu5vH~<((`FMMnnP z&KEm7>H}A4-k{5G_T!1*qxz8J%1ajdl5@d$E^#3}?j-N#F&y8OLtWtP7PgsH`@qWYB623B!%JLT6>l=5~ z5<6?N;8hO#4~9((6>3U7od?OL$=|5f`ftQKmAnl&b=2?Cd8}BNfpQaW*RbnVXrP~y z?NIN=s7{Py2s%pExeh3Mp3dWH){lqF%)UZSO;VPRklk}9w0?SxqTMb!b3a;T&|9F{ zXp9ZgjPcXuB`RjS9yQlPgxO_6N&H7~8&h!rX%qa+Ur<=q&VOY&q~L!ipC#}^yH-6e zT$K^itHK0>3feS^JGiTuE&qzTwp~q^c@GMLNkk_Ni-N=l3G}>m{p*Q}^urnAy3mfI_}8Gy2Fl_bf*ZU$IliHCTN{MScR=C#JR8;X5&y1nE3;V>~-0Lbc( zEQTV}*k0wLI?B@mFd~d2&vPd%c0oto%6ZJz49)N+E!4J-ipnvBPhz@@ZOMJCt=7Y4 z{Jz=jf4nXK(?Vo{e-QqE)gTMOKg93}F1A?f1tny7P$~#LvbUZuI(nXWY2U8bM4pa6 z*ckL(D69@h9z()N(mTtkQt+@Q?#171<$ZH~s3S3kb)3cdpS0gos+ph!JGe94uG-(` z(aN}4NwdpN_Yt47(A(@fmj}d`_sP@-Y`8z9^I9m^;zx+xm#O5YPKIYr(s5vHF>rN) z`jxL33O^z-(F(DyOT~D#78Z)3P-0vo39-k2)QxBmP7ftY*-#8@FT}|2*-1F>wTN!n zLn_t1Ck7=pkgl*U{L$qFD=(|ZSMJw5kIO*n)ABUi>t6*hEc8ZH-_wRav=P~&IgHbm zVIVy?e`~2vl9HASfLlPo;+ZpcR&SfVxw4w79*8Yy4h|$$?nxKWTGFJhror-tOOaA@ zCI`hi<(FQ*PFVQ(_)$sGJ|jo)lnWgn*Iz|pL=~5x-|kcqfV;To(o=qe52~XRGzv#- z%36O?{kr1e8!|!*Ak51SOB3Z$mCw^8QJg6jus#x!XL{9S+8eSF1m&YFiBVYCAyr{J zr?kTth>>6rU|#oU+E7#qI?_D8vYhj1W9NEMnxr$#)83Iz>nOTnPfd0Qh6uvG{NKwD zZwQ0^mHz+UkgrhIt`nbtrRpO}Z-ATD?fT@+>68)fkNcPB0Ld2z_H@@7=ievoNq^vEg~0FwjjkQmph2?Vp))p=ghn;svFn33LM1{oBM_%) z9<7P^2zxpt5=0!kN;o$N^Qk~&( zfi$XEl1idQ)Q8o0OMSiNo0evE@tZC1M8|BW3f}8bJIrwc~yYz}1ZSAQza(h=>3`Tzi{!=Tctbb7Qf!tZErLi0+ zkyHA)-NZv^#^&N(1w8_h8Yej-n=0z(N-lP)m8ZmThQZmK++1-^hr_!vCFALVVnX*e z@@YM}^yIc^(i?@R$pai$6V%gUPazuJbzU$L3%su`UH_Dm%uC6sPUWagR2hK>sSfk{ zm0BMxW}#V)#YmzS2J2#FIDC5%fjmN@Gb_WN8d+P7<02B2Ox^JQ-8J)O<-a_I|9!@P zeDXK^zh7>kJ}DeOgKZ5D6SQ6C-C5l)Deta<^LrOlDJ@E}iWp1S<27g09jZ2#p`4a0 zt<)6i?2z&@3Pmk-%dH}xYHikc4KIN+kh*@`6u)q7#?OP^|enzJ*H z4o8S3%}q35J!_8ZKuGyc0&`t@Y)#eIImjRkydz^(~J$_)>-!av0B0lnvr3}Tx z_JA99rZg0?A_G8SVq~96Lbe=N80J^?0M+ z_aq_AF{{|`jeddNwQHw_H(_efvR8byN1<1|>zfcF==K2q8qKS4PdC(gs=yKNrE;X& zQNaLEwy-4(A#g^x0uT`*Y_@Ay*K7|T;$k8)U?w^0 z)kh;V5BUiPg{wz8r-hDhx)5#U=?+^>nS@eW&o(Wyap?a)(tkP}1^8CAT5;A2MC)xQ zW%T{4(jA(<{lh@Nm~34R^mZ(+OLE&pB23y%QtRbf^n;l)6+|wvp5V|(NH88z z-eE@TJ(R`Oqz}uY47FLP>5-?SD_WAuB#$&(NlWXGR?W{f_{q>WJ-u|WOyT!+KMEq| z@>%qk1tX5?--%Pu-e7RuPyTPq?pC8fdVMJ}s&Th@Oe-}}?dB@0VL+<2tAKUmk~JXh zdqEWctB#c*X7;kNvEHz_d=Ew`TTMjox{<@faAG&K>CdvQADN72S>1I&0*_NzVZ64S zixUy}W3v5&%i)9U016mSMO<-VYfjO$*US&Cp;OoOsapyjXGVJ$n{Hg;q237HrU`|C z_W_4S+405rGucFeyECC^fdg#6-n2E-8$fSINaqTWWLlFn+n0mXDC`y07<`S$(nw_fn_|SCA}`F^#Hv7d1P5VX0YB zFwh>;MH|?;!QRGdbn_OVE06q$kmnzpk`@pfks3TP@opds!e%k1Zt3_#w^*%3gx`>d z#cCoM2T}(+inbf5DqhmLGZ8vfSJS#-YW`WD1AYXY6jB3ascMS;O!rxPIuyu>8sZfW&U@IP)q)< zt)z0{a1g`kjL|dCOV3DIXeptX7~syAq*U|uj9||}MOz>ldq-(R zRhHdf2xKGwZ#s)y_OPK z-jk??AT=1BP#l+PBLo?0Hro`%<>lp07+)slWhPzC(*cy1JR+>O?cx0ohR6qaO^;4W z^0_{OW$VHmbMxNQGVm%*2r>(Ujb&s9l{9q%eY^3Ef9**3i%8qi?xsm=FP(A}lvehR z={3D^q?d_#mJ>LBOYO035=QwMkF5by@9v55@94mC_==7zPQBG5S=Vocg!*FiC3cgm z?!9PZ+*CH)X2-pd?Cf`hMBCC$%(4ib_TF?anloDwVh=dFV^y-a)5|l%6j2!|43VnJ zO`EaSnH~wMSXA^dzrDHE97H|s4;-~;q*XgpURk*YDjGEJ@*oo{GnEQX<5BJNZqi&lZ0f;}lmB|1>47{RuE% z&)XgURSh=$Z$E2FB<|YRKs|!5C8tS9UA@h`mb$M~uiKnD zFl-UZdE0aBf!d}5>m=G+Zb~W|MT{6!Vp1ym-P5TzyTrmD)EBX* z+LpgjXHnQ96mFfy%v>wAA!=xd&*!)sEY#-yqkk1{E2^Mtu2=YKo{cMw{u_1_$98ZH zW%graa-nT_t=YjuB3!W?lA%%71COOtipr=cwP6%#^a}wrhb>KJiZMGVCZV0Wrn(*$ zk#KlkHk$Krs}j%E8S$4lo%75!+oAY^D&oKs<{zxM=rGmySA`n!UQZB(TgI+vY$-x! zS-J|={q@anc9(EfaD-9O!pK8o*6}?byIO7yMl8)FN4&OU?-}2Y_V<4cNo9A8&0%$Z zU8)B$e5aF@Erb%59t^S86B!iXXmq^G28yfjf%9eUV4D>;sm0`+tsM155L!y-?EHGUTI@g zT5i2B)oMY2HJp64Q;JsIn>}Lw_EnIjn$_cF{~bdaHcq^okBpl(cd5wCv95ioGxIk} zYL5&sMcw{l#wD@4 zz)yLV#rVP`#v3_S7H3n*y@?5JRA5@`a3H>R=7>q%sxCu+Ph8KRzqzWpb!IGCX+)%> zstqqLKxt4a_q`qx`*NVkM!%W%?}9O)wJtu)mj=bn70_1Ulmf;uZMm` z;?lwN^2#JcDKw>XV*W-EuMA1%0K&Oal)wzz?yc)g$qEp_e&G+`GB{_fVCB{2;UwCU z$CZe(eKK=T0)e%HFaF~PdK2?43PYZ9kGk2{f;Rg(?XA)E7qPBTwWKUcX1a796w`ZQMRa(mT7j)OLpfS!!6f*$}8Y3sIgjgC6b<{COq&g`i|Tu5j*jA9jGSEdK4A1;P9q!?5FG)|00 zDL#`e@V1McT;`EZdQiwG$M~19rw6mJ^OH%^@S?Q2-$>|qh74JpO&}6snk~sXaq&$| zZ%(OFdMyq#UiZOHA1JJQrGM!Lb8LLbkvw@m)x=<0q`TG*+N~TO6U6E5S_y_!qO3Wc z3{p{?7@*!}#k%*m zRSM`6lxNs~R67ECj%YFbUrpo3r!Oc*@Xq7S-d6aX*}sYB6f>vRmFH)>OU~aRuJS7J z>fakT?sj_&3Gh?a)-P5#@H}$A7lGT%x_a+Qiye8LyOx!sEP&%+Sp#!kD%#6~z6sIW zxU&t&#YZD}E3ZYB%4m4hVu z4w!=3Y-OXbM?ommZUa~OLEJ}(b@gz$iAqD?jLCFE(BQd-(H^_QT2`8S@j;%!ijq1oB$T~bYDt6iIyZ~hRwA6b zY*8_Ko@OPmyLFh^+LZhZy(rOnLCjuoOeW#KlYgN4@2gTh%mXUlET@fT-OBYquRm9( znwS@p|8_rXBz+4R!V-GdYtEyNz0aNi%nCX#SS%h%w&E+8 z+!8ryN3vaK`n5Vn7a`#;@t%2$XJBxkt2!?fY>}?Z-#|;tq*Y%hX>Q(}=h?%pm7taZ z+>L8PA)+u;TQ`-`!%yakw|9QZ3ZZp2#fpXo6nujclqZTB?jc=Ff!S+E@(=Y*lT5eX z9f|2qjnG{IcQVU;V0V)2yw2r>YgF@~yf8gEs$PvBuMU37a^3&xoaBuO<47ZFz4 zih9)f{ftk_8^CO=Vj{H$Jrz4}?hBRozSizSTLLq|YgE+?=0TaWeOZN^V&%TFxJf4^ zJc+SsT8{BQ9AXo;$LNA~bGP-obMp5``Rn0fc1%5Ya}#ajh28s+qEtd!c_sY6DqrKA z$mjkAXG%7V>@K#^K-=VvO?LVhWqXBxP7}LWnwuB%Mhq}9agNGYT|)wH{gG>JR^V+s zuF8eIx7JT%=Qu0JI()Q>S+tCX>SlI#g`PD}Sy_8v(rDk2-NtE8q++@4`o>1-RKCjo z#d=#=NmcPDjRkDM-{Eu>)jHGDOdKd?>8>o(l?`{I$KyRGU07VHH9tpx^=P1BRT_HO zKi}Um^i*!$x3|}ZQV5b z@w{m~{~o6GGqT>8>(W%oiy?E7vng&X1&=OpWASrD=M+-xILEW3Yb(pzX~J7Zh%W|W z{TZ@ah3elgz}!l2L=0E5D_L^zuQ#Q>gB{pKK6j)uP9!5jZUPYiLkwjT8b<&8UaB%t zqtI?Aw;9=93SdW7*{AuVlE-4NZET{f&jYkOekuzQvCXU+D#aiQG#xfv_p4*S4Fx_F zG#Y2*i3wQek$sQ$R&R(&D91&tOO@G^xfA6itTtgIjm?Dd6K2_OB=$uQlF&4DZL~$!gORH?+BABg+#gM|zuCvi#ukkhx1aSTSejyhM>SBi# zdgdIOa}-op_wIGp`x1og)3L7J^6K~ZyQp^`E&aY+6$snY@c*np8N`I9AZ`w9PIdw8 z%zM3c4$ta<&)VqiFF)h`*{ckm$O$*Mm@RZ_ho;+&K7^dn~WnOxLqzSUs`3>Wi${@BJewl#G?;oUbMv{9 zmj`IZ#;1Fl+b*aMn#1;P{oPgHHxjKs9JZr^ zUxDON={Vn0eln1Q%1BZE0e;~VwMRgjHc3wRE!YMxo=wZJ7nuI{uQ2}Nv9U?-~1~e+Ajl!*IzIsU1dc@k*ORv#1{9DL)Hp)`V zuGPHEk5V0#0dCgqvLbDzHhy=OGzlfrBU|@RwqLzdJrC)_Xehr18lmG;wXE8W4}%3Z zrMYCBhupUkKke5dZxDiEh0kcl(pzNGvu;SXDCf~3M7uES&+_~r%J*{QxCtNR&p%D6 z$F1of^9S4l(LWT%b(4N59VdPc%GS>Qkp|^q)0(}z!khMSx;|W@_>cj5k0ZD)1y4CF zig41>Vgl*aBkO~%5oRiM^FFR92A6+a(LCDssw=FUc(lzBBSJ`~XaSXV;=v-s4^-eP zAq$N1i?OgFL#@0A*`UxDXZ?ePpu~M6-jdex9vt%grX}h;OJerffjnWhPRL1zpBx2u zCRBD%UEc9{0SS_7%NHSZ>}dS6{#Vaqg@n9SZg|xFm2-qpxS)&O#E&*gVb#>NUDZN9 zh6YO`tz%eJI}_lcQ4jFr$2)uiS3M~4UQOGH;}!8{VSIC=M{Rizue4hJvoc;(NQSa{ z-Kd1G?O^RX#y0Ih19DHx&U)=e-}>7mkHY@`rl5;}Hk#>5T{e0}k-fHA{Z22J<*)*p zC){N(FH~o%mE!6u{aPRaNycyLw)^$JDx=*Q*6mc@Z5u0qr^i8#wWy-qC7VwZpBK7L zHrfl7i=W3fG%$}#h^&}pq<;=F6S`^leZ$k$@~XC?s)yE1RJv$&SX0eZ=-ZT$B}21< zsPfZk9@}LsVP8gNxW0gg;QP$vcIfx1$nEd98h zQikj^Iv=RdC4uk{;twZe=owrz3$i+rCZjP3SRhPHPTDQ(6>QAFta~O$g+g6cylE=h zpZS&_R*?j*hCbiM3J`{q3obx)g{7sXq0ECFG_J2~TCdcdZg-w;HpJad&9E_eRU-MI zAxFZVf*$omB|eBDwhIk56`)buW!IxRV*a51{1{QsjJ$wM)<4$2QtD=6G~a2+B%xpo zg2xsPdSbp^ob87ytWA@o{~a6^3M?oP4oQPGbd#J8)U=Suf>I+JehNg+>bYZ7wB6FH zf7H&Nu*!?xZx+jRO=3N(sQ$WPn_~o#2b`atkqY+z*<9spMAWLDuJ9j%CxsN2$(S=$ z0}E0LzD9+7Rb90!;;uvdO`Hj1YjtJ&w6w)2nd*Y#-Z1a05+VE=>Hg-|w}~J?5sO|g z`nNIahAFeU0wN6hCG(W0A3r!{cgq%8co1=9lO)08)@_uhGBEq^l%U-F{MBH($nGu` z9I+N>s@zewEqC*??mO3=VU4Q&9kA4Q8A*wsX!P`oyirzxfnG>AZ9iYMC^dj@h`ra(RXXVYyuMip)dw&d`Voequ)F;&I692^4zJ^tAuq7PE4srQphJk`)d*|8fG7i(H znV!`+v|NxwrWQXpYU9ZR?!RJD3rK<0F7)fN(+TTkIDT&2JXAWsBs?!?WN%kGo+G|p z>_A()o-T9V3M()P$0sBd#hBS!28C0Gvs5%8G%R`vgI)@>?G~AKGGA7eOk?Num{|Aa z1L_t1?%PUTRigA!GpzM1KCaf%*9zT?*E_N1ZyE&;?RbpeW1r+G@NN+bz!_?Z&zrH0 z&kEkv^oMjVRk#ZE^0yYX?$ARH`tQj(~9F^+{56eN}XP8xq@FEVx@`yBSH2E zZSEELJe)MB`H3SG;`m}TUZ|s=Rr)+#|a}fup(Uc zrXl5#XSw=93?$qU&4qytRKuOgXygv$9OAy(msM9n^>WhEKQ&vTeOF?rJ8?>ui z1Yl7D6j5NJ2t89pDqGL%Aj{>}d8n4y$#UCxxh{WLx#XCjasQiID;V+1^G!!t+=6SH z-oL0;nb+m*eLSSs_**7!{R>TtKnnm77-1+~uBN{e#h{Xw+D*8XK^D8AR^Z7t z$&alC&N#57OHU1d2?pHZ_E++=!x8`nL(a|3)wD=Hf;DXLCu>+C zFh2?nEmnyPemd|em*V~i^c|)4Ca+krWBZ-T;ckvfFbnLQm-aCQ|q}+Ho5$N)vCj4JdC;6eVpZ!}E>8aR>vgSyD>*Eg!;~X$dMp@xQq{sl_A52J9%rmTbbsktc3FiyR0VcF!Gdicz zg)sm>l93+_%CQ^Mjo)RYm08a;Nr;Hoc8CV6j2`6a^K)53iO%f5m-aL$j6w8HtaMLZ z=b)%p20PfSD*8|KU%XWcExfxQ2w8@wE2O^EE#HG$0zxKgQgWM(dFSDliZBK?f(W?TKF+NZ!rLDpVsbx-0l)@MuJ>#GH}{?`>*luvoE2J8W)z!6FG^^Em}_DmU{a`tD54@Wz|agp>1g8D+R%Jb`2+ znI9gVq5n!PQzY&zAM zywfEWP7oKkBCK>`u^nVx;8OEa%-ZQf^YJ)AN%zFhM7g_JuHnX@*qSfI;RUu0rAl9H zbRyyIUe#Oq@SjZC847=-0M(Jgs}CZ-^J%R89oN7i9Q|~{F(y7seGG%LJ4a?ndaPb*D)(mZHYis{oeOG0}s_evD;Vx@> zJsZU~tZ+i&k4)Vk^tadd5}b<@@}mh2WT20DgPf1ID(LOEe7K|S@3wY`XWYCWhjCFf zPmMUZE!iaH(>2%#gp7AwtA2Ws{RDvv;_O30a#+p|BNbgM9pTB`@MKz7Ahjd4$E8v$ zr%_hXt<*x!pD$&1j$X_u!WBMk)TVZ5c9o zfZ~t*^Btg1UDFf-dR7?YIE?zb z_LdEcm`Q+DlBg7kZG5d&Q5G^6dEc1W1!Wfx&wni# zT-$xr*3!c;P7f^hw>#x+kzPVC#@f1q>V_@udn~FBp?7aEN)#J0^x>QY|7q3N@L=pR zkF;>)HR*vnpoVrdtE;8UX80UxX2=s%hSpx+uVSf7M=grXYXAqMOhv4@xovd(vRegA zn1Uhfa@)~=V&UXhAA+%VFG;wzKGedgFFP|#+thu zB%wA0KsIuxX*}6xDqP$(|C_vW&nrAx-WJw^!GQWBJ}9p+9>II+Tpbl@?84&Gzx8F> zU}bq7--$$}Lf{>wc=^~`ssZJ$%s8@~y5LE4Bx5MrTk~m$j0eUq8AYGFDR(^dTNE?yqms z9dW1u56Y$5r#Wib*7aaw134wC{2A<%NYGB2OM3H8Z~**z ze4Wuv;ukNd_TpU`jlbRPTF}W^G~G^xEL#)uN&7=NxP%*iO|Izh^B45PzCp-Pji>iL zJo0c!#!QIX`_V3yadf*hWAucKj4bhsSqz_EG@<>^k<_B=a5sL(Oq4NXxK#rK4it_A z_rNEbYopt>rG+{^d08&|wqU6S>sMPwzfuhtzPxECz*g&a+r(p;_zJp3&}@(&j4e<= zv$uCus^-SH5;&m%-ObquVn2M=vkC8w4@?|9cP$NmQ_^>7Q8B$)78TT`p+9}5naG7X zSI=7gB8Zy2+x+Cb+KJ?2QBj8x&`B{`TG|)XOla;psbGS_%s!5riM_%{j>Y<#b^O%i zlfL^!@8Us4M?|~VLvaOZdDAvIOF|$qSz)S}b;}XAGgsQHT zVza;ZB|DU@d#@m){Bbmrl2I~iVq6eggD zzI)Ne6alF;(L7ii*3uaz@qK1(#+$vteWoC4^WJxGYb@L&T5Y!>k@t2XHO{r9GW#tI z82a5ri#NULx+3w++lAJckuXZzLgvr(f(Q2g-`)D6b9 zj*Y`$K)!Y}!}CM5WF^Gu^y`MI8b3(9t$N7Y<=S`I<-OH(Jmy7B^9U2&(IXf)TQxHk z-i)+$7QlTLZ{o4dGlyH&ckK5d;wEX`YkvHd6i4{=2K#sfQK=tqNGDKl)KQZ7r-k~3 znb&QF3myM5lxdwZn$BvJjtg1W)@R`&tA$eHFthWmCU`FYMpFafwu<0Fp|Ttv+meY- zy&w7q78tgCWkhWH5$J3Wr3-%aj~PIpz{NqjCRfZ;k2nwHR}Updv>rMa8u8OA|@7*UbXKcE-Jb$SAPrb z2*#T%c$@^c=71g6*g|)wf{%^1(P8thT=}BKiZ@)f5;;}ei~wg7xq6i*$kFy=HmgZ> zrh4||1YcM;Zhu(x;(cn>BJFjv2X`vgl2%FbkQ_Ja+M#fsehnFA-^?iYk zWQTZwj?wMIsph0FiLSa5ZDl^n!<<=dcJ`q|*p7tmn0ZR1uqvVY$Q{Cqz>(+2`%{%X ze@znY__9vA1f2j}YFB!5Ax<6-k2z{Gpl`gRaPNZ&Fye6%n@1Hh>TXfEfb1jr`}gnH zp(W+Yb|B=x4_98;861`e5h=4?dGW&{63s35O}3A_U$Bld{KL5Kb@yhdz^)fh_h8!@ ztFaR!UWJ$mPGRSt)9MiwxS**j*QEN@{yP(!iJBEcmY<($DOW%btTW}hB|@!997Ymp z>McEP@Rkcafj)RfCjlZQ9D(ECIv|n}mM2Yc4ud(2fmT5(vHqhs4<+8LE4>`)n1=(qqse? zDf|0o-|hY9$MbO;b?iXROzsspRELE)0|e}-Xp{P$j`eu#@`?zW_q1^#oEi3>0bhH`VdlgCpzn3HYdyqSL?N~ZJQeNt#i{%3tBVe! zy~S!Jahy0x`kNG39zLaMgNo|FhX6^H-FZO~rsYqkCVRC#pY6uy)5c^c2I8%VG^?7e zFWR0S-m51Ra1O(ZWN%Y}v$$w$J1elgIt-QJdbN=bw!YiL37(K&(fd=}mgN^?w|{oT zQJJCsvmaWdJYxr9QdLzwG|**;o3HsV|*Wbf}@ldbqb z?X9D=^X^MdN5j(QxH&vKhO9KVk(5Og92AhdX&jcr=|C96Fgh+tV^ubNI-+f(RkdxP zB|`kDq-T2HrYB&x<)nFSa%hcgUvJsdL!w_)iXd)erndwY81}(`+<(E?vX_qM5_M!v z$U96i>N&D2NvI$AGa%D%kuXV2NMG^skgtR%@N0qsp@7T53{?-R(>GYI4&dodM(TT4 z<)m89n5c$YQ}3T!Hw$toCDM2n?33$y%+z(VfKKz9j5*>X59*L15D8tB0Q&Nen0flZ3C===>fT^=@VVeG;WukYM=_g(uS5QEjsu0;F4(Ys3x8Oqkx z5xMsiGP^d05HT^?iNt&DVtwbfHQG2Sv#RV7ivv&EEW4Dkd%CSi)qL77wGm^F&H@5c zlBIW2wNDk8dYCQ!jTvx01s0Xiccyk#)i|T4g=yED;n~x>0va=)C_hA_266=Eei{<6 zcGu6<5l8cbzQn9O&LA@r${AS}Eue_qT~|h+E{@%SY1XQDm#HFK z6x1Zl2-Poaaqs5qFp(Z=yXMB}=HniBJPV!0?=>NIaZf+A7txtnI8HV5e;H?MR|t`E zIdif#9-2RH#kbgP)^0>;mc@~)&c3gpL~=@1{d~V0(4C?56z^djLRK-fA`Ex@H=n~! z&NkI%bFu;44TOi22?`y*Z;oFw!1zgzPz+0^Kg0LGv+OKk_1Gm_^DTLdj2}zYTi2fW zz#A2<>li~jK~{49$G@x+Dko_?u<}g89g3z>74Ia5l|b;5n^cQD?zGD|8v4xG zSi%=wA+NLcsziB+&fi9QKNH+SgbVwyOSM!s*drBre_mT!d}}=BOPj@cxhFXt6YKPT zu`qdaOB@Y)BHd*R-R`+{5`tyLC@{iXIFu2i?|MUWjJoG8 z2mRaIjmYU9hP58Dj<>YY-?JmA1%X~(H|K-wEU~5BeTWeTHdSU;7hdq|o7&%ETZsUz z7&Qxu>+D2*J{+>B(si}vS0RJs*G>dP_Ldk%pVXE$4T;W=|+-(~2qMHva0h#8%|WNh~4SA{$9e zOiWfwUT(dVY=nk-CSz9CD?p8|2afT)_*%oJf}9%6?2oUg6f|8K#ShNBN|gA z@9hut5w*8E8&yivMSQ`_#gPO&$IDejCv99vH9`-s=e1gLy%DD6Uqt*qxk0mb7xPLs z6RMr3n|=51uerjLTD0;xwvuC|yjD5Np40aCjJ#kJvSJ5TBOw1{Z-AUxL4GOD<6sr6 z%7FwfnjA@oU_PRiz1#v9Yb=e=jh!;{UVS{`^&va zxqGNvm$R4}lC0K}vLc71d-=1SwUbl}*%9AroC6zV*yV|&VdX|&$G&%(l=r8=1k4x; z0>Ba25vi$`rFwOgDKiy5qa{1ePZm>s&L8@{!%e*G5L%VeAsEiT*6xH?$ghAJB#ugT zmls+yKx6f3hj8vM;iE!NwIfa0yqWmdB=Fp)C70zclLWou#U2Tj_Yr{b;|j^&LCe?8k*wY+-5No8Ada;}d=ULNMXt*kH>MRn@Cjl3g%78AW0BS*y! zddHJulurjd;F2O9V$-|#{IezLM!5WpJu*xDqz62KZP>!@wA%HSMW6yL63Istm8|q!8Gt*!S&%I!CzDJXev0=vuf153I4)Vu)8fF!g!>M*qxZ zc(9&hpHq=Bymc~c+YON^%$6&hkQG~0oJIp%nnw3+m!M);(Y=0tCu&0Tz;Yt|tfWwX zvs5sP9jGn}fkW6du{-XDZKnKksXpwaIz#~V;35UyQ|)AF(Ni}wVa{)(ISN&ELc^Qu zHlzAfc2<6uDGZc=Z_)ZO5_B9@+vK7MDq@*Y3-4>wxAVnz-W)xui#A``iqrPU50c9> z9+k42N;mH9*s7Q5nDzb!c_<+igdg@aRvDGmJq1bW^TK9>?=!vK?rU%h*o5z}^D>JO z1Js;YIybFh5jOg6lW>Isre5Cn=ptM@^KQ~!|Hk4E##a9VP#lcktxTKivhpnTU1}Cl zJBXkM5+<6Qs!vEhi305u5gTh#;iVa3RZ~P%dU#mZ(A>BKDW6+(}9L0Sc6bP#nCUm|yP_cHNxQL@^=qpqUtR8mpu-MJnz?9=BlhPnYSLZeY<~m ziH*5@_1?>I-XX%ij_i8>g*pVk)FI;~u?a;kPj4^s5*h@e(Qraj&!SyM6-|~A~ z)x^}j5feojw#UlBf}XB=wKSI5-X1BB!8?fvDl`S1R2f*a8J&>Z39IKtuVl=hZfEAF zY9TV&+AmvC4{y=RK1?xY+LkQ6lYHHhb^q>VuY0(tkN!M8J1ByyD9$Kq{P&RH^6i?`34r|U&)!GP$--hr!Zsh#{J324!#UlM3?9|Y z#_#tPfuDA`${q{01Ad^#EV=D2@FM*gkXBwu76YJbJJs~80+xQ^yGF)h zv%2+H6@ArB=@wHTUQ(!Qwo;^8U0%dazbW<4DVxK^Kf+d=iG3s4i@%q9uGdMw;yC3U zI?v!YI*%g5xV5FHgu><)D2_)9L`Y>f{vI1WI21r#wf--PvuMNz+~x;7WLAs&ei7}0 zSCV8544}i2a(%qk%CVrk(7KjKKb-HeZq6rKukw_C-7FK7arqgXe09020(QAcZ1bFF zylI%l-U_CRs5B%*DXlULr@N%CXBulGY`Whsu`A6xB}H$C2<~S3siqR!N;zEplNEui zSx|pfK<>MBmI_Vu;n!_#bAe=>oUaC}jcb%44jpT=Vn+?H1D`VDoAGkA{+bLrrp6oL z@PCI4L<%Efk^otTzXqec@z;7)l%Ppu%lX;o^T?Q2K?@5*Dtx;o_)-@K+uaa|`4I;n zX#~xsy?bjDYaDjuufUL}o0Wh@PYWB1Cmt+1?EG2*Qk1bHyGEL*{ z*7JD#i*dsCw6j3?r;MEUVX}$+dCXS9EN}y`E`?gR+#1b5fq?jGFT9fIouA-KEi0=qb2ad&rjx4Yl{zo+VK)tRZ8x4WO#k75$= zE|AIz;(iVuo~#z5mivu-L&}E5wfg#@`tAC(^)T+4(e(UUEk&>r{ryk|WZ*KfL_)7K&^oLa z8%@#L&~r*k&P_+Thcv;PQfcDkUZXqK*YzwRdNjZB?gF692Z;EG-UMpWw~^s-r1( zWLJGBh4?NGO}B*MPA_e4!37+CMWf+kY0OH#muw(_Wf%K@T?QYnPi@ znXb@upv70A<~mM40g7pp9WRt2hsSZFTV%fz#t{4SYxqi^Zt(whZL_wUO&L~0=H0HRt z>YGY%ELOaMewR7OZCAZsSXI3=r{r`0Q|X#U8>}ouItMo#zynp53cdl|A_pgeXy;Np z#h_4dbA^~U+g~i~T&`g+%sP#@YiT~-Iz5rFjNAT?yJ>U^_sVrzp0VPk(YCZs6$-~2Cp0%y6U_Ugsf$$;P0ZVY{fQ_r>siea22>#TW9wEADQz(0Kw*bzb8u5 z_iwAO6$#kodcUpt2Z7W(&p6JW2gLs;++I@Wczz`HzX*zwGJ#frwGKX!+ul`bKR955 z+-*L`^WWh?A(_9bPDv+TXP{?Ft17Ef-|LoThn6{$Z4$48Oq<7?mZ5(m;#2^DX`yH} zRZ<~hI*dPtPUqfD= zu`3As*B};Hgbqi9VL<$EJuZ2DMV1Tm4%q(()P4Ru`;%3Zf(g~X^2 z9$mAhPO-ELw{O_q3{8zz(`;nNC|d>op2>NF3}!In^gNHc(f!84!uof+R<)uiFKC8D zM@M%tTKVU}{VwhEQ<S&+sYADEpVMtdg{9D^xUt776>@V(*)jZ6DfCRl7> zhJv{x%n6fS!#)A_532TS`yxae?pDpI?&8xxSPi&*VsmazM&FLq38dZ#Em+nrYkKq-A;V#0)DU~W zx(1$H1`RYr$J_g+ufAS$GQ<;kof_z#&%L&`>*|q>YPd}N4GklVbY5r=UwC{JVEFA3 z#sr!urlxKNKh%KQ2^V<`ZjQ+O_~@M1GeSb*9->z$P@Cqygs1lVqe1rRK*^2gc?X<_ zaeQY=mr9nzdx=sc-Eg>ifw%^qA_Gzx&f2fkf7W}11b5oy1zRrtju5Fcjf$)fG7fu? znbj_DkLL>%a|G!Gp#Y|zjj+`n2=&jHkp*$QNIxvb)Lw1N|CR{7KaQ8b``*`b^Z`8l zE(9+EKcOm}$00soGO zJ+9qEQs40ILfH9@^-0U~Fb-zQc*l;V1vHk+6K%5eZd`p=xQ*U?i5-vQ_62fw&3N8U}twcOluI%vF&w@ly4fK*ui7fp1zvdV;_sJB8 z&)AN(mPtGsyML83Okg6=N~qG60vxygCBKKMGI<)uPheE)>6WKBNWTj{(f3LFa)Hs$ z{WGf!(m^kCO#A|-B`Tny5y$P;GP?r0^@;kA!)zUoA~@N9>OL6;7zP%?QpXA8+eOo^ zCy@A2^&T#9Y3Mu+iw$RatQPgWqVWf&{Tk^qwC_-+U1!j%{lF!|pLB)tm^in`pa8W) z+;Rkb_Z+)9mXd%$!6v+e_qB2>;GfCz7~}DweAx{rWU)YH6yxwmrMm7(`6XR>RwBxy zSxt>)ADWbt7IAw#*H3hy7%*S0-y{lP+=&(LA{8D>T`=U9q{zTfYy(^2xZ8T#&kZbb z$rP(cNnC?_j{wl^7k5uyR=&ThyLX~NQ|MMSU6#QG{0tAB8-KrYao)IpLQgS8zj@x( zdPw}+iA)N9$7!}RKm*77{d&dN!GoW5N_kX!n_Sg(HX+JXK$;0DH^>HKWwd*t5xM4; zvwbjBFDeI@mg4n8n_^&J2rAyJPhMTRb``|+R1h9ME-|9Cv_c0^{cT?Z4gEXlzIz6z z{{5+sP^EBzUKbCAc03j?yJ-bG%Ndb=wZD*lz5EPI%V6QPND8cQp2||lJjrN(^4Msi zgo6B`M?DPt*JBjV4N!p5rRdlXrWAlC9dZx=fL$(d7qn_w=79-(!zu5GY)l0$zJ5L( z&o(W$Pj4Z6Boy@wFtMX&H$3p?NKY`SjK5WqDXh&E*3SMnG&T@%4vt=aKd)&$9|Lbz zFoRQ0r?OR=Hy09|dhC@JB?s^UcD9YT3_5@FKmHZpMQd=*ymElvFIja$FJ=BV_YeR+ z($mwK*_-fX?DUy^FE*22ZAt9*O7+UBDjS7-x;(43Ut6__h5eie zAY4Szvnn&pmT5XJLo}VP065&?$k3inR;z9UW>CThL~+%2zUUO;mg-?Dl#Pg~fykPj z6*^XG*x{EuuWF5Z%b^cY{(bz~G%@^^z$^Li^YNe{UZedS2=yqbzd)T+)>l4o(2d3t zFtHJ`qPZPKUkMxS051CV9X&dUXMaTu4NigoEB6_9m07RXj0T7dO{k;fO5VkIZ{JYB zM^FUs%Vx(tN$qmIf#c(@w@j&s<@yJQWq9A0x;QR4h1|wCQ_Lj;2Jy$KStCok|N2L{ zR$Vdu@7vdnA1*fOVnv5DaJ$^ZqPaM+eAi@0*Wpb_roMn-%ga9=A$L3MV;jx2z|qAT zlA_|HYY&C6yhEkTql*3x-yDoHbZ^$7p=V)Ngr7zJy%(c)dq!40||JhWYk-9$+a`vG4p~ zr=XWDz{s(ff{jB*nYowCUDIryq13_XpXE}zPHwaRYs7QYs?wnDXDq^Qs>GC+{iB)R z?p0Cx<;%3E|I;T=`zNu7!$GeFpgD#6`BIQNw5u%4f~5bLSsbjj+tJtJ7@%PaQnT`qh-mu6xv(=jTBvS%WgO zTh^?&eG}R@J^+3qH3nTgS2;>VNqc1=w`Ud4kggeG(8e~-_|HgG4l=RF>r>4+Z$63+ z&$|&F<>x(`l38c{)L7=`T=0O`Np_|yN=cf+P}jJFhp9m`r{o{s&5&08p#eiz6l7nF zrGnc6CF$13P}u#@9>rfG##Wu7Nkx&xk2sanS9>rHHBB>&cNqb$s0DA)Yuu8=nxBS(p|Gp)g;#MJ4o*5S|UT%znRlIL*H*jZ1n4qZ_HYJNcjt!t`z{b5n zEuA`16}}s%ypC7l{8E;@=o;`{J*mvIPpq3wFbA!Tr@hYe4bAgv6X9Zi-7x&UeUHue z@=}+EInf3ofPz-DQ_9&$^q2yO;M4Pjf3%>-4Dzm4EP8y(ZZ1m+)pkH0#MiuUTDmw6 zLb?ipN7J}0$@WHSYjYNwlI5Oy0($Mw^|PUIj<=Q~ugPNJJk^@0)2=;ylhc+da?1!A zDADDy-oOId7x-%&PKR9QMA1FnlxrJ0>>}=0oL|qn*p{F=;juQF>nln;;q4u$zE$nj zPS}(nQq5pzU;=Z=(X=)0tdx%n;;nU?z4!iD%p}SF==7Ps{chqc(qz()=C;7 zubBOM0@u*D?rCZps!nM##~cS&m)IKqV+YHgfu8N5El3Le$6}ofI5e$ncz05uH!@O1 zQ0u4ZoV1G`RP$n=p?Zu7UitmFONd%a!x(dIkW+!G)5upl^>nr}6iMQQ;GOTdQBl6> zEv28&eUm8NwEy%v4vm8J?+(O%%pxyl>tibEoDC`pr5O$Aw$DZ{?-koUze&rVTUVX> zS<1dwajmOuPAdv37a#tS3|j4zNp>8zYuVIkqyF4dC|ZhlG46BTZ!h-;%J{E-=p}vs z9YN}c6)$uN`^I$rt*Uk+L-Sx|@bMyTg!<}2Gj06&NvqDctv(JN>9vQe&rXfTBGaqb z`F%F?p=?qEA=0YMk$qY~SH(L6dl|DuWyO+L8Sap67TUGD9gVi$r{D4dm*e+<%2}lw zOU&17bRFK5E^ux7^4d&zIi1f_T3Ox|t@w_nsqc?!|9H*Oddob&bu>KQf2}AO`qGiP zG`=_MBzc20sG>vytr?FpjZdX&?cXoBiiMDKQ)bCBkQ7Zccx^kIS)3;L&f=3BIV5Kp zQ>T0Yi;fo9D`r~H>+Y(G+8K7mmq$6@ZuK_18jm;gOA_@8KAx`Hr=2)pzm!|Qp*Du9 z!bvH`JEb}un$7Y)OUhaA;Gc6umL;*9OGo3xDV-6ID zdDOJ(hv%v(Fx=kezFNi@<&)i>JBSm~yCFIs@r5TIeUXoDT%}s#R54txo0#AwzYX8F zcy`^G_{3+rWZXO1;6vTEK7mtO=&lc5mArjhkmbgbUUVT|RZvEZ*#3E!C8MB|9F^8F zVi8X-LJm`wv<+~(ZtK#ZbAkY;(p2q~Va6*`ElO?j zm9m?~T1hU(U)6uKU1UMyYpzah3%;hozE2;gok#P-ltec6m+jkqxWI#|gU&NPI67cd z>$s#-0Kj~q)gMLB|6YD2;QsVsm9k`Waqw*L2_U!WI7^eMB_-YO3di9@U-aa_{Zm~i z+Q5#bn&!SNbbe^>+Y(0-Y(BpWfj_b9!34~HRsbmKI;)T2SU}7s*RI`N_A$rS;2xmE z$)($@S-vkDE|t9;{-5Vk+vN%nMxfKlb5`1H`M0eke<@BMK$E;LWTM+qCnN8ar?0F3 zE6bdc8jJ4Cc0n(14+f~wT;dV3IUlGoH&41ZQG}7VWk}Op|7AUGX#vMEf7RvklN8;m zl5!YRWogV0?;A^VJ6}i&tp=04*x70Z=CfBP({cB$$h`Wv&^td4vq20!6fRVBnbo6h zkrnoSLV3UXpZ{k*(FXqQj*C&M_?D1RM<#l2D^fP6(bwf}u}fVO=0ClAPM3XFVIGSk z+dwA@7>XQjh%$Puu{7arc}DmzKY!`0NHV6D94D_Bl+LW7+OD=@wQdjr@(W5kRJbL-o36R4 z92u1w_kRkTECl+HO>^ z(JY`^UF+MD&E+1U!^vfRWKW}dg~sNelAHms*h|~~{PpbJ8|wasVh`vp8bC_knv+ki zW}3G(LwxmDe}TUWU`t^24Y7uXU-?vl*=K_2?i~8LO>;$piAJn{7vF#O8yF6|MQ?%pUs^D zDWfSCYVVfup6;syHh<|%A`idLTmmKiP|$A+p$zXFEIH!D=D{V-XF?|a+Ij7@HInRz zz9mU^ld|45k}@<#8U1H{T$E8#1@0(gG7QvtL+}8 zOyd$e83*N&8u@s(VObwCyXma@NGuo_T=JZ?cT+j^@v)6F>;I%SZ86Z(bl}kJ3eI}` zO8#<1__WKbucCt*kib-$F4ZDIj4>;!3~GZL7{7)c@{*$h^JXat90<^LE@+m+NMG%;_lM4n)HoDQ%x?OYq;dNqF;)PQV8;5XJ<_qrc|(uug~xD02edc;+g#3$~~yc!MO^ang9nkU0>~w$@=M0G4 zddf+hBS;MOBD(RXQ0G+2y!Vn?Qm71y<&`a|SGc|`S_DNi&s{o}x{6hBP9Ch_Yc+qd zT%MEt4U@60AUoxhTA-dafbqnqbTMBX+hoGRPMU0<=}*mtaKGlmY~OJyNw0n#@O~d~ zL?0jY34t!im7ASemK5BV4KnmO<;awmHwZ$jrp|IrikgRGJewHgvpS*7WeN)JMyEgT zC>`A!Kzh9px<69D-XDgn31H5oWZ|8Qn&e|LY2LUvKaa_Fyec%ZmM1zn zPG~La)NcvWbU!&rs>yu*DoDx%yb#5jp3=v%rHm~vr^CX*E_2>_z*OjRsCi`Arm0TKAOzxnp_Dl@%nrEhPycDX?6?LxNs_yBL}SrETYR82wlS6v;RG#w zHCf|`;X3O;TkkBE59UgB7XWUiDz4Sf-I*DA>;61mnul5eTnE`~<{0!`Mmc23MnJ!u z&z!mtxEKYy9ENN%Wt)0;CqK3Zrd5~vl96vMwORp0_ZZD*2NZ`nN3{8JI&lK!bRyHJ zwj5tcnfnhT1`A?MX*0V;Y0YQJ#&59-anpQQJi^e{U)93(+YDys|7#^GwJO=p6)T1+ zQH#LU*`{MKFl|M^&>WS{y(7MS)j>8(z1$vYxl<4r>zq%Q9*o@{v0X`@1Erx;KIc{K z@W1p;<8f_%qwKgJ@+>ydS2h-80$=FauC~I*eTc`tPoD5b8~17{lrI0i)IyPWPdT%h zM~Pa@+BN`*KWnLKEMT;Oovg6XB=YEUB;sC(R~vWtnz+q_9CyuCego-m^h)dkhfNA#Mwo41KiOZG#r6r+<0mF$I8sSrZs*<03sIjDyQMEq>1 zpS-yfHZCbxd9VRvYY)yMJZrC>g7q#}-)qEZ377Sa3{Sk-8)GHlTIjGfDMSYl$uf zPm(2WTsZ@z>>?qJoCEvn)_O)Zc!S6kRD_<*{QT%MhL+=Oh~XpYg{JZLkyrZrY_wLp zH4IV|1n|*td@M4Zn~m77y?+Q)4;xY~MDwh4h8Nm)?6c85xHfRaQBks;B~3^ST<&R+D>k6Y+aJ+*`jXE(UFC)GrU6nctm= zqc*wLTrsJ%gX3)8E+VLq<9fZ~gA-X4QZ0h1v%O`t543Nm`7qX+n%U86I@7``Pw31A zZWAJx`qerHX-$_Y?{_&&1<2WC{u{PFT?CK&ggl=gKDCziMeNcyaf~}rOtTnQHcN6? z*puNfGi%H_SONg|Jex0#`LLAcmCF=v#~xXThzehbwOXQgEhlzUx+k!#*In3Ap9K#5 z?pGtgP}`tJITS-QuJ>Q^<*D?d4^#2~)rsKu*YjCYQVhCG27MqF*NS7vlP4<{-Tp;q zj|DV`Q6S1lAs)n3{}?0AT{6k&q923DDmq#+E^tr81Uw+8Z*o#%J*XdMQXPMnkdRQu zjy5qL%jAL1yicoNW;G4f=l%n&Z{m*L&VOp2t#KL4YyV74E%g3n0S9EY8E#)p@Tp1^ zdM({{eU%FNS|=R#4RU~p{hjvMp6=@z?jyg0y|rT z3O${P?!47!t1^!HZ%;Q4Ou*ah+!O~01TrI6F$a$=Vk?2~|GGSUHBAzml!Q?f)5E-K zyGz)EYZGc^Q^mZlgY={yu-CSqvISW~+O*GpfGR1qT{_Vy2BbXzhli_L4(QlC4skLJ zc3V+^Y|E{d>?gkfu*Yh!Zvc_*DEPH%)q=6w9Eow+tnu{s^w=ZH+0*a*XIX8k7MFZz})AebQ)c$em z)Yqn1GMt#|9kU=aSQH#r0`lM7kJ97b1O%jA&ESSbid`?rohxPH%I)h?oCt-K`0K8+%`z1ULabGEcc*~#?`sOdwOCjW zY$)kuqNoaun9nk=maa$Q-(}=0n;bu96_N6t3+N^*PTf{hpisFa@s>!Z z74Qu&qP`sVWQ1;DPyX*C_MgIf|J88G@n%;C>0Lq$-1F`{)%gBADUuLVMQ-BxHBb68 zuLJFyL!qC%%=flz9*4YlnaWyev1@<{EHc|BR`GVpBC}sc2Pq+yO#|J$;lwywTYNE| zX~=dNA{Q1DP@tU=>*(US6cIG`q49-#cSe|;?ck!gO`nZ zf?F1w$-a2nFV8|y@Q4yuM|b0^5cT&DuTNIEs+&Osft+fkiG+LJdGr+&@vskFieWI; zAD8Uu=c;G-x(LL6(BME{3?qX=V9ERIKn=ZU-Ys-V8oij1ry!7c3Nu2(#@fS*&fhb{ zpj4CJ1AA_Ux^=I}I$gB1v&{U{Dg^eOR5ik2rQJ?W!wpW{=I1g8(3=iZyYs4Dn5S5Z zWrzC9NARXA0HIWQ4%y$oe|GBG`=${H{_H@DD)iz=uhGl3?rYj_vJDkdT1+^8@|IeO z0#kGKMKO|A+=Nc<@Hk-$;_5(DR3IE%3-|^EEk|T=Xf(za0kg?Q6XXaRm9QisA)~Ca|{V)^Kg)2Dx)l$+-uTx_mc0%@9 zUxnsP_nzZTrkA|_jjzQdE?#ZNuHe(vi{nO_0N-``rh zVqkQO84bY+1oc78tyO8+q=bV+^N;*aB;Tou@*tCly7gPNUb;At;o(9%eMLFdRVn1> zg;0~4h&^OVl|Nda9r&=?#|GwBG1#RH^G{v4-9cJQw$hz$WIiQtv|0dIpoc0GAoz5{ zr7@Y)EJiwG{y5@?QgCY*Dn5Bw(tv+`T*h|cvwr)zb#cPejn?$`Pu${VuG2Shj?)DG zI8S^xC${*19PK^PvTbYSmvq;kkBfU^+0ZF=c?9+C5pWnDzG_n2fI-)(#EVggJauPA9~F1t_T z#3a4>fo?HU<4jJ@=esG*Wt9{zQ8{O4jXr#yD#}6b3(Y@pi_9tOF?|zBib){~hx)04--_ypCj$^;TIUP^3g(~z(ct8@!c?X+~n z4ihUGO=kKp=M9Rm{t^yPY8r$;m<_8q!UE-OH7FDU!z?hoK{Pn9-~$NfW}%RmWt}lApT>R;114#SF64x z5%eM$Pq4-RP;YbAjL8q;M?@XYZ8oD7oNJq1%8axQ9&GNj&T{|+0Xqi zC}uxRlxosbhiz?{)xmVI7fCwmNJ8`z?Ss5oPbeby`^&XDw66KpL2Z{5c$v-RkR2t} zz|!G%JZCM}ZaNsJF869DQW*LhhS@c&jinTb;?HruxLK zDtF$TEe)*P&q}^fjA-mk>10xQX-IF!R_A@-pC4`=Wa)@w7sy@ycs|#oT(h{}Lj4mA zy$>m|!BCZLmJLfMwsnq;RGv#C56vmZ_X?3pA+vO(SfzU(YAmR27H$J>eIghIfCil` zSlGYn$S;7*K~2r1Ut#^V)JjtvrQg@wkQvBD-rv}96};W$#6^9t_2Q?NT*V}H?Fb&B zSUuI@Iry;cW@ZSDnx|m`hC!GMpf0lc483m8Vk3_}(Ji zbRKk2o?F?tN55!!u`m+3VV&aQYhxy?Ol@pek(dQ>ug9=;J7-%I)ah`^8N2L5eF zm{Te$mlviX;`ZioI*At0cB>GBC!jH>FKe_CO*IO*05%8G{|jInbv;~?9}9zZJy^gV z%<-l2cbUzZD2^p!Uc{k8pZ$@96RfJ#VSVduyJ8Ro30(QXhaqyzuI67C=C4QP1!4V_ ziN)mr~;)K@njM!3ui3W{e6nZ~5;dx)U+^X|2G zVop{SmJYASapdy5lh7IH-q`h+N7_2!W9CJEtrWcv=d#gLiFpsU`OC$V=ice9E>~MZzm-=1WR0%FX+9W>td+bm$CIxdrnax}`oB&})iQl;pG(OE^y$xBPtY~9 z-21xm>8i?Z4hmLh@V-=qDHlkp2Na6lKYd?$La{=GBUzu$99Bz3yZh@%c1G0l!a&dUJY@dwQj5N6X}5Jz!-U8v%gbQDkE8ZnvV`<%dtcYjajb{o%iQA9u-nqtw|1ad0;Kxjc-A*s6r5 zOQgu3Zp#>3nQ1Rgd-ssc_Pv$Wc2rZHov%6;8k>mLN9p@2&VS|Qv*m)+_{~(VwO4Da z)|JZa{SMsPv7PRqdvaEhFrVTc!59xp(699K*L|T`Im)Yn;~G;_u`>&TZV?3HP$&!7 z#_qhE(@I4M3v{qeM2ws{SSE}vdw;e%DKBbc<|+AH$_5EdG1I$z2$*ooeLFQJqZL2_ zd)>g?;2A7uX>uc&xi^}O#$(JS<$k)1jO0F?X<#v1kfv-bhAY)yZXsvZ^r!Z^s4m(e zQ?@H24~)8EgTf?f`*Dy$(fF(h21s1-l9Fz`hE$r)ab8r|0;~RVnLI+O7WAiZ1f{56 z{IjB?gv4pLU|$c?_xcOTx^@yH4<>0zh9a2?OZt0vzvMUaf5=&neQ0HW@J0OXGTgz@ z%!o>qT3M;ps%KC6QarIl4;{Uv`9T#T^poZaSEbM0>Y0Q8yzlj9%_?G?-y$ zFRlCZqFddLOjg13I4rxV6mF0djS;ZgSV236{4==@J69>vG}$yQwdi~N4}-S9Q6*QI zusXZOaNg~ZGOQi$`;!F_N_3i?uuLtQZ})d-nrYa>6|AYOO?e$sDaUsxBf;%#LKs85 zq_HQKGeV{oE+=Vh^}!2n7t(L0Bg?;32%M}6A;gsWWnu|-?epR`WSi;Yp*fHiDFaia z){J()zzIR_zGXTS{h1y!bfLjZ7W|>SM^$r_G*VYz0}buAo}VpWtU`f`)Ypy6*zu+c z{Mcv$Zy)1$c76YBd1k6nHkDeDod}49cA!v->@E3QO)~zD5!&_4yqZ7WbnSo3Hl1lK z<9-M6&75oD(w=eO$k>qtfnXrFY8o1;P0jBYce)OnlTsvQT%m#?9d}0+vxnze=X5$B z>25UsAAzFOkUchfK9fz+Vak8Hi>W?X73@PABS0X@s}sQZs}4 zV7QM;3o4rkOq@h!mEr{Mv|jF7!0ML~B;L}r3m4mcR@23_6-Fxq7MTs>f`pp-ZUD$U z(Z%Z^bRVi-%iG!Cuek4MtQE7_R|6hGQPlRGw;F(Xf2kgiPN=&uVCHEePt574tfU+? zRdx4#4z9W4e?DoLwQqtBRgA%*)iH*iK?Gr4RwXd;La0h#opxn6cGIBwj}K$~(-4M< z;6Hj?M}YbO=smc=^U^@Pgj_F zUWYub?`Pni&6Ehgp@q)<4>5QiEK43|jN|W!j=&Yq6DYgR;oXB63azY!n<_g@cfH7y zc2L#*rbF>mgpI5Nyfl4#q10+yj88JcReRh{=_lTul4(|T3ZJ91lpz;r!$3fF-|C}1 z7MC=y!eo_ zR((!(MvTqnf+lT4ea=lU(c@^1fXY4{DNDij^SV?!R1*P%*g*}d_wUab`Q60;L%zkN-G#Yqvfv4yGIrSQa+fR50x6dA_gy zMs~u-imW^3m1+W+TH^f>dS8h;)%RppNGs1Xet<#H(hY(l+0W`$LHlc@3mtE|e-KWd zgXg-JP|U4m?sEj%rARG^O#Hm9jXmwNaUW9&%l#ynk9$!=j1AFG-_D@KHPtBU9daGP z-@@$3+?%O31U=AvaW@+2<64M@<%1JB;}+E1PeZ@ui|`DACgj@w#zQe4pP+Zhe%g}E zd@R(Vt^R1ha@ks^5B)Ho-hYw)3qeIjD}w*DoW zf4;F$-+=;m9#!81Oz~z~keGeo5$F@!i2!-$i{(E>vE<*-vYG80fZjUthqms%bN`a< z2oj``?5b_fc|EaP2jcxHwl+KfrXsB1gYcjOG^>+>vEdzwVSg2=w3(5wqJ8CY&8+Wi_GBGy|hT;<-v*?JWNcAW2$pVd5=Ydi?R+upipiN zrhUsN+94)aOVS7!zodx@AJM*HFVn+0n~wtuAeBxf;6o2`1>E+xIW8=L=8(G(d%r?l5yWqJWo%mT6#^xid6g2x`i);^B2W z3LVVx6!ow0qww5{?nK`0P8^&L_w#y4l*-qsr=_LsF2Xg`8|LR27Jw3iXK{Y(Q1q|S zb+o=wdwy!}YP6TVx~j9Co7duV_zDe&lYQIQwO;;t!*7HaPRa^L{CrdIEV;j6|C(YG zU)*CV096molQIpd=Y$iR(d^aoUFNGjpJve}tE3!Gmg>Y1JpwY{QGy%c^RSEqRmVWE zVDOn_k>&MdyTitz)cb#RUz7)(Pe5I#Cmvi{%BKG+I)u(a_LwFX%I&p}w z+Z&Evjz?wGn;pqgxgJYMeF$^(xT;v()8ug&`on6)dvr)|a9~4kqKn+AV`0E}&B{)H z`zMt#>Q%>YG+wLqGhSulV&SK-ALZOykWQs^J>p`S$dsIficVogd9%- z3aNNi=0Vz%U%CB}^h_XO?bA&P>iZx$q{T>Nbw`f4g0R?m|uWJ%l1_r17^%Z54yH2I2os&U)S3Q0o-riftgvmqvj(nuiTJjRL{r)< z!mlpX8ZsyoK07UD|L7sjIlX~4BwJLnH|y!oG&#tZ38@g*6)qls?|9ui&}1i24d^sK zdEIo6Y?iC&>!uLETcSp#WfQ`N^WN-T)V<|27B@aM-cc zl)oSX)a{qPcFX9W>QaaWYr=>7bsA^DT6EZ6(uB2_82F=5NX98wXQcE;ULhSSqACb^ z^Fw4IYInJf$7oYc0A%PoCK=;){|uyj2^8N~z?W5*wF=)>r5%%YY|m0@i804dFaWFW z1+*}jqh1ZIY<>Ag#zZ4`R-n=B)Xsf&`%oNB3ugG#=)Zj!Otfz4dm%4aEcA#G6^(4Z zmRoNCSidXIyI zjvJx0zZIp$wY^y9Y98^K1+Tw@G9F3F=^7LC+sC#qx14I)q|E;KoV6j8WcsQkGamVM z+Wbh}nQeV2Lng_IjSlE>Zc{j0szvPQ@sj>2FY>E}36I~49G;ZF&Y+)A^gd?)4!=0A zGw)DI+6P+yQ)=_Fws-#ifDkV6e8lxpQQ+~rU~MI3A0(D*HB=^O! z&|{u(zZ8mGccA~RZpp*XCyj4@$5XVZ2#S{39!VsM+E#xLFeX`ox+G@y* zv8!VqSiTlhYRAl#Avj=9G%=4?A7mZ0B6?a7>A^}{gGzSHz}49QQ>~`g{i3}Ks=QV|4zsr^e3m_nA=ZLN>yj`yZiI$ zT-3#RfNmnX=&Isu5e=q7>1~V_6q_JnDKIWzAz>1V#4ev#whMisP0f*kCSyqEsI+rZ z#Zr#H7{K9k)pY37js^F1A1e1F-qXx@U#-ZH8{IlO$gK0Aa;)`e3hMvdU3I)QUv=E= z*LUj1&vLxU`*W~b;02XP#z7IKyDjVfx>ddn%z4^oNPk2D4({h`vABkwFaaG;NATd7 zk}i|C4lhWk035Clw2X|%?Pk&qiQyhzO(~sQS(mduPwDiNZe$xO^vqFug~DUh_gkaN zSIjbYFCnh36YuBHNLSyq;y~Ct5IMltn72CXlAY;!9n5meh1*~0E7t#aPYHxbdG$z+ z)}D0YI!Hz)s7#yb*{Kd~I!36HUce0Q{VJ{wz?B)IwOnr_d_o~8Um2pw^X`hjx>8XW zg4+LDtHSntnoHDGEh&2pjYh28raS5;kbn}O+zQ0Xuaa6bWcU*s$i2T^ivL}^D$t474;*$fUy}#d>3W3e!-P=+f)W4aC`O|sHJ{2HbX5`=VVc0el zugjM_d1|>iucF?5T}sm$UJ!?nf*dxFW69=tk0A5ucZA*yqE@zTPj&YcflQ|_+}0*^ zlBh9K&KcLb3LI-Vw#k@@IyO(_h=Us_-0smO>gm$%J zNCFBo{;e6zMbPldlY7J#jfwO|Uv~r#t6Ve+<767=&Vh@5`Y-`=JK*e`T>< zsP%>})$2>YVCavbykzM(K81E`I{N836HCkBt20L3z$A>oHL@cW5LshtFB(a76hV!z zSR8jSb9GQh$3F;HsIx85$U)k&^eWaEJfPKO#VGC#Gc}PzHB*kVX;fUp&vZB!S)Ipi zrTk-jZ;TISxWMowy4D-=_{bscD_gq)a6k(WPSH+aMyIr|Y6p9ez=s5V&k1?y;; zIa3Ll+qI}k!*4)GDDxlfzpXwCF*`}0EKHkUzduCyYu;bUxBhn=Wqx>7f4Hf#*{oW+ zk0J-dCaElK|4V)=3T6C{omrdoX3uz643{Yqf>2RY3oTt}3LHJvfC#&CHTkddnv?V3 zSguk`1B>hV8P_KAhu6ZNg`-*B4ezk|-RG}CG_Z7gKLfT9-70%FHJvmKoZ#vk8mh2H z<+;{l5RD=HRRCrW`<|;82Ae8#%bbMJX&)3xBK_a&pC%bLxHm(lm4i@;`HY^B&rQ2F z@@N=o2e#4H;w?zF7u>8jTNoU``^K5BOMe^(y_B?+ey3%75j9x&M>RIG>$$DQavSa7 z_4QM4ytWwhQoMsy2WB}b)vCRCC-Pm9`u|7NSw_XRE$uoGT!T9Vch{i7rE!|Z-QC?i zxI+R2cXxNU;O_43p43NP#qEJw%uHM8+$9=cl!#iUYtn?0^e!=eDuq>|C$=QE}X-N9&AKI zjQ$4mM^5GCi)LfXNeStX{9t!N-cIt+M>-K1?Ev0Gf%-4IGTj$DDDE$R?w@RXcw0Ix z2RO~799k20pQa8OzM1W3JS_z z>P7rxyxQ8v-6*5MoaVU6`vjGbvX-#Q-9TF;d^TLar}byt*(NxPo)9+gx`InWJO0pe zbrQtXvm#d;N>#-k39iyzhSg$1DQNKtKEgVN%LMozxANV;B1)U5)jK=bb=_^SO(#DP zeC-PEWMe|cJ4!Fnj;2}&D%*~2qte~0PY{y>m1o)K8a6Kud+`xrd z&A7bQyPhp<=jkV_y+<|OaGTXe@UVRtYx0k&n{$tK(7+;TAv z>iA3>Y~NR!MjJM&m-I-{*pAOOY(^@kV37h?j;_yAPxe$z7<2#8Gu3L*Iq8b@nn_<- zY_n|I1G!b@H!s7%f#Y>Q&pFCXSpT?IR|KA~ZO|2k&J4AGSO$r~HROuov(W~FeO?|k z=x3r7Ey4sJ<%K#1g-Aq;*-+jmLSGKO-W;s{`8&A1%QYSW|D1g0@1Y`eol|-ZmdVMj zj~We*l%|tuA#R%!{qB#9gP4hH&{ zE7sm01GM|U#c%z-D>=lM5^)@62m1UiSJ}Rz58#Ks zwOTCiIkoePvGcphn{xQ-U1^(ek>Cn>_40Q0YCbOlsUt<(q^S8rArixxb%1A5lD`Mf6ctrs{yM15e z-P4rO6=7-ET;?&552~s*)PDdaeeM^U1d>AcD5Jk&bIH+ak$m`*th!kbJ(SY{p<26- zZ4qNv^O8ir#5riU04CNU3!VzAA2d8ElvcdJDDEGLw@L?`1>U0VY!h_Gd_z_`)x;HN zx!VaBWyMmtmZ^RaP$p}y#@;+SOu!M&AEUH_$90R60Il&+Bcs14^@4q7CPH8;L*${Z zCk}wSh@1rDi@i&Vv*x&gpoQ82PU434Csva7bgDwv)YR+wxBHsLf?y2iT>P53J2GF*(5HUD zE8{>9kr(cMx@oBG_lM*gGUsKLkocW=J6vLNtuae&7~^sf!i5t(OFSvvM|PRr{)dDw$Szr|U%+C}Ex{fQwjZrX;lw{N;zrjeDK+YU)fTXMAA#?0$-QJMraPd43NyR5O_Sfrt+ zRc>l5PxtG~iBoS2x~7dpp$C=s1FC!@m~lW~Ct2}SGq-Cw#ZT-@Z-eNVonyrVgeuk* zo69E%Cg^WAb8et0e;+37AuAS>Bo$zkajWheb1&@fRyF2FIptOx|eI85eA zIF1pe*@0q?hY(LuELkb@U!f^>BRGGzUAUdQG%;$3i=>7&nZ|&bRfGT!@Zh8_)^21K zw!uV#_nwzm@97!EE|by$B95hVd;s4cqMuJl2o2Cw0V%iRKLF*r9JfTx2#G6NQ9_ zpC0eTHQsX6>sc`-yKX2=|9nUcnzroa*73&JV3!Jtc#)-Bbc9yc7SjMVG;$J3-uis* zhWT;srUPRLRZ|JYv&P{eNa*NC=e$oUN|QLMtdl!ojcJi<#6L1$%tQJz=a$o9X1}qD zYd8RIIj+_v1e*8V_*<>UwEg_fy*DuH9zrcg$!RjbAwEXeelW-DzN0i4!UW}f%ieDX zH=BJUtKNJ#3 znF!aN$Va<`pDhLED7>yj0pVdfs9BR?0H#(r@jESo-VJBrdq7}{-H~qu0$fGN-?nE{ z2EE2{&Dp8PH_kQJGAn#ZH$0?wh)!-O2oeTX`- zHB@~XOQjAD;Zi4nBi=f%Mn_S{>%8G+T665qsP~%ksKM%;jBH zSnQKoJ<7iw1Ul6it)^&>B7FE)v}gNq&J)d(Ae=A9fHHC*qd}GNysBNlB*m@zoTck# zD^%fm1CGP5QIL+3Bd+s2b99C>hnb^?nw->(?pG>CSHPH6^g==o$X!X-{s=597B`KO z`a>m1_p)Wv0YT!2OLW8>6MPlHjH%6Fjsm81aLvw&e8wT7F>7t6Ga5q_=3%fMx~$r@ z4^$8Z?vVwC@4^`M$HiPdxf#5NBLD27K-6+mvpiL1%RI)9mSHYWzOTlEi9w*tF@FRI z`k0nATFgsSepZ&CKK__n7FsC4v@_PdQtPEXm-pKjh$7}zI!X3ZMom_21jqGT`EM`< z11;aX>9rUrdX=O@vi1A7(QA%AzmuFKF%kJ8z>h z6b+z*cl`6YDv!w9K{QTp9>WRSc7Tt>J7Aw4L=%Era7TVy0VEzEU~l<#*Cnb)ka z4SYx5F3YN>$j5mP9=Qnv%F%QxI7N*dTKK{6;vh#MODN9&q?}+CDiK&_7i|;FX8xtx zv7o`w{12GEvmg?j>Nal|^q<&gK47iMM*uhwF#8AY7ZCOaq2n2)YPwO?b-_#D0F&oG z%QL}qE1Tih1HGVms(-pr@z0PTIf9+%<8fYjN_i2P3pl^uC1K@!gRmCLW7`^v{l-_r zVb>JF4TS)L%{Ma?d95_ZkW8gx465)457sPx6%yK%X%Me=4l|@38@`-t)PW`Rx@qCr zkE)w40dP}LQTCixh$$J6c7EJA@jnm0gF#|g7RNR$t}|#nXFu|iK0UVCnHu%1RT;0k z0;PQsO7Dpm-U$`!LdYyqp-?j>pePC`jGn4{etIrJMG>#S|6WNVhv3`3xeTONM{2dq zRfR1waS(y;Ba*)#-hPCD7S}D`1jYQ?JnujAXj4*@rOf@rUdkn!1v+zy=wHv|;r|#< z$90?PDK0MtVsjMxCw6$@__`fKFLioE)&}l~fNKaE2zN!kLWJH?B`38=V zvxQ*Ay)nB!A5*9tZflhiYX%~=G>@_-R-D2lrqx{bm;D*9^+_qcrdG{DjS$AHU@3nB zlTj(4kR&WhTC6CBC{A?^o5ZIDi5_GdSFsopJk=NOEKSPQtbn zG@<6r3>~-is_h1)3m+ldPM~8)9BYrQ{o4p!(ruD$=@Fz%YETqTt)yOsZ7JL#WXb7> zno##J>u$0YgYE6}+wjOn$ZRYh`T#U^Lh>TD4JQ>Q-6xnpw#Vk3_=JQ&G+3m*dUDj> zVgsUS)(RxsO>Ca_wk=m|K$Z!EQhb;V-w}vjc(my2mL+Oc9l^~gd$qM3gkTmY4wzx8 zl(Lz06D|5uyi%$6EODMT&g|eAwJz_=v-`bm!sdF-s&1-KPRk_ZY^9885Ioup{IFN= z+7R^_|9sO1lqPZ4?ih7R9h=COl9KHgc-#m}RNzIUWxRvlX`CS&|FaQuZn7XLi|h|_ z9&9*`%E3D~**xL%3?2Nwf5a!E(@lW?hZB&pb;Y8ltA%nBMB>N2tjW%ia?wF;I4;~( z_dlL7(koV~E&~5+d4r+wB`b5Mc?GT}y97j0!}l>p13mAr)J22HiT~t*NEJz7c&ow2 zA}W|=To@PkGbT^|88t&bbq!{3%duq|r9%}^QrbI~VIqq!86q+~RHPtT zH1WG4Y2ovFl)%d{`GV&AKQ<^$ALn*n2%txmQb^x&`q9L=s^BQ?Sg7Q9UMi|QHyHvX z8M`o`!kE_I5&%S)vidoCfpQ9_vkJ?Fn4={xuj@sO@8_^wg)Rtio2-9Qh;iTm89axc zYO7TIH6bppJjvwfprE`S6KkK6ZK9z&!%&|QsAhP_yIr0QJvgqw$Lg%K3z8AAu&_9q zZNrg>#Se||d(8#UQBVx2lCf6GtRQt)X){PG7;7l$hMt}2JUt&`sW%%7fXbPL<$XVy zU^zeb*7Ql#-$WLmXKSifqb$q!y!#bRcK3_MCfhDIWBki6^U9M;scBY4#uqU?b;rI!0G;XPDnFty-t8 zfXX?HHw{M!T1ldpVcWc8QM#W<zP`0m9pv6Uf)lwWeN@Vznpf25N~Fq!_j%8v?!i zrac9V{bSY2v!9fxB?~b`)s~9{1~XQ-N-UppzP9YmT?r|VVSw&{j9?v^v<(Om# zawHcc%bCf5uq(5KHZ^CV_C)^9{~pRIHY-dvG)GE|ZHGVSMXCM&TL*b8^>d!2l^ti! zKYebenE%D4-fDyH2&{#O0qU$zvxOS;|JF_91BHbSynRs}>lQU>!TXdHzf19K!74Br zlAqOwR}i7bot=!2z-=PktiqzPFn{YrG}`X3d4}UjN%KL+^q^N#S1rMGXufdZjXw#Ol<ubOUio?}bes)O28XNvG} zj2;T&FgNHWO7#b`n)g8ka_P=@m#YLiyl#pqbn3;mwUEmi-s(IT`+PK5Yoeh_d@Dn@US)!et?gw8J3X#IGhv_8MlYETgsc)p<9=BruG@2duS@ z(!W6%U}x&jhnf5^yD%Qx!j0B9J*S8=pBw?o*XK7B3{MtCCq;7Rn~#+D_kA1ky|-ek z*x{`=Ln~qCHvKb`=EwH~Hod2ClpJ>T-Yz{i=j<6g&Pj+qZBOwDTd59P!K;b>hJFg( zS1wGZlNteUy@sYK=r3!a2siX2!*C-xVMJEKF&X$UpXpow3y`8#bpq>;PsxUFj=oOX z<~SgfB3DV1%NQR*%ZG4+C8pCYZ)kpjT{$FN4oqn_J+Kvh-|ltxS0Ocx?rA2L0-u=8 z>~S|BuCkHxqF4wf=illow#RA`U_ZFBmjI*&vwR~V-e0qwiXP@|)9C2S;wYUaUy#$Q zz1$kp%*ISEN{VR`UyAL?Unv4cxk>qQQ$^&;xfU`<9?}TqTYT$Btjm(pK7V|QK)Bsj zsYLx1yNE%IxGwQ@Y1_cih2SNM$nz#(8B+l2Zo&Dd#ah>v9RahhvahB}gA>!~e<%Nv zc;rZLWl!rR%sQ`_?ziqnaxnhOr~(gvtl%&+GV$X{@*T|(Zs7OK)gPPLEjgQSR$*Pn ztq=TPc2Pb$8ce|f|TVtu!gFI5IV1|Sa;rMrboUUfsxCk_18>doQ;KNB^#iMTID1<--rl^m-AYk$+fJtCb+WV5Ois0X38*UmL z<7S4(LFOp;UZ$6S*T=jjYrX4#Ugd^G|GLRW5W||S{FH$*#6GWoxQ8buK!LyW^C<{jpSGK~dJ&VwG5R+0Y@rDw3@jjuL{b_^3eFnv zS*0 z&%c5etbVM}S-5h83-6-{o`_9K9^KeE00rZ=llV6!;T^hIsDm0351UlbXdv9%Q4(HQ zUCenvkVL-JyKnQ}^H{7iCTttHe%54oaF(U0do14OdLH*P&YH98v=)@BJZt;z(H9O{ z*f7OlR4`g;EUAjQI!8Wc4=-5T$QOREb{%3ql*=4n$Fo6qSdfM_G@qo)Z*?QxVvP3; zq^XGNE6cj*ZW6-IsTV;Q@zW7X2D)#s$pd(R->)5mk4j5|^U5_XC<)I4>GJJlp2g`e z6iF2+Sz)p43G0JJO>n7XO7YEFZSEy&9n`*sX1Z@t@yZCnh$0Hp}9{ z8xU7!#tKl+yqAhi;-fn*6Pf=bV`VCGumkS->LiqVmd|iJDARWzDdHMYfLmp~-!-ENz{ zo%lQ#MoT>kvsms@?+W+qw`QFQ$4u+>h8MbfgL*@GVx8h8foL zZmDmN4h9+Wsen%ofcKx@1Vb%k6+TX~O%iHr*^G^i=is!Fy^>!Tx6VrZXK~X?y}NH1 zwA!d2@K2L$w4;^%qUj=;@PHyN2^wczTp^`Yf=`t2o`FLV^e(XvT445Nmv zD5`6tlQy0~jg`V~ymZ_4CGc7vW65SGtpzkV8yHo;-V8$KNdD-!3Ta+jMyJ zm%ck6XM|^|T?WtA?)9wXy}RbbE=NDx7=2?lwCG~B8Io})xNoqqYYK1BE)#3b__-$x z0%6}ceiMS4E^<@L;IYA!K#~$^_oJp8yJ7Wv29GFt!8TqzjQo-`!B1_-dhvc-4HJ`h ztne4*R^V5FPqsIoA7ngiYYfh-CbRsh{2ZEMQ4FLy_DquElkZGY2@=y!TUSIr8{D1j zh;qQ7J|%>xcuP#JBPfz12-?X-7{RPsF(dNKjB`zTrPtib*+H82gCAqh!atNXg|pC< zw2C!J#`k4ntu*v9RKsZ%;E)?ymeAo88?sFYXp$=<@bsj$M9@HIcr_rF8iU~>EF7q1 zAP5YqPaz>-+}b}Eu7Bd?cTe7{_s8xyQc$3QU$-y0(bA%#{llS<7Cq?|g!7HD{xaMD zoh=By@c7ctpb_>otg`Ija* zWot`W>zAT%OJa_4lx~sYx^Pb`Rz^=Y6q8RvtgRW%mRWJqIeOq5e%QXV77)e0ZT-r9 z=ldflID*Hws{l7oxxNAQo%>VKzNJ7~E*aNY6fR-9y)S8qw;y+aa2IXM`*YE=LUMKB4G& zcR+=N6kPSUuy{-9W$@eJq7dML?=is6oCL_nJd^PK_8%$KDL3)iY*9ofrb zhlqN1bTtoMtV@UXLr5esX>({pgj|H@tA%B^zPp7)?)QH#S>6jsu1|_Ietrx}w6i-A zxSFaBTTmbB`X6TNy$pIf7jIZy2vscd*x)Fy^|Iy;g$df3hir zR~aes%AzJ(s4W>}+MGpklCEV^f%P)t03K_dKgc=Qc0jP)c4`Kz;`YcvKbB^lq)peW za$DJMp49vI`}}+4KH=0i7d2~VM(>7#3aewwrG)i7s@xZ~HoKDyWB{07Ef-Ak)%UFi z`@e6&KVN+8-liobo=t`NX}0RADqCQ1xyCi&17vtO>O4m%yK(f)oq+!q%Y0j|G$*YD ztKQpTf8=|M&L%GEm{oxFt{s4Pk@XbiPjE$zQ)#(&r&$!R6*ey6;lFIdEP-8CA`Nlc z&~z8>+rUvCUCJXA>1TEfnweSNy*p= zQ&Va71a%CF7QAGt63D^)IP|cNck}GKu{0tl+k|;Vh*^=cXwHm$w#drVD7!V?-O-T| zWrL@W{Wl$OYGd^CwHx33cZ5qxO+MyQar>YkAkIcub1B}}G5;j<2>VPI?RT%@?PMVp z_OB_=+@6h>ef8%r%#vKXJ2TWKCS#T43u%@r>q7MCCD;vi_vb&rF0;6aR1iXMpO8pw zDgWK!;Ah*V4E9AD|E9L6S!F<79_b^bLx(lv~a!G%QIa(1!uq=>H;3Xe{ zWrgNte2wDi_-DJKR#t28{z6}OzsH(1eu1MZt}(6{5z*>}FZEoej-jm3rsgX?snuf+ zY0QI{HsD|o74@x}+F1j{ICZ6|@nkh`r9M-9$tO$j$uKNyVmiw!kF`K{4lhE<06$`1 z7*rT+hEHIvs`>1o49EW-v#-h2qh|wwbKgg(uc)E9z?JaqPi@Zsd{+@?@GifnIu;&h zK!OSs;OK<5g8y11qK?z+h1p7iSqdmR|Cy{7zEbg1A~n7XsIB<-Nxr)z33q3AcRrzK z-;q9*t1%&})_->nfyZ@f6dp(+8^@3NG*q^As65lccvRj|0s3av4rBx@SI(3>Vh*!U zI46ez$^;8IvN2(cx4LogQi?ZTI+om;#=molB>F%9T-e#1@f5<+eUIk!Q8Lu_9c= z8hl{PpR#f)NyNnmJ{}LkNbqETk%=~X43_^d{#I|+czFJCtp|yP zIX8nsTv7d{{zmgySo27+vf7zX6YmGmO%{IEL;7kn16(#%h6JS9;8W@Gv_PUYbQy* z>*_)fI{fl4`V1*t1Vv{Gy@iDNbt9hMtS*CIIj~{AREaicq@`%W#ix*VQC{X(XauXZ zcxv^eXiWU4ik9Nrbx#}75Te!GXw2n2qJ}}&J@3OMWgmm}83k4OQ7wBM4Om7s+EYdO zVOwWEfHQT2D^jLLw8fpgD-;0=~TnGu56FrwO;^KWFmIt_V*Y^PSQA65s;9v@ga$rg`#7Ypf# zIZ)P3&Bt62a!vX&1bGH(m8a*xPZj`CLjhvoAAvg1FjXmdo7-qThr6iWFHqz*fC=B0ScV zNnG9*;>OWw%YkpJ%2iS|uX-By%$GB`b(90>Kv|#JdScDss)w&>C;Fm?<4P32((qca z16soPmg*z;TmkNd4l#LOpVO7ECPzf*<1`CMpLjpMfbFXsaOg&5_TOqIJmxbyy7-x! z^F@A1uFP4Wgpn}8u8TfXmd&?XE6dm*&_!xgt^hsI<8FY?d9|_iluKGb>{c=Y?J%XPX!OEM;WyEp^2yXhW83C4nIdRLhyr_a_!x6n z@*N4V9L#@3V3#o9*nvoXG=za-E&DJ_ku>C+oDId?Dek7H0%B^7Nw$(xD0tc}br!ob za+V5mG1Br}pTFSS6B8hX!YETZ&1;xJJU@d(;MgR$-)6{7~T2CA7Ojx7TN|&#J<-p;hQY2sY#5kK;Trmdwgd(IuoEx7r!uOlaOl z>4$>0ZId!jw(1vz8zT9LSBriv>i`dD$B5TwC| zrOgsdLhoVv((YG1+umAEtYKQ4AUTiUtX{%s8_({fu4m(_1-venk$u#tgTundSIuW! z&E@Nv>!^J7n9&tNGuPoTx2rj<9QD=!;yO*>U+0DAuaPmo9B>7T3A{TIfIyJpewy6V z(^#^4D=G2n4SO{u;?u*B_P9<$^vsM5t#}B2MbzNvT_+n8EfAPPPp8>u@P3mzN(Ll! z&`hzvQ`+V+^^Gy7>rrf>lvlnxC9nw}bd|(9sF&s(Oe;XDm?^%IHQ-&<$7{n{Z~E?k z*uIx^Jz7)V=y<3RJ>RL^AK!ez$v6R&j><9hYthkYR9+}7ZWhIH1ols-IMmP6KZrF| zy&4R0y2`w><29XvbY@_i?glC_?UzW>H6;t-=Pm&E&+2^3`Yaqcr~*(7I+hi|Ec*T* ziq``;0Y)(pD-CsEo63K)TBKK6@6J6R#!EYotg+YifX@}tq;Gc^SDSw|=|kTkB&$j7 zI{){hFnzvZlZPt3sxYF~;E82Juv=#HL7G*Z-YLCxL}-V7Q18Q_fXs5N{+|+cMRLm& z-m<)My+>uldKWKQ1KHFPwD40x&q%rRA#t5dNS{_$M;?sr@YtcCSb=a>Soz?wedTA` zsmaN)!F`;}FdHo{dH_!;@v*|!uQnR0wO;b@{3x=wV_b5IGYycznu&WSa*(sCaXhCD zvE*Z`E_L2V$Hc89r2-NnGjLdTgb-Dlqxk5%zmL{fkxNRBixDVDxw|kmmOV%P&yj?cD72n@VD> z6&z(8_w^XfT>U-!4Xv-U|2&v=>R?B1lhE2mUw|1gyEEY*&B_H6b?g^}Y|2B>XVToJ z5`n2nvw(eKYeDDGRQC7rxzowfZiYf`CBOdcZ6(ntE9=txaqU&$&E)a!?svcp1DApI1Z>>P|{Hr$FfT=1G_z>s<~QOl*U;zN*gWM8-kmY%{a zcNiI@j_vQTQOS>5U(Agwo+jEG#}*2KWiHW#YMx&0FxJ&#)*sn1xUdhlJsq>0%8GvQ zR%pu)rp<$nVi_tmw4sXF;%~fK&nkyb`cA%|Q!43tM;lfZ)zu4ksHq2xCg3qxT(gm- zFNlU^Y`W{wP@>N0UEJ8#hwC3vQv_I9>0W}+5Gr<9*kdeer|4yQqxoAl0~ zO&Dn5ePsy`M7qj7^M}rRloB0TOlG9q*KGF_EMH>;)Eg>4fmL<}3Jza7{jpc2LQJNy z4eJ%f_3LPwRD!K+NJCTXMI`v9kg-C1Mv0OwC9p=8OmR0BF%N(C61#|fC}ZY98{un| zQ9MibavtQNT3ko!iLipb;put^S;fZft*=nP;r_|{hb_Ng5DuL}xe;jE)D!-}+z zk3gp1#W(HyF}jf>ZNIUb;zacmb*U=&WT?2n%j*q)< zCoj)qA|^-d+6~Us2~X6q?f?5qpzvn=TuyF+a^YNw4ig`$=36_8XGc+D9T`MJCOPeV zz2LK6uNAk^az<+F3z*K6%u}n<9gOe8kuMgs|NHLlx52+Fh1&|x3pO$M$8-c&l0lPf z22vi}%nsJ~4}=uT$gmgu!CrkJu%2Mw!$WQrmNvd%h~LI5KZc7ErqU9;lg|qu8VL9F z4hQu%qeg=s$4fhgnIW6nP@9Qn@LL45ZGDf~=}5c#BXoAZ*XOSfj69>uB6C}fQE*KS38&90g;l7;9Y5z>x7H&;9rOZHg{c2OtvWV`pV`IlVK|>FhJmffr0^E zqs=CmAp`l;?$RpHRd|#t9_b{t=iH-(WmoT8=XHp(A82Xj zn~A=4bOX>hK9LwuyS$r5WLs})P_gd`OY|eR%dF0q`k&A&|1m<_~hNr<)SU8%%9P={A4MHiP5h)gWVIX?qS?j zj21$46KupR0|U0R`Q`Bt0A-gl5%$fBz+T{fY%Q)RJx43EQXHFM|5tZ@Fax9ux}abm zT}G?MqP!6;j0{gDH1`rVIafwcqf_bmc*K+vlbvy|*w^eqAO(=}^%kxz*02@xR`BL5 z9hcJ;GSKmsCMT+&aj65ND9ahCw2V%5NlM)a>f3|#2FwA`pExG3FYC(MNAv7x0&F{R z8CxQQF@MTjF$X@QL}vt$ZbEr43AGJf;8(vE1AyvhEzj(sbKac&Eb&;Wc5*EvS5DtQ$NH z#;oMG4Chhy$f1kxwbTfqu}D1v8m~f(Bs-|kQ2aVm9c3H>>0!U zz@WKvp&%$M-$45@yT)SxnS!@q_Y`$qbXuhr=#dz0wJ~sFVk2~`d6sTqG%4KGGeqEp z{lB%zcYFAGh}h~37YPq?*o`hylmy^!WbmKmpt#)WLE8Dg(*=I%1LA%OU}KnR7c@56 ztcF@uww5|T&Kmxe1_1i}NW8|E_}-Q}efTOn4)9G3^z{_|MM)8Qz7ThEOyU;J?-`Sw<{USuJm^HD_Y% z_g6UB-83^4a`o|xj@8!p_G5Umb-9e!jT%NJ1vBM?8SK2g_+XnhT#jmzm&XyYt~E@s z^%)w$yuW!Wj%|@EHwN6Y(xppwVNb{m9rcatBG~zAUA@hhoy&Ud$LJ^mC*DMf*}{AV z+~UvKb6Z+_4sBcR3%@(*C_HZX`f|~u1k1@vqNkBqrtV524?2a!18nY7@IraXYyM|9;SIy|I!N& z8A=Y66AF_=p}SNqUv3tAFOnWmzbTyqh9*XB-EZHM)!PiH4Gnj;!Xr}ZWpiR>NHdIK z;TP#Mz5|9d$!dQ~sljQlXkpK2E`2UBl4SAvo`|{csq!79q!fdf2)o@+?nMT(s*eil z?&+j?P6hH_XB90N_z*Kn9(S6gMADYNat-%<*QzINe{o(FbBF?GFH=1o_A_TnQqmDa zfdd3r$A@K#nwnHTs)!qR9oU^!$ycH``hs*qyXB=pcRJ@>jBLy;%*kJ@-<@gUvil~;2z|+hrpYdE{^ArXgx}Dhie4p6509<_Z$IwsVmVDr@M1D# zX#Q6W=>#isqjp_jKIo@8>>3k+b|npzwZm0N!qgX8i2`on!AzRH^OC-oXucZLbt-UR zfKQ(JaOK+OW zD#1=WvH?jL8`Z!)3ppYDWlJ%swK5lKwTxa-U5|V>S|hTMqAf3uC_P({+-vx7KS#>I zfYkTBOmD;tX+X!u=>^Yhi>&kd`Ln_E&HmG^%Oai^cE$CZ*CnZ@#t?#2&)ITu#22Ic z^Hm(TkJnAhwwzA%TfH{WVAT&;*2wqXZTsC|_Ddx)Tg3maNKx>V>4%if8Sd4q8GBFb zKu$Picg??niKp0`_p*wHe#81qgAh)-q{CtFn!ETMmc;$jW#?_oN+S=8IrL%jqOQtm zUwqew{pS=W9m_L|BeJ~4#zqIW)!>7-%hp%hyR+q49!LAF^w-T~?5))qfrcyO1nADL0GFK`Se2V#NMw6H%`vLj|N(^sY3V7G&s# zi$cW2HW=IkHJ-WWXu7YrHYADrj%qOSD_bWt{S#xsCLwTqw~gFrTTh?21ItAZf``)K?9=+$0sZ!^0`QaK5$?Ui9-$V_c*ZHwB9Ime=_)(C^Ay}wl)Kz1 zGL@vOhU#53+K!qed--kpZUcD`$4l+h2zGwWFn}&C@T5ZQ+#JW=!%6t)C_dC1dRNU? zuhil)3*XH;8{Wj>yVXS3Jyf?XoHHi4gubsm;r6gUktvn1Hl%#`FCOrj)Ju9h{t zb|biS!KpuT;@E!UD;PoVv00NzI!fiVi7TiR!%W;5X?fo%MnZHl)ku*^H%2ysR^MNc^neMMyW z94+#?FOk(k3<2goTGTQZae5A7IobmxNeS_j`&1PhtIva)&Q9y;KKRTYEInDhlcV>BLb^foKv5t`cUbW?oc7dUgTcg^PmBlPV)Rpwp~~6 zsXu@Ipw9Buw6W8?B?d8i>Dp)!^3*AGd}gf?it?K1{deua3L|cg+&_9niV_VW2iDm9 z8{G`13xFx--7EW5xL(+>GO=sdQj_=)Rf~~rANR~p-V3W)zk9lcgIK`C5u?j1!`DU| z_p@oqXaQtuMZ34vP5Zrg$(=~BsMruMtoH{IpR4|Xl4JwV^a|FVs@m3lJMt1x6+thU zC9mVkimKvMIURFwpQ)s&Y=+?U$P|A6LWLHq-9~$dwu!yS&t6P~bf(TX{0z?tXj}mU z^g+3_sO!Wc!?k`|T>4d`y``s-S!1sVYlXq)5q_pa6FhbYHi_7*{NCs+He}Z@MEb6G zi8dcrCUJn8nBSkm>@bj>_LbOx;n7qN&+!wv{achE?tBwAp2O;wpbC2^*B)Yq07iAj z{d+okf)$r&wV3%{;?jiM0(%(5_^p!frfEbSj-F)fW!!J1+%f=q#l@+w4zgwZ2V_eb zGUXx;(+(Nh(S~wQPGs6|4+y}@d-I!J|CSN^6Ou&<@xIyZ(5C^O9-eJX zsBhMTtV(TY+x7PZg)>OWKd~97=2Jr9@h`l1rYm=je@5@K_j5b519g}Ea}zvEx?l(9 zrPUj-p6c%l$=68ZSvi1YlZm(_bJYxw!N*emm(I z6U|`6J=T-81sVdN!|_u3*+XHfHX=V~mJ8kZq;}Gef3T*PQOD|T3o3)39i#7+7wxh# zcnlQ2WX@-}t1`9qn4RAa3jg?-;+SLHyEjKdY?c=P(*rFp(-M#@^P%Ez)Ni0o-YFNZ zM6*=0oj*I7_$r_!AUX91d$p{y5zLeQ%h2Bb7=6U+VAPWkf z+`@5#4?XVitVf!)SkgIUUr+)!cp^L+0K(t?Cqk7Gg#^YK;Rc;w36j&D5*B zE?Xo8oHXkHv=BVFD!sjR2Mnf!UKACQI0RdVRG&ru9aT5!fLOy58_L(e8dfnWJ9an! z?_M>y7I55+9+ZGeDc`NmKCXiMU;e5y+$fiYuZ8_vSYGer3Ca6o*{ryvL}?Wpb^`n_ z*jN+!wqL)TMq^A+f&IDyNJT^SpMIb{-P`%*QR$FxuO4OK^5J?bCB-h@F67M&h0lKu z+W9RG?cq*t_qn~N@B*O~-)ScWTMx|Lj$dHZNkMWx%?#L^$5y))DBcpB$0IreCR_8VCNiLtvGWn z2sajm2@q{0zHID*E1@#TDLuvATuI_FS~T?rWy5roWp>B8qpngEVaG&f;x+ zzt$(o8x#LV9^j_EhKM3C9(w8_CHz)G@^U|NfQOlyWVF3A?{4%V(f-n7JFchgU%_{} zl}b=lf=khkrMql$o}}p9Wjs{<0nc;sgBW*-9-r7u;EnAA8WPz)41wiq9psSgc>uf- z4BZ$bX2W!=ywto}n_=#ff>!p-GuIy#tr1qn`r_Ak163hAK_>idO3pfZ7?ZPnnr^1Y zDqBBzVKw*uafuwa@eBNOh{9OFK!}qQtCuCdBirw*W*R2AQkGH6WCm0Blwawxo5$57 zKgpk$z9oPU#$m~Nzi*y{mA(Iurn3rYD_WOuTUuO-6qizp6@nJG;_mM5?iSp=IK|!F zonpb=U4pwi;il)Do2NYHA$#qA&CEYvY@YA6OjdZFiHs_kVt`oVM*oj9Cxz6QSbDMc zknGX6le-bEjH=D$Ub;Om^u@^ba7gbR5kcREC`#=0&12^-U~TB9Gyc}kF+he5JKQT< zoY=if2Er${32XHzW#b^g&a%DBoC?@oJjRB&OSZJE^kUKH-i43LeHiOyr*cb|+rjhW{{6Tl3O+s#4~UQlycl zGl$MnBkHYRz_a?`p^*&TvAC9u#>}h2y9O2(v*N0NrW|4&TbP$pEz&25u%I^4(XquY zu!55W*}@MwK077knpi3-L?iXXmQoGIMqoPhO{TZnEYI#ZZX`vZFW73zvg$Wh4QHve zltS0fs#V4vDO|DRi?PdoTDrazpoFEKo3lN2k6o`YVh?@&xp`bbzxkRZ7 z*}@ky78qe`m08`lr`vNbNFxF)GCt!7qoM{9$}g(#^aqc%$*U>-&`(K1i61}%jUwP3 z{80-0DEr0ZzS?jY9tU=J8GU!X=@zE$W$buPo)doq*>=yTcuL{Vow6wN__{t7F3fbC z0MrbLe!oPTFN9+#=K^CQa~89@O8i4fFaT}EHQ8{b5;j5QVW*RM_%G{rS16OcBmh+N zd#q9j5b#W4IG;dkWGX_od4iz%^6`NPuec)FZn_F1Z~c=^kC zwWQRY%7y&Hgj-)7kPW186w?HigCvKJ8vewqR<*PFX-`oTqh2J|*DS2k}W_Vx8q zSwde|aPivi8-I@*%Ilr5TV73yZ^tvZYFx(f8@$-JoH(Z{G}&$iJ+2Wt&*KkgipV%Q zmlwI(AC5-o?;R3<8tjPe?Cs%urb^OvC`ki_6%@2q3owO{kglpr+m9*U4&uU->|Wr8 zI$(-)#t>G1eWi-fmDZqteUe;tTme8C?V9!zr)=QL62&fMSjnK?H63P3E!h02+4Q z>|ZS%(-5w84ArIdqdB|ZYN;&0)Y|o|6aNsDvI9Kj+w`U{3EJ&MQeTy$7hDy3;@ahy z^@mC-E!R$Zz%IzBmkqgiwSGy>R5rGVMJ+HWN0^ZNmDkT!Zy<;eAB-Xp3)2s;VB#EE z`>~?{GOa9|XC^wGJ1Ejq>ZZk(dyGeb88l?*Fv-*TF>Hz@)S*tg<6sI9h|sI}dkLVj zELt=HKPnmH6FIhf@hkapvwFi__-D~_A z-pc_bt|~CG{12BfwTGl0(}|!(GMVoSv+akB_@|K>LAcwVa≀F4b=W(Mo-VBw=T- z69NJ;OYn=Wz30i#!e>ivvW&s^mEGxio?FF-WRn1Z@U&i6erQxj;2#AkaAMFlF7umM zq&FUu&$j;1XeU8feqkV|z8_(Q;nXfMPBhN4bhJBVVBI!ux2M6)rck=Q7HjZ*gtAxr zBe{XQaj3i|qB%(;dOsKKm-x$(=Ajyi2BNpJ{;E|4VK^0iJrndjLM{x&A{hZEsq~LI z@8lxvzMDlTDJySxu<7=Y-LD0k61S0zBzr}LhckVIQ6O%EskubJWwQD%lj(`=eRXYl zIim|9-q!_wisrn-x;bO}h?=aK7;usyIwRpguOQ}>o#1(#=*-?4eT1ks9^-1;4;ohR z+Wgvcp7l?lsKMFGji3`SFvzVb%Hb;A1Geh<)i}G=LWRrSqiZ`qLmLT+@TVw0%Mk7= z5(y|ba%2ap5-&uPgXAM%3N-gVW}!H^wZRQrG}=I> zd{alMqbsB#)*Pf+ssGrc)>^r2j0Sj;1NL6L5YVB2!ma1b)p}&e9RB?cjz~0*X~q)a zGv?{9^sCKaSPXhcdj^a-V8#h3su8 zXaI;TWjuRM%A{h=g=~(GOTd?*8g4p}eh~X)mn_9LnERrcIqg|`3L8S zbadf)@nBYS1dssQ#-=-uwJ%w;-h($pKf%)yVlGrWiylYKqAEGQlTtC7KGCM$7q ze~DuF2qlrdG^ZXDV8hHlk!Bc!u{YR>2zm)f3`MOJd>eHjbe%OrCSaA4F+IZ;1AS6vN|&Ghd-m*?Gh&`x@D^R z`kwEx-`0Lv9Y=pO(EK22U9rJW+>q;#g6a41_;bnv&Dndpax%+^+I=CXO|;V z_%T|gWD(njo1oWyWWMY9dWzRc4M-;?ES}<&++U}~!8lnelb9B@Fj0bcU+l@HX}%h!Nep79dy$^jI=FkhTd^IuJN5MO0q+ZGXyAh) z@eB#g@jBH~pq=boXU)Crxm)L1|H!BKIDcfUtjeEGZwiuim;_GvfQ4@SAd%^5*P}gd zTCn-`QypzlmUnBZkG%W{eTkOC5V>c68j~^NINuwPn-uJ5`H!B_pJUvz@p|S8n)131 z2I|PBF!1;9dW<9iKzRSvXd_;?o?q{b{#`kzNTIch(yQ+K85Ym6qQvsLFP)Gl%Z9z= z0!$fp{)`ACXvYFOw0p>ID+tG6p;8-{7ud{c13jWpDdrMA6S5$$1&wr}3mbrCOLtFi zMqUlI;Byt_yxdaftzY6LRs9dP;xCU`2?j$~5?GQc(Y1!Ag7G(v=O?D}@+Ufs9wvdR{bS2rvKN=*|&_wQ#= z33!zIhzfkr9r7W2&zMUKDo+l$Zg`oVm~#`OQAlT6ov`dKf}<7ZL%war_#kmUN?+r5 z;W+Wk5g(OVUYxe0U2aFQfwy#DV9}s0yP2pGSn63e{9VF$R@%EDgj5^Aj}+ppj-m%-Ofx%~_o8K-Nf&)vS6 z-)(p^EYB1fddN8`h!qPX2l`@%#3GhqJ+tLxf+-g{#LFo<)mev_;n6I-E{m`3e?@sw z9TAbqnV!c4>#;rf%VX$tVn`4sCGILNe^#I2NhE3rMX>(+Hxii6*+#E`xuyV17Wo6u z(7buz%26wq9HkL~@=n=L!`Gb=Fc;mYMNpiiM}*sTYlMZ|d)<25Y?qpug;4nEGoW+I z^zloI07ZBxRk41L$hHM}PCkzyX_iKFRe+e0q@`C*?Fa$W-8gR(hrb# z_(0T$Q}adbB^0DC>c6SCk5sfjR0Q6IqyD7*!Z?GJ_atZt(;x*s*3hgAEQ!&Yx*=0j z4o%7w81B)a@YKMccT0RDBO}$up6^v`?s|?7s5=5MA=6dVu$OaRZ3(heBNyWeJA3eL z{ydw+Y#XqCTFG~{!H(uNfM>$6kXM%vD^92xByym|P^cyMMapbO&cEY?omz_)@?t=7 zz9oGC-d4N2=DId1q;r?yL~|NInOrl-QwV&zaLq&+#$ob#$UgAZh0D>C}&s8y(v zR)A&3BeG&DiSoRrKgj2*8ik7Y6`Y{uAp}Tr(7c72`*rglK}H)jM1x!>4-L=Wr!;}@ zOG(d}_v*hu#JW^?I-c|oc_Lr2m|^)R^jc_U(BXw8c|jBM7}6WPoG8&6cX}MT0mqE> zs_#T6(xDsf$Q%RABAP;s<^0HEzSsq-1 z1KG@n=eh}BVW4D&;+#DP{?hSI8g#JS44y4H+&`uj;PMFw;yr)4PBhy~;Bfp6T|jDXW*2Ih$u*Rb zi4I?Y;v`s5g|=PV7>y3(wA|;EANI%C$S7Fn*&Q$NSb^-dwY9T%chYe4l)UO%^E+IG z$!vRH4A%$9A1u_#UCzwq3>7`$2Tcdk&T-fZ>vl9-|5~P9A@X%T6hb|;hk?wMD7dV} zppdNPpnV;HoH5vSAs}c4Gi222bbbVSux`4}q7bka8^1o?Mj@@Szy3pv7$mr+s!M>+ z)39{CpHG_}RyH6egx15lZ%?Y_+HET8AG=Ia#zx91yOUCTByl9vZbmrJHu{rxz) z<*Sz!YBfFZ6*(+gjYQy!RqLj;;Fy(1PxSs@8^G(R@R3_k6hRd8|CGDufXj%Gf5Jrn zmhaxPv{tnB`z#Z!u0}}PX#1oDIeUwF z_4@_S<-&5(U^P}Ykcz^hc4N$u>0ytyt}BOFB5E>{0c-2zN_E6dZS|B~j zajOI!2Q91Gr_YX;iFs)j-`iH7KKGp8ZU=-A51@!<`BQqoQqp=~vXn!N(C5AHK6QG7 ziP~T8S1uNo94}X$eFTN|YtYM_dDr4Yeo@Zna7a_ok&`syP&zC@q$ydSL%~~cEf!V%q z#*;_)JDhWYYEePPpX=Jnt#&-1D1=shzvquPrvL&oy4}5M{1((L{DSr2FwAbbY_l7` zkE>Dd#n(cLAf9&M8^G3165H_G+zHnfuaS(lXzohnh|YD@Rv^KONJ0M_`u^bh;gMmz zlVOM~fHmCKN+hl9A^4WKH|{s*XrQyu*-&m}YB|;V7OyP3UY%u=<|Yzq-9S&0gXaBT)-l9^fNOpxr&B;}9SB_=J*!J`hlXGn_4+Qw zBu>e9r!iOB?+r0(f2VsQ6AmeE)fI?wy0q9HZdSbWYE|8QAcGq;J=J5^A|~gY>S2Ug zPmAiQWsp)uxHT&X`^LxtB5S9-F%!xM%;6#K5PFouOQ525jP+aT=BbEqLBqkne5BI2 zk*URP9^24(_=5uv_ zaqZFI)|ZhJ#Kf;l9VmGr`T8e|Q>{zNnz*|PlI*rDIwisj>Cfdz$9;nY3l*T(whta%;t2)^lX1=N^PDup|HmMYDqJ1ql>S*pKAtB)b+>(%M26=L`yp6_WCR?6P zz*&`M#(mM``UIbYj2vb-JKG^SpJhNUAKv_EC-?hV%w2CMro=y3l|13jzv%e54sMLP?V(f0==|fF* z#qx+cKu+I9OwcsDb!?pIc6<7bn`Q$ADdNuB*i_UTrt!SkR%(AmS(&L4pHfqQ5 zmp})2DNOzXmi!7O#xFLnJ0w!`A6u} zt20fwJC)pWBvU4Ot<^^uACJnaE}*9_G?DP%Pln%rqXg`c3|&r* zEb>!?si?b}0re@pYkn0g50>gW~*smqXESkb~BPkvjy9PA!F?(j(v0K+cpta-**e zT-x1c_lj_s8d5Dg(~@&{(L`K#wawG`Sf`P!qoUVi6}sAvDC^$GfLp=EeJCmXxT;O& z^_K`cg4^SSH>_wKn_U}zxQ|Ba4Tsi))zmjbno+1#6j_m!lM-($E?VojFGGHEgbYp5 zsp-mFoHR%&i&LMq?CiVkS3b+@&OHgi2$Sk|+_9dqUw^ZDwkfc$H~!&;qNZA7n=|g$ z%?QFZ-CMsi@-6&H;@eDe8T^%Dil6J59#HRXN@n@@a&R!i*M6{BEtYbWc1}wFRK}l*RJKqq;RKgwgfm)K2lwQFw+#6SIPZP;S zUsXOJU;KUQ*Ta(hNT)xEJ5)a3vhr>_M#;Y(s$ie{chREpY_H<7dHiTCx({AMfBXZ& zvJw*;;#YaY{G7}S^S&)1OdR%g8pZPSF5*{SR*f@iM44u>u0$5e9Le10QaZR1Lptt} z3z?-kW7TZ}@h0@7M9UT&DObgM; znbX5R!e@oVKTkFxsf!y=M+f{)otM7aQNtsqZ<((cVj0PAf(M)w-<-t7@nx4QRH)Z{ zyj};Qzjd6;>>^(5?q~g7Rvwv4yBz)yM+@~?p&e%l-o3!l^g9vV5E#R-n=jwaML<)W)aD8e#x}# z82WU%Qx@gpdZt!rHvVhrTjT;hWFxJ~LRt1mXxulyJ?Pl7b{A#NC(?=0FWKpUt@bn3aoKF`)oTl7AVy49@KE-Ak4(2h(ZG}!ufLk-a*sV2~xf_Bsf zO-yPgt)Voxhmpr@OB@r4j#m-9Fu8Sv9jna@cKNE!S`~HvQcIilma1Y|k>e7;#6ZCPgAmNQhdMHwIU`7>@B)Y@Sfx7(C)z>j0;l1D?s8 zZ1}=|SRD}Tdyxd%k%&iy`LJ_RTbjCyax^{8>K(0tkAh0Y6Q#RDhq2t%#0SzvKJl{23wa_yFtS7}a@B zBP3Fa)LcSDmU?z_M#evmbKEqRT+qF-RKmSc=Cu$rOAPKRM#=41Bq9HMLkG*lBvoL|@!O0zYf~Su~ zl=9A`93-w8R&=H6kJq}Lvk9`K#eyH=K#<6hrrJrcZUSE44)QkbTBIEQ#11mQ?7 zU?`2jd1d~==q?5iQ+FEba{N@xiD2?LiZB7wj}=lc?AcTQaRk5R=K%Nm)J$fdhr{W3KXfmDTsA7-!#qs8Rr$QhI?+~)7^}5Tq-#EPzXiV0UbrkAz2i#Gp~y>j z9%K1kHd`i?h#v2W8~2ba;-T?z0RbQ_Qyk%7G@ZbC%7-0_A?GR`B;7-bLzS0ROAo$_ zOc|*W;XPkW^fhZ(d;#j>>z3-ez9?bItAg|LkS4$QW)I|SW4snJw@{=#(l@Pna4BrGD%C7*&6yW%G+*8w@JEv}(N7!OK=hfsY7sfK1+Ez8k{us$Y;L&Z!Eu2#jaoRbw{t;da!gheU$z{A$9 z`_}dIuVh~=?vg9~TT=`Zk1_dO=EnPwU|*7B8i~k`q{p+@n2VRJw;EY~>F-!43^JNZ zkNDLMt*1lHFhTQ55|U}*b~7_GjLsxyoDb?yt#Dx+1CE52)p|7)pxKD)nSll%PrxtctsK)$Adsgso+n(Tp!&1^cZL^u2b@i z>0L$0$$%X{K=Ffr)LyipRR1sK1_Gb<>QjdRS&U|rIZhu~gksRNgP4oedM>F!!*I}7 zjnL5uF&H^g-ao4z3&+FAjlo>%n+!XrGF;qylitF+mZBBixS1#DHDLg{u)zL6_+`u6 zV=R>g8j&$1teE=^)$y99q-UTqXXz?Ktj~+#`2-iDtA_uFq#VJJ(o-JKJ8Q2>a;ams z`s$e~UA_jduNUOv*RC;p8~ZEU%}~+L@LSGEaZ>Z9KT;%Mvu1#px$!P|n^5uP`l1)D ztl_^Afqp;CN6FCt+{#H&E56u$@aK!pa@!7ThEkFvnTZCVs}j&VIQ6}vHj=g^AqNY> zl>E~a2#8tJ(I>>k(42*RF}bF!S($I99a35JkZ1PRIdzamV3>aBVHW0R(u1%eVVz#g z2``t;WL!F)HgCE73^VmRM=;i+-CTqQQ1M4)FXd)@#g@R+%>Jr?hQk9Iy*s`DL$gH7 zW%QFz>YnBB8BjWMlr3!P#d78PMAHYdrR3W*RfzpFZ_rNw|JHb(>YGkWr3FgsB9-MN z<~MD>OdUo_m%}*f;=rGWe|R>p22=iqsdMnUJ-mY=N2nwb(-(;t%&4A_al;epoz&6z zU1V(KplhBgyjiOK=HZ={9<@usogI$9GtT^1RA_Z~oL+Al7BDx{-KuOtdsDY?g^^geY$Wtzy7_i&Js16@9o92<2I{SZRwVq~AeY4A7=|D?eCrj~sZv z7G_#uw)7OTVT|9g(lecSbTr9g-(rFm(#sdPEI73b`dOi_j`92Ni(f72G}wD5Iblb( zKdxOum+~mF9kSVr+x89RpXV9e))lW%gPpuugqWWZV_o9Bv6IsSY`mfaD2;z04uda;lG`rUMMr7? zwx-QQ>e%kE+0`QVRM^!o8a_urVwBKQa=1o6(T9Q@5W?PkboWsh6{E4G5Xs&d*v0ole z!iMh@YTInf`FzfSNF+tDMe(M;6xhiD#eh;S_!A_~vaj@}P#2 zg>`G675#I#=yA}V?T>o@8T`Uqf=2Nso3+`-|372$d`KJq1>f0ep|*(|m;m7hQ;NA< zFc`V}^?su&+WF&5a$AtFs)DL!cv1_ zshq~1szDZBd>qs#2^l?^3JsT0;sg3X>x4j4l_4e@^j+JC4IQTUHr%hXiWY4=k&Ifh zv5ge69(N~UihJWMcfL?w5`m^Rn)I)k-R>yiR>oF9)@jc2DknpcrqDFR-Y1g%o5RI`nrZ z%LNoZxB0bxRu&OxqZ7fSkxJi%7kaUam28~dGOzV4esJRY({BoS*ANjjCgqmaVxVf+ zF@_V==$DUKFV%8wg^lq`fzU5jX6EwSOXGVhg~IB8=j>fuzrPt1|24QD0E1E;Vgwk# zou|A7*L^xZQo?-F0Db-wgJ3Ck_%FjA zyS$yjI$chNgA$Uh75ax%5hXij)K73uU1YC`)<5{EKW6_H@zGX+OAre;R-rC&FdyM+ zwR)mogA5jh;r)mVJfCAmzzbsu6^O0Z~P7~*=T%9N<(sTJRe}Qm~s*?c45#ej~!HUN&w&ip52bVNE-A%sr zz~OMr5$ir>zXQnVMoPK`=A0{vB^_dLJdnIyM)Fmet{6AgxIhv>>+oj?OAzBI))=6zzCp55oL?L;Z(Sy=9iRxJ z)z;bTzLwe`E*0=EBIIF;|4f22kYb@vtP!5K)oQO<`Q>|ER|J8kY8H2d4dEw)X+p4g5JfSK{coHbLRgoXC9ot*Z5O zqSzI3{SJsy;S+rp;d<^4zs^c=?J}z*q7^^B3yrq_f1F7T>blm$As zHdb@Tb0naP!`J{VvlC~c3BLPujIGHvRaL|ALk{8-?!mLaX2!X)S-cjW&!9@5n%?hR zWVCWsR>Hn@<`JC(2g5%|$HRDAmVd}=uXV1;H3UP-7gp@2&;^ENKwCH2rZ&%=^lEBO zU)~`1U301Qf%SX5kA-PA3YOlmlLq5wYi)@vX)Cr}+C;YWKyxX)o;G}?z$y+J*bQ76(Yw)$DMF}V+j$_L|=OxiYSUefnXUNh}h zvG$rj9Ir28>s`1b6Mp2AUC?2jCp4Ny?@=gfXy$^|Isms-KXdy9pvh<>ce|mt z3q|))rNwJ8#@XV%4-B+{-4_kYv3KRwh^lyGi6i$!H~uL?1=*(<;iq9Q zow)Wj$_->`*G-KsDMgcP2K}IxS^tpqbKo1X>rmrUW_FL5wziFtNq%>L z0v=pS3@M!gf>^ji7u(19&nwo*x!~!740Tq_U9Zn`VybRf=QkrK*+@IDUQ3gF%fIZjT?3dELca|ur36h>8asjqOua-M>EPU6}VT$60PW5U%R&75YSFrX=D0>7Vpxsit?y{;l(C z1@j52di^0tksYsjwZ*t)*g%t$Q|S&MZ-OV+MjZU70$FZIGt|fJi?g85gW#qezpOfzZz;lT6nX)Zgu^qO#$> zPt+ji2E8m2zC2F&sO(c=Z6R?0_;H-}Gh8#53mfPipd}n+94&_Qf`1IK_GaP=8oVxF zt|!V^02h-0SJR7WNqUynFC=U>=^9NTZReeu6@~@|%fQ%BdMhXtR@*u)$p%WQr=JP> zva;rM{rfb^ z3pz%A%NK!Xk+Q6`S`$9Ysg-VE6^0geD5*R#zQrq?P+Q6IrO0HZ7^RydQo8W!s1qi2V(kS=Gt}J_?g1CaJfX)zmb+VOgyOZxdB?1!>O@VMe4QPR)?w6cEi=^jg;SPXnqNwa78*6P7u$fC%^myDXqkuB>67!xwJO-19XL8AS7bm z&{3aTpwj7~STQzRnZ(u(?3X3*6O>Tw6k=Sq7I}0_pJO!_Q4COv%5G8#lWnwxpjLHU!0Wgleu9Ru z6{k(TMj`#y>XDpBJmG#1>14*S0A+~WFMkESyk2Uzjne1t@|+)uPc(o2QlR~OSv8*a z?z*v@SA@VJU#2ewfVVMzClMlfR!huf_;ascODy!TW6YaM3OWJNnpXj`*mWOGsHKjM zOXU@n5xRiEiAm66vV5IN^pR0U(GS%rq^-?}J>*~k17O0X)+9H1)XFJ;*Ly*R;|GrB zoA8az^Blz?n%lTj68jDkiIc3 zE!6?5C@x;X3H(~F8eV8kaUbjHFCB#&P7TT;&;(o`A438;D6>|Z(^*|@BC-xE0MOip z?45_mLkVqt5-vj4Mp;fM?8O}+Z z-gC;TTeFI?$}1Fm*Qe0kN9FVh-e=?(?kjj1uG62Z4kLi0Ri69RnNqu<9m*?pX|t{1 z3D4M+-2Aq)R>}Vl0du0I0aIKzkA43mQ02f=f@S$$opvWuC{o#MR?X6v(z;%D=^u`v z$++3sSyatQGwZ9~p4^W1yIE*Q;6QOH>gMJCZOmg`VUgb8-;RFzjf!$mZq@MIT@AA$ zL$)nDvb1m4lT7S#bd>$yty!;@9Nxu)CO(?pC~9#0??3Ccc3W-AaggNQqma4l2{F<1 ze8C@OAKbP-y?q~=Wqssz+Qw_;C0t%^?zdI@ z6>D~jd0OMx;1`|oD$O<(>$l15nCEy|4&k|m4%@({KBA_L=%6fCmI0qzmW5)M6L`4s>(UcP;y59Cigxz+7imJJ6Y5e)GJ55YT4H0!TorZ>oK~>)N z*d|f50#0@S0YBJGCCoXeG(lHMO&6}qr8o?$6?y+zo23-zp8k}dU@7(jK&p~&%EpI= zX+g}Zyc{5PxGLleon{91rr0maAeK1vE)MJ@So`NZ0>-!NZybWIiY}|q2W7Z??!kek z84WaPYh2fMk1^vykUMFMS{+%nvJz)9dYj|+v;?V7GdTj~TA>&)+VYACx#K_Hqf+)6 zS)Zi&lQz)jsF_eq5dxa0{J-W(@@taW1kRQnqsPvQ6A2)M`D4Kx4gnM6$MQb0V+jww zCyK)scu0o(VCP%e3S>7B;4F+e4Nh4!Qi4<1^?0A<(?HC1bzl6PqiRDTf;z(Qr46`p zQO>K(be{X^1Iye6x^~-f@#IjmzYB@p$rCu*oR)?5{WuT5?*DB?S&@^MC(nAE!sV&u zD~uWuFv;bvdV&7=BA3)(B&zOOa3jEdL`I$$e8I zD>B8qD7$z(XhGKt-?r-(+XZKu{PS}|Bnei0&}gR^l9~cWMhdOgQ0g`#;@qtKqvZP( zfJDEo5Q5{8F~UL052<=u2U$rkV(%m2$YjPLdT`>*;qPa*(6vV{yR$<|DjJ;bY?QTW z&&>_CH^hK=oL-{UZ_xS%B8a|x=^FEt*QRi&^ynVHbGxzAqaf3~wOYfwtoCOHR%^AA zVGeIM42l>DfrOQ+WyxLAZkYBe9yYj0XCSuriSx07-^HI>Pl- z4^#P)TtNOuN;+h|~dw2lT^qgXCH?!7}R%J0A<&meB^6L!^JaFa?I6c~ zW|_CqHz%G3zP+2rd1mtqi({dk2TYm26-^uKRGm4JewLM;8ZEOC>1JV^@AQXrP`xJk zt}c3;p&=p0XeUCA&YasiF|*xKEMe!s$VlXWct6m(AK0$ZJ7!i{#X0;Tcv4!_^5M`h zpLx@DZScHp4@VoUCTLBx?sjO-4cy33yV&Adtk(y)oDKFyTWeMy#G_sG_1^1E4V>rL zsS*==ZqlvZSEXG%2txP3+Uz&FY(YNc#KJ%HFQsu!^rOXIUR*eDzcWxKaNwQWE$Tbs zV$K~&{Tlz2@C895ez{qnHiGt8q?0VQa>; z`*C6`@icUaH%9uZ=2LS}|48`7Fx)3MOMN_@j4mSEaZP{g71t7%;j<}}x){RfCB;_5 zc{McH-9_|W)|GPSRM}{|t~v@S4MU&ngW6hgO+{dQ5_}{9MwDUEzTRpvuNbrd%37PJ zQ==AkqN@|j7N`}t!26?*=Gs*cd}q-@2gPQ7`04ff(_wU#rIMyCckJv}R=QETmjOv6 zenMbMKIDM;$iN7V8-q@k+dtau`(0L0v3F7TpPyKCuJsNRBFQpR)71B9lqz5z-bKkS zQ1C<+XeNd)a$#L3G~*Ks{Ko>yB%nRlqY^KD|qM6J$1=IJu!a>VSF`W4WL?vj<2om7M{4-YaP%;sn z3Jd{fW5z310KfQ_3I%N24qifS4eb$xREv?mGM}Mc2Wzh$7O=T9S))p=KuzaEEFVN!5LxC=<&)Fe-`rymR z?E=lQpEi#SakN|h*dzB~P^BrsxiBduC7fcBw57v|UMU?YeI2nmnRCmOAEf>J~=&1a*iKT!zzhC{!Zv$F;QyMprrdG6(l!1aTZCsRwsgOf%H>j0 zKBT|e^Be2iQ&nF?IB>tr(lv0uUJ8XG1x9NDjA;d}3y%P3JEh3$<`J9sJC;Wy`Iaa7debC0L0FflptQz=Ob)D?%e6V9 z?hq1hGs061GgObtOTjTpBy7DQwvFP`XpBSRFx%!=2%68|iOOaH>GF$^#y8$8c*tXn zPj;(>EbAYet5CLYXK0B*NH_+H1S%uT2K`sN#TDk9c>i+o&`uWuPoe;9cZ!D1D}5jM zCyh6B779jr={*-%d+P^?tB8i*fr5ZpaRrEgo;QdO@?`3EkhyYs<8wYBc)uRzqxGiQ ze!quw!D^;T=FIX%t@Z)4{b5JYZR--Q`eEiCdZR;K(TT6w@>2ZU;~572OgY`~8Kjn< zDY5u9>zEMEe5r?|I;WO3G_h=cYlI#fDs?tT4S_v~pH~Y-a+wL1Fp_z`ivr6W!ztpQ=Tpq>FkNaP-iyc2I~ zB3ftx)u>3>aQZVBtP#u{0yNshA*+^4Jau+YVTO$Lx`bNe?_i_TqcXif-G||^)to`uJouMhrr%oM4y!4V z6ClS53uX?U-o0;onx>kXFq7S6+pfvBZQE|L z&B?ay$+nGewvFdAzyJO8s@0oTYt?S=>%7k6;BXenK`*1$k2CE)_!}y-ylO5&)J@|( zkqgmhQQ6TrT&E?H!sJ$4gR&pq|8miDJ^k^na%UEvwA|srn(4U%-N5xS#`q6-dZ&*7 zU@yQSiw_>U-rg=kLfM;_L` z>UcjD)Ib2K%f`|Q)(w;_z$Cm9_|0p7e}UxRGU%eft9gBP-6$$)o9*!j>u7!b7;1K! zaL4xC>2U1`#$5&mfb3aIkIpm5((5^|x|S0$Hfd%1 zF-1cmyS}>lvd;1G?P^+jz!PwB)f<^BG0&oje!pzn+#YA$FlE5d|07A_^rB~XV7t5S zvO(X-0qNDvYBG{Q4$Kv{iEb`FEnvmHm7*E3F~BI?37P7i+m{Ydvo)SCA&^1mrb=h)~lz*;C*57K(lh>iIU6&;*} z?t%8fpuqb0;)Sc)7s6X()=(S2IcaNYte-E$9ST zH27*{w$n6zMBIro%{c^Vk_`pZnX!XTXG`8|Fg>UV_j!*4-?hkoMCQ{rBnS-}a==#1 z?x3!}P9@69LdO~k^h1+B2#%>78G&6s-MMmj6dd4t{T734SFE3ANDmNuARH@2j1LfPHv(pKO=4wWLIu=*SY4l99heA7No|(m_7d><}2l*Eqpdqjts zRRmQ7yH zFh=i8q<#2leB6t)-`)}qZ8q``5KHIQNg7*LGVh~~TBxM5l30D;V3-E|u9@Y}#m06~ zk6v3a(GXcu;V6L)JzTBY)RwTW(x&!qY^t9sFupkm92=8NXE1@cZUaR*OVKn!cFoS5 zDH2H}(*UnqJBxC)4$RditA7B~-0JG@Rqd~}>e{aFZfhcC{D}((QX@n-?mXd?YD^|qqtPaPW0^PPHXzcCnW`0z%{ub zaNowLvmOAqzkklx%0_Zc{Q5BoZMQv?z0Oi*@8{Vpif~rP#ap0(k*m>UJ&+o8RT~jn zPbH3~ZuPdXg1PT-{ob0v^W9~h#PN#RaOiu(c;owp&qo;*LNqozqC(`R$$vlt4zx6` zF9AMC|3g5s83H+&oQ|wb=aaFKIn(thp-)IYEoi<>1yr0DWxj*e!XEMA^YP$wJkI>b zqoMlH^Vj26E9(@TT{ez8{#-%0a;I%_brd8pXCgg5byUr2@|Gz{KBlQyN%9` zwY@%yEpjOv&K`3_m|#=eG~iNJ!IM?Cx37DMTAa$JK8Vq_=TYj3%}mAJgFoT3^VqRH zHTwwa-R`k!TJr;jwPS3vPU+qQ7|o&s$TP~Bi&{Qjd2M+*ns!3r3r*H-Z_cpjY*S0K zRPV12cLPceC)B%Htm^?ey+I{sHxukd5`!hDYnn#_T0}FZ{?uu#tnc4N9`ja^WVq)A zJ?m-N%-pYp&~j=SUX7_p$??2iuLhbvcgZXyp&7haQV(owv^$S>T^_|xVtKrX?E7{; zzFABH0|Q1jdbm1|Tl#wrc+y9n_eTRwr}23*N=n8k^HY4h^z1e!Zm{zG`hvGMll`qq zs7yh1_f~gCyV;;S*W)e({q@oUGMbeNN4)ep<|=QGeQSSPGXAjf^MM8xt+3hX>z_Y1 zhvi!CCBubch>4(8=G`v)#qm&SD)`)(g}yj9r^nQkL6JyihRPWf;j=f8YG#^}X9-CC zbm&>Tc%Vq86M7oeEqg>?*UyiJJmeTAIXaOyKcROnUq}5*-1UTf$A9)duxAhI9MtYk zfsUWw<<3C~^ILDb1bv(AJ%8n5?xY~%R$r#m8!42)fTXwiR+*SB7I^_2m}y^~#B-=W z&^gC-Rm0*G)o17=dyEmtuOcHCyv7z(P;GYKRjfV7`V@&8l;dA!u5+@6=lkX_0$wdMpL2u8J^LAQOAL5xePmlPr{6qcOmtuDK*QSb9s?9Z6zr_B;3j1bV^VX z9s5^AhpJR&>CHWvqU-F{c`jo6-8-U~0xuQWgM_^laqWuAPStlI?RE}tHcMpFVRkXU z$|cthBqWgCJ3FcVj4qzMmc7jvi|qugGVM6KKAB$=mv!H>Som6zUmzq(M@^G$8`5}% z?}C!Q7poRMKmK|Bo~fhiN4qeeE55_%sTqOAI7qrvuQoh1eywYeiB{#Q7}~#?nAa#R zvv#em+lI~@&1W5vt@6x5&2-cnY^CYKP4ONtBTkrX(8FT6E1PR<9Y)3nAWWBW1 zdSfkez69QPtG3sWp0^(eS#Gq;nNR%;&rDDjLe4eNr`Np{HIlP=8?lLvNe^g#6jV$| z?pc+k-M-~*)Hmeh$goygfV9adt+Ez^8)W0nom&Z5#OL4;&Q!4;NM|RNz+2-T4T-i< zr}3)a3w`1!>2;co;?zyfOMZPZj^HvbtZ8E9J!btZb`I{Nd?x&HqhWYH=VvhKpT#=#L60|~gb~Sd5H?E+wrpOAqvSglU089;R(gpuFyjM7nnTek5JOg;>KYheoDj=__Zh&o235O zb^xqS(z#x43IEn5;{AA|00g+H;sFjP6-_%$U2he3^>0(putEYR z>2|`w<(Cn--0CgT?FX42nAA(B-@?qtHjx1fpIOS9-5}26IDi<;bPIyRD%3vDm7r9g z5AE}W&tkQ~jRM*v4gX`1UU4H{y@(QK++tWwH>iHb2JXV)y+z`Oye(cuG;|tqvN%DPmdr#GdU_QI8{YBo>5}v;tNQ78-rWyR9VBKY^ z2A$`e3t$Fq$Kkydhe{Mx?o9Z+Npyg9bX^Xn^Xj-{taM%{clFWNnUq;oEtZXabUj#) z^5#0!o|P13DaYdz_xCs7#z{mlW+3>Kw>>RrM0WU(!T}{Ch7asvV4{sGGGXZzSI$l? zRSFx&v3|`xU&3y*;m*}!76|;-d9c{@1C`Pu&6HDG6U_$=NzMmY0~;G-Vz@YzU+jeZ3+u3%RJ>0=X~})UG4z4>3C+? z@Om>lU5llCu=S5Bm@&h-k-#J-0vk#(a@fiJHqqxsx}R;b2Gjg2kU|m|pGQpaez(`V zQ|3gax+AcW@wY$OsfPHDW*}mjfaLXjKe)9WAG^XWl1aWZk5KJ&r&L@?Hn4v;D%L z{yY_0lkHfvmv9p`z@^Hw5c(oVgGa+vfEJaS{xw>mZ97LPyOoc^8JToDkJedtZw1G` z0$|6cE+ja56ES>TgilcTr$&k0aIk3G8Y}{^D_NT1;vBUU9vZmN3C|YVqY1h%S(<*i z3|QJ4vH`T61=XR85kJ7~Gm1U+vgWLCa*0WnLF_P`^}azkLAatRXboDgVRCn zrEzR%(1k>X3A3D=KQVK_#zU7-%BW={hW#X9p}^7x70vbbSvWEy`&>i8S3$8F%Ou?s zyOe@5pEoEWtpw<>qDXU6fUReQ=ciK4b(Hk!OKPpKe81JbyC*}QyAx>|>lQsr${{&c z8-m0z7zw+nF&kGIT5Xl@5R$ggu6ITv21@AQ{_cZ%t{>?6MC|!g@|~Y9wqq#bBXr5W z!49@pWi*2-MdVa8s9kjZTdP8saWS#daarAOhX$s8Akpbw%C^4^NGvrQx1`foS)eC% zscd#1uABHqOs3_ZLx@)!+_P^yfC);FF{_st1n6h|Pb;vWUc31@-Hnsgz)L6;`1_K1 zd#6=>zUMNi0udSIgJdq+zo;mV+Dy!fuNi^&AUOn6;CWtxoty3dA(A(o!F_yv%KJvE zxalv&*2zURng3$(BZs|S_Ni`^79m`pGb>l(9x>3jasVw=uI?<=`q?cit`i6sLY_dN#z9(d~|je}7U zg9%p|pd=a&5(og^ED*U0j3>eYEx;~NTj_nd=;})5+xvyll;!yaY4J${$qSoz z@jf0!^3o`NJxCWyPZb9$KO?Il4;Jdzm=dvAoH!UCFWl&m8Z})nCI+#b3 zYjw`yHT3Q_x86^qq3nDUMIo$q1)%XmUn+q3QG(O=xWfM2eshnFx9+vY zXqu5t@9bam`=DwY* zA!MH}A?+fzS_lkB>>ZNVI2bIAB(@c7`|)XAKn&NBk=RYavp0}w&O@)L06lbd;o@`Y ztuZqe)_lZYC&As20D`DjdvR>U-57<|S^TCow;dgL#wtrh66T>$Aqc3LI6;?qoZ z9+gz64G`y`LO=+KH=|&k1q@oXV$Gy14h6hrH$ZPSPI&2@%A_u#nOT-}cA^5$y+J=A z%9_hGg1OZfg2O|S2gr)LrRug~OpV6#*!x&i8_V2~0VLP6-ZPWr+C%F5r0)>8{CE_U z7MCL@cssL3%u8ySQQ6ec^9?hbUiBNF6;Y^q?v-eBOB0gvZXE(927`RLG3h&^1)+DzZOV zlaS|8aJ=LnsY}Gc%P|RWM`Fiz^FK6&c#rZ4!q0X@rU=-QI;ZK zyho`l)+HIViCT0o)#Qjh+FTfz(W%BDoKXI^t%^Hj5U&|bhRc>a(|gyw{cuRQnHz(DryQGz>r0bKfF?0M|7$J|ohh{@Qu8XdYLUux7uxX`7>JXy6S`jcry zYqPQ+c|}{to9}R4FE_k)&+KS=yQb>LjJ>RpSaG$IoY&~DZ;daupb7;2b9P=~cjLx6 zIbNvJn(n1zOM8RWOj+Km(yVTzS?^KTarUD>lwet$uMrc$wi7~lxnfa8o=jCw*A2b8-sVEN zh<+QqR%aqZXqYle(P9X#Ae+_wA-s z6KRPg;*xoz>*mWZBiUf|k%KS0=O6i@V)p7fL?j2rXFyKPSAhV@^zpijBy;L8yjjy5 z0@hAr5byTt|8xU@fmC$7mmiZ*)*+^zl>xcWjMxC`r5jr7iati6^lVSzg}+!l>BT(! zYYp8@hN6b-E}z26xL#{8A~@2jb0G7B%i>R$K3RjRH^Kh?ogJU`FCtjH@Wz6J&N;x% zkW_y@0gJS7E`Yv*g>9>%s+SaReDK_JgOmlE{svw1p-IDT#Vwhj$OW&ND>Gzx9hHvc z8oejTmk6&X2rjM0NQC+ryu_Z)K4Lq1B*xQ9G~z~2HVTjMr6o24BQQXfl#3>e#jm)$ zR6xxQoPxqaPF6J}H}{uYVX>g5K0>240t5{*m}rh71i?v3)4ZNqggIv9P-yX*yZL zc&aixd70`7E<{dU!wGRB@@lFt%Nr#tT7jwMTju;ss-)>@`{rVBbxmQplHq&7;(j^O zMp^TC!dzTZA);9hl^1m1H?82V&)0}W6P!>{vwe>+u$jfA9#(YR7i0=mv1ftHI2$G@ zb1|y!H^nIm=pMZ4kYX}Xp^|5R0|HIY=O@heCR@^leNug`&TkURD%)oeoU*DEZ_CvQ zJzvHg$C(oO3Tn92nTSpD`P^j&;YRA5**8)@h*7;)eKQhMi*KeW!oa7eX zS5-zB-JhJHC%7dCx=+4kcMr-hC)}mYeIbS19U%V^$&>=qosT%NbaSqfk38d*Ko@q9a&xcCmn7{!B2PQE^uwtUE0 z>;X?=8DMp>#7eyz-?4u!uDCCtOCljTIWIe#PfcVM4S1HN1JJY+|KZLRE1%}u8Hq^h zEx?Px()eda8Gz^f@1s5|$|t_*U*+#{BZsmS0B4aYRC+oX=-3k2>VyXhnN%B$9(?@* zZ$(KBMA>>r*Axw&9p#94)D%kR6+nt3cMuF8p|n4Q0P&bakfU>h^Fu$mavv1U(*rP9 z+b07*^C5*Ts|7V zvMYn!qH$O!mS(@adV5a$6&DhlUT5)Q3(o-E>HMN1EWqGK7&p5;Ro6kibKPwB1pYDL zD+Y=rd?BIl!1BI2>;PK;vjowz^t zBC;zSGQg@L-Mk2zR&&Q0=-mYoSvvYLoq+z-&Eh{Am25KQxpD#^T$t5C!73Md(zO-Cko!DD-A%+?FBZ|^Vn?H zDtXdwn2?7BQbZCbQXv{EYI_+a#KkgjR1T_0;#q2{P_WzDgL!5xjo#ZA!67Owgq|=M zUwl9^zVK|+y}Es$d$_BWH%KGt;1>6#BC70yURwCcOkQGZMF>A*`seZUP#4hQ)f;ZY zl082O4AM5+fs|lU*z%^gg?_P@DL`x$OtBfvm7P zth;gFPu5ZY?d!4mq9Q0<6T?k8pG4x!Y-+Ii-&B@M>c5rB7K%X($HRZZ;bodp(6R#5 z1~bBbgeHnbWP26OgHHn31uOzlAbNzKLk9a2_Xxl|Cs4my<0>|71#vy!FD zZ^W20yhAq;(Xa0D*^VyplGRu(vJyt|Ao8}pUDr5cT-I@m41eV72$rrgy!nQvUd zhzf<$%#A%%rbSzU)+xzUYWk;UWF)C;p}9sp2T6%Zm>#@bOPjPUxAM$2Qe<%l-}pbm zcQ4Fi>~x~5yxbeSbP5ZbV~VLfz|tC-QMRabvTeEgjrsH17k-R@l&}U1>djh}BkCJoqAjCQV3S}j$B0k6)I=eIk)FKiDR9#y3pB5N`~TC?=q z?_0A7UNe5%H4C<8F{Cn?#c_y~*%}N+F-NfkS~sB&0BiLBSIyCNoKR^0zv^>fV71jv z&V{%6-81GLh$IIHg=(S_(KE>#gyOR0w{$lRceEnz; z&D^QSa&nk=75wqSYt)m)dHGh1Ja*lv7KP!n=} z{8<&(%V$&wX!_I3$ly%IA3=o}O^pO=H?l!)p?*4@DqLu4@b0L9k`IB%Ug~#=(9c@9 zmlmR_)RMwLy(yc%oy=`TADoK?ldxnR&;zTL2`QEZc!EL;G{h(BHslLq)*~T(kV`EJ zI>1kPS(>$^Be1wXkxm{5Z>*PXU7}^H2!CZ1_MmG{7MQ5(Ao|gef>mK4&Gvo2Y_;9M zkx3iGY$<#L8lRo-Q2!uoFPK5}L+4!zrGI-9bv!VztwgIUgyYNFD1;Ej^5o|%J>DHz zst+WepOE|&XMDYOAcsf;cC&Dx^s&X<#7Vd!@eEl(u>82-h_T`3L*J=3>wC<{^4iVT z;-keNJk5<>?eLa1q``{EoY)rIW$-Q2>lvEsVa;Kw!=g!?lY|6jwkWcD4J53~XH2hu zw)*`9n#_Xk)WaKt7t_<*6^p1#7ek&~gWgQ^lgUIz2s9|TSKvgxRC1u_!&u`_E`Gx( zlDgvT(&A%qTI7Mi<**53Mc?7G1MKuer+t@EkApoJ&-)>gZWYi^d-@g_3rH`m7C(ZS;OXzxe&ROj+$Wo&49V0arP#Gd}A$N%4 zIK9|G=S4GdH}V2J%z!+((|LxxsEk0JuG=p`xXX=uFfa@5hi^Lr}uxvB5H&mg^V=L&F}GLxlj zY+nCw5m8k&z;5j)Ixw62zmFFwv1wsT&9|tU#THxrp!b_2@GM?ulD;PHnknpw;KhZb z$5;t>R#x{tVZGZ+*Rk|J5#_Mae*%ub&V?!}zbLu4aC2%mE({%Uqj1}k7K`P#eca%2 zm-vL(^+jMDP7Aa-yFO&NsAqgFsjO5kJT8*XfO*C(dfW$4R(-%~b-2R*m>g<{Yr0eW zN9T*WW7V9REkpM$kx_L`_;shZ)o(Bx{VZ4I@8zeAoF+K z$2C+$x|d>G`6uknJlZ%es14Lp0QO_u-|luJt5UTNXUgU!gGK7i{2K!+`KJUI5ZA@b zP$LzkyQAuZK(dr?@9_u+d7Xur%u0KzHJ&Ayv}`R{)Ms%E6`aBmnEvIbnx`Y1_zz-< zwbDrJMPryIgXF$Bf^;Mg&& zZs)qASAn^5=NFMOole`SDqTu6 zCXzK@91K4=-OkO1j#J@+XLFvJeDW(}pSzxpM~h3#WsMlN^Sul_^M*9bpsg@Y#=SZY zKOLt}(-?Ds6u%()zD4{B{aytZeME@@i(y?vh8p7&X;#K$MlC`ijvx7F$wbf$Dh&yr zQ>yx8*e(pa$4)U+5u3OtmV3UJSo%9I(AD8w0<;!IR^Q=A`5ytBlh}S=ANIy6K4kAdTZ_q@LU8jds4KGkBms7bO!= zBm|S8LC~?3Alz&*2Hrxp6s4f`vpF;UTu}->Uzd+r=|CHyz^b-z$#JJ)cqx>VRU4*< z8CFy)=(GG*XU%di8+g1`oL^v0ys%g ze<}|w`f<0}PG+!fmre2pROKiK7Lo1sDbUL945rq}@cqT>TS?r^$u0j%ndBLo+3}qF z@fW{TX3uKX&!+QHF!HUP*XaWqWZz0>u`rF!WSae_ctwW`J_-Z>w7h~Ls$Npl9&sR( z4GVOT?mLI8CORT1qW^GyNSu|?8~x{Zd{qY`srDPA<3)x=pJ~Qe3LAE6&4q0+qGNE4 z(J1Qf!2y=YZAXuo$}F|K#hS+?_wh1$oWmri3^#%^B#>0P9(F@1;qfd@l@dWP5Q;>a zYnr}w2N2{9IcS<1>GwY034a~Ws%(Qd$#f&xAIm5cq3DW0fzNkwDZB7FGxG5E_gr+y_OWpb8d-5^ zPcaSlG#;u;@s!CgCSezo*|{L!tplr|KRT#5H06v#+-);#gaQcbqj>o%RO_{|DDa)hPzK5v{Y(?dcW^>|MOc;lUr`i zIW5@a=3z&^->%*mm^j46r%QQWr;ScC%G0@75LMbqI;HG9A(5^c2 z-T^^GZcYxr72d=Y*N2VI4OY2U+XCB6!rjRtDB9;yAh}D3>*ag3w*Z;!7S{T>+f5`Z zKy6J0?#ClqN<^T6NCA2IxEdEzK=7>Ztc+(+Wd)d&hkhu~9W<$I=dQj-;ca?hNq@}R z(CJNthDcfKydAnzkXAaZo1bzQ42W5Cd*Pwr__vs7MQpz9v1q;&rCot2E0YYSFJC-I zO2^sJUeUWc-j!e9gI4Y4ZLImKHr`^Alc8FV4PJqb2yBPf;YW~;%^*E#dX%b?vjXPd zVN-5=DYm0A;;je0D>NO@jS&P{=>>Qfwbrj`l*Gor`pGpBl^V^(Vy;eeP|ZC zGVu898wkmHU@UFeQ25k?a|GD3i-xF;c&dvg3f3)-)d z$b_r;x5XzeNxXJ1&W3~EoR67a{B2o( zD?~hz2bJ0kBElkjHax%zg`M0|J9>X`RYC+Lq%9Di6mDrvghiA!k_W|2I_`Oo0VAmjG_jA( zj(Y{$Y}kVn*b%qQ zpXXGperb78o125zCRw0=S)+m4$u$!j1k8OBnG)%7bqVu2FeYylu%i`&>_s@ghvS7y zZWXaGWXbYAD25|CrIGW=cd=hOVDem)I7@8RhyGq7f0c7BE?0v_o-1yYx1Qa7k6{Cv ztt6f5YC#mMq5C$^^x?Aa-#|=DFHbD zrP7JAh={aC_(u2pw#tV||2-o_F9JY&wERbzK)7GTW=Rkt}FALq(Y#m|W)!$kiER zXy`pk_E}70mMK^E{e$asOG#RmBPKec-t4tBR4`zlUuG8S2GfGS?yp$XkoLTtZjU8g zg&w!9HpfB_#NONO&Jp3*D85ix=NB|%c9CAc6b_5k&DwTjU^MThOKLjnq0%JX0ZkGE z0PcEwf|55lFHKZ5>FBm`lAbI`MfHxB{jD(cTFnj!GVq^hxaDeR5lWxcRiQEY+ z8V)v#pLf?@Gl0mTOT=8Ej`wgyd!#`-E)_-ALq* z14?=hftW;FtUmU@!7FE)Kz}kXh0s0g(`0+%9=SC32oI@8!Y7f5St;dD^u^F{eJed1 zuGde|SKGl^f48%7zDoPf+9Of-HE%h#*HRvEfupWIwmMBcmX1T}w<10+M=j zd--`K{b`P9=ux8yjGJPLu-!?9Ixa35)m`7($DHlTPiN6mkD_o3%>Zl|11>zMzAz3N1xIg2pH9jbe;G`E4hFM8u0{ zX|Ls(^Ce-v2*@gBK!9;euF&Vs_{Mb?Zr_qb45*JjUv?x6(#39+8V~FUF zeF|Pn4J^KM={4C*0(C?u-RM0uo>NdHS9yfmu*rS_=KmwGy9!5D~Dzd zxVuI7xhB^pO>MztSMnbpRgd<(#61Mu>S++PpW~}GQNmBQw|@ny3^<tTFRU({aLh4dGY-oXS6V`P{#{DsN2)mk^f$6s*@sY=!M&{xqCzWm% zHu5%J_d%RLe(PS{?{-f{$vM^4Q*60UcQ!t&xf(Lp$tP9+X^W(}&zLklhlzpOYd6ot zLG8W~hiZO)zT?tog@U!k`brFF>YIY1BFZKO`sr!$vHsx$fPHMa+KST9&>%ci8HgI0 z>3z-)$T&`9v7$K5YvR_q@WVEo1WS2Wmb%_2YU7Y{c)daQ?1lgkES?jvz%BN*BP&5y% z-oCZVG;4iTR!<~Bi46akAZoC_(f}-220j{RVD)$YDE^k;ix=~Xt~Rln@5yvp5JtH9 ztjaUtRptdPz)HU|0|9|$&lkm+;oPig9dIgE3#A%=OQ*H8w!}WP~Dj$*%sIZ7*l1U0!BtW4qjg|WSnOBK|JfwEWsQ65k z#(~Nld8KA(W}s6Rrqn90+T4UA)5{DDl}eSYh^W=QimBJ1WlQ%yO zs%({qdj~-)MD;wD)Y%SCR`y?!PAcURhuOE9-2Ihu+3@$_eZ{oElra1~ZLg_5*4?30#z^Y$38DfGABq28sQtIr6*JxC`+s>PP^w~Q1J|}5db*)7 z$1=X6;fO1OM{r(5zwaa%dX9t2-2eXQ1OBeOp;muBzlg09$m3hi)qgi2QH6aP%ZeJZK z$SR#SM8Iw}umI?3tncj0lZ{3Tot9dSxEn21!z3&e zW!1maWK&Y8XG3qT8jW5)&f09x?(snv{yo7C$&Rd)OqYjDt`+WuVUpe%{nbRLIZF|& zfm#%hV}x5^z>jXQFK0FgD9WgJw2+X*m~CtgWFUt`YA{Wi@OQUmR-h)GsLNkpR;ik&!{qr)Z>i z_nEAoFJaI`Q7g$+eIpD}3XSU=I*Cz19`3QO{OV|-$Su`gsmbr^IP$-s;BE}nOW*gK ztl6y!7gPK>vZF6kT33*v#I$*QzUt7>cIVOB^jY8~ZueGsx$fW1r#y7Cl97|E>_o*9 zK7)D~i}WYPtkIXV78$bR;|p3$b$#ex;L&E}rlkzmL{q{j@{X}IRV_yZee;(-6-EsA zMGX5-b5n~+bylrb<4kruV{E*;LUpQY2fLu6?)1B`>diX0lInLQ%%zwzD!Rcbi5f1q zjK3-xkVn}62@lo$n{6*4{5#1m0ySnAa~eWbPL5pL-3vd{!wN&&?Sv5-C7IEVZEr;; zl?`*2^p-!J8o@~DL{3R7@|lmz9gZ8ve=t4tc0(llB1Ix5$%E>+z2@?2L0QO9jYubH zQI%}Tzw5JH_Z|918$54|DU0z$O0lL2M(me7-+{`?AfCebM60Jsq9gOrw|Ic4E#U7= zcz|H8;-cp&v@}ZoHxC7KE3K-l8yul4WKyL?);bH{K*q<6u=QrQ*+9V{j41{6x|m88 zYNKk5mB=d%JPP&vs)dxu?k!4Fafw9lD2a&ctw-e1wY#X)i+$s$T@74ogKq5r@t2Vh z2G5giCgRkTx$K2ExZSu-)!>=S2U^qn3%}+gh%zQ6!EeWJUG;ffUum%Ukq8!t9g^Ma zrI#4wEPCAex@uGHd4x8D>qG%XtZyE4E>bGQ8Hp^zG;z$0zMiWeL6{+spt-703#BWo zUuw5|xrgo+6>ep0X9^e;T>;`0@P3h#`*GfOfNMYtOTCw0P=Mh96?K=s(K5#IY-%u? z%SgYD`5&|M-(NB|7ZsY~fAeT4K_N9<)OLrC8WX#0!@Y>X0K&?E#gqPMn)b`=PPb=) zAeszZ*F*ezCg@kMo9M0&EwwLU0rBI>n(ig;3Ta;3lZ#rxz=Q+Kgqhp@_V4<`Mi~hm z0;%(&GN^Z5LvDqwrNze;TUt_La-cfjdLVY9U>ahcS%uO$S>0erJcQBUnXXT!w5(5~8x%@7vZxC!xRqpw(S1+%Z%yVVX z2VUJ~r$6h50?vzT>l|#?Y8dTqe+b0J%ZH_Gsk3Vk>D<>R!mA_dQDqeU+>=9ksU1XF z{|Rv_cF7Kvo!!XVson`y)&35qT>c0T&nfUkOiKMcUCmR^fCN{x>hFQ)hK*Dty|~~@ zWR+Y$cweDmyBs~yo0;)6LJ%mHZ5O`-b?>A^0I{x6qbS%?MlVg@>ZaMyl`gxW?N{#( zQYhGV+slD4`)ejSe!H}m2~IxDcjX!qePaT#$IOHif(Y{Aa6o1z1~!o`1I$2usl4TRjz(Jcz5vV6hz_A*0z*=%KOOTm${=JHH2}Z3xew zKZ%Bv#=Yaj(Tg67lquHAN(!SH;3B+)B}}IVKrZT*uct;7X{-7QWzothH<&IDONYzC z5)~*J<=KY3%ororUP{vKCb+xXet;(RdUnlbGQo&DL&KtyJXjD+(jAdY%dqC|3JwQI z>{3bEn(X}tYeb$^t9ZQZ2FytH_IKY!qt`3@_?>-X=QfLGcKi3R zbE(#Bc~C~e>KN&WEkAQpyr!%WVvKiVvn^>S`e6JqVGWvaYGN`bJ=TFIl@s zL59Z+*bH!gTjhQKjV}Z22YKsZGY8It-e`v$o2*W z`}fRc4ZlfkwkAQ9ruZJOh!SQn!#jD6uwLHye^bDM$f2jKB;5)gKbBXAsXTpM+P6 zZCT=k#Ix=B&FuylJemM>rEmZ@AZ=Y)b4{%TB9V$`)H&D_S7q0>3ed|rIiYNL+`uU+CzMU87vmF0 z73XpwUKxBAf_2wvG(>TWYGFN}_KQT^n8Hcs_(`9R81(CFk>DbJq(UUw2|qH~kosqW zVyd*}2v=lCQFOw%730bgb13S~sRGn_(YR#%`)uEzn!;)~ng(yTc7@&jW(SDA0t?70 zvg&->!R8|1X^}fW*Ad2+M*0(Xg(&gG(R;XdU9F`_jPclkm-N$jl#%#%mFOi?s2N19 z865#K3KRYm7KNQg=_@|^lTqemQF>{SoJ-*bCJ-YudkpeP@7xdTh*KMp_9A%tb9dlX z`4=xtNZb2IyY_}lM9*u>aO=@C`J%ybv-IQwnK1}nNZAsB+$MwoIZrCVH|)V*I6Ql| zd4(ReMY$ZnCt}-&=rvz*Dd=0m`1D)_!Q%wP%cO*z+Yw(XSqZr*eZ_JiCSW!}6_(+` z7&g;$`8hVZA10t#8*#voMIr7o)GS|C*`zS@|G0X~sJNn}YdArIySr;}ZGr`NcekLy zEjR?1?nZ;VyEZPtJ-E9&1ox1)=bM>lX1?>M*S+08daZlv+^Su>_TI59d5rj@|Hpz4 zcNUI0E+I2AyE8n$v=U$N`ddR`c>pm|>2ofPAylSR;<&nD{1ubi_AzQ zct9wziX_eN z_To)hso#p7!=h_?rbo&Moz7!>zCT4+^D1zm9dDaO_t&Y2VE%_tSBl`jut^pcbPatk zk#M?G081^)*1t*wQcU=E?H#BK0RKG;dT45kBfx6H!A`uiqk}Z%`q#?mp?)NM-@d4y z5#-)*Wn~f7FJS{Q1iK3vPTGkb=Vt#Bc3XkEb8Yu~7<0b zyZHQyaY73uT|rnTs*Chk?6a&$ z9ENmI$J;AE20P9@2{STdn9ipQ`Q80OW_ddJs+k&0B&Vhl5D{h;A8HRF#DR~18qJdX zW8;)4>LkAd1k?fHp^tBfAT!2Du!&>`-pEzIYbs-gULAjyjwp6|1$I%W-`!?C^va#| z%}mxItlu#Pw_Me4S3F1@8ERO61RvpBE{RLWI7W%f#estW1L?xbN0e5n*0{_y&sfxo zf*x`bD4wb6sz}6-^xgmpoDbWQwam-|*op`NOh52B(l{aR(NCki8r~YJk`>IjPqodp zWQ3b^=i|=6veod%*Y}D!LU4y!a};tHLSCeI<-hDs{SrJ`uH_SIzZhYD<-;F!$qG=| zKWB9RBmUK#larH?g+(*Qc3sx!TS3s8BZ0L4EpzCcBtvm*^x$y7d&%~b?H@ifEt11& zQCi-dUT$y1_AB+XkyH)}DW^WyXCzr z9hCB4ai)bk8Ng}&EQ3I(OI@lB(#WlQz$=LjqttYAvs(58pLr&pbNe!b#HbM|>-HQ! zhY1l*!J5rw*w(k(&td+g2Z3EE55kvl9UhJ9vifgkf0pRaByb~T3xmww%W#?hb(3AE z@O|S&B@&SzWFhbqX%#JeZNF~b9ZxLI?aB_OFZe5Ka3V6=^2uQ%3PLH#pys}dkAo8v zUm(35d7KC(UqUId0IXBnpjrCewl;0`jUcoQ(wGizmIBo&OD5+=`DOENoB6bdJbSAGwKN2}Y{RChZ*30*Z(>hA;652D1H z{FKpU6~!J(t666seqI0W>N9~_^tSq)pHkq^EB90Uy)C(qRXR5v0+Y2|ABz4Xis1r^ zg`OXGBa;saEL0tWE#F)JO>=oglT|)HLzQyZ7()Z&zEe z7-w$cOcgR1Yfm+S$5GJ~gqgaPmwdTm3zl^Enw#e%-nsRBp2qi zQ4K6C`KD8?PPqB|p`fr3_jJLbdr&E3yQ-u@P;Ou_i7-*)B-0*4<@Q8BR1F5(mxt7m z;KFwg37Es96`{7@Od}d7SlzNmeP&PJ9px@2l_l}Th{i}&O=#9IQ$h^rDYu&#DJ@Ia zk}JrDK-(6IRw8pYnhWkG!Y|V^f<*+V50lzCkez}dnN+r=u0DICsW7CwD;e;K9OW|M zj68X@(H?WwHUqLz4T@tNGl#He3b@b1p9oQ@XbJ?a6v+zK*yecw@kujebu$4#0m~Cj z#Z->EFr-6F7&J@9wOe%NYhxKdO}zYqOlIMnMU3Vc{K~@4^BK{#v`Zgpv#V%gq1&a? zr8b8M$rLvb45<r)%+a6(w=>vME#|)gNmYhGD zSfZ!IfQY;iLH(Sd(YO-8F^6lz6&{)NKj zsi`)kbw|wl%|SR^Z~&hKLDvm!m7~$@r$4%UeTOSDdxfrFIh43fI;;BJxG5fS;5`JhAe1?w zITQuOE){cKST5^GM1DTD(X?Gw2pLD*J<4K1;jfluJ+!YCX=X5t^;82V!xvlm>()Se zpLu}$w4cT&V5|vt{3Y%^jRRJF}vHatHs0Nw#DVG_%6Zwe~ll)`5N+m|M z5|!tQ+1af9sv*8i;D=z{peOou3qJ7Z>w%j1B0UVLc}&6rDvI-7aCaUH0a5~=Z$uY5 z?vkoazBp1n)wZIJ&DwrhT)0U=O(5h^7a0ldACO+5WvhqemZHdH2{S4oSmvlwEk z&@%JVjy__QnqK&(+IFYZ|LNnlyR1N=sv3FpAf-TY{su3y!UBTJZ&-F}_Q2-q=3542 z2d{|o1xpk4i(J}-`k-A6YsOKRPx)7uv+U-VwegYB*SW>T(hF*gYn?dOSv*Mdyx8h` zZ97Jk50bgc>hbR5_nfM9+SGJq8Epj1+2hdY6Nk5xkEEuzRTY$y=uq(%J(@Xw2U8I7 zkXkd*TGV9~&Mi*3DF1-_!%Gh`esWvgkt)1+TB? z0(_*yeFVKO%1S(sB@?6wHGMOGf*LraU`$9bXXzUDFA%Hx1sn^++W=Zm5cw|=3Toh)43-3J_#jF6@ z*U{kcLTto*=SfG_Zcdgh8(M;L1XN8XrFal@R&bF+D3+uo2{D8k!E!`;heN6FYgh5IK&K&F$E(6PowHRg z>xMtzpZ5%Qd}u{Ci$|+rUysJp@7ngzVl7%>wbzR5T(P=gtl%tX4}-judBE0p%p+7l zAHkQ>K}W9rGCj#_VtN^uC#y2~SzkZh zjyr>j&w|icC1p(z+P&;)aoNSh!>dZvJgWLEf#g{oh*M;+`MIM+8VnboiV172`C(K- zqRz`3E!)qNoX=r{O)Zu2x6`r8C=B{cR#q3iK6LLvK5 zY^~`(hJJo9@-fKHgGjq-TCBFqOz7(0IwZ?em`6F+@jyO^C;CTR5rwEwMKn&?tUZtE zZ^@ZjG2rUh>y5cppLJ61gY%_7)_P*&fh1=nky9OuH1QhIOrir9%E~BRnJo z>$T@I4Kq>ZcBl`N`8#cYEM>P*$GB&u@hj9zG(IgYYP&CDw=hvzd{WjdVqjaWUwA#z z<>$YFAYI+pNi$&zil%=mvHUYaVk8K8T~=lY*kag<8sGr0_45n!yWV8s8a+x9uJY+J z)UoL%8(zRexjk<;0~FHqLG(k@;{3(eKVit_d3ST2Y*s{!C4Hdh}#>oz>FdX zp|xM%TsFk8_k%ke$}vuD`1Y+vC6&5Km`TWaC(G1V&%@tE;QYk}Jkqw|BQl|o$YV-~ zMTzvXDE6R)VUB{(c2#w0#UPYH!DP`qjM$XV?3_l10!fd9xUd}PRX$TN;bwYaJzmnD zE3eGIUdIEm*|`gc z8|@j5v>9=b8(Qnb@w8nxtBX#zjVE+hE*!O`3I<|vxuv=Wm_}X?Z1&(+Qhw!(bdW8M zD<0wuW1U-?IOjl$3O|_f2-fd+|bTJO%6z zTlfqMa8xIEz46`d3p1!YN^C5x_&OCZF(NPKSd5bQnOB~fSk-7qv4cH>s7}^_w)0Qe8ys)9o~gx{|SGi zCPjFFkc>V~8A?h?{t`neb#3LDA1bL3s-B*}(R@3Bx`z54X`66yETbyT88@;CSj2~! zp27n+At8ZxjS`7gt=0^~v)UJb-@sVXDjkFAILzicb|4~WVf!t@WblA>fLKLPGQJM0 z7@qW)1Wcpvu+ySGCTge-f*}Sw>vPKY|A`fixJoRh#6~)vv2|=lX#eIg^y5$k>f4ye zlemLT;bO2*|y;@Gh+Jwr$1W}H&Ed! zT`xEq-+5xb=npA6hSzV`E_SkQh{xN?qoS+xzt>|<_fvph|IG4@Il}*~h)FDKuH&1c zf{WjyX~!(+u{Sb$ihdS<E#V9&6V!OKEPx(i1PR*AEUSTwp<{%$MoVS#cP?}$24z2s>y&FC5!QEJjM4Wr8(Vd< zbFm4`7|B&keQkHEY8plr;?W)UTer4)08ev1Y(J_mg&&;9ZTJV#5?)(Gk{3pAB@Jq; zt`1|~stlS>5;TOG4PDDiOA!S<&ulIt?w>=pIft;7x&&;gGKHALPBdeUkK3IGulzYJ zuT^R3W>*kZ_0=Lg4D4!cWe{grlulViKd*pl z{9u~L<8DmVVKAARx8gqk$`QptAz+pCr%Cau&+{5YGl9m;a}H?j?XWis@NRy(&dW&+ z?ZW@k(tf#3<7R3c@9MOA-baJejS-!mip`inodU#edF(NE#eg-=Xc2%L#rdA>^h*kz z!72$th`kIj$9jFu_pC!v*T4k>_$ahGI+oeq1cpem3xfGO`C2VJ(!;=X6)B|X6t^p$ z|K4H$-{)f{r^*BAf3LQ1UW)Zf&=EZ#OJO=9E&D)}BnwU3`o;bzHivj2%FG2wq=4r} z);lt$%)qhiJSJzT(Ue3Nfb7y6j~LuTDdebpKr$Wj%UD1m$RF~QdN2}*yXpMIh)mx9 zd&iw$iU*==o*WWYQ_d8DFW39amZyXfdJjy^CO#b!{~nV@$W+utFP~mcCO(LKng@$E zcnoPEIUykc#I9L;6FIceyjw9FI39^_4=fe4P`k_xre5Goj?F^&+m^4+&h`h#GDFdZ z$1YS>Q9?;c@*|OWy=bHwEROT-5=$YiywixlmF%Wv@dpkE=(IjUEeQ9mR)oxAF-w)P z-f{g?rG6tav;fm=ww@%%OK}G`^}2qJ1!5{^WrnK38p>XO*osM}EdLohwcHMd z*98Q=CnmAUim=peOxYbF@{bd~G@PSX8ajjj;dQ;-tP1f@Ik3#hA+%2^%ehz{+U1iT z?kB|Ee7DUpU{}nB%kSMOBH0V1^p*{jIeS~M+yp2`X^DotJ^F`eeL;cv?K+70=^6}S z(5)mK(4Vif^#-WdC4~I%lK7a(@B#h5mXWk2S#r%wu01W`eLmBk1_5{l-`E}~L`m-Z zv%#lyDk$;zCDPV<=veooz896)S0-v?bnzVw8G96Vhd$mv zPv{`k+JXkN#+yyx8cPV~3`Zc19fvq6&I)x_jKg-lF4e3Zc>-Un5bn9|m1b_=GeUgA zp7dlUEiFS!{MOBIE7Hg|Wx^{P?p_P0qYd_}BO6`6yUV_NkZ=HF?{>Y0I|u|~rZoec zt{QKqs?Lf66Smweu9pIiHWf~`6Tv^CAL&@$;~m8>1OYW`24}f=L12z&9t^a(vz;-V zpHCD8zn)Wl`ps7sHT?{u3JzzZzwTR9X2}|O>#hj@!yZX^7hvdjg}V1JF6L@S`~jUb zczm2?Z|_Tm6yrkHc`gTNG4z~Al$A!B1G9T)0EHv)&2MgzUpFsY6%d_OL^b|q3Y+cY z$+u9mIn#A1_cG?FVo0>(FiofZR9Vn!+;{n6IXh%*k6pt3_O07?&3P%rxj#a6 zE(WuIM5L;ju{_zvx3|+n_!G8-JIN<*r+#=`n$j@Tvi!-@SxfuKA&X?ks2YWm*?D4K z)NeeD;Ka9uYY{em%DMr5)|ZV(Z{?OsoB>v-i!$LNMvCBjM+_-4>~e%X42B6N@+euu zXeUim(|t*o@2l(+kUr@|2o?6x5)6>cq)CmOp7*I>lCCU0gZ}{L#|p zdJ+2S)F_G3A2H)Jupol_(~{QW>{o(T!;o>w<9|a zuoQZ>y6CR$r7X_jflp*mlKi~^@tY-)lN({S+iv_k^cGF<5z5#>C+iFOPAQ_-p_@`z z?o^sGlW&(*++xFR)%i$mCGvpXB;=6H6H`q`o88SY9~jTHlyk&Szi z@RSHuy&s;Ip7w|{v3V|SG07;7mH6u&W0cG};fwr@fS}@3`f!deXr-DYh1czWUJcI9 zHcDe9^#8L1e(_8St`3VZ3_AS%-o3{;R2D#^PbFP!rgUj1u-4r1GTf!?ylR=+22r+N z9GL?@o$UEDG9ClFgZ_HW;oEU2!joxRuZV*mnQe{L8ewUn+CQ?T$eP&wPW}8RJ2Q3T zrN~Y#KyVU6TDoNiqxzKs>f4^>3zJW+-9bLLI0bS5kKlq@7^@-QFinvfZVxQyQYOa_ zj4BKW%5L4dIzO8*9WRZVf?pqB8Xp&rh{~0MiDZFNda_R`h?}=lNi$+f|MTRi8?Rq(>uF zY0Cwwg<8FRMdY*``hllIpuvxm5-=D!A9ZK~&M2Ul9RliA1CIe8{Hy6*K$opd+R>Dx z$h%2pt$>F|&D+VPAlya1(36;{CDjP1aP#f(FDZ5Nd}O;FqzFqOr^a`W+#E9qPhS=5 zL>>xU`sHx~U8<;)h}~D_x&|*CtH}WPnvPE>Qmf5++C@ObXbDc12~;^ZHb|B}_Mcao zy_zfCRIj+xp2LTNvZx&n4TNZCz+h2X^fA>%>erb}6#Yo^z_k0RKg~Vc_#ubm*ZMYz ze^FM?xBh22Z$bRH_Wt|U6qVIZ*9(Vw5P&oE^;#&^|1(Ap8RTZZDnT9Pp|pWY_ChA9p!RfRIXW=i)5=uFGgySmT9vke%k8_Wm`qd z*( zh(yFhwP(e}e(-BQI;b(@>*aVw#^rVba^*61_nOMb%kfhKjzGOCWFzQI6{o|AY^Lvt zDUf_m2P=|~bD{E2L6(p!w?81@#Ps(32W<0D*vZL<@qh=7j^_<+7UR?2bZQKd$3o=a ztSkc;_0k`I*cRQ_yzxURz>RT_iR}w4;6oJzutk5a@ZN8$NsCoVRF1bnN=#i24oxYiZ^s6Tf(|!y5L#= z>x>taf2R&HE3VNMJxEJU&E5YHqNGlM+*H^p(ll_J0_IiNvrJ-g71pOF{U|Z!0n}P2 zydC=8oVyMik=nFMZ&ZNqyfpMbM+fxcDwRR(fA0BC`}k-v7*=(|X8Bn9D95{{ukM1o z57Ccj_(i^9im1S`A;siGE?lSoT`Fo8RdYCKE{Gf!{p!;Nf6#Kyy(Hj9ZgP0dJBJy= zzJxQmu&{f@r&8?;WljfEvCa=FYG$<5i9qNd3(Q*bm6)URjLoOm@kLXmpLNhB3&=wYaG(442!D|2{_@hENkL_j9ww*1av{Ie(5Wbp9TUO8&)=O;Bn~sLpfQMg%)$%v{Q$f=`_xkzVY+ z({&9pM&r+0`4j4H%=6Bq)08s&P9ffzrqae9Xnwq6C-gjnzjinGN$6@6s&_>pX^}`$ zRyG3IUaA9F+EG1!IUk(EQUg--8e0d}swk0%I@n&gIq0|*2!>W|nG8CbqkRI@g#TjO)~S zk9jtB6_`_k^*ppgSQyhepY;6;MQ-@JT2c3^nXqi^Y%~>w`VVhTJ;ooWBlTcZc5S5% zKY+B;#@7#}C(c$~?>kYq&x0!3MKf*d2kE%0s+o3?mKjh?<_h+!Ri77qb(!1OxnR(k z?((!d%b3zOT9}k{Z36+s3x{)u(pP{LXR|O$UN`9+#A80!E$MevDFSe?Lsw2q2gO+5 z_S6Q9j7tuPeK*DZF)x;+9j>Z}BMlu@G_R*9khvckk$DjRd4^rcut3cq9Erp5=sbt` zQ%k4nT%?Z&SK|`0ax06n17R8=6n-Z=h>m)(9O|Y_5)t5k-T0gM1eUR;Tt?3lw)`|0 z(M_06&Z$1`XSyv(B}Dwci)K<%u>DSs$bTi!q}x+7y|53Pu{DO? zbX@`K9xd0=A1`NfUf~o{*c#0NXDIhV6<8Td+-tru;^?@^7LruB#;TwCl-!ONnuHaF zqC-*>5?9SsZFW-}V0xz|J*bx03}TPA6L^}bIa&52bI zZ}Efqb7=m11wR^APg^5heq>n2+xU82GoOxv*IrS<$8jk_Mh9*kHR2XPdqcPK#J#w^Y8t%_Yw1qa*IOh zmC>^aK+yW;huuZWj~yPJiuls9<}i;kuLpr26-Q=15!Dof(i_j*^h#`Ji_HdYhw@d# z>d9+L!IYTyl&sb)&*+5Uq$Ewy&@~i%vgosqI&XfNs@6H>>2PHJ__5Y}Kz=;y1uMGA zNd~~U_@O2?(vX3)-8E44DLPaQD1mVP@qo#Lz{zl$m3Z8=UBSLXgu-uU31hofPh7d? zy>a`3$1o55H?W%VH^X{Gw^?_qD8Sds^2@=t!(n0R-=g)PVd0^(G5;ZC{)KYjBgi|g zo!q~Qc^L!|L3mN{BM>~Jz+GGO9wKWw88aF5STwF!rTBX!!?;n`7rp)8N!XV2m!0TA zQKEkXiU2sc5VWPHZP+=@-$}xU6~kRSHw*=nK^F1Z%d5zo&O5#nnF33-0iDle_h`!E z%4uBiyMwXK;$R_|@9*AxRvl7B1H15M5{Rs`qiQytB~Z*lC03_`r=YIrF~0*I+8Jvq zBQqo;lmmRH8GW@=--Mlaeuviyolhkf^+&8UZb>#F>uPFJf)U*7(-s75zK4k8Ac0*I zgn^L`*HR69I4_?@stuG+xM2@y-n4NRAa+i7F@2fN}w8ptiLD%)z zh7UhJsv1I+UM4O?@ojVWA{3P2mEKsU2in}!jZc`LmK5O2y2U<@{7j%Ho@(Qgh399> z@nY=eM7d2>r76udfk#y4hamfRs^-`ZbM`h)f?{$c57 zu}uB)_&|LpXz7{TebXDMI4Kej%1yS`g!H{M*;XhFVBFX1hIV52mx{>&{?28ma!`{o zMPVD9ic^IlXf>*_=xTo_*x2~aoAH&0LSNLi6{r8VbWSg-q5l=*?O0XZ8F3>BlC-Nd zEbaiI*my35Q%H7_Qcw6&Y1Wx-yXH@ z01nhGtk&cxu2Ty=%6{a1Q0jTM0ZfA63sx=e3UOk4TCEj(Q;iKU9hQLgC-g}=QgKPb z@D{PH$Yv^hBI*1T8Bk;lMYXafnXGx9ufNAxFwlIc%&By!{Kv;S?^*gQ{@m&&$qx;0kG-}4&9UuCKP8Vp-tzMK~&Wa$kTA{&Y$J|K8M-!|=z2m=&1`;D%>zVcwRaLRNVaBd=TOxk1mp?>V($(sDs@RZ-D=^V`{E zW@!>ulavVkj{}El!wugSNkf)DhiJYz)B}&4;!x=SszmfJ(P7p%HuVHs?@==o-RlvC z#~44IvP8~>bf|gf>-FN#!S3&{RdIjGAIZ+4CQ?1gtOk`|yYqNA9~YWgOn`z;KaH9@ zM9F;5pi2Dap%+7u`Ch9GjO(4!&+~rt0C%$H)tI%{ZN@X-B)pw}N1yZ3)Ja+}_Jd;2 z_T>Q9*1r%HQuW^LcLyDB3UivDoLa~c{d9fKY@4YWoKo>%*6vG0%`Vnj7qa`_uJ1^k z`t_`{EYHdG*4!S}y`Zh-%FZT%is)jX9{4)H{%wGP%sQn{O@L zeB--!e{ba^#Wdp%ZfFFlkfO4aadHtdtlm#3ZAy7dh2hEPU(+zdned}Hn~RQC3ejmO z+qn63R$-f8{krwwv17mLm2)OgpPk|GdqhMf`9vt7S2ir0BBFSE{Kd;c;~g*WUEAwq zlf!^+n>&%bf~P?uv_vutV`D}&Bf`b$AN^9*0zqYX@JB*wxp|A=yecgt9s+(O@WlUJ z3kNW$lJjngfFXSr7@44RX9PqIzi(2%ho(dC!>}e*=X%$u6XHgIrNPuNas_vJnB6tK z$lOmgtxWb+7kW`7hh)^OF9$XByBuXq=vLblj7(2$^I?vF@oL{#j>k2F)DVW@M zD5EY0m6XE!#k!$~gJ&ex`$gXMu>xkpRd^fXeil9%J5k$zaGa-avs1bFPyz(jmSo2y z*d9A)zO67g&hh$OUX|db3izTlUF;DSO+}8udB^1>1}RJ)McM9ZU?Ia5p_wu9;&~8; zw&o;nftpit^EgA-GRbA-m1oM`L)RG&GD)yLNEz+#TQUw$_Iq1Hb8%y_FZ5?KHw(De z1tWqmDxGcQ6cYwTiNDX-Y4GE3?Q1esQjn8b7`xR@*=I^t*3SqGf+SAaT@Cw~`gg8n zaKmMlD&23}3(u`=XX|%lDq2a1}&f6ekc~3|t+j+3Wnpf08*mot~aT-(y^r#*O-~XbZf( zyY_fPtS^x?%f{xQZ7eTCS5O;cFXuuvZ5ZHU0NS*3j3u=oqXx}bb1l$9Sy$j+2sx=y zoVyHM3SM8j-H6Jw1ix+daw{kBEh=c1)f5&?MKyBq(p%ZP$}wdVM$zp?X=hLm%eq)R zP6ZJ1*)#g=5l{>8!bTyDTzdK2B)I5ktOnIz>sK26L>fzGO%Y*fhI8r&_j2M;xa3@% zB%$ffqx^-KW1oq%=g)Cu7n_)rl}B{nH-ST4k=D~; z&{Z$@Sczz#f^O5JN*zDl3<6}KgmaNsAD0(wKM^Z!fjNbz+i(eyDNfd9Yv=BxHb z86yyd{*n~&Da^uUoQc08@K-wT<2FV>Za@TVh?9xv>rugT++SJq^OeR=AKI?(-e$(w z`ckSpW>#KaZ4e`Bo62!X%0Jdt+_Kwr%?IL8N9YvB_pG% z{(_D$ob627BGtjcB=Wq}o-EXy&6SBIMKX}gSon4Ftmf*MVA;aqXqedauS^3aCSmW zV};x>Fd)Yw3vze9Ik-|hGC`p6SdDh5d&ComHFC19=S#d^56!X1q$xMH76;fV$G9p`Y9-i>&C0d%#Lz0A4OifG)QKqzHP#nzc z?pb~Or4p6o+c2OAQFbL`E5>|07tYY#hXQwxez^6WU7z=(jlkuCZw$18u9&}k!HG{v ziRhQqf1|9!vfj$RP1CY|(Ix_isu^pCudEQ`Y2N-`#IeriLf;Lirxu_Jeh#9@sjeQZ za0(1}kZQ+5YB*m2m~NKqM#7NNa827Y5#|L&{}~Oo?*V4Bu$c_jF?pB;wlXD|n&1={ ze2(y^HA{vk1K)&;jEl+|K`$E(4>d~@W;oLys~&| zf>yqwGTbQ;sR-i8TP~>qI66IUjp7g2!II3Y6CA+Ug>=?%Cd%RPZrg=7D)x_f8rXyn z_fYmJUb@8q(HZ+{3TM({jaFaS)E{7F#JH>lM412>U%(FPgX>hkz(tTcI>c|enJsm@ z11aLerX}2_+9?sB8h+4oQfnKudY*U<3}PfzlC}V#?R$vWr}$2$-wD=wjX=+%&JTAU zyz1~YzIhg%XVey*%X|S(hERRe+U(dJ2a>G>w=c2bO=jS8p5flP(8c#PL%L`Q3F?B z)QO|B`uYAX5MJf<9iq3du9}k@mDMHT@Uj)5qhoLt-97r~4)5kPw)kw&DV+4Ne95(+9gk z!!2rD=rO_}KQ;7@o6IJUDE+ytwg(@VGhGM$%Fl;TLc*5GW_*h_^P9W~eeCFGyLt#C z>9ojxf=Qk%F4}u0&N}w%4_Of%?@K6I7Io^a8LoY4^V`@$>qnuQ-5V(_KjuM8T@4?K z@RXK13b5QnmqP}|n#P_E4(lP(*JuiFhSDrlJs9j^^k*ajcErs~djb*T7IeXHDYj5I^*THq=C?S`+#QmGvZrgI(I>a% z1t-N==d-jrN`D!t$ib9L{N3;3B;?lOeJ4GOSd76=O#2o}N?tBON(0cY(-x_`E{|MA#HabJ!D+ch z$o?7>%8#?JS2%5ekveP7Gg$`cz%vcA(N7pFIaP9jz3~caUk-WUf=N?@%P10 zUmI}!%_Q}k91Hb$6Q?gcRy_7~1Ijl_sMAGaL$Pj_@xLB&Y;RnSsmvsA*{R?+A8aMa zH~C3rV~3pARxCY1#maaNstdQQ_4lk9$c>EhA9KO(`~6@6WvN2b62eyzaQlU|h7!E- zW*t_H!naXtV_}&16RDAQJwaP#opYP)9>N*Dp8FQG?u;mZcRpo7l0%ss=yKY~oLI*F-|(7;G(<;&)Dl zf9U1E)oB0h``$BI{=HAx<3BKE1kTUrANx^#@gAgD02tDL@_!;Eq`i-&D-AfuR@?xp z&*%VrVPxsNt}gPwZ;L-a@f`l1@)!gYg=i=X&#wq_<=$m5kbkw+i^jqI`O-(>{7htR zx-mpiA(i6A=eQJfT#~aP#N=11YoryO60>k>@P~8t!;7?KF4jk8d3W&yr&kIf(jc^Y zAgO`}^s^);Y^iiZa3;HvO2)fWkz~x)`U^O%c5s2@qC^FQO1(>RG8V6eWrTuay?c+k z0(_3a{Y3omG(*aoe*s7&ypCMg*S>l7lWcH%LVBKt?)0gwF#`H6TRfr+VW7vsQ>FgU zs9l$vgM!ps-jVLSTZRzgd{4YdaqI1&WAa%7Bz*JU>*C))^jKB>(m- z$YTn9c2?O#6T$cst|H?z@$NB^3)6;Cro09_Escn=%C(>)-*`4u97|K1-)t!RgZ+we ztV8>WnvTl*%reRpspj1rq1~_@#9NE8R z^RR=9w=UF3U;!lsuQmL`%gh0hj}BM_1B%?mDt$$VO46I-=dwV1DOwhP`af8Rp>e5{ zPZ1xt6wbbf&Kav)7F%2thf4l5kpf_qVN|_?4Xj4{MS&|;McFrS93HEl(<$tgUM)<1njEjjXfXt6*H1zK299R z9?!aRmYQ(Q6uue9&JF(ZxqMy5uPN+uboB7ee5 zi*nZ6$EI)#KmW?)UP#rIYL=7MMrUi;8w1##ToH2F;|?mNQ?FtTkN!&W^?K(U{jGPm z;e|5R{ZtZ|g(+arWi!waS$g06`MFy2fhx zl;Z0$x|oXsy`USbukXF4vP!zFR!TG8#?pj1o+ajvii|&cc<6T+GXw{k}J?= zPH34%Y%d)FX{^PNmuhM~`p6Ot2J^Nwjt~USqG-F7AN+z%jWFlJjvcf(uy1Qql@9~o zI&w7ojiUo84Law8ke=Rhh7`toW^o|f6RMI);#fmso%Ib18QE4!BA8Yq8pG~u#ntE- zH+nCPg68%*4f?sF`U{5^AIHj>jZB!BoTS-HI9v@XM98I{W&`DvtyY zrGRG=)_ok;qn?&pOOQcmRwMMt7BD@C#B}}u@l$r~pRytTA{5GLBCyukZX!N+$DnNZ zFh+J(Eh@ZIE8Ym!1&7!Uzf9&U1T>=XJc$Ui!wGY|TuEx_*Ip6S@LuL1#F3WBa>USJ zRJXNEnWk0zsU^Bdl^x>u$zWYK!`-Nyp~@>@`OfuR*1r$eS?%^9T&CW6jCV%00hT-v<5A&~U%i93B^Cp(iuXK+f2cHUg{jb~f=X6q`4j5dl9LKDAy_Mp_2dS> z<4XJ*cjO@H8jK=bpUAVhPS=RY6Q;S=n;j$Dz5`Ezr@eGT zYPqnD03%LGwhJ4y@c>Mk(}W7jpYfYwN(0Fw)GQcsziqzBDl4U28PfX?)4}nkz17|D ztv)7rDK-2(GQa!;O-uOw>*;jC0L8U!K^J;GwLvj8u6{6pY;=#Bd_8X7Hl(1NH7@< z&s4I!uu)~h-K zn@^d?U{R-aVQTvIA^G_Rn_x=@AI0wv%0b;-Mwb-76sL=z!BOup+U16!5TqM+#;yOh zM zHpWLI6FXpQof*{y`$5(|iqgS?sPOaP-SVMPkP8k&Sz~4Zc0@3#{-$|D>kM|oqFZ4w z0kWNq!%$=a#P67!MuaP$xqZ@Ga`#mGzA<=4hIBk#5S}O@WUx7_zlnHmhcrg#AvH`o zMv(q{2N=cYAdiwAC9hasvKNinbG!9M_NRs{wiUU(s;Qtnzi`N?Q4S@kV^Ze0s9+87 z7F98mhsa_OJUfY_k<2@~9}LAQY$d&y$>$cQ>*F9YE7|cUL;cgssh`*o;9Z$lb|$us#&#OpX>8k>*fyHR&SZjTKHu|P=Q{tv z{4jgJ_kFLmUW@&rJ@wpmF|EyY63W}RMDu&=ZgED!P4V#qkqJWX=AZRwaw;ns|0~K{ zB4suCtJG#UtnK{;(e23ZDZk0xq`z)E<&Z4wl?nhL1CGR~zNg$fyPP`g%+%{{3y)}d z|KG!piV7F$N%=q3!$GV8n*8gi;Y8~*nM`l7Igb`;rd*420-0a^fV6$6qezMxH?E!>J{cb0HYV@H zhZsReG8J^{e1epogx4tZO2I}W+`Lxc#ENyCg$?7OetITZ8xCb5VA`)!${k_?uIakO!O812tc zTDJE;B~`kv!&^&Vk=^htvPkA4mY3HAz!T*i2^Yzjr6(=gr0|Xvu8dSxTd_jcyOBYg3byv_b+K;czd-0PFtQ?F?1!AuIEN z{@mx%9KSE2G58^kcP<3mLT4-b!RLD-*yy!i6Wd}5Ua^Rfu>EQcBMWEMwq1 zhT(0fnO~p7j`h?i)Je^3Ecng=&h-;*#gc`HDUy*Ux^E3kv#il!qJ6AFFBTZMKJBnl zq%qXYY&7S0&qV+eWI8%!;v$04wD5kst-v`H#XPrZ%<>Wp*6)&&YBy68qrJfhSZq!U z7EOu8B($-zy`BOelYd`GsF@byDk>{@c@feo;zxho_m<7=P|_h2`OzLP8WUKNcV`~R z68RQ_;KcMWe7FBhDaa)56|fI=1slDY@v>Ja<9f-lz8asiRX=f-1mAicw(hkZrQoLU zG{&40=`_>$*-FC9(;h(&^xg2N@R*dsj^MzCjzA)sIQJSTk>%3TizH(HrYR|{@N4#? ze9Hzm!ezGCJ7OvoMI)x@P4j-1s^o5RQk*2zkh9R&{kC5Er=D0*=!R_LA(Lz`eT1xk zO%0^1VNkfoUNap>>M6+Pbmt)lfQa}UuG#M$<-QPZzq~0rjz=TKr=(ZB8gIirmY9}p z)@;HuZB2aBu91}_VLbY6Gg2QZxU`iYv}C{K2eGwg8D6gLAswsge$RHkXiH&%7Sc;L zj|R$GpRYPwKm@;jmF_Wc?f^ikZ}|rAZ}^;E9A1wnz)b)unnI?K-s${;X2>SLP=g2w zYI083Fa_J!`L+MYL(HQzq00B)?jnpTc7)7dmx+*?mi7;VnZgvY`-WrdX>~^>K2zHz z)GG=cM)u81Nlh&U#m>sSwA!rhbQZ7ZJ^4ugC$T=bJ?WawRPnSs-*dm%F#)$NFJg4Zyl{x{Ma-tVtV3Dddr3jC8dB)pBBysl7arA{|~ z7W~`XZw+m4Hhr(_A$3_sSC-u0m;GyhzFS}JC_@!h?kH|8Z#axpPVgTcFkS>XK78Pk zatgCnaL4h8_@AaGjj0c{}wTH3y{bwm;TP4 zw0oq8tl()$@ElkFSwX#n&E(2(B25Sf>x*Rkt`=HuhY01mx_F+cvQ)mpOO__BE^1gT zScMUYSY#RrPswpj@%Nx(&|N%pC+?%HgX5C{Ay zyomwt%ZU_6rt{<ggz?9Eu#L@a)kiEbtmZ9)j;357rQmy6wmrjmbUhFXs zG@Sy6<_PeuE@6e(Mh4Ze71I3o!9PJc{Gby|)n`M^u z%mv9*88m#loXiOcy9D#Uy`~x%ozO*5SCwl>t&Q-}mX=V~n6nTIo{RbH-c&elLQ8d+ z0Iwv_F`b*$ZjMb#PP)md@s`_n=2N+~`z$uX{^I#5M*Ml-(W{=0vaW&kISHYD8m}`; z0;~VPjk~oqtzu5}PjD>$^ctsit@Sdq_2nq=A=6&FJ4n%}M*n}y4QR>5(&aJ$ygFS; zl|5j+pRB4llnW)u{6~m+TJCv|*?!+eYu%sXcYXg;7eZ+48~k@RIzW2_@D-pa+|==f6G307m~L_jWYd%MKhp z6VoD@za)t(c4SnP^3R{a8V0^Nz~Sh=(FCfhmEO7$(kTARPAq6JYymE>%juD4|Ne4qKRu7f%+spQ1c2ec`(5a|x6?Cn>yUYnrWx*xiExfjjr|a8x7uz1s_vaOX+3oFo3@{c}Rw5D- zUqVsH>_S|~eg{Z&sx*Ey^J)TqbGzsd#53Ei@+KYjMiUA}BlZ6R+VUjp;IA9(HK@gf&COwu-pw{{(LTPl37~CbF=gQQ9+>y0E~HkdEL1-#O3P_Zo^(QZQx! z@E%|GxhnMZHfvA`mked6P#Au*Q&Ak4>2N(%q`Lfz^HQl>)P32tU)1Ip*k z8%y!*2?Oa7n);9zLT+ZzPXdMwKUs{0f=*jEhZEu7%Zd@(d{_HP6kZ^{7)7P+@yRvU!C1c zCu@?4HeJg$5AV2#8N*2Bt?+6xVk-3TA?yz__N4hX2Z2=TP?lh_vT~n8S>1kfm9bK= z&|#E+mA)#97BlO)jbAta_9Cq%SI)cQ8O*?y?{zN+)7%4V&?+KCR5+SAJ=`hRQ}jpy z0Klf7F#lZUib(2KWe^~SEAi*`YyCM;b-!=5-$z^wp5UK#aC=kIiLWG~2Y7U{Rt zLMJwaMp^y_S*Q|F?n-nq6Mi_5tMM-N*^j8RG5z&W0z`#Sz(Ym-u}lZ{uU3duax?>DK? zk9`hD3y|W=C~%r~ychWZR%!U@jHVRDT^TnPgfrt`UmQ9jYb{(YL0x)8esB_SPZXu3 zssqxF+FuF3w7gBVHMHAxkh&~9G^N4kw)_?vM_iGhJ|^fn`RDL?PDDoL&zTfG+Y`k$=Krsc_3jmD*> zruGEcek%bo|yIl^4s;7{E_eTHD7FKmp!TGVg#l3tf9lbY9gc6Oc ztGjTwUzS>Cdi?#nV&SU}x*sn({$0W|!#zY9yvi`4A3pq@&Dsjhg@v+E1{Z*_eUi?{ z{~m{fh7M1cw7T&XQAqx*k4ch*uulu9`Y8MGT?&Coup!JHHJzNL#8H5Ci2LRmit9=f z9eIy@!Kl>Zc-q+uA3{ihho3rvx~At(wU8MNKQuQ9a{RthkQJM`K8;YCL4;zFP*kcq zaAb-W{BlLk9`u+Kq-d=2Wmut2W~u{B?CRj~H?3ic4{1ALx^7}(g39j1>i;}k(ZM<0 zc(IlH;k{tD|B_D*!Phq+mVJAFNanNUVklZW9B7-MgYUmM!JQ|9S2q(rBiMnyRK4>nUeM9E)3a}#XYdbgW(Ya4OGem z$LGR)O5mEGvt_aCzfp7bIEhi|ywXO~2E1Gi;EF_w zeuU*1V9J*$i;~?|)^+F$!TVE8q}^@Vb_(-B&PNxIqeTLKA&g#~VZFjG| zu0x_&njefipZ22kgmNMMVI5KE>ee{t^Gd2g$9~>Ke*F7L9@mQRz2m%O#*lwaD@{gN zOOra`EtkId{vBsl8?Kw~wbuJ)3~G>x-`_>yJnKQBzS9xkYL*MJYyy5@jmx@6tj9#w zZ_=-}$zFVo`R1}a_=Qf10VJ!WPw6-q67+G5ssKyic{<~Gci4k>Ob&2}%s8Nln#N~| z?p1Ogz}<+HfPT9(SX{L1Bo`^Q5Z11Q_OqkpgCMi$aPMgX|JfJEdJ;b>6*%26ha+AK z7c@!wj1SBtg*4iFl18vhK{J#RfoS*u0hCht$y9BQfF;MjBDzY$g$o84T)3m8m-eVx__Yb zRDOBLGL9sbmeqL`d9KwQH20m6*Or%Y|J3Bp1C#xn&(`ysQL91D_MwD%~^( zTPlW@DE(4JO7Dr9_qw6{jFH?$%47k8oWUH-FjHsmp_9Aos=58@N*fp0`{`K@ANaXvVtS9B=%Yh!}83{KF_f`vw1KM zahFmub&%D2#R~7%-tNed1l^3I6K1p~lT6E_N90%`U#f;7nMe1gmy$(IAOq_{ma33T zN|TSsPe>3rI+hIV2GfQ1d?&(_McR|e1_sC2nj)#ZfuUx*tr2abQb3XBY51$OtmRIo z?>lq$uDd=kiLqha@865iI&oJ;qd|mDf+`RLB*nN}^c%EP2C8&kOXY|A(HD!=ew=UO zCH_RTu@l1w(pU#?V_s#Avc~DHM=VAt2%7uD*Ld3l^KpP* zuw?$fHapy9kjW|75TI4{14UowuR=iGfj~tb`GGqDtLT)KViI~?FDp~=W7*F&U<;u) zpIw|*$SJqcMbfm<{+^;*R{LSYq2|q+j>ijKPk+sHEBdA2U8~=e3rxr#SrA%`c)Et! z4YAt#E9g0Bmz78b1P-4^FJ9o(BmZ_`01^QEWFE{}u@OK0luZz}qW z50_B5)<>M#POv^Nsjpe;+tgV!lX%RE8YT!hw5AQN{QJb*=S1pl$9?3h67n6K)e-}C z0Bx5vY%vbK&cZ810n1){o01_ry2yHs$-v);6k>i6>4mDVn8RUgiS3_11rbBN^D!(1`R5T zn?Lm4CDpT;8uO{BPPq1Rqi#c5_roY(A+%O)=WWRcL6G}zf)!}r8z2?$RiYM4ISy?d z4BdA$_cb~lxc~WcUr7=Y69YRgx`{LloMRNQ(Y0|bZJQ2nLj!;B#{#z2_?>n#N2_?R zi;@@(*0a3UETOM9=wsfrxcKQR2(7Z~BEPYYG}DT&J4dF)c4V8SN1YD)+|+svI5~nu zeZl!{<|O=C2_3}nsOb#{g`6&Jn4cl|WxwD79y3b)O~aDLvwCT-)j#mmfu;>3&Cd4a zY$k=Rh1APzCX1Ynoe+m(NMifCD5d%pcnvEHSFjGWQ|Zq|sS9Z5$Yv)9MoC?Gou0Ep z&bCIVN|&h*uwy0NYRX5?T))jhbbloa86*>dA}k_{q)F@A)7-Q?qX6uaAxUv35feX$ z6Wz)V(?6hF{`{CII94`>%@w>C4&$gR68Wgr2KZAyXhl8C7q)|IuG4IYkTqD!{s|e& z0HSfr?dni&F;ryaiS4F@T`23yrU!S%)NR>jzg9!aBsoO=lTLcmlbP}=D(R-RM!D)v zy&D@=*=OK6J&RuSnw-+sN@3u|MVg_5WWs=oh?=3<#a-*e<-~fB`>`#Q#a}V|vrD3V zTOionRyR?y%=q)arLN$aDc&D>#C=NmJ`4c-SaS0H*u6;7wvfL7!%qUr0BEpjAQ}sa zwY7#OeBt>jt{ec1KExk+HO#;Qe6X&eM7NncEJ=%V2}WdIs?m#~BlFfwt+cW!OL4Px)Uq$WaIVEznxw8h zaW5sysMAt8@&dkPv+u*izTAjWnrW=ksL8?S^dYZL`aCKH>djL&&wJdll#-cR@Dc2$ zHo=P)-JQAJktYgh4=pR=?5C>fz&P2WL>^-q0<#bAMW4`(KBk$>qdYv#3oU+t^xU<* z#GJZ6P|@iT#HC332x)uosCTPM<4kJM0u6PX*c^dRU_qpbm053TPzm}4J02fVBz)TePJ_Ko*~oZt)OBBn{azi!ewpUa z#mh+U)tk3{KD5AijrtHI$SXf3X{Mf%bF4{m-Bv&8_D+f)B@^{%C24K8eg6y5o)0T; zNkeVFc>OH|((Q|s@sBSD3f;896KP(%As61=I<4t4J0EI2NR)-1%$YeEYlf)CyLK?V z?!|t#`&OOL=5$_PkmI!PV>#;f3as*sTqVic5gpQEfpHe9)C z`V6V3;4YJF4?q(F*5ID&u* zXgHtO?{@Y?dW0pnF3G~Eg0K{LgqbGX7Ox3t#DBf`OpcAs;-Ny5*!&kWJXL@wa8|&Q zr3Giqwifs$-=N2@^(e#oLFWZ?8Vc4eUT2@;5xqT+j(_QX9b)mzcLXzX@$>6kn!hlf zow4sdtlMksQdE7dC-JH7=epIp+IOw_9g6HbUbbEQ+O6-t>6(hO-V417pD@$T zS6KXCPYql<8;4G7daCbt-N&b%ntd*26NxvWpFg9J=1C~)FLR$XeCIC~xbtmoxjQuA zGu)rw7TOs=s3%_%P;bn`;}bjjXh#jQm(>TD=i0)$1?0YO6yrK?xTfTQgv-@abd`J?O3hGQJI;@DCR_#KrrO8x_fPWG*G?4|J~c~ zX;$}}eC220h=^VM2aR&*9;-4O^1kgjBZJj$DreKQTb)mmI9`cYB6L<3|y4fch5JYD=nL3f&xQVC_e7ru!Op=>{e z3K8!F75RhW!m862N<&B?&??B0Z1;_T%WW4dq1QWA6nezVbk52&)fad=FqpCth||-kMXcy86G`(*Qt;dJB&yc$Tr2&uz9|eJ zJeU6Aq^($VC@-R&d%HU+L=e+wk}bB(NaL(sx0`Z*4KBc+;m0TpGqYkY$xr^_0IUo| z-@>CGo*nbld!yZ2i;yDw&f}rqc>L-g#&Q6d(oTlu@FX6jK2&UmeF+2 z(o}~_uWmgSr@YD;`|)QjMd<1ZMSdd4t~?^xYrD$in?sBhGj$kf)SSBm@3wQG;{do7-@aQA?KGu3bS-iEmqU<=4deDgl{ZEJ z$>q4X3gvOkbgji$@UeJ-m;k)zZ36F^2r|!+)g6InNmdF6GFe&xyCOk^Q4mCycamwQ zhig5m*=R|YWhX|%Kv+;5(aG=Y6qIMA2)M>S@?(VyD3K7Pvmt=R%r8UB59i^r2MTt_y6N!e$JrPM?CTPH_+F}4k!TTO;@ zV5QENUEkXlSKr&0>py;t(hPjPrh>dH%EQ@8=#LXFll+f@iAnK0rAjfcCRfj@@yq6z zh@n|QdFCJfSQX2)xmnJRQduVYxYGYk2-WYp*}b1FNaUK6A%P3ha)xNn_`c<{4&4Dn zCwwR5a8J5I>WTy&oG*Ra9>R*KlYy?Bt7x1&iO=iBbwkMbIt_ivIOSKfdNC?Pauvr}NF&j`9BzcBU8Q_L0O zu^Pv=uCZNtr)xBV4HIdmiojt|AAM~&kLbI|v&h^4RB|72L#@5J?`P&ui!A;TRXQDS z+2dx=u+h^n3U^sk<`O6*0U9kRZyho7fy0eP#VyV9`lIc5P_N1#g{zYfr=Swp0d_Zi z7m~(j{|;N4n_R_WHRDCmgXMcww=usSAhOJ~9{s_5e6Z2%dV&@#xJsG@%y5)J4Mmn4 z#xWQjSxG1#ow}hEoD513Rdsl{OOx^g{|mA{;o$b?fw~Z@1mVIiLUKRqs?=6gH#e&T z=&F0(yl}XcqI+wXSfdMYhrwza^~Cl)ug!>rPX!cEW;lNEjMZcinot=fDxwQ&aA~fe zc1tto^;BM2I3>=K(bZ1h^UH4#yU^o?GtcYY{JQR3occ)j&F`8r)?nLuNJ#CZE-84N zp=Pk9`<@BK8YLG)d8ZCadUM5&S(&=9UJ97e_Ily{J2ABU*t#D(f7{!PLdYQ{uBhvE z4L;7*2v9k7ZgDx8<2uDQs993?+nc{?7JTu4?#j%@Irs+#-*U zk1wnqw+KG*FUPL`HaD_$eB5-e`0?)za=CnM5f!_N=KnmO`xCo~Wg9|F+)mQ1X{rSf zGlgsiJW%>+ZB;XCj9X8|%6^QZaXQ1)HFJfyDOeD+IGfA17zSvSMDz%*)$fdYFXRY9 zE)V>m+tA@WdxM=)KykSj18eMJMZl#Wp3^?}xyw^--^=&^p`3V(^Sm z_q{2LCCx#N8$nD&?UzhL4?BaSjbj8-b&RVv8}0T-p1wkOp{O$I0J6rV#mm<#utV?u zb)ma|!xRr47wRFJv$lL)Dzb+J^lKn2tFbGZ7Dnpvf!pWx)I;?`4+5#(GjyV61~eJI zy>tzKSkAXsbU>dbU^n}_?sDxgca$`=$zI;4T~%}OR8?E*_r~A!tD$B_Wr_;$1mIZI zL4#e(gSzZxyR(yp*ri${R_x&ExyqWP$-MnUsJ>zwZv}ghv*;5)viEF5D zkD`oK4$HGmeq6FN$)_PwX69lV)AU=jab;@~bzV8(n%H$rXgIKIg}Fi=JMph$#JY$Q z<;YVmiSePvjbIb1UWue~skeULkWfd4%jRLbtISyNYvl@< zdmoB--u$y(=`2C+7dH7F8xluM>g8F zBRlaUPH2R@^u5jE23bTjDOtQOoDMFgT1d0G1cq!%FZ}sgLe-a6HLh`GZJ71kJUnXT zB#9|?agP%u{X1nj>LEk_5-5o(=4baO_A9?4^Y8xVTQa5-4zZivX4Lwv>1xe1kF)0+>Rr(kHz6*cQy>)8D zu_|aL7r7I?e<%NP=yZ`YEqO7`d=RC&gA26?z!_M&?h^5Qqd}s$V z&D$W%n;kk=L38V{KH+{a*Xl&}@9uQi+XD9oNlzf#mffREe*?O&XfToO{DD|OT#erx z%6RV=R9$r%PpI0^lysOPf zmP8E}9ENNx_q@5rGys$q>P^Nlt8_GAc(5_+&=3(3S=}#myW&)`#-Ej7z+E6# zzZZ`tV+Fg;Yl)ZvbCwNegKlELAxzB=h9B9BKxplV_dWY&(hXSH0;lYr7kXXK0ngT# zPUwj#w_lF9p$)ra6&?q#kJ}p8$fpt*bWD#fFw=^sKDLj(U;*nW9s4e|xCTF;Q2Bi1 zs=D*7u8v8zIW>KcUD&f-vGySlOHXumR_o;_+w6{NC2j3LxrHrb$J`)eA`8xVVBpO2 zMnJSG)C%*Z%|5S*rj~mv&uVUM6)u)PmbT#+G<*DX9p`z=fooy&23FkpQ&CA0#Xim9 zXzLDQ;)oc^Y{BW<%dn1ytS$et_ZbNH)SR*`)xro)X9t_EJ<-X3>V6d5d4mK1-V#de z<#{|$nN$_S-U-(Hv=9H|5;&}gI2ZajjFDNJ=lXJ8blxhQj&=`l!`Yl7WHq`v{I#>H za4)c#=7aiR`XiEFh=G;`&34y*tKbgw}H3d8vWNGNBMDoVD*ig2YF<-XW) zQiwsw`~ofTslLq3zW1I%IdYVv522`Yjd|GSb`}w zv7)VRV~oNJ0rQS3SO)T|P*F@M$4coUeoCXpz6L@_@tW;wQXuv?fs@O+FTtfx1X>{0 zsq+U4wyGLt6s-H}j{(U9hX)Nme-vEBj{c4CgMJ!E#cC5CHQBF8e|srmQ6O-j&O6TO zs!!23HXcq=>2E}*ilrH*n=kjCq-T_DB~I4srY;J>X4b%AS(zOi-WGCv zt(>uci23=85?SF!%lHFnlHYd`vIky(JCq*Xs-6JMu{5dB8Y3Iln2p8Az3Qw(Vb;qT zpITp76&PI{*IDtEOG||t`qsZ1tzqB~$8ZD)(W}T2+l+nOMO+KyMhueE*OoLO6lhb8 zXFFqTRlT7`B6GU=Vt8;6HDms?db64uJsb4OV?NA=&rw_RAYEzD$_cbSjy?DAJZkVb z3-G>v3VPfh;Jy4;FR0B_p8t?8R-{Ir6zf2oHm&NcV4PdErh-!B5mrF+kiDpqI;eV$ zLIN@e)J^YA!G`cI-AHpyOfML?aisanX|nIx3fV+9usXU%FysLA6c_?yG9$02Ly{O)Z|9=R?|3yeC@A0JqrZzB6+^X ziC_G3MwcfJR^otd%Foek{PxRS|K$Tnz4G^Wo{KXMn+VGdeffo$;NkjZ2;S~@F6;#l zK{EqYkYi4X(SRfcCzIY#Xi1!Bbul*X4-Cviba|4v#!dt&xv9qI4d%gWai6p-umgUA z!v}8}>smh@5-XyEGUB7xf$%J9l1sE*zM`j!nNqw|E>>BWlP3FoHP$Wlt1Vhj>FhS2 zwK6s=hkbd#@FMp{^exLXWoR5>)I=q*Ws*h}kKj zYg!ZKA#O^jQ2%wrzsTSCG2Hj?+?!NPlmUt3+NP%BMCpSI`Gn{DYZnYjW9RsxRQsnY zm`43?NwP|giT|X2Es-7jzSK3jUwND_YPf=xplQa|6_6aJP#8~gG@&427t<-)I#=_x z`n7NYIl!#1wj?{1{p_$5@#aNJ`oYlfoqE$AQB3J)=es@6I*7{MPXuev_c*N4M!H22)kGi;Gd738v5iNcL+jH5%!ieCWcL<;<7&y>8-;Q#*S#=BECwnhj(r-P$ zPIa_;?MziSTj6%|)}+&EUBIn^thjMiO{0_`!7=imrJQ;*%vIH%uREDQoC@ea9HG}VPA5JME?|yD(C(p- z%=o*~XVeqkv()-CY4S}s$l&$cRqp!-|F;IMFOiQ5ZQMKd{tcAyaRQ$P0g|Osp^mmA z)3}JcZ`WuHfxQrl5Dphz=F?dIUp?=e$)X8yDEp4(3*6hm8_Du*KA~>|WP}WY+}k$d z*sT-l+$`^x4o}8H%KvjK#p1U%j&{Aw;8}1b1MDPXiN9{MA4Clc86S(Xmr3p&Gz{#< zX%)Wj0I-|uw$+xn8y`Prpc(Xx3H&%uPyGe+z6-`F-zL9x0KRp4PMQUw!7f90WK#07 z^JDe?@3*%rbeWbV`> zxt%C-H4w|Hn|;IVx_4@@X2seTpuB#nO)_18ds$JN3y+Na_EY0`etZ2-x?0|lO2>P$ z-ELp|=2%b6U3roZ?*F7L<8VNc!=`0Vaseq?UPrW)bPRunzjClUDu2zi&BH<7yY<{X z;*%mAL+==zs8_(&Yt?Ix54AnG;TQTk-?$uW*PLZ{j43IcBq4t}iVdn?RMT@5OQ1RvHJ-o^GRJuc9woGt>L!1`I?+e-=tEfKTJ%938Wo4w3}J|CSkq0h;#c`qc@3^)+V1pg%? z{x{*!f+GRcy-FndOuh4zAkA}J<`R9jpL&{Z4*<1>D+M>;_f4`;Kxt?h>-3z_O>_a2 zS$^~Jn~ydN63@o7H=7<0Lul70<`o#oPI8tUK{l=$ka-w_qFD7b(p2XG%CiVu?+5{X z&>CsLt8Aa)bibdKutciG9w1@_w8`8;ksOem$H)Oyw^79G9h-0OFK7WQ29igzbzH@T=s#*8UZ9e?aoZ9gOw4(^KF};%@bV7YJ&n0jESYU9SX(ZIC$h4i`r?1e_Y4Z8cw}<_zzpue$ z%3QXu%^V;_f`rLlKM9Zdniikbn~YYX=0^MSI`)4=^1Img#Ej3#X|&5G5UefeCIAcZ z8(-iajL_W+v5ASF74)`jj(cL8HzDNA@{IriQ>K`?#lzCGRFaNw z+9q8#yR+`yx7kPD20AZLd&`n(Za9J8sQ;Dm<)?;$qGJXi~Ym|MDP zoJsa}6*if&gxdTeEG3gieZ5~_eL}x~vu`(C+@IP_1|46ljim?D(2 zKkc|c%|R0xdXe=vhXtP)Vs2zLE9S4{`CpVx+r?{S{z~4ISP=4F=%{kz3sH4_<9@pC5{@drx z`DI%LUWr3ex=baW@TLm&yz)9>y1H8=@7;_Vf1+i72;9?Ji`}rNK`Zju*w?bEY6&%Q zUZ_)yZT}3(@sM-7cNI@J@a07Wrz$x$+3+OMv#g2@7h~d%BPv2(gN}xdik*r;+7A(h zUMgIq3E^ghhuezqSN%AYg3X=Z`185cBWUBe-O6(uwuS|3Y*kda5NRT_sz@A}Pd!j1 zAlU@(%L6y)`&H{h@XPUM&2l?-yC!2yBv!Dp6;^QRYDUDOkan$dpSbRqz%I!;nTZ>e zihd5v+$B@(Vqk){4X6@(i9+H9^>ytBeuV&3`mHB26LEw+9cgirFS$N1`Vdq=4xA0` zCnV*z{a!#hkM>Ps$8l`CssP*ht>EaFH1JO^u}kjMF!6j)y(<)_LA9mRilo@ng*5G> z88bwbfgb76^y0wt?RX|i>gESE8Xw$OSYUD1im1y2-?XBNN_)5Gi73JMR~?6qU}Rm7 ztq5p?VGHkZw6&Trw~9uIsb(k7AUyNmf~(fRt9Frkl!4O}=PKU;ANmyI9#$09>z7;7 zVVaP^n)6~MXrgcGK=LDUYVKa5wA_%tga^%e0{Ibeil7GJXw0L;u0(fuS?}{a$E6M_ z)@Ja?5U0B5!E?fmM%C6YbAz;?p^8ryH#3+DIb!i%QfpFTQ{5GCfBHqQ-}am)ynLbU zh%1pLC0~l@!WM5Puamt0V%iC{nIli#=h?>+`6-G`VV&9xC*Zk;r!YzE596UTYawdz z_+E&j?2OpFGppWvJRM2PnArev#1-4Ml;ql~dMo%xa=1%KGVZ9HAg zWQaA+KvdV!sIP*L#E<X-||9m4vL2icxt{d5sP%V2B@TX>KtXp?che1}ngD0#27bS8GvxX7>&iuZI zr#x%rltg*)-*ac}lu)w8D7%S&8~!*E%hp%%6!r1>v__}+#r;QJ^Q+FU+YxnH6-3@q3hFVJVJ5<_P*C$VqCV4z+ zw=T=lwO~8V{qXzgQu>;578x_iAz?OE^@vTk8|A-1CTp!H>}ut!DB<@bIq zIio!qv&RO>;4^pQ^MFnE>10#z8NP3dXKA8UsB7ggTkr3pWaS1x3XyE1st-OTrG z=L!6uaUPZXNqwiHraRJo+qVUbf}BBG44&4|_Y{9z4?-h8=QOoEs;>Z$lMthtL#;j$ z&tGnnoevz?c{gxty3}I5$(V*W)XFKY9c9qo8^;_ZEZbrXQp4q8fBokbY}lczMhBB9G6?iYBURnTT{h>s4LS z-hG#!`7>SBvJqHg;J!)WsNsKK;qkW*PI&Q@&_b$8`-CaB1*FY zas-iF6WxaD6|dJo(}gzEcGT3=l%al|ku~}$v}uW4bB|~>L)$X%m2Ox_kkweP_>wXUyXBPWq{+?( z_!10&Y?~;44Cg1DaXVos0joht=+m{O&~0aHxJ9J2g2u@*0Z{8X;sJl%7`{`PC=7_%A79Kf&xatJTy; z=F~LWYqQZojLvlY8XlJYp)FA`Qs?JRf45<4Q4B&|(Kb)`UF%{^#?oN^)lioEaQ;0J z-*DYN27CW`gPE%lamhOn?Xqf1IV3(C?>4^ERIZk!Lc_jSb-E`A%s@2rmn0-qsU0y} zq&lZ;NXq9*8b{yDmXyn8!z?9R24TN7VwLB*OxL8iZCCzZL{1kS1w*Fn^eRwv9H^{a zxj_Ci#Ny-=hpi8SFbFdi6CuCeghA+ehpF>wT(?rQ3of60B#~F{%uz(neFd({cH@c7 zmQ&~9<2<3P_MABfG;p+(Hgx>>5r`oBEI*ZAk^sau5HCVu_K)2FsL=FYIQB8e#vYcl z|NM;yJRKINUu}Yw?_&+5XmjU;#X$FGj5#;b5^j5Jji-0DlxEy+ypzki4PkH?kOvHU z>Ka=e;1_A;+8cod^5C5g>uEerz;up}J#S?fCz6*#aF?B-RhdiUg3+&evzeAn>&W{< z+6|W+Za3hc&4u2K(Jprc(w$=x91gW@H{%Q)jk=NoK#91eh&c}^3<_Fd@L5McQMPsK zF8gw)9jZd!dTYD4o{NjCTfUR%daasH%0^7QUJZ1m;PJ0qkzylq8jm!GsE_uUA76Y> zui?hp6@{beGuLX0Fn^_G&sTI*FyjMsAO}6uoTji?T#3i|9u|t<@RD=mYi|+&+Rtfp zAAT>f49=Jy-7S0f>=Q5JEbF-pwMR}uRk=9lDPGCfZOGQ6%L%E-DUWWXr9o{fJ>T2Y zzH3L#ig8RebZ}1{>q_dpo#MBuDsC`MY+c~aZ!H#-6}n#OdHwowrhp*_T_o#%id1?T zXzucaH$ZOy9|PXYb^J7Vt_QIedstR*WBlH3b5FVaR=-15@`rI%hgh_ZcCHMhUpOD2 za7o*j*Cu`@WfW2y&){lAE1L&SKgmHIGIuezcXpS3`2S&-p9FZIhM(($B*lMdq>w&* z|138ce~vjTRR4*$s8bz29%5lAr%+jsM8s50YI(_^u0&m&LpCM7MI5Ta4gcys2OOZm zP(A!8edOFaI&TRs_ki2ZPPiizwa)$RxUoa5(-W_7x*;7{)0 z)NuLZ_Qy`uYJ=8W)aT`l{*DipN5A3zvXyDkpEvM|Vq*tg(dG?hR{7FSlq>u-0pzFwsx%Pa7S z8-|jAvCTy45K`p}C?#)}$Vr=QkNmI&<5tu=PK|WHl*C;I+p(C8Clyz!y!VGLj zq|zS|LcT$%=MeL9wRn^e9IJE5xj*p(;W{q7^ma|i70In8lP;`NawN7Z>Qr~ij_^ST z-Lg>roXFbC>I6sQ#2oeY*Gh^?vLRZbCMlChZqIewmi-ezRS?2#8K$A4(-ooRJD<_F zoX^bshZ1_dAu)&2np*n5>ZMqMu@HAoT`}k2vcI?+w~uwC)A#3pSx8|Nhw|YtDqmm_ zgvk1HY!*W6YfVo0ux(km?sxoKh*V1y28Ik?FuR|dh#ZI13P)XNu8TN?aX2k9^F7yT z+U_j7s8cwWm2BIVXvwicR1w}}l}G0+S=8B%N9jxY%ezi$NpXDRYwQl4%mN=6c$|-? zhPK}yT8@g@iTTX?gArO+GVZD?D+hzn1oGZQCm$wn(GlHxe#811>|M&V>v?}_r@sFG zSUSs~HoLa%R&e(~ad&qw?oM&1Kyh~h#oa0HS{#bI1$TE1l;Q+;zTD6IceI~wxtmI?@B|eR3w<`gqP=q*k+rO*N&Ycr{<5F6f=*W zg0@mtcHn;TU5|<&A5o;6)CQ)CtpcyG&rPp=%ckX-J1PtJ%>y{Ta=V$Ln{~!#@(sbM zH5dV)mLqu9)IC2-wWZ}b=I;ZXgJTP1>TpSqWR&pVS1qu zgWpxOo0p%DNDX9czJwL%qL#&cq>O3MxkzX@LhxygUnLgV`X`ZA+MA>}5FI;wv z*F#xMCPr`+MGMT6`=P;>*h-eO^7B8}*KFW@q9%U{9((&<&W5{F>M3&U;o{wWFh|xV z0j(7n`EY;tm=(`#0)f)M$jjmR9lf;FA&X0Jmx_ z-o1%x6m2&&~z$V*N3VgPEc4fBVQcHVd%{chj-=9fBD6vRN ziu+2i7X>UPfRI)pBba`c1)dO9b@kFu*@MWIMOEJgTThW)TXIH?v!gI5epJ1crtE1X&rz;0JN&2=`b>0I}& z1Lx{QNrYs+9)~qys2jD2D~vIg5p(mAb|7s{;!oW8w?BwHi-q4${BXCqQkYY&i2?-+ zKE&o?>eLmYP50c8G&`)5C$4HZ+#GKL(tt;dtuN!ogT+N7#?J3|=vhnb`amO552yY&1zeV(q*O3?rt=LZ*<`yFe6^%(kq+f<33f!u! zw>jc~A}jASae{Pf4>eT%$`1=-~-v=;)UULfd?BXf<~o(S0? zz9Yu1mJ-}K6y>`=K%q^RrVvijrW2#yxNjG`IW1eg*ecVYGDaTqualUz!|cE9|K3^! ztqlp(pw`ReSQibS%|Zq*02^VNE0pfLsJ&we;sYiL;Ox{m{Qi^7<-~nz>l=eGTWb5R zV(^vC7wQ_3RGFumW*^=q*1Xtn3PxhOM`-+efzv0j%)(w>4!Ft3UTH2j98D)I7PE88 zzX#`{eR}y~nVzvS4)gyMqEu=z4UTi>fq?Iig6Cae9-+Hl;`Hk~M!L0jqmy#E#+cM) zBkj71)@?7rM?d+=sXu=3(t66n+mVzwu_Tgw{12NKK$YR~H@5!^ImC;;tz4ZE5^2W^ zyIiLBzdC;J?G0=_Skk|Jfn+{D8^1?gX^lq{Gc*$wACx^1CiO5Lujn8+4 z*=oZ{jrj!8N9BBtYnfB?j+fPcCMVG4A!Tm&Qa|qd1fP#4{in%(w1r`=68}4lK{Z|lPh3{*g zN9nsxg454N`uuWPG6T(5e@-*@_YTj)#p${9zNO9cE8HX21MYGjMtT7ieD9^Tv`z(=(E}bNHXYU)%Qd2>xGD|%*t{ax?mgnIX0xQ2xySG zygO1tD3kENdd=bF4qt=M`lCe&?h84{Jy|9OKQM#S>R7J@4NZpOg=7N0P}t?gCigiC z`PzA|k*P^`9&>cmp}5R<5z=>@0QF`BNVCM{*=#vfRim0i=4x2cK?2!)%nja03?e@c zB=tP!9P4z8@*Ek7qu{qi@>J4t_da`yOn5J3)bY_>qSm|?RF9UKmnt>*JrASuZbkgp zj^{htPiB`DQ4nw~l8zs0g@D)HGw9D$zRVO#8@&Vlu8UFmM6Tf)9diX&^+*nXTAS~I zCe|}QXD?J%miODTiUj*QzB8V;y~ej5ZU^AK=Y6xgei~OPYHk+?f74Fg9q=?Bo+u;H zisp0d;=vYdag;6|EdE2TRRwWYdI%fBpis-(r{?{N_&2*$glKVek}e5r!zKQ@QimMF zt)QMhrm#AT{USJx?c(*Y&i~d=^VfwYGF|gQ!VjvSVeK4t+nt~Cn7s(HQhOLgvFQCw zKTfPs-+xmMa-G}!T;ueuvttNL2Okoc6)OljT0@l-?2NEZX5DAvF6_U zJ=`yYtM5>sI#JYUzfO~laIW_*P)N`gF&Aix29-v|sn#K`9`%mOSb;Z^p}iePjyYGj z0+SI~IwC)gB=ze?KqvjGEU6pEoQ&Z|?JWp`cLQcBM8!EP(3}A&ujAu^VCrtQcJ2@- zRG??Y*ql#K23FY1Y?s@lCYgO(kZ+D3(sa&{Qwq$HsWmMBwILHj7s|f|v|(6S(TT6f z^jTF{VDD>nP>{q+Y&6)S-)Q}8n>yJy+#JvE-DyeaCu^F2!&xWPu zh_9$MLTiVYEV*6}ByH&Li1*u%+MN#*13FKm!w9m1I*zz3JY|Iq?_;9#+(S(!wI2$q z>uM7BA(2QYN_33uN(f?V$sc!t_@;_K<%e5$a z1!I(|uE%9H-s7vocS|pJJ134Q0cQBLoV4(p#^wMWhZVc3h2j#Qgsg`9`^mu9Nf>nr z37EkS0pqYJ*1*nN|In?JCmb5Hr^wa6T4&HFb7}3WO3(oHz4a?7j1}{I{5kCUeq>@ZL(e7>w_oNtYi&gRk?!w^48rjI>l4Cy40V27hyct?kK25 z9LN6`AD3iy48?e@_~$`kG|Swd^&-w)B_VA?_g{M2Wf)dbetBd#Oc37>%;?a^jL(ql zp$_+xrCn%TtqIrMk?zaWsEU7KswdqT1UCESfT| z`g&?5s&OLL*473!(|Ec#J=D?|MNr%a5^P@g`}?4;UA8cV_(p#W>j7TI|CJxp z#?s=lv(qhp*7_YVdfm**d~>^oGIz&3hPk$F+@C&8{NRb4il?I5;?}5~lN-zFByg4@*O@(2O3RbG)9r!>hYq zi!S~pKD^DN>-qX}GBm&|Gj6=gDf(|+6w_)Qlph%vLfn>d=!Hy)X@7c2M&~bmA1RT81s$B+g)&Y6)t{>cIHQ% zdT5G`eDLzda22hVmU5Te-ti!hSfB!2xy&UP&!E4;p~)EevrgehqTLP5?vpACUubdqkw6ZXIuX+ zmmvFkI1F=Z8^st(5mLp7<1GD3`bgTJ`Y?3HW53UCz7QVy*-7K4gmWMfo3))-IQ2u~ z=Nh~v57% zr*mCelZTM#gj7+rVPy?-RQYD+uS&B_RFcc1-pS4fV-nW$ADHxrdmA{n`-YUbfETHD zZA6L41R1Ljix=+^iA6&c?EH~ditSSJew+S=x%QIHMxwzhsJCi?8NBL{Q0!TGKqJRI zeBt}V9h2qNSnPR%g`ADS$hsPeteh2*`6MlAK<_dUZv483m(A0SL{LMm-XPrtx40Jj zeUyC`XS6@N#ApG|w_>q4o5b5CUM_T+a`?-Ezh*nOK5y;NRN-R#HcrF{G-Ep%DoGIi ziiGWS(~5#}nv=gwdHp?$FO|YYn8!zYx2UP>@?J1^=&urCG1^CK;paXPxdcdNH0M;8 zPCHo?KlCKoP>`pxiF^L=#Woh!R;6X`yf{Tu^VhfjqO>j|)72&CJ7>Dg-|JpUNg9`j zqT6BDQ^N40F7~JB@pd|4QD4^;j=2_jcdUkU;!LnFxSywQJ>O6%RfLwHb#>dY7>Uf< zv+ZBu$N?_{q-?dnF4MO~Rrny1wzak|y4}NRcWBr+-nOPq`t@1d+1dFzNfpO=Z7=5YZf(FT zqeJ2}yUV8g@@}s0x!OCr|K(>~V^y{R>Pms&9%%FOR`d3nAedRYARij1!ixH}$K2@# zi)7F1u#U~Dv}Bg=&9{D!Oq2%jH$ zU^yE<)NXI@rE}ZjO$lBI0cobJzz{#^5@CaxTZgXSlP>SPaMrS2^GP$RU~kY2M|~A9 z;GytKnxvqrPU_~gW7qAHzpl57(?6{rv6Vfyg@m=ZdWlC!J&&lD*Lj5Ro1U&pyx{n< z_RN!=Yl*?rmN&Zsx>l)#sr?~SShr7k7VDn~wnWiy zsCA+kytnJB-|9rGeO1$}-QzXdk6c%GcjlC^SpG+7kr30>&G5UB1?9cn(59@6=_0=+ zJg!5rHU2eugsj~Kbm5}P2+Xv6dxYV^qvym59pC(1M-na?5dE(g>HOszD?vvLnb${X zPiO*S-L}3rPlxXQbP>GOFTtd581bTy-?N~S@`Rq3+uF(9#$uP&0iL&)v>s6PT(`u* zL#nrspZ+^IUgXbR`_SC9$ok2oqh1kzHi);Ft`KvMEeL~Rrc-58ux_9QKuyG2w014KL2DvjHlJyyeZ3!pur216;LdLC=eSGO- zg$)yDvD+q={3a2EBd@?(m9x-aAv^IDTQ6-|m4eR>t1rg>6Epsjq`ZkI;2_@GDq?<9 z;Nvu#<#?o{x!hocBmUeINpirM#(*I-<#h(|}MhxB6^5 z{K7)Gl_i&S((!_b5c5@=Ly3g*5Onk;eE_y(Gd=!L(Oo-qUr2>hW|){~OmHp+Y{Tv%#r;>_E5urasNDz}uG2 zPwPcL_-{bO3w~#vR0hYTR`e_*VPYw?&e;_R3deS-Vdl@D(%Be@IpfAZbIWkfd&aXhJ3gW~cD>SOA~ zrHO)CQIw;sy`fI^Zlg!@Lzvx$BKz;A`6y;7R4;Ij3+^`bG7X$P@7iwYCt>7u!+5;q zbF}pLxdlwr!dla@0*I!D!b8fU91)nSW-?L#qn2Kp(qi`;%thQ=TtV*+y?a2spynW# zx5q=z=!dWkzw1c`3JRQ`D>GO4^b8Dh_ExIt;$GWZ#tLlqv)@i6?Zu)wc(=TYp1|uK z`49TSy!qUeVb0}rNTGMI>xG!R4X*yv5uP|83_aSYcwe?1S08=9Yv@&?0CbSO`+F&^ z=F!_DzNl-&>V(4V-`@r56*AC$;Bh=}e<;$7T8882M#pBEH_&KgZjKWu*cHnrZgiGF0N2~mHjJveeJsN>($=O}+4k#u_a8G@dFTYGRQF%~Exv)4b~9p(7Glh%5x-6QcHI8gPd4+x7V ziLV7-!#^A^_k=6dbmCd%1P~}^_@kAQ_;Q5B5{1W9kz9JcVl~_X2lh>fXcZ_{>KmYU zRgnl%^9TN4>3e~;-~F!DqIUKir84Tn$Q0FshB+pCaiN7_1-`1WQ?$}1{u)wHxI z9C#}#7}U0BLWtTfP)QSF7N|JOYf@(z^jha%v?`3YgLZ2a?(_@M+p=Gmw~OrfN>Abf?8S(JIVAl$*4fEa{{KRRxv z_LXl;&7oWjE;A96|5!plHu_K5uMAr zSK57w7sRo;B=3-+@ZK1DLe0W2Eh+vD2#i1%l<)VlJ?H6!EIsSA?DK0n_~N1t){<>D zVEX3~ntGB{6iL*ZNKsl&Wky2}p3`0Dg6O^w9)HWalK<2N!%` zU}Ts$O#THsT?$!&=9)9v!6AnWH=NILXNfCwR??d0w~Wl&s%|BFgq(=^g-nqW3Y?{^ zFj`VPmeWYKTRhrjxI#UUJjled-(7=ay7HGwl%1<$s~pQU>i;zWxq{lK=eqa5Q!=Zr$4fGwZoD8;p+0NMjmmYJuI z%u0g|&>68HZ>X)?YSL!}p$DBSL$0zMyR9GN41Dg-tH+h0>)`S2eedhN`QPhleHl^F zpg^Fp%c)8KK^P)zNb*og)5#CR@CDwGde`Z#rK|gH8mCc$zR}arT zAznO-zCzhjej!Y?@`k_Dqn-2m{%>FDaESWIVVb2@ViM-~eTD&!GzF;AUCgBWr}%LaQG6Dy`fnqA z0FkqGER^X*`PIEXc;MsAiYgR`ovQ0AgLaFG+4=gB7K7jVW6YN|_i=&(Rh)~d>aXri z8NJ}o%jXpT*NDIElkn^oTOfc^1DVb{!Ewr){~3sJdZC`cEuuH?9{P0xgR7%|Me6~K zFDC5PSKq11igkR$elcqOT#9Y~bTM1K{q&b=UGptp2!$YbwqEX?v&UUHOlAH4Iw3JF zy7K)Fz6mr-(xpC^xYSQE{5Ielv^qq?6f>=eW_54}0`#~D*K|Jl#N>FT_?`cSZaWKH zHaVnmKEtCAH-c6A_@Ne*TBCPnzvsVsJL@ekMBD9;fQL0+$3Y8ipkbV0Q~~7>8F`>W zj;sJ4*_4n=FO#L$nLM$uJ8Wd$)egRm%yh?I~IVfWEyrwK4P`#y<@ z$6|%s)p_?&;^iL9fzjsAieqWbWv&YM=uRe+{s=CV<7B$Cm;lbqet6}P@h+Cku)Sk( z!RYRMzHijH@+r0+Oy&yJ&wWe148WOQtu}NSQs3W5bg<35dx*MpShGh zaz{-)9VGFLgBp#n&%0#bFD37L57XF_b$;rh3~s2{LZC%Av)89;Eu&BHxj02lN!L1RMqw&=%nOjcQdJ29 z$sx?N+uZ?gqhQqATb<5`)k0!3V#)emYa^R~Q^F3SDmz&#hz zr7@jF=Q4M*qpFNE#r5wiE`Jd+R{7IiCY)Q(hq9b@Ewl?fd&ICpk0wNiEEcjmb4R8o zCE{8~WmE>Vd+t!PfwKo!o6-G%Axfzq=)HdWgIuerx$x(F&%8;`vzeKxwc64+Ern1-(7*ua288 z1O*-E?Fz4u8HS0r!`#Xx=>F$Q{^hQvrz!4K&_K(nF9??5?a0A7q{|J{xVSMx1Sl}Y z2S&Md9j(Hsj%*$fg`OopqV*WPwru%SI&>iGQ#JK~TA1JNuLEbaM4G)U7Aw9zWp^@m z(&gD22t-}#3gr1V9q@UK{MU3g?C>b>5%fN9J9HYv{cAxL=N>gqMD%u2fbf^tR!(h7 z1C<1YYwTikiDgRHe{`y4k($cNdD0NBuCb;F`odi-O+PQZX}(9S{uY@B zvTDwIZ$(+b7teZk@H0oM8FqX)CFAnKE?DZ@@m7|8WZE{b=2BD`@mMSC1tqCGg8r)#`MgxhbuWXL=pYnir1RiQ_ z0TKDXe(@fJD_hloe7wX&G6h@sJDW1z2V$YY4vX5Ba&%ZfSKH%-@}=Csd!su;ZJk!9 zf~{xp?$fy+n>QbaKqY+VB=$ew0l61j$9Lp7fp;dxVppUvw0=*LE&#zJaczr;h~V~> zJL}(FTlUs6ndR%_ts~OK; zlbA1pm{1o7TKC&zmh-quK=}Mr`-gJtqoj^svO{p})S2bydwaw>%|48G3zp=kqrb?G zjHgf)x?;c*^9WZB;^}+~p>hL2{DtB8AQI@-#w&3@o?;XrE&qpbRE}l;;DO!GgdvU~ zFSY=Pow#Gp&$Lz%{9V}?ClU%@9g3*yVYP zX@BE?Y4KiV;6a~PQnk~O*U8;oT?tr{8JSL)Vh$bfBxM!${`@gJC(VQ(H$~G5+gLMV zjt-(GDNFB$iKnq&4{Kgt1oiA+-5xyJTPgr_QE~Fzk}4 z6$2%d?Rj!pO-(E4Yn_~w(W!CX#yDMFA->hXn!8S$9evQp^>&!~c@Fe6EKZ>P)$Itz z4u2DfH->f_pb07jXUT52A7r1Tvx7s2C-}{U%D=f1qi)2S)&#CR;NqJ|*~EXPOg!KYaaVmqCrffP03b4#@G4;C{qM~e$YTG)X(^z;#YvcEQD@-0dy&OsLvuB~t z^9dd66GGpRyrq>Dxg@4TMQ`qz!e!rHiPvLMj!r|97OiDlBkuYXPgZH2vd}V34vZ{c ze8!UX^Wrk*L@?&6F_EB_!=GCpYuMpq-$?Os5uAgwHQkuOylN>Z;wq%Lau6=H_??P4 z)T?nMC2K1JOiQ)c&06K6bmA< ziqy)rEb_(lgsTV=uJG>u|JXMgc^=a5pAR?zHH4I45E ze<5k(F|1&{dg(XkG8N-!XcgM1q%4l*Q&z0+8!kHBY+BJ(*?*In`Q?>_7`-Q6>1b%X z%Ro6Lxl4wDp&N?4N`3g7+i@`j^_w-v34j{heT&{$sBm`NBrV$k{HuRO{+J@?4gUsw z<1Vm-pdyA+cv*PRLqlW5O80B)hS7)y)#TG@~>aNj%lItdW~^j6hUPX-cyT*d%*e=bR{5OY+?S96Sm~@qpOn}$ID5V zY0hVqoJB=y%jbmIki?pwHW7>f7rf@s?I-8ZenbOB-hX}Fl(M2IA13idp_GZU(|EXk zxt<1lHa?KK9lFThc`kZA5P?|0yWylu_EswjQL}|=GUAlJF_?l%p8r)w3|vO3kIN!P z&ROBZ2g1CN6Q8e$+B-L{5DcEmxgkq-bd7RJ7iwp1UhQVEWz~lrEt_!rdaSTl)M{0Ajrl)X-KBRj6X_0=q_Ievy4i#W-Sh@x4mQUU z*A4>t>iji6i|FbVISgj%*)iKJv=H!F5iZKdA;UvbiR4; zTTastCs}Z}--#+ESvPlF|AD)=TT2r|5Fa z%QgH>i}*bazcA{d-v!~rTQWLDnP&m+8jp7*J$}kk)9BdifY68i1urx8Ps&0EZpCF; zwgD$gv0iVZ@O3_eWs}$gjA_h6=Q&aWv;E=Wg3W+}#_s?dTZTo7*zq$lc^fzmj)vV^ zrz670L>h>qkFsMHb0|WA$%i~(GnQ?0h$`Sblq|_zTqZ53V36R^efV&IL>s|d*Hn=t z@u&F^jp?3~GbJaRiz>r^9MOLT1nEKogu_ZBz0d?0yNd~jpOId7B8W+!1LCD*nfM!B zsYV><+wHICEqTLK*^`l=e=sbS1K~|JIpX~<28B`en*Y9v72&d;*9M+74D!OUsNwEj zNwjxrOsI$d3Kbs>QCcR6P{_dXk&G?DMNRC?8svS^t+G&!AscRde`NiHyRB+4@L9-# zS!C^r51ji{6FT31suWqp*JnR$C=b}vFJ4E%GC&`^0ypiJn{ zMtBIX!Rge=nv!MMQW#^|JoUq%Luc=ep31A$9imKft{~%AjXJYQxyg@R?Q}Q0u;#?z zIjzP&MfS@A^9)#Nfarr7k-x(ONed=%C#nfHGWm1>yYX6YpO%&foz2%|w> zo>Z?_qC<#v*i<*K=V4EU%1pdEu0J=H2oxTC7nRLIC(#qnzE9%*1$$b^gVh7~T7+2aVhhM_`J#5U88U8-X#d;(w0-ECX-|5J z#!LY&5r@+r--f_7yJE+UxR(G1Iy%1(NB8~0=XA*AN#?Yd#ynetaP#(Zhdw zC4G;mV!G~%R6vR&5&qHwtqT*kE3kBFg5PWV0PM0s+p$})XZi%q^-=;&O{S+T?Bd^$ zyzC&T^jo-J)togt9EPV-$IH%GU*XPP2|<0ks`I!f3_ULgtnT9nS@w+N5a`2K#nXCR#3qFY-D6 zpZQ1vdFw)ZfRWp*)TDhA^fzIV0c~sgttQ>uZRM>3UYLpxu0>yV(Z8fo#6frH7snUM z0@yos_Kh)K(B?q-;4L^_)ad!gznOw|KkNdG3gHt8p#ZuE{Xntm7qE33*duJNgS;PlmnrO6%+u0;RN0E?+xEv2}D!#Ln82 z-EMT$lDhj?j;CHOFhBX(G^_IpiEMi|%X=60Exq1@=xuo={{O~4^yIjX*Vm&)(okuF zLf&)lx{b}ptD?PXVv2OFk%oJ9K6}fx`%-yKi810@97i^kl08Q=@> z=`J5mkKb0FEOLG<3M<=*Np5hyJ%GjMXIhQg6uu#FViGbEh5Bsjf9#4g-i(BtWaP1% zOC!rb@?)1zHcuYtY=QUZVeUuUJ-~wDzOZq+%RXHpLS8%7`B7pqjnO<7U9&TShaE^O zIKJf$O(pJp7P*`wPA~{Pb126j$^T_+zV)C@#;Fh8u|LxI5&G}!VP)T*)q;n7p-v&c zO9AEQwQrZ@78!TWqdm#UW>5z)y!~XYP5Oc$6xIF;kE%Y7*u=f)bv`QN1kD7-;wk{f zO&`mtol}`!Fi59?q)_J|l=zM}^^Bn+jV5oy4K~9V{ILYZMg)5tnA9XlJ zX%I1a&Uqo-ZQrUPCPA65Qg$R4Ckfax9!%z(3ND!LjP8ZBbc1j<14)qBr(M>$KR zllm$hG9YKC{I^m^%HM@!_~CEH(;s&nK)QuB7jll?eI^fg%O*~_K9G&z8ap|SIQW(w zo%M|EOiKT>V2|+c1Ru_}6Gz8^%HH1_20sMZ(|j0ta+ESQ5Hq+<7uYASv0{$s)~F~@ zoq{fgn0e3=DQM4jG>`-Iq(@B+m!*k5xKvdaM z+}WEAVyxk2DmeVXwWs5=eiR{Q3X`?c$Vp^B_C~}Sacxn}cSMT5FO=P@_4uUS zyx7oaW6Z%x1qO<1WYt4}c(ki|4Lxf7w{8M#WwYH$u-=Ttd{zBGNm1qiGkH87wb({x zM?#wekHbd9{a+Rdxq%P-B|zxG4E_2SbmkpZE>I_h>?K!WfEbR(FxB3Ek-GCnh$f`W zY;6TckvJ_ZF<3nz`6%^5J4p|ji!vub7oK-GsP+T(ZCBmSJcZxgs(N`@c{CDuE%2VL zJ>kX^az|me)oOGVO~%Ox4>0thW_iAHA7MSMboQ>PV7%LTZ87Q-b$l+_$PyK2!}uyM z{{^aBgQ=aityqG>y`={9i8fg2G;=bogm=z=-jKAl-T*}VFaCB%R=!>7H@Uc;S^#zz zYGDd%`%Ggbuso2QL0%yV20-y{SdaIu-ly< z%lC){>ue6>Z7*hA7Sv?UZeRJ0Oa?}KmxiC4p3t&W(j#J8d2_5`!}}knpcgms-{Edm z7Pf;8-mH!Dr8rB$$b>mR4pU5nld=MQdAKut;h2L~O%0tX!x{~`Jp!O~CUK+PzDN6m zojO)Gn)97GA%nYc5HjvwLBvq=7nkR=7V~RMN`^z>+MBh&x%hER@%Ax(@KZIos!l~#}c>wnP@Y}T&E`=tH5 zLpbIqb)hETdj}j`+@pI1Bp*7RJ^nQSU2nm^(1~n*jTQ(9+1>hEgzAoq>C3*Cpn?D6 zLHofU%fZ3Hl|A*N`nUuhc0(5$4MoS z@$dtzoFeJ>?z0X`_IA~unx$AD-xvUP!{@73N(TLh`OyG9a(fsM~<@3M5=Zj$ls5N8wKRHl*z!f$$!AIh=^U=_sjig)7)0NgyhZybjcWvLb z{?b3tai674yb;6G5!%B{w1R=(ed$GEXQ4Q4`B|Q_LCsJ!4G!L2|Eo%ORKLh)Rf9&@ z?WeW0I`2&mYx=T+q9rb896-Pk+{R0hF&R5MEN7lKPQW`@WyghfCk{Rrv;s+{t|6Qj zfv}x-fYDbP#)Wn$A;Oj*dg&2W)fK`tBR?MHywuR3;%~AZXP?rZ3z}F;Bjx+Dvv0gM zoP2d0;l@Y-@8hCP7^Zt6{aEq#$pP(dIE>ZT69#qkpDha5by`_)?}Z*dE!FA|e@?LD zCRJ{Heqq_TzU0K`HLXa&#ojsHYWu7maKv%CQLl7w??ynm`b`0kC5kO56Z?5N!tsYY z$Q;C|hYn>p0zgrfO{BK*{OmD@Lm+mUhvl=l5%jGDs?x6^pJ+%-4@yXn{y7GYD!{_q zJW9{Gq#8-kuM|9l?IDQQ2U&cR`BH2#{*lDoaZM!H(Azh_F>_dJgO5^(RnHMI$_eGS zY-k+ts{)xFp%f)(-*L>!FK;3Gj0#6K{l&fZ8-K|27Z!iLFwT)xlK}nQBZ7<{Hb1^f zm=}R~*(chP8c)%y(VtaiQix1?W(yPb_cRu$4g(K2q}1R|&G-*-I#vz`{ydo-O4VaV zb69Qe+v{P5N8`mRid3Z`aThA>HNsoW(2S&7u+^M$CZTzp2q`$qnYm639t^GwOFr@S zH>*EjO1w^f+^ZKDIL4x8=8u{$Jpfl>`zVbt&>T^(|U<9Yor6Jl;&m=Rrsf`>bttiH}w6n;tiu zK|1V!aqjftUi6xQhQz(< z(d9aq1Eg{(S!tXLz}9wS_wxIAtD$^fQb=c9La$!Bq~Yv9%E z?=A}|0JC1m_S@4k^qkWSyR;ypO>oE4&0qUn2wKqzh@X9?)9Ja`^3`Wz9gOUSC-E6s zI}w0FHDG$yWE5ZxcT0F+G+0HRaK{hpdQb>mMWkaoMxff*2fqTHz@;B+!3ywKymB(m z2;juVMy^c{+GRt}oG8Wr+Sp+2o~K{9?E!Y1?cYMlUd{*70_i>+G2pab5+JY3k8?KK zN!v2!^oh{q+?x8jdBoX4@#3YQDBqUM*98Ot9$jli)f^q_Y0Z0e(+`E(or8j5YA;Zz z(Fpoqd{-yFs>i#Qawjf-J?+zpHSnhAXWk8y7aa8N`&`Jn-+f1K&zl9bZ~H!#pJ1`X z1nxP&Ybe$fGKiY?w^S4>Y-(ILn#oM@d;dmv`ZDPl(<4j=(|AE^uvc5D^|MvzJi}^k zp#8_W%hacl~dlhoY+cIDpPuc7If1{Moix9!EPx_q#rad&I;?8>Yde*MlOM-rJV5MvI$E;g*d( zbGlJ+r%B&mtPG!DWKFCe9VS+r7S{y%P?V>Kbi3e(l@dwtt6}-r>8N)kohYxaubsBR zwMCBaeRRy5v3VOWs7%?AjnQ$PmJ!n&N)*Vl&%^8jW_X`J4;Uy(4XR#hS=ifEF)vQb2WB9t{)rrK7vuMeBnqM==c6PSgN)yCC_`6;;zBR` z>kt2m;=kIOWHYtc8>u4fT+293Q?iZhZhfmX7Khx~3qWeB6A^Gc zoc0W9=M1kh`sBPG0Tvml4`Ix4h)(Blu6qB z>8KF-SmZ*%d)>QC?&B}qSWcN=mwclf(_NV5m7@wW9Um+i)>CAu&1d~G7)t`1t1z$n zAWnM-(wwDy+reF)ry-CIH}UBy^3gnTx}9Wp)O?mjOk+Ro;4IUTnNJQ}}s>p!UozmXXM-`G=Fv*RTx z;(~%GvVC_0>h2#TR1=JU4wJS4S`2Pgn9@4sbde_!`3g3KxC@+iK7tdMk$UJUuAU#u z`8CvV4O@77mSOz~{z>?td@bv2+J0Ei?!CPl=A1S-;$@#?P-{?dWqUV%zXB*`@k~at z=OZo@Ww)&H;&9pDu4^dIwrnx;5G^n`y-T3;7oaeGw368E%k62ydJL`PMYc6HHT}wg zSSzz2smR=M!bR2D?2<%u zOH&LEAXbvi>Q1qXl!bwzPb{1`n0!FGz$(xG-$FIK&pq)^XTkGGV$V%%5#tYXZOSbA zdWljFPCVspx=LGt(w2G?=jg8+n)iXFVd@Xg$MIeVu_~9V=p;IK zpEeM*tFf`Hh?)%8P8$nQ`JDGCox{IqByHXOmO~%9M-~LPX&1*%i*V{$wMN$Px78~r zNopbyV5=Xckf$W-4Bbw2Qd$4-fTxk|heN~}Qp6gL6GB@wpy=Wh=MUxTgIF$ur5XOb zvdF@a&jwSGVnyN0j2cezmc|Y_JDsRbGE%V<#FB)Gkh#!%50tEp&>~{&8Biqo+sN$a zXDABwIXjsqDRvxt8Ys-TIOtA(e>n{$H)^Gp!$PDuKpY!Gke`-IA`=^4yd1cdqL7hB zGj!DDs0qQFo7h19GB0aVD8vy?H6eQvrX%50@+3t=(9xJEHp)w+pM#EgLcx74)}y~H zzfZVC?M|ic&;OK&k*3%%J<;dWnBSi=^0To0)h^ePVJCbheH)dp83h3feDM_;!st zp7G~2d4ycaCMUx(hl;Z7&QO8RwEeU*b|em`$MV-0&V^1m)ZCIDcZFQsGp|x+E3a*214?x%sXzNSpB0r> zDpuK)UU`bU+aPqOwC8z4DE;n^4wG`0k(%vm*r8W+rHiBCFEU^Hy^fCHAtSGzW^bMR z2(kg|jrQT@$`8c;0ZXAP<~z0kSPynYs;`u~`E3!t{!rG2XO^30B-4 ziW49>#a)WK7ncA90tC0>TBNwUTXA=HDA3~2FVA_-`M=-JB)^$VW-^nxckkV6cdv^P zxkd*c?O6!W_;;vmY-Cj zJKKZR-TETLPm0V%8jK?4a9Z7I`+WMYCB^(mb@#LAsaa?BvZzUPuHXfp%6PofeMish zw=ZnY(=u;B^skqJ%)&!{`2*~v7kKZ{{4x|nRGDN3bveZNn0vcgy%wh>)7u0MVPWol~QvsVkeq-z*^rW>3icl*6$4oZ=mt-nzz%T`D9*L&jF3cb_R>SbFJh8Hw9rB^JWP$x~i3Q0Qj_8 zHl1*dY@5wWeR2Je+i_w_T(OJ>iF}zveUpW~1sfD3md}xdxR+NwX}2z;M?u66i~y__ zDxA=UG(r1!UViJIBy_GqC9h{LGerC>awWgRG?! z0&;ksyWG1ixPZ=)xvOejBM9Np*Nm7XqG_EVYG~QGpZX1inlE9_;#$?H`1>+bW6@QN z$HBxdq*8&6>Eiw~rcl+vCeOLh+kGc=>-vTI(bv&t^|ly5Cc#?;c&<~UMYcuwU2^Ms z0SCS>KTs;WgP7($Y}#)|aN8dP1P@qZOk^D18NaB;mKf(mI2A8YrI=8Hj1V5V?3%7L zL@U-@U@G6cyF4dkpP~lc(@CAMqr%1u^fg5Qd-n))diY6XY|~N9LELtc96T*BwdtI# zS2?4>ekKY{X)yIcqFr2xW+CR0pEWVAuTCibff`6zaFND*Vf+|c6;9Lt(ow_Hh#~gE z8OC6IPed8;yKH#Ku1J^AD!YQjv3&AW!!_`(%wO)X=ff|B~q5l#oME$vdpAEX4Ab7_qUnANa<3Ek+KGt1mYi*LiXPYZL(FdQFeZP z(=YfUQG+)t#P}}ES!WXNXnOR|E7=l^er4`Vlh1mgplDN>r(url%UMfFMy@SuyG>w8 z6N&eWE*)IS1Mh-a_EzT->^iRTZ2tTDbOqZ{Az;XMhvJ#TKD%P>w<&>JK9KFYhj0ER zDV4wMD7+OHh)5BzRCqObdOfDU0KK{2g~=_!ao~bN%-7xf65Ss-xRGooDE_$Vlyve@#bRQ|qU+!yico zi<-QnHFF;L9uXcMp3)J*=mm+pi*-(u?l%m-Zwgd4JC`gM4PjwwO}f?C5vAoy+t4uf zdv&{O5r13Ri`5gkr?aF!!6RW)&vXY;fud0!Uft_f@lNo1Q?D|4tK0X*CaS#C;hcB}C+Gi3suFP`rx{Ptu-?iLLE^fyQqcl&T|ZY5V1 zk&KM1lK4rCn_Yu0< zc|I}efj7qs)v!4cJ^HD53HfWz>-0zNhSGy%e2{`#9mZ}4#DLo6f|Yw0v8T;Ksh}R zaQ#3439*tW{XjT#Fx-uhQ7^gngLTZOxH6EPX3MdG>PDdk*c_;ySSMQ)sc#%@lHtoG zN{xCre@D0-j{4sFCUM_;r$O-E_vD?lpop?EVQlBw$#SvpS_V_t^lI_bjZ_rin$B$K}sHmBzs$VsFc}wWfHC=EHqZTRBCxMBb-5ppWv8fxzAvxtp z=03gx(BO@ru2_q48$d{n=zJBe9PVFruAr!-tfJ%GNL8A}Zx^LK9OHVNh}Hh;5nm|$ zQ1Qg$?aB=pe6ls%JSKz}&@(>3(_3QDkvkYH7mmwIiGB;%qgV^Pn@Hm|CpodTbAP>l z_in1nUv6)oP*w8*)Q0HPbt_`^`kNKkC4=6M?7rA}w-&ki{YQ`hvd3lhrkzB3G{!(K z)Kj4Nj;elg#LKMFek$n*r|QEai^$VB_kEJn&O3VltG8^OM>Ju5rWkF*latyv8kOOe z$;tNzr`6f<17NeMt)8Q`7H-ua*LoOpR|fSul!#JqkJcQL@L+zYL)!lOc-s7Q(dKeJ z!XV7~Ph#Aq{(O`3Ch+p2g<%TH=aMmX=;W4RLnBy1*M0*LBzO;pOlkjY7i|v@(Vu(_ zLd@cGjZ+xr4QSX34Z{WrRMYv6y;QGhls8f=R$>Tv+J%;X7)pHGQeCse74Jg>3oHMz z8Va47@p6zo==YhO{p`$dO~ns?SQoIqILfX#8D#m5GBL6;yGas@+?~}4ye^r$Jld3) zZnXO-SHSVhs)!r|L>(XB-H0R7xLQ`;@D%x{jkW5_c1p+F_Aa|Y21O6%jFbPXv{7t`` z*xS(7Pku9mQpwIE{D4JOjvV&{60;!b4`rnHdSH6{XK>oA^mF~Ra-YtE(&tD{5kAA& z@g8x8__r$2r<*Z+L*X$P^Cx>BXl1%15%aFMJWsb~uhxgJ*G z$NVnEkFwSTjS}(hmgAo3Y6-2ty?9rvtR=PEXpeMv1PXF-yz#DuGG(!GvNycjJVsBs z@J-@E7{>m_(bj8oLw+olgDYjmqpqkX|_?AoGQr=gwKUtv}F+o$GXSjjkY?UNAN-eF%3~}Rc70R9174b#OC92Xl z5t&I~P6cvkN=|TX71kn{@8bH%thf{^TN0=yI)H$O*<*4Y(rn1y1*@U zpG$9RA0LHU2((QG<2JWpY=i?+cWX3@<~O;sF$B|^@Q~!62J}+jgDX|*R#E+%rgvL$ zT^I=`xG3iBuy2pn(5NY+G`q;oIwr-yr3r6;4*g~8B4Z%)B742L3_K;VhG@V8a*Vx=CvUVXspjhjY}fi zPpREk`a1tw1-E*cz`;b;Q5Xv!VmO^4hxI+q&J7hl`p$l;ktCO$)P~thH-GV@*dbZi z!age)^k!7Xfsb++gM}ZnuE(b&J?4NYup4g4>F-PSR7z~EDjQO2quge``rZSu_l?=i zCBR9x?&GywW|oM(mL}Ncyv-~XB09xXtr~?)ikB4%&_0g~v&upVA z(z`W}Z<^R6imeprE~8b*{Nbd{^Z?p;zZ1c+k@k!AoByka-^)CId2qBxYd@R=XoL`8 zG^{r-Z)=HKij@6=DMBRb`^V8>h@zU1cb@szjN9aizz?alUj97{s71YO@Z9!9n)ghZ z*TK9)j&&=IjZV#57XGm zqv9Azea`ng@rqdfc-m+HQB}c2G-dMjW`U6*00T;((tVG9!w7vmexMAx?mDJPs@FV_fi8p z;OBfF4`3S4?wShnC=Zm#aO{j!Drx$~p}XczF^jXM(CvFhSXMwen6zLY?53!WFQGu* z=J9J=u0SKT3OA9j_?P#^g63`u1BH|(u$!gtwh;YoA{IpqnCa)+YEjOXPd|J369c>3 zWju5?Q~`^bRVXEGG+%#4`m|DIozXAmJK`=PFz<+}8qL1t{-AL6;APr=KL`-H>$SUo zJRMO0UzMecdR4aAdH*q?$jBa@m>8<1d+)mbLZH$4E$rA;vxOJg^3LS8!sh-gF-{8) zlXqkM-sXeY-y?sKKT8PSFUg-(jq4=Ap}TTFO31vjOJ(m7;LbW0H;y&~ndd3$IX~`T zOvqxepGNXs`xD1IOCE5n^j=B^M0ifH_fFN`Dzt8UF^`mYNjt~hQgXb(+wl1eD=Fp_ z7ICe8PlnIC~+KOE?9wKkrbOZ{JzR6juxXOFIsMlyu-${%UALP|GUZ>fnC;f*FXkXi) zW}5Gbk5C$lx^A*3>+{hO(o$pH=*Q1G*FG19s<5HgY1V?L7=IQYBo0!Cv?QxP%rF54 z8f-S-p9_1+n40F{dW{l}%j`paprIsm-gQoV=*dV43e*D_fh}}5R~VLYZ4QnGW6o|w z92Q4}VrA(h8tq%(3MVP0ZFKeBPgmZGwt7iq@)g-$e|4b4L!FyjFjsrP9XD2m4D3fs zFZ>ubp^$Z+9b9E(wo9^8{XkPmQm1C0Qw%PpqsKG(rJ?rEWzGuGp87ae%qNO9~g0%NZ7eAKMPJVu|v+#E;`Ei3BdhlwGt0Yy5=e-+QrBuTF$SB#IqLTzAA8roJk7wvyD=|*5w{`8thg?8uo1zm#c7Ngp6E3l!Spo-Q zIa$+dQ%;}IEK6vYKj82$G8;MhJy%T+q>fAm(3J)&6pli$_V;!kPpgJtBCio^Yh(-pS~pW-=zopl6ygesyB01BUbQ&A_D z1*{$u?7)^S_?Tr+eLQOO@?!Mbcqsex-D`)qt#3sI?@YesuQrG7DJht^Qm}H&zm5oV zMS}3lP6XK)9bLQ0f;f0N%5y{(zRx=Fkbl1*^F7!1L1b=TQ-C_!BY2YVV^P@iLE5}L(_}1O@36WMwd}{KagYYc3fDYdfp1)O6wbPV%|9-XMT0`M z@SK}5Naa4F3WT*}+qOE`J;(CvDO2Gc7RD1%HJKM@0eN5N^L!N9#tD3^q}ECT5?5^| znGQGLNv?yVG;&M{jt1K=6rzoJt>V{c8ib0-u0g7!Pg`h+&WHY3=9xGJ+czW_Bo(PE ze#)ZT*1ThuN)OT)EfTh-l>okYqFjd>moky#uOnpYas^0aQQEE$fmFYO-$*YEI0Mw1 z@<=ZQegJZBpu#W`sfi4LMwK99IKLrEq&#+rE|Q~~nuVy6F)T52S6264g8KK7y$F90Eqh>I~g|vy0yS9BY5Q33@K1zYFd|t1yYoaQi9Y?7ybIk0&s0PbzxE31Ru99sfq2sbp6nIr z`;L}oGaSr~&kS?(oa|5JE(h*fTh>I6=ug{5Uus*KbL}tge?9iT?{ncl&3Gvu_Z1WN z@d#MJEw*Y3Xe!iQwi?tnOikI@8`j~U9D4=KBWA@^>vvG`vr{e_ePJEE?8e%KmhXIIAo|f+x zydz^V-cUkN7J?H;hZ~ybo3Zwk4_W4(f3}J?b-d0HSqr0AVu^dE{nYVrwy?w_DxA_l zx=v=LvDV*O`Bfty&L6XEP-=n-@FvZD9=<1lDLsTVa}B^yh&gX2NfR`3iiPBIDtc#r zb}LMaqjE$Kh(dcGO|Vs;2$6Z{eUN9+#p1sKe&VR5OQ02#TFUFUhwOV7+AGw$EVKi; zkLOO#VxVFDda-<2G0-%IR77{yX->Ff95Fw@1 zaOvRph417)^H6Htq`8dI4_KfGkVO+ruGUi<;VALyJ}bOY=T^u7coa&18ijQwg7?fh zS!sX91G9XOO0+?wHk#(7j$tWk#snF1JXTz&dg1-VvD^Ud5w(SnT$U>fVqYu7s>uW! zTR+8U7W?2jmC6j#ZORuGs0}lOX5w9kWGKk*P>+}Br^uCHfN~qtc+5DlXk5~ntBpqw zsfhAD-$Pn-+me)kJOD^!jvaER$o;d=N!;L$wRI%b(H$*2zZ^KmLEgqD%<8*HnI0;s z>!%E99ODGQqb436PF0-z-+hv;SZaLv4>mGm3aGbHy{%lCZa}(SxF`#fX?bFXg2?om+F%Lrx*(x6?+#Nv+c|J_Ih{HzPS5E1?WZtb`A{N7G zac!41pE=z7tz&n+;*AF_Hr8|nPWamjsvr(OWXcpz-S;`IvzQO%k1~`<;W6DTs>G2% zr@7C7jb@i+-WJ-%TaND#j`JFkYGf-5ZDZ|OC~>?JK5{h%*(SQH>rGOSTlf77E8O8{ zq!IQ>@jJ3&P$vE1Cq&p%sBvXcF@29reb%^f9uMB9@gM_7!nQGO4Da@T$x$)yIGLA z#YoL8DZ()JLP*!2JpFoLS+`o4Q;!I8vByau>n?CiYbzuH?pigJMQ2{{444m7vQ%3+ zmeR=rX~vUf8IwXYFFPrBJ(u2MY$Nd|EMP~OEYG~l@|?M1G#0>;cb?s}KhWp}G?b`@ zqVf-Q(4-E3yx|90D#&Bnd?nG3i2)!HMXd>IOLZssabW?rh=|i8e!neojGLPfDva?= z=T+TR$ao-k4K4g0_2JfV@FV|ogRx7=C15Gdh1?K}WAQjH;+T=3 zMu}!&siJ0=ARUjt|0kipTY7XvvpSub4v7xHSI`n>K@hhvL3D7q!qrb-rd1m+(tD+n zXJ~^tXg`azE_5*3dUZ@x<5LwSO;dCL>(J!Y&Dw(_=O|HUnf)JDpJw!bX^TT=@=P?R-FgogpR5v9ZE4C$#85* z1RVqwvR_G)1>_(Hh)=$+qP^V=y&gsK?w%%tsBu`CBN86=f`ofJr_i zJ)yz`RN4^;s6zcfhmv4HyIT=22qeJ}5L#4NOK>MQz;*7`VwV>Pd1 z6}xqL0x=;%)}QAV6h3=Y*62akFRljr-Z%r(U1@Bwy;Icpx*!eu{e%of@0CG+52 z2=|AFu?pP}|LruQMYED=X?1HG!^Mf18MxJH^yf-+ry9dk-xze8-9*rB{hwFp=dvd_aIBk~fkinDjNezS8sLL_wv{(%FJtkbZ z+M0;AYozT~uJNc~Q$n!G8~$|{%Eom^20B+jBGB7kj3tYov?SXP9#(b83iW{ghJBUn zjc&`EsC3Z^qBZdV@odGXnM3PY=f!rURYy=_*NG$M8 zR%U3GSc!MGP|lV&-w(a6qCfpDz-G=y63;w97cEJGKD~nWobWKH0bc*^L;oe_W$d;- zArXcU1^Z4^(rgNHjW@|OQIr5wKc6N6@x%B0`=jq4+HXzi6jt54FWO=Tml8x1NF#v( z8BW)|sYa0Ak8iKxF;I}&<3DU;B++PcA!=b1d0)BT85G!aRcHEb8XR(xW5C=oOIdg|nZf<};JZoNr`x!Fbd&Q+ap_$Dux zs?;vcA7jKPf%H1^hGy%Iiin5Ay?DZ*8-(>5rqXFdZ{F56}X)-i%y1<;6c8%kZ9P&%)jWo`$s`&&*;uN z&uMz0^K6a<0iKl+E(TYJ`*+vcCKQKR7o^{oIGTvEe78e$=cA=uWd~RpLkc{%qxQ3j zU_4KzzTiGTYtqcGqm&yTUwVNv zW~@623jOA$b8=FpQTTa{5-SOUpn(rTE0bH%6RDnsAYz6bGN}!{LObz~MmrkbryB?- zof1;b6!X)VIuwbwq@&mgmNo6JaQV?)61LOQWPG>+mWwoJYvP38GAtuC=X1+xVopfd zZTsMCgbCl%I9Y<&%IV0W-P#9$n=?$df3_pjeKg1gz9Bw;D{W4DT+c!9Rc1Vze!rJA znk62qYml=r!O6$=rJ=>{E5|7g*DIHtYs^6N#S99PW%dZkyvCAY1hlHSx%su8Wp+<0 z%SOwb2huq>yV-wYOm9)>WzJ<1<3en#QDTjoi((KCryEPnyDtNh6lq#~J5jFL?3&5* zV4os!7>@vJRM)tCbkl&%jqs8FFZ+fKpj2*MZfhIW>}9fIe?s_qfL?CcaV5Jo${bt- zV}|+fsEG0Vl?DVDRrFSt+Z)FiT^${J+=>lEE!--ktTT*@iTA{)Ez#rWJ~`fH#G!JI z-EPt8VQ8sAlD%)JJ2dbl0h{sn30jGDeaeX%O&d>CNLa+dSy=`ED5`gdktT~?kcNr~ z()*i0Nxg>SAD`HvHVZN{sK+E$=9yYGR{IcvrV@Z$vjfM65$h}Gc2SCx*1TI%Tp1#% zoe1NT5++Iwu#9d50ljV*A~qCtDVJ~bHBq(u#~w8>EW;_uIiEA5kjrYF>pKzdkUC=D zxH(TU(aAenE#(*Y8&W-Kje83}rU>IF2NZUfdCB}gc7H9`v~Ey`x`=i1m{AZuFpRKO z4Am<+^QBM3RMNKTE9Z}MWTMcP-1D;I)nUbO=T2tx<8esSWSjwu(BVQn)C!^%cWfZ9 zqG-;edFxsTkW`Wgb&7s<>adl|hdR|(K-RE<7Sx&pPv$#KaBF@~1w>q>{A@2{ zPO9K2`JwMcY&PNv{k@hh_FhwcTzdnhm1Q!}LSi7=-+QiW=A2;m`5<}C!6iXD5)tx* zlON>yE$a!Gd(`~Z*ukoBA$er|sVYe2n;)yX-k}P19HcO~%=U5rn%16!EjZ7|Byq>Y zxGX@U=$e&l>j6x}Ul%E>J`>yVa?{y`xyeEk3$OgFFjx|A_tG-z4MG>b*Rhy;Y-&`S zA4PJy{+vNfvvG2H@FQ!SWSpDlm47fOi&}j1Q1SzqQbIs0+j5<5RKdRHxqjmh8m=E@ zegpDWL%?PydOmCrq^JIdKnl^y$b~lez?f9cp6_2Ok;u@ZW24G6f@$LrJ6{%}{x4g; zPY$vw`Q|qRb!t>iV=yPkq$~y@$j0%JI{q_u^^aYhz70e+aE9ZsO?vP*fw_ZC%?w-B za_0t@#4_-H`2A1;mTK?2baqs_+-7$STugK|aORUyyh$&H>tajpGF5f62}kY$7#>cF zew$B_w_5cS-BdPag=ttX{u;#7V_|ZlodZVY-q<192L@*d#(a9u5UXdOl-0eeuc0j7 zfWq6Zs*iSRlJX2sdgGb+> zN}ak@)e(`(Ow4pXEu2T}wVON-SWtdrhhzjt4l4Q4%>P3mZ62C|251C3_B51N{tf{y zrz+1|q^$TSLY^6Zil?NS4Iw^E7aq8}!Fc-P{W}FA#^XU|^CU|70)fTo9TE0-k`#Lp z&%Yid)f=&W!pRH$yqGpIda~5-+u?W}v^L|Vx%Q2^9%jhvFa2F>OZ5v z^6+iL>o7tGusPT}p{z6x! z^q({&r~RbWp$G4W&-%@45nDW42nr2HdO58=O;jF2sKeCC>oeN84u8-Vne3RlXU8WlAT~838-_#G8-M~Av#F8Q_rSJT&;(I>n;TIo*@OI(BLN6crrxk6! z)mCO1r{dhKRu^U5hzw4eJTU1IZq5OLC%h3Ze?Jpv=+z^WPg>V9MO}&-d^p0@tRIL9 zTbe6fUCs<4yDZKj?b)XBdm)|%6V}At570|7{zp$Hvf5^A>NH>8EDBX`JB%KXpWq|O~3l_WD!+TM<`!z_0 z+sKTz*u=ya;1(DhpzK3Am5QX)#j|M{n5R^vICMR?()6MK5Xo1<}1Xn$tF`P|f8s(s9@pZ_X zTm%T|8aaN&QBnaSpq2@fC{nFq&%5&L3(@mc{M?=IO9+99T3Q4_fNvqQJcDLir z`N~p_3GVje3bxGRrJHi`QZEZsNTka?WGe}!QRN%WpDk#Sai&uj{Bzv8{mdQ8jP+8y z@khc+w1Rkizv^8;#xk|d$Zw^WoyfB*!@y>L17ar3G#HvSC?_A#WZ+HB5h(WSsG!?r zh}cXypfj`SS^$(9Z+iQZGCsDp1&NzMpIkjG_0FlU#&w23G{UHH1!R#Qu(qt5c!^t_ds zzcVtq6jqt$KU(noDx8fmmjfUJ$ul+)wLU?^4OB5*ij7JltpLQ*2P#pru2bR%``*a$ zGlC@xxQ)z1gB&2d7CCVdfK`I?{+L=m!2~AV%nn()F5AF!r^v|X6Ag93!|n&oozMz8 zW1$bUN;6<;x3pLJn=0;*56iR(9EGg5>%dXps6ma$#2eFE9-%mPs=kD1ixs<38;UA) z8(zzC&6bu}mYLT60dpKggqgT7;?&mnb}gTp(F!52sEj$ z)f-|F4ChjQ3^bU!433Pmeo+UQo0jA#(}$PQGI^-CVWH}_2vXC%Ht(?@2rBv;B{ew2 zk$aKGB`QC0Lqzvsk_>I!u4wO;b9D(bnrhPuv11aU1d-mCr09ZM7ez9|MyM*$MrRR

        d5&nQKpRwI}?O3L-Daz{qD_I=JJT>2TU-|@W-h9c~{5v6m ziy6rN%PSQ2bCXDpBd+G3ey&X*CDH9NW=_V_%Xi`gn$yTDMU}PC6p#;|!_;Vh#)}(# z2(?JH!_QXC<;;9YZ{}(69ZrDsBWJvKRm{Y&Uyw_b(bJ)cxmN**w5f?DR2k~8Gv6o#lI^GHpZ1{|pMLTnY^Mds8h z=p4pFu16$#1nH;2fZWI!Q>AA>ra%D$^6f~8S*8Gg)WK+J2lzOki}0ZZ4smZ7ePv>h z6F+i%<0GeEFnrkncIJ^;4Wb!Pcfh8KA3>p?UVxo!k!XaS#=L4SCzaWsR#%P-5kUfg z3v}UOqH~om2(THtZG27@_HPJ1H< zcOr*0P$FbDyutW`o!IZb=XZGdhx6W&&%c&%2y2|Csn0B|rY_cmp4ypi+4%Rew(yG{9 z0M0I=k#0l&h6a3}-sfP@;{0Wd9y!K)fQQvRkrm437cq4vR%Yupwdkyhg?;~beg1oo zPNVy^TGzB}4U+2f2{+7t8a&|Kyk7D$&UMgd_-|m`A$)sr@axOB&AaD~93Ir8%}wAq z{DhieU(kCqnTDE?(M7*bJ?7f^K@Q~ve+-lE=x)Tcf!R0$Cju(`oYgi+ z?Iw0w)$DQ0_R$1MaJWGpNcj`VjW%6!>v6(LOjKPcIb`xug9c%?Lk!9@URj)|c&eGI zMY#Q`uW>$0#oYI{^1~OCNcvIev>p)NWti&gxTi2sW-es=XWVVh9~TzQo5=n|zXFJ0 zTB6TUa|`?SpkGYN4}rMFP>SqOqBhVQ;aC*Y!vw)4$5P5wtmI!D;)7AEp7JQPO}D0L zYrPo9yM0FzElcHJuq9lbEV5P`nWX<#`kD^s!V&ShlE#pWs*Wa`wmF0>eN!HdBVQp{ zg=~=Q4nn$*rlqC|jD~r#Pi!_@oCc4Re zw|Wf8G-W6AcGXJkxB9N@==`+VB3`9Q392X?)@pkNOzz)b~@j!-;MNjCIb2& zPe^fV4~o7y^TODBY`$?3O+^yharp185TII;#f-_HT;2azHA3EMD*21LicT4x)$WHF zBKXS}0cHQde0(X}`MT`0>3DOtJIgxsAnU-JYdk*lAgk#>iVQ1@zp0RvnK~*?roeXt zw|wMl#`pF!hA8D?!tqlrGql5{`nk;7j!$a zF}n%k)SgjJHl^zE&6AoFp#_X|-b{=tU0XieSb~6aYisLntj)kULAQgWX1)JE6slu? z{A(Das-th63_I%0dRu1GMxDgiu0lfX83vKhZdX$H38eW5+`3C1j;&GkPl>{BXFl>R`XtSkJM^4#-D^6wz79kmP$eH&`B%wzyR#NM zl*80>kUlAzg#^dc090vFZ`2AfdB3X$;Ig78^i7ZEXP7DZcw~^IwySBxK_XNhWgOVX znO%5vTV{SDHkcH?&+qG*nEPtvF2Z3o{kEbOEqQjd_qzSD3R!{VmKx9x0+PLNO(&k{ASa2@g4A!4Elkj@Q|+rV{QBNdjuZSLio` zu-3~sKJ!Vbuk`gg;63PyOd9{bSpNqG>r4t`wiA)is~&#fTEHY8QM-q+f&0blFlrYq zbD_~74KlOsZkm2VcTY(NI7x1B^B4^${Skj>)=`E_xfY~1VM+WTGEDyJwRg8n+8LiT zEfAWn@lDRVXLlG&vwWodLH({WZlbqjlSPgzxmUUEG9vNsF9viX0Yskl!JE|FoZYk} zJbJo|C#S9+f3I~&oS3&tl(h{n`4DG(LS8Y=d{uvnPZdlrY2w$I56#Ob$@G{Q?FM|} ze6rQnr<&9s6Oj%$@i%F^Blks$%+6aE!qf&`k}J@ge(H>0usk?D|8|^$pblH{S&Cbg505mx-K7!onFZ?Wr);#QV^}pg^&CUHpq&1^wL8fnHVH& zpQ@)NA9M9Z$!HdL!kO5COwUlr@+5x*AV~uf0~Vs&Dkw-nhw7_c)V+o;dzKk~58ym` zrszPu3mv1_KcMGPpY()W`_gsvL+9EhZ?q};dtF!z@OyqQb4r^r{a!B@_w_)fIw}JX z>V%^RaHUaDRCGS0rseo?%H_R#<3V1# zsl}@{HQb4T41Qg4M<2f@;s_sx=o6>A^@fVAyE>oX zbZ~fDqx#KQ0Wu{0+lk1L$l@^lZ&Pli)R|9dC1_)O}%d;v?3+ zJ>|QP`^Z0zw_29TuSOKTuG)upy}D2)6^SKj z;meAoOKN%GkM+?lJ@qpbc~)@}QqXPn7q7$jpDwi@N5j%Vd0fHJN$Kr{i0&NyojnGT z`{VDQx66DneO?Dp-uk80F+wsaGJ@ke%OszaMXy%5U&A`?gjE}4-@;3H0BCT8hZDUpwnhq#Wx*|Mm}G;4aZ$rIzE$8R1MaU2DImk6h*`+r0?4Jn zPIf;rn6j1Vf51jnAOa@Fa|@#+AYOTvQ?q~&ZfcL27?`M}cvaTHGq;Zbb1~wJUW=qg zy~7oARD|7#bw$40zN4P)Y_I(16@G0MXsdkp2o(bZ)}p}|R!k~5hDBWGh4+`EUZ<@5 zoAx|xyi&@_n6IyKfhI7XHsx`4WDgGy@2hY^4!47Gf+xosUwi_5lL&IJ{^s*WH#79o zbccm{)KUWxt*V^%SKSJ<=T7Vu50XeD{d4-o{o+NT|MTqVKcRG6_G|*jfURKUte{X> zkMn@xUlct+B65h7W4oxUfO@>?g>`{|_TnCUT|8?)44njXow7xxt0LgF@ab@X(ENID zgrrd?kj(9@Mu01Nsh)0U#jdL7>9XT6Ob>~_>Gh#Hut#p@&MIid8$EfN<5NFPWQlq! zko1?Y8a_%MOVW2o4aeasWdzKI;rkxYw{e1-*6xnCZa|h(bONuht_W*%8}WX5+xXbO z;q?EYn9gm{{64~$Y^$YucO7Ee%76C}`pVaq4?3ilwa4M1h^DRe<}#c8 zCQW5X`^ObDd|xOMNvDqTzESQfJ~3g|p}u0D$gGCr`OGUHUa@2&cILTs_(THak8tgF z<8uBY4%@p@bXO9ZfM;6SLi5b|r)Q||67yD*ab;yyp{ELwI$-8%gVTDDUyDL(vePt#85kHwnk zjWE_SI~qQB*}0q?Omh)dF!oajP}9(H1s(YG&>FH3%%4sVQMSirR<+@}eFn|)j&mm? z*40-qc%#F~HQ*KHbHTfi^V<67-!jY-(YbX$fDPINiodzP!4iEc#&yPxYHpN?6;@;> z*xq`%mG<|qoSS@<=i7VeCztYx-5acI%NzE8=x^t7=WF47I`krC%Lpq&|9yfS}jPXZTGf7 zD{4r4`!lEtj)4iDB{r-^WQFPwXwb=!cujtscnZZT>LG(|jU{@t`}pNlV>)&HA#m(G zE+(i(WqbGTo%2m)Q+|E@T-5S)kK5_<&Ck9HT~OedeueO>^W*W-Kg-_Ozvdad%s0lP zl!wjyrwcBB5{cd7Gg$mTgxIu(nnR_SB_Kd4W6!(Rd7Kk6^dG2iCpC0gyu*Bi|1|hv z^^d0?abX$LWKR;42FpWn@~_^T$!bq?Yd6?_w10!_HAc@LR~VU&U|tULm^qGLy@l9C z4kz)Q@?RwOpHHZin&W*8iUeDAMQB&sI}hF-J?J7LH~MS5=gjRb&IAXGivmS~Y!-Z> zi(dL^VUd66H?ft~990tCr9u?Hl7K|Sejjb%F_6L9d(T}3E-!S#J7>GCyTkq~W=+!% zOP9KPK+1QaLpUZLSr2P z^2I0Py_qz%zj%ki|aJ^2^@SA8`?Pan$@x;r5rwNtgElMzv0+9kxuQ1M&k15D7 z9M?!|-%vX+M@hNbil@o43V}$yQ2F$X69IUag~L5)U6XOmk%^HAYFAVCYFu=+h;39& z?o^{fv68E7tNBtn+0$j0n2gM$GC;BTU6owJV65}6e#4U^1G$DOy`2otSgYq>*pOlb ziC@5!;hlY$5^dkwsNxs324|ul!HBje@}1Z%MGn>DP8|4>97G?5(j@^<=^2g4-bRG! zswblQOED61-x%3D77I02nn9OJ{`^{||0(sCUUu)PEvMK?SQ${fuNL?S^ zJh}S;am|JF^UZ_gjFrVC--au+Uny?nRtU09ONVf2&_b9#Q_=NPn#dt0SSu|uey_rc zpv$R%O211UOQEJV2fE@P^0P0-g}~d^aMI^0`4?k;BV7qZRR@QeYEU!mNr|X4ABIe~ z?y*r*l#MV_#4+X3_3nYmHQo2cLgBcS!Hc^KfWE<}I zaADI;8f0DK6$p+`hpGk-B^v^}@nmGJ{;Zx99LVOr&yg-2Rwj$V(JuW}631qkQM~-a|7GeEIlO12lTb>25XtX2jC=WlHiv9gDTt`_Qh} zy`SpYulmm}uMYBcA3Gj=_Gv^r^~I1Uf4<=Se@vZaP@CZvt&5iyr^Tf>6nBT>?(W6i z-HR7@cXuf6F2O181PBCo_nV%3&fJ?BCO*=D72HrF{uOzL*9}J|bj*b<08cDF%MtsRWE2t@fzBcpwPofI){tXDj&^P}- zalXIbNF>hl$msIg=u8)o7&22x82cX!$Pgo(vvO0+!cm+SkZIq! z{Xoa@MW_XR}8N)RU7#{ynS7=h3fHxRYHK+9$Mw1B=O@zA~lVqkz($LnB`K;H%Bnq z%bq*TOivi90J{nZDtVTz`OqfA43nm;JkE;8oAsyq2Nfo!fo zha{FqSs%PQO<^hY(4ud)iW_l1+Hk(;?MTvHdPy!`O8b0b9#x>845qB_OjyB&eQA@7 z4B{j=f**WD{|Jv34M2m@{nLd2CG8;Kb2 z&)`_*&LO~0NW+jK#vsK6G<=(m&0~ykalzf$cAD3C4X%JQFj~oqRqQxW39tMy3-L7I z{?Jh<)8%Ac?Z`6DYp{5CH7SKTmB*Nd@hI_e=aVA#xY$@GZT$toO<|2wj*n+m+%+Ys zt3(k}6WvgeuOmwhB8|)r)+EPa+IZOzNQs^B5YtmQAg_jo6f3eYKVN8nJ==QjHmnZHhUrZFvp>$QgA1hjC7%*H(S~Urn)`w(X+0XiwBo zgzgbsb6NK4wVWcX9cG>ilr8a zt{rld$kN%zK986|zcsgChT`w?u`P*U6YL8GA@JrS31o3yVvA|k^~~v@u9&&)Px%-K zaL$H5(8BbzJmL@he~<2fp`4;Eg9FhS8x--M#xM5&xufesj4X#x9}Z4wA(^Q5oji~R zrMd%5SxE_eX_iZZot>r)mv}5uw7;%XIOb~o#Uv-NjHce^FWp}`PGA){bp|+Fb&=S9XNIQpqD1hbm+hFPFGE z7kv+@U!VlN?s0$5);G5sO3UFv5wp)q0+pk-hkHnhnWFJmLvOZ3=tUddw7XGU-Oacrf#evh2-6*Pfuwz&yPt zI4XP>8$0|d9{8+4ecGKE1@&w-MowF5^eBPdyY@%1pQufos#q?j38C1S;YZp1+iWs4 zq^LFd*mHqk;_=BXIMpvOOYy^DR`uoRy*}UTjyW|0!{AI0ZUmH`iT)9oWF1X{rSWUK zt@EcRo35b6E$OvCHdrZg?J%QPEvlbo;|M-IUVFYu!txgUJjjh(^VS%(6pvk%#c*x7 zJk9j~k?J;E6Q%L}RBR!F>&(-QL_bTh=Gr(VPA7CEN@Lt2MIn$66KAcQ?sv9$v&eK! z+sHI3^=L47hVKoHltryhb2e=RliNa_7B`mUYjl2nJr**urHh45RA<%);kLHlaJ=8* zfuBRf*!K4%^zERooMC>e`p2$DOcwzWAq`6T6%44r$?>6JcdC5rB@`})m$Q!#m>1)% ziq6VB3%^tcYz9qgUh+At%#iY@s89dmH_3nt%`Vw|xDRCp$qa7}5`y&gu9UKfMah%H z*4_BGk#{ADO%5NOcLxycjhG_>)mYxdJ0|Ln$n|}^1-f(fgXA~7KuL2`Lub!X5_bAI zQS^u+^<#UIlRwCv9A&w{>=2grb~=^ATJ#dxs-p2?yF@LMl@YQPLu4EddxJQu3W2i} z|a(}ka04G?vx*2Hr*Q=om9b8MVN(6uIgEYWgqCOb0|r$@JJ8qt2asS?jSn#`@O0pw`%-VHlIiq5uFK8y#>*9?ZL$A70+Rxve{T6S$7lESG4&!abk_ zxP<6p8MQl3(;F|$l9FCFPb>Y&$77&2P&Q$|3?(mu{Qy~G(tM`n_iz)&iS6V=b#+CT zv!3cR)cuCjPk1jFY&ZZYi?bPL^sUtV0X=1}*lj^l7BYC+_Z^YTY3msQo&b9mF2QOu zH1m8SDR?Go`|@uR+GieD^uu5h3JZO8;&Sr#@i6b2PFfx(TX?Rlj_)D2}t#BVJZYV(aN9T zY{X`LBq^hOLe{bZ6njLrCTVPEH?Jt>>JB=1(e>VnqY6ioc|Q>Qo&yr6{Uh9L#~pS9 zL}p6$xY068OHwi3s{cA3W6l)5-zoF362*VrE6aHKkl>sHsWADTom5Ct;d#xI|MTJT zUI}uk7;x3%jCnLz|f9qW3A^#UPLx(sunuCNviq+&0&4--Vb3%It6}1UNNg95S z`t!uG)YxoUypz*ed6s~v3it2P<@l&1%umu;mJ;F4v%jgnrihztND+Qd<|HQakD1UD z4y6f5%j!uQI^XuBvsPU=yy#50Odc+G2(`ss(Q1j0Ki-Ionyo+%D|Q1O{~++bI$X9o z?z=#s`MgIOE;ps1MLYjn6q(Dw7XpOnx^|O&Ix(h6i;E~=$sny$mks;~nD3?7YL%pc z3L_^RBU>W1x{t@m2}W=iyk!xOSrOWkk@W6Vr?1tGfN>`daEJ=V+b8ZCFAH{;mYSXLT6 zCaS>2haAr*%YVeD)}4w*WV!#)4DDnhvkUt2KP_tKUU5EUdw1)3M&6| z`f@NB&F~~mzt19SHBxSRUCRN?>+-2-X!^?H$spW^kfS3jpWE9d`H^4RwkQw=ZWh|# zLURQIr-OWXY8X2trNr4`VZP)+=W9P3R|xgdSzTc|J;GGU?z=sb2?tDrQ2z(cP!c%?3hDn)cf-eDRZY!=3HR6E*XSEO`WORB3z}*LOC@w}Uy|WmRI;^s3VE1Jtn;iZq=W;cELe#9h6>X6|In8u zY|DxPT4xdyr-^5QMMR!)^bz}Ur(yCLc3B(`Ii8x7l=ZzJIuootD(wI$H|4q-H;@Jg zS*K>WO1A!{cqxng(6s%u>35V8dGr&!qZ5)$E6I1Kp}l+9C3}|ek8-YJ z(S@DJ$cF4Qs>CRT@-ePWw`JAQc?=UAvt>0h1tkJ8zjrC5LSa*Rq^dr1<~0jMJwd)k zsdTc40P|yIWMK|C7Y|P~v~`LKz(;9}AET@e#%>!(P&h&zuVWxcH)XXMHr~2A>SI^Gl_muk5JtQK=-nA*KXf-6eaPq0ChQl&2`mO|0^KWeD&$ z6Y;JGMI#8ud6abe2=k&DjeUFhOW52AnqN~LOHDfMm;|{61ne<{&RM>IXm4n z9bG=qZ8cm>+K_h3LGnN;$E{UEY$Qt4R|!c4E7(Jxh)amzAWNMK3g+M^@_)HZ9^uU9 zaqU-vgt~)&*=@8N-lQ=@o~_*m)XmcHe0uB?n9)wG>Yy6Ej_;45X{;cAer+4BPJO}l zTfF1o|2?z+tfF7euEqcRJ0UVU;;}(Mcy=|}-u2~T0QG6{qC{NZPXHoP;t_JLEn;PN zxb$71ll^%`;r+S%$B>$u&PCbJ@1z?*G`u^C^*fx{Cl3#=p4n}^HF=Xj@Z@5^6-0|4 zFA2-obCZB+rRM;8O@?DtB&u;X(k9*(C77Ph41E%vL+)M_nnTvS0}PIo0&J9MwM5<| zg-KQh_DhEm?V>Z0jW;~N!;J|lJMBu@(j{n-Ly!ocuJe3%{G{C+C-uh;to7BjN!!4MlolZ={tZU(zDOo7~`s1Uc`OQ9z@CeN9HZLS}0 zMDV1k)YSjkq@S{paDOYZr57d0G$-Bl*-H4##|-dA`>(|LVDzmYX{r+-L_8j>XHct< zGPsTsP^mcLlBN60hklE{aXQinoSydFmyUak;n}5*oiOI3TfnWCbMx2aL}b$Ec6v){ z6`3R__2&~R2%b^Kh^8nyWrJp^6~OgY5fN85`1bn;!=%pWO9eauPdV>M6Bvs7TS*j& zy2JX%8Yqa4>A)7f`qWxu8bk1G2JXw_J{+zpm3?NIc&Yo-7_WxVFq>IEM4wqcFh7cO zKV6hyvnQnbiL+Nm;#$(mPjDj3A4yCv^eN;ygM7>zXB zY!wvmrl*WOm&GxmnNe6iFnE;<@iTLAQeYs0PM30qMBIT<_T5he>hj8P zvOC-W@*Sr^tW#ZROPfxNZ*GU|%f3JnG;5}esHh|}vy7!2+>H{N&f&J**2UhyCp>oE zA!irk?X^9bi^JIvd5gJ#ReNpHnJl-bLmr8hf4Cz;1Nif<7SlvJf%g+uy4s!l>k^Sz zBL2Un_6DzAT_is}7v~^C9Tj*VpznQN4G4Aknv&vQ>lcYEv42*GhGZ*nZ~R{q4&+UT zhYkv&>KjGE0`ov-+fRY0>6{vLI?Xm+&%ahORHzFSoU=H-hhd1F?L8J+H6l2g`MZiO>5` zoG|yx&f{ubo3oS)QynJhX^y?fwIF$}K19=t*+|BMnwncFmi3EF9gWjq4x*zSX7-J` zS+kqaf)M`2VXRrAhb{p<-~@;7DyqkMwZ_HWG2>P?r~Ys-r$OJ(uxOnWk2ztFR7q$9}f z@5}nPDI!BGbAsosK>b%aQe;OmzQmpW!3);Pv^MVKv1kkOtyX%^xGPDZ>#wA#IJi*B z2nRs)*C)2xZ8WBA%c|J&lD-qADGVWiBH=6E%!8p-N*hW@;72&ZQ^F% zBN8-#E$}1~um!W(0fiHR>6|ewyUG3-z8({yB^leydke=&?kwZDl=4RjpVH2z_(5rf zby+@XYUJheyy=vCDxb{yanraSt#!?j5H<597V(XD2a;oA{8FQg$08FQBAm05YlZyo z{V&e&TTc?MFPE<60jAgnzaZr&j1SMb(}S+5@0bQYFF6V8NV0PB$FxE!P1jx=+zvXa z9+XlUw22*|&Q8Mh>Y$IXFB!=jEDqz+Sp-k_AGhQ9I||&F;&!D*Zl`rw(+rMTkw>&a zkHhM+X-lN+Llk~BVhMh1`p#Ueq+iJ;nPe6Rh~LpSWWYw}dSO3LG&5QXg?M5bWcrP7 z#Tf#d=nT}uGi#r7qd*3iD-!2MhdW|kzR0kFS6!(=&8NIZl>uu%Uq~cCFFmjL?tE7S z@=pV~Gv1Z?7o&Kb``zV}aK4mDmgBvrE1^NKvrAZ0qAZny_@8s_3(i3{e6RB=v>Syn z1l$+{VW{rHxN%7vC35&wCQROobQ9UUONh3f%SkmJvWt#|Fm4o|q| zTr|h<7#pyzxhr{@k@WdKj#Wcf_k7ARVY&KI8bJL} z;*tg9>ZUgt)@y9Bi$1CakEdb^kFC*&VIKc1bT<}TJfEBGuo(NfUrW=h(>$M7GEc3c zYk4*FeA(rbtvyn)Hiu31=I5OzU6&5oPxkx2J<4lh##=axd3ti2$>yE~BSl0;G8cp( zGZ;Zyo0d3>8qiU~E>|mSdGZ&9OxdEOlK12-ZqwdhRXaUyqg$UYFdasxp0^85@B80T z_&&wHy#gQH`VsOxv)By{Td`CsQn>Qfg+HezpDZW@LbFoLN%=f&d$-;MHaM&Rr~BR+ zxUu(hy*W};=~S=eSkfV7kFvdA-+74NUjZve-8nbqQi+kMEzad)12#&S;DgZCOW7+q zKR>A97~D|9*G}p?1&Q7UXnn>I*-A=8eFRUM-I8V!=U_DXFGgZTFyE~@jD+N{RTo=C z$d%|Uxi8{INc8eJzUD+qqZtOz$IFVMiE?`-(GNjApHcU)mIVkW)cd(BImgWSK(X`h zz1eNsV>BSzb37quZ2Gm|wk}~}mKbweVaFGe<6^*!^Wfhe={gK9myFOu>R9(2kI1X+ z!sNvB>QfS=+Q+*SNuZaZ9gO`;saHfcQKMDLeRA~J%Fv9DlSJ&~^RUVh!LXy5^rbZv z6kEGwP*$w*s*itNNt~0Vagn)j(_Hrr;lnzM# zDWLMVd^joq6RtLPwK`Clg*t$MzvPgQ#8p$Ox0%#bL6o=px}4ng8y{ zDDe`(Qe#b*rtT=lgq8S27QZedl>H}=`*A?^Gfsm_1-C?vHEcK+UE!c0u0d`rp0)6A z@<=7j^I+3>0Zoj<$O=jG`Jo8YQ#@ttV?|q*9V*1QU{*cUaoNJ-3R&1CPirDPIs-1T`pa;OCf3LwbKXRhL<1+X8GO*|^baZ@N0>H4rJ4rRV_i!%aH2<2~^n zugUwsWlNp+mO%&MuT1$Dn9c5EC{_9j2d5gmq^HxX6)P+!m7iLs6q~;HdQ?e$h7ttZ z4;g{Z(x<;C>xwh-joy3g%XPEWMc!Bu|G&bZL63wW&4t4Mn*2S8Ay!`#N_i>Hq9tR%Uh&OkSdHACxvMuh|_lej?)% zQm45?`Pl6NITf;T{_lVjX=B2l{EvU~@YqNEJpW;i09D}OTPO-)M8{dXj1(1lIU1|^ z)S&Bx?q>L9L`eV5W%M8qdmwM)5|Chs&8!x`-~R^tJptm`UJsIjvK zvAmI%8o``d@U0=mDA%|~RcCmgTye@+7=A*AKR64%lhu)%$h#Zb^|lh2RHlhBU_4Df zd|j(GPo^4kiSH2WZUGL?FUY;=+AkuTxHYsKW*ZY z*_n#7zP@!rHmDy&qm*=d8Hd9@fM1^u;BWbP%6TrI_Gk8f4l=x!l|*YpbGB)(ekjDs zS|rctHegoZtknqn8kxG4)4|k zMii@MAm=7sjh9QO_sgQ8<&+b4^3J2-hj0LQ2C{YA)QEk&X>#Nrn?oaR2BDz>G0D<| zJTPX>ap<3ysdDY_mM)Qd86^90ss%a+^1NqeJe(t}TcK?VwTwEb>v+bY_re`7Vi$wh zqi_u6c-9l1#?2Ft{KPU|N|-bvYF1woOsNVyDz9g(Cx#Aq?=W0&{g|(wvVtsT0?K4= zg-OLuQI!?5nscWTsPtlm&t;K-?MTn(EwKqcc%`Z=b@c3dWI_vz1sU`nHv!~m6n1R= z3z|mXN95=3vc%i=>|KJ>m^s=uCek6e>A452&Ll}^7~o1#DjPe$*nSbGFj*1BsLUp! zif(BUDN(jV=pP|u7AZE-xvLJ=7|E!Te4i&hXbe_z&PsM$#4L^i=?tk~C0>&15i(r3 z)qzyFZqjL0S=XXtK|GIkl@&1sB*H7j@W}vOY^lYFF>Y-jnuz9=BQQrhI;!Y<*W%vg z!`3*B5K~JuiZ!XwBrmz4Vq^?LeCrw&Obn(3GgfT5CoKl8k#Y&i#JTERGfGp$c>R}& z+c7TA81x`rvW$2Vit-`TDhoUMYL^DB3^XIy4VBKFtg$$zm zhW-+UK<79H{x3@Q{KJ^WH$2pr(U#fYKJeq_z7LKGcv z)zqy+n=6%1v33keSJA?rEAa~>?tX=LZCdb(QSnx_)WW|x>vun#(`oF&g;OzI6Z%J>JIf(PC@fc(Yb_DCu>0jZQ)XS*?+LK74q;krEYBy)Pno zwz=re%=n@Kr!gSKvFU%#&o9x!*7*p|^qO4Jw4m=t3cn&BRgu}-d_HODJN7a*jP1Ic z1?`Bb{8j8RB>$>k*l><`_>irmm))E7i2QJI{ng`O^pk9MH+b?u>zec`^P39lIjvNM z7G{D|-)`3~j6w=%PKsT6_mTT=;kmqA_W(Ve-)LF#`PAfBA4?~_UC{mU)!uma-_Y&0 z{hR^FU*u@wl27evpy#x}vrXsK814U!lMBCeG;L(bcaSx??wzR`x0mf)nC1Bj3fl)zEW-HR zX++M6+A^Ab#Gt3Uw98QyHA3{~ z>v->ecIY#BE7%?OyapfMW(~&oyx!JEix$*CG{W67r6XX{$oMpXs}04z+(HUdSq5BM zUpIilTUB%!Ci>T1`;fl*DwKz=tkzMO-uUfaaA%cFVYubID!r)XpcJ=tZGmrmh3ZuB{Nw<2-|E2iVFV^KUM_DER4XkMUMVTg6T2_h*Evb1GJTc6`8!fKn z7~c5vsZt_d7*SHXo4KUY#ab8Ek}Xm!Usq9Is$_xy;dUHBBtuq?hNxU5#?rBb1LI2u zuwD5B4|qiPT8=+P9GNOxLWOsLK^El|8;X4>+^F)%wVy97gWoKQ5CehzO|;O=c_pm1 z5igZs2O`cllh(D)i<2hI#O++dO$_^yR-ss8=$4%VTv^OE`HFl9o^orNolL zuXm}=66rAjc*-Nmp#_bkV!84Hh?D5$ zW^wk4CNL!WgSawgNpr)4i7|B7H+eTk0|#ZYzQj9CeRL$^&ex)*yD;w2;{hcNc!7$7 zytaaa+CfDkURy;$-dn9O?VtzXO_GB>f%{KX0`H&h1hm`66mMxT|2)8ED6_bOBkrdiSIF3+crrNZ zkh_gTD%hY#i6@qYVd6ALYhJx^u9@&}ld)or={)QZJDD@%5@Lp_u^9ysMNpaiZCL3m zx&`pv!{wlfH)0hf{#c%I7wbk;-cj&NBXLlIJ_1S0bKUQ~m;`ILnC79oTLrj6B*zDp z$eAV^xZ!Br;3>U!8M^6^k|pSr(H}1mhZx(ckESPIIwXFlFl;c*jr;z554?Pti#2{* z*ODCJ&)3*xOgYwWIpb&cI*H+WNlW~5|As(9#i()QSW74;RFF?Xlg6xP;G@(wa@mB0 z@h9hLI@#ld_+829=qN4ME|cM}!F z!%zqnH8snwl*lfKAzbW0Q+dw1^& zL1~WHcYTj-xZ4ixhz&CKNtFRPXTG-wQ0qzk`20Dz*v&Ig+l6cKzY;CH;54JpznjT* zPzZsrD8pVd#gX%~XM@lrhpL#Y52Vz?YXY8qy_FO1{TcY4^qbY|#sV3$Gk~l-43-Gv zr*7xdQDrNn0tBK{dxPc_1c%f#^!ADx89YFvVY>5A7c&yX+;#AU;?ez(VWJw(FC)m8 zBu4Pf!w2$TucB^Nq0h@YLc;flB4dzVY6(z=v2k~}x#0}KwYh(wNx^Mn<1Y9?QFT{i zsa)hE%oEt~oqz4;GxJb}d^MMWf5#DLSVW|c1(2hxMrWS@iAWJLC2eY~hiA36e zt0|K&lXg7Qa5=*nM3itD6zFK`+p4~vsh0V8x|Yu4?Ch5=So`3RyM$$>nh(y@dHk89 z5Vr)KoSe*c9mRUF-Y|W{Udx>(PZ|?x%kjha4WeFeTWmVWz=q3y#-ei&h9~58QzZo- z^>XtcYz0C3gnW#<*t@B^b-KM&6xmW8_YeJrCugOp%qH{NN~qpk+pIol5<)(8foTzA z)odfeOzfhs9K?)|1`Vs4<7;u&w#854djSX6lBws#4Faspnx_$AO<-Kg#6aFsj1Ime#!?V2(-==OdSU? z#sw+b;eTnw4XoD>`!?_AFPae29)4!`k|-f6H9PuI_^|C@j$UF)!S0um*&KB&Ik0tC z|1RE1(OJ?gQ81{Afg>pK8$zs!6E!pR({6hPWq4q+sm6#8&lqKyrTBH&sM(Pt=Rqb% zHsM%Nre?X?sNk$1vJ!N2uDF;f0V{S9Q^$JHO60G@YfMee!@j|m+&9y-M&PoU5LOkDqMn+YYRQBrIB(cr9s!}>}eO9)*h#A z-j`3;_uHo$M8jd{e6iDlk00j1g9~!m_ybWPy#?R%%qS)uSimL_+qUtrjj01+^4EQ% zXLQ>?=P{>$fbyqx?^CDDe)}lP_JBLQmU9%_At08w?Gk)PjAao2aPz>K@tRTCcF3}& z39}oHQs8MQmJtB`2HSeo&UlR69`|k~pZ|`4YEL{ht#d%8Zs6eTV6iE?x%OCbN-A5> zU5ZJ63U|2FB1o#2eYMM4;*oF$pEq^{@W$H|&mk>Va!2Y+bt1qMydl14ysrc|t6n~$ z{Hv=48&^C$Y5-Rw7{<*i(znGvjDPrx^c(aErQNwB9GAmBMij74bT-oA!mgOhmntc{W(;u0uQyc*^?%-?)W!-L2&CnlN1lvhk$MHaZPV2aZf2_ zuSYowya)t;Uzy>k+K@D2Xyvr#7`L$gRKP(r)Y)!DHP52ocIoDG^S~-^amsYQcJ6qu z<*(#4Q}LtVXw_nK1?|GGy{$yl%3cp2Q)+%|i6GbiE*-SS0_h1@5r~Crl-eXWd36j^-8>P)$->EApdX?QKd?s#i5_L_LufxE{7#BhdA`EE$9+mlcF zwBAz4#2f}SzUgF2Y7C=VLR|lTQ>wmKc_J^2pF&)t^ZV=laZ}p#4@u!Y_Qw<*JEeLh z=L&;xnZP(*HL(@^?d=F#Ki*hdKwH7bp4E=L*R+fF3oq9cgaGthVp+bEXzj7!&LMr^g@KaqkExLo;vNB|qCtx!y$G9*jN z`YX?~80--K9RhE#y9D>a9hVN{V^6$8ZqXe`G8q8Dz8?=Z3z$vkR7>0k+^=pyrVsmh zo<98Ch3y0x21g$(EJ0$hUEX7P)6j2{5bE!2_C!CqGcG59U&K>Ci;ZeHo}3;~Z?YDNHn*#9JW5tWUMrO@oweoN48rbns6W`pxXIr>(7 zk6s03g*u#_4TIgXChB{ZW3qLKGFwrtDpZbismpZ={vyqzF+(@%h_6+GiKOi4^f*ZW zkKIRBl5dYv`j;}=q*B5kXzgtJphUpU)doNaFl_3xL4`72>T%Wzp$02_=nF{9l^j)Y zD$;PX|0~9wUL3)@ZKrjc1|zuYO} z%@NHln`t9r$<^+YGyF~0wHdJa!&-G~!F|cI&~E6JD22NDR7Q{reC2<0U%GF-3pi}O zdn0xP!3gdMYHY-gGxVTn=sFUwRt9x_xKvFsH}3GxbdIx>@SDHee5$ z!tMs}*D?;mV5)DOai(q$V`FcvQuz(Ky7PsE^%JkA z$DgMr)om&4iUU2RXU36bXeBU;@-jcMD_2<58>{>nGc_$03G?Zij~YWG z?(^=RhoUxts8l{NcRm|*09(W-=nC{-t8q?F7H3q^1mV-4J>yc35x7aiMRn&MUj!v~ zuAO~H5XT-#tfxoDUALqe{7D<1@UaP(D5nW?2BZe9u*s;p6j$@j%3*mUG#jBv>~Z?$ zb%QbH6i;%)f4)fU8pA^dQ!zWMjEBk~lo-xn9lqric;(DTS|_NQlw@+;e zi|CKwarhx5|0uaaYUcZhyxI0FMAc}Qc0JkRaUJuVr8xdzNrvH2W_!1QC96zuWTB*s z`G8--U6yPrBP_G(uZ_ufPt>?us=L6`gS$WNc$Kp`US&K8)lvjG&X)N zWW`xZNf4-QZIQx+KOZ{fJ#q;G9FMcH9S&kENcBEu>aJx1V-t7#c^(TU2g5Owmqo8o zkMq>O-M6f-{@fjjmtG|~41>+HuI*9>m3#g+9!}-2?S8U~9v^0%<}1ut<+eK;|KpS5 zx1a6)ohEF0MvvvcNwHeODPzok!w5ZgCpuZ#BL%(>*~xYovHE+3-IzLDMOVqE>1bpP zUMPDMJytF2e*XLQLIA{2t_~z^{Ii^;)a65@u3BBi<6hVcX03UT&>*#u#WFH( z{e&5=?P>wc#o=t%1g5;O2cUY!#9O0W4xkD)wwBlDkN9bRiJc=KFM(O$gLH+iK{n-i zmP6pYvEwEvpe{(H2kZeZFI{|s(wEW1C^x9~j3gF(Lz)wWI7h2_@piqhv%S@On7RFt z!L^Hcw8%lCT#j}aa%r$I+y{T_FfpdCAjJY}NTP;@@%p)vl7}m$#KPQWBBf zHYh5*BATOO(a9YBilUm`A{|Cw_St*Gcpf@2j&&ni4JYMxG+BbVBWKe%8a~NjG5(m0 zppdtGt20vJj%^ZoIvMvK2x5^==j(G zrW-tI+e>4&4)C$3>kk|LcT6gr+THT zs~e9dn3id3)7viP8+pRYRA82Aq5}epl_m^yV?FoAnIu*-$y_IM8a~XKPYv8?MUrpc zn4ggz0$+Fzt@*8vCkm#Bq_SaL#hzx`^Y+ws6F zNRyIiT>(eLo|mk&*N1pbl!6@(B*4}Df|zg_vWzyL!p`-df~nYc2Q=iFxFR?uz5V36 zgy94~M<=`DgBM8(7|HR+c==0e>xFQM)mGK9NJ+MENl}x}&ogMWi*EQvZDodbQB(V2?7$ku8>83XBBO1y_Es{bc)ySr@=hwU0qv1d*uU#M!M zmExueOMZqgkK1{e2&BA=;c42n^&(-sZu%i;@42T(e?W_IuY{ukHe8_QLzMj@{GKe2 zQw`(d4dLyqYl{`{apXObhfPyS8CHmOG3v3wJ4C?^ugo42gP@zV$rl@8GZqi#%M&qK z@)m=^t8W|{4$i3=s2m&u4_h!BJ{yWY+?KOu)rJ-iztN|Lees;l{eF^iLaipJKTDI+ z-3QVe4$~DLmN)~@oP_mn96xeh29LD=Twn|)_@jW&UU-sG{ltwnMk5}^Fpw1o;Zp|5 zv^q9KpYyZFiz=!hP3mwW7z`I7+6b%_H@h@X zo?{iXw&FaW_Xy^ApK((}RY_T&wD%^b-Y<6&Q>72F&)g)f8+7EA;9A*GQCC_|h38GY z-}}F}%(BLxU^824kHMW&JWgcx;5s=kZ4x}?hY?j25nHV~vhOQqB1;L(v(3+5n`J;3 zfe9c*uT-$-N>WTa_nQF-L}iZu)p*Y4r2ccL;+##Y-ywfwwwxsgv^cGT106xbhnWbl zla@*{3S0z>4l-NFX=}C7<>`R_f+i;Or!iC!4oVCkI2|-yi9jTvVwS)h-;dKp?#2Yd zH?gnG8=Rlux(+sn_!HmqVXx zdAe@_MXCA*r`o!BTDSLyJozEx;T^c+;K$wsr@wq_dA6a39UFJTOlgq`&4dnr(IpD2 zY`qso`jkZ^qWXy6eVFCBUwyJ%--edGE|_4Uh1%eUlyp>ripDob17%z;o`a}q>4k-; zk#b9g?n9*Fl&Jg!UXUbSsSPm1U0sn==+h%3;8cpIz-E%vyn1FbS~?e@Thr%={@dTm zY4dKGVOm-r_peLPZWi-wGYMP{M4j`d;5{;SzoG7g2Mc@vXCBfWQ&0cps}xTBLRCvL zby21~+OvXVk6VOoavO-pfOpNZnNQ56G|4%GzgI#Lm2t$&l#bBg<5qu_Tp!3@wdHZ9)120q_kr_`1 z=*DZXu*n8u${}Jils%4G6omuyPNC}6cSu{JBviY-t@{z_DpQW%5{G6c~(-+rl3GVv-AcptWhN?L{5IVVGFP zzSmf_olx(w;!SD3I~#Vp9(NidUoTuDZ#(X@cHjfCf6b>Bpk7RvXg5NxZj`$~%ytJi z$qN(jFH7gwv>vWsN2`ri^D^Yc)AM)~*TVH#C>c}e=E-C`fh0ju(?6Vf;!C3B%bw)u z8OXaG8Cn_0H^Q$R_?c?OB{Q;$YVN)VdSZ}o$I%z7rFn^Pds-~zf9~wgOVCWZNG+xb zJ!VQsvQ}9^+udzRu8{MsgdHDoH4@vCg*eZ`H2I<_)X*Ir%M(o}*+Z%u{IvL;PRk|s z?}`r!7Q&c45@>*h2#t+&}wSgS<2?1ETPHz#xAWtW2k9_RD|rMz21hVuY|L+{k+ntd?U<} zEM_u&Vq-T=ItBCKK`$;|iY1%?5$6jeqQ6h}$<3wIV$vJy>`y+~_}m?q#@JsE^FrrCJrhQ;crFQv3C^Gcp4c$~3E z_m#XPiiltPl|Fz`zkM((I%LCbO)l0aeiW|hvh|yihwYXXkIveQbw9)s=>D301M!-$ zCFqxH{RVmULLqD=W9hdW>06C*9~LFz;?JT^W=1~=k5Nq?LgFewY9FnWDWiBscha#Jw1&E1&(^oV*e?DHhlU;trkj7 zo3%uTi%Zm+T@HB30_V4wsQ!%mBM2;{S)8)k+SSlI~H>Mq9@KQMuc>R)#Iva-q?Nq zz{Fboy5crW^&))uXH|+*BbDxu@s_!E*VFb{`1xVCNg$GefzRdRetURkv{Io2r(IbM z^20ZmTr5dR_YF^~82KzcQIjCX>wU?7i-_uJwFKd+u499Xzir;vRec#AoPgV@)tGx_K#3t)m-x zeZ-YBGp0?dcb5e?3AF&(ZqEif)GB2?i_FR2ShyXqid>c=v-KIVzC#*K^0c=9QpHJ= zrx(&L6ZV^=G+9S?4U+{IstBX{#)~1qN`rkgnkq4qMSaPdcpz9jhf-HlnQX;I3@ugd z(A|E07(eGC4d+Gee4_oNa9i?>+X9&Y!NFZ_d+6_)i`#3CrN&dI1iAo13ZPwJEq)t~ z9t9(CH1u|qXH??z0`(8U7^pVo`@>Cxf{E5k-5Oo?^mF}}HgDzY=V!Z? zz0tZyG|Uh=M6<#VsPt00;jFnL0{9ezE3edoW14A|*Le4!CCpVv(gpKQI|xkqHuh*x z2!=T(3qQC~2T_f0y7rc2lh7yQ#P_&3qwVHold5B~KbLP|xGb{?(%>^#14!T@uTCgL zNu;K#TO%wDTGiN<*U8hDg$mGe)kxNLdd$%wlmGeLiErptNIKo49wM(nsog3y_H?bP ztr?TlJVfuH7kZzgFjMDBps-=TLF97H=P21rIaZr1*8s zlt{$)4@C_>8O@pEOq(x*OEeO76%0wcdalIiJRC_!OJZ}h+V>@yVJ7q+ixhrhRKE@k z%Z6NQzMIDR8OVTK43}n!KTo!+`J%{9ygE}p0TOpQ363**7kkZ=KcQw7KC#!8e0Sxi zX%ub99jqf2QJT;-PRezqZaGpL7P3Zgb0ZwuuURZr(^rpy z1;V!Y7y{`+uZ2b*1a8dsY*>qR7_2L`dC8D1{eNlu!(O{UL9ms7UA(o`C)y-G9ekHdBKK_SBI4Q{22-SjVQRpw9)%kEsM6LP2` zo>;(wpj0xCKX4P0T;#t{3AEXr5%p^6K94EBNWsDwdXv_D_BO%FyoJ1vW4w~>FC2FMdy(_Ae zh(^ZLWp%%46ZM55H~r_el)(hZMSDK-?Wy;IxSyv_+RS#N?V@`zE5>cdrpWvK>ELdE z0`>FgS84|5Y`K3c5a%FIF5B8^!O3qt!YBqm=v1fS@<8mP zZIr0%qxErjIDFSKH{jXFwmRRtf+}86;q94ZyR+_I5l&uK=)9FGPHYFJ39qO7@u4{F z-%*g=>l@jJwk3--wg3B74A=J`p0>s(1L#tvYLYps8iR!#ujW!G!na~~OSbG*2dPc# zIB>!I#aqu6OQi(Gh*-4Sr>;|d*ElPo40FVom!(vfFVOhHcFgY=t9mnSdTbkTB_(BE zlyG^#@Xk)ZHbZKTqj~f?r&)>9t_!cdy*btZT|}l%_z3O=P*Ymo012Od9L+v*I^~gt zX+~&L3Lu_3_;9s~Zc69|;Z)EIG5G328qPWdoWE?t7%MdvuY>d1@6nvbg01Wqz$hZP z;2vMZf$g;JVTYdKoj-?DcgNE&5L^Gc*3G6F5=6=Y2VQ z!ha%kEN5en3fSuFW)Gn$r#qsBmck@!_eCH|x0K)pUJ|;(oUp>A8IE0qI-t@s%jbud zZ-sW49&fZQw?kPKuuyYsQ#=Qd!WpaP-^K3w)Du@)n8BEJazz;4X6I!DQt~iKMir?N zhKT~C@ki~dsJxYO^ZJzWPiX2-^=78L{gE6_b4r@e#c$j^>8fZN;YLdlV!b|+lu5)J zg0Lw9z7F5!Q-CpD&5Qw=LR^j~4P@3l;xcnMve~AU8N{u383E86LI)61ZM&&zo*xVp zw@Rv%BsUE!gDq}Z^_B5l3O!|{gxmS|h`1a-`jLYNI|*<$h^2~tciwtCBXgw3OAMQzIBASZ|;v0dTY`>oEm z=Sv3W)IOwfA954ByYir zf0sCq!v&H78Hecn0okA1311EuOW70@R?9xM$L+<#v}WS`NEdMx?0!7e@OwJ)h15M7 znK8(=R?7fm*SO^^5cdu_h@^*TTF+N)|8qEuch13}WrCQ>9Gh?1LQGuyFxE3r-UV**Og(y7 zo)L##wq74&v+BIoq_LQc{VTaf9>-7LP&bt(WSD2X1bpmTEl688twvmc$RQzMn(zRB zm%8a{mkk?fyGlG`<^YkA_pVmfzw(7Nim7GbYlFRKsn)HFc;V{^n;~noOdG-72&#pi zb`S3waHgjZ#N4s?O{}jTavGnZQ_e1PCc>gF&h|ZT^HEWOQslK_T z@hf?+^b?y~r{Y;z_gJ(4M^g6WigX`7?T03?he4x8;=Z7!J1yYSGf|f-I4z2E|{R2b{w_7vQT+Ww4KA$mgHfo11ucyt)G1 zPMWT>dWj%qi~;RQj&kj7@9ig<368qR3)QX=Ncq3KEN0Iw_q6B0qiyZ(hx3ls>%b4a ziwk<29~qo&<&j93Qcr*F4a8aaOZj~1TPXf!B>nhh!J&&h`}`v-gHpcW$M!ifA0<}4 z9HAo#TnSelB`;H!@95C1aSZzHJz~gnb0^o3*LXjfuSLoMn zG$u9lJrWRp8xc_tD0jGZ5?Zrk$aXN%zlwW|bp&Bh^ z65EsUOM+j+z&(}I>SzZjzGsc3l(dKI-D~Wef4_|6vIFEXJSyuDo;(!zy0f;^Ixt8g ziY80SPY599)O=k7m4yIy4keoh@=Q8M65hvT?qFtt4zIU$+fS&Q7*>k;f!F-5gB1iuvPzM6aa!( zr3diZLs`u)MepunM=3taxJv8};n1p41JKU=uZaX$4)niGb@97Ma$xV#eKlvG8M0>4 z>g|-aPD%CJOPBCvm~S)vI+tv|Pe${7BNQ}~aPT5a=Rf&p^ zE>754dWf`b3xSeO>-kV+Odwe*i<7OH;22OXltxiA5)R?7Nd4rVr1ej|`LnGzPHpUr z@W%@rlQ(6J95RZ}rzsp85yLvQpE~7weJktZGeG~HkkXa2AAO17X%}8@H!UTkSK(R*~#!XAv9Whnuvknv{1EC8NhBOnfx_&Ql zzt$y*mu3$&jvSh}8_SI;M{5NmS) zq(;z)^4^Iz?O^)3Y;lBdg`8rctA_droaK0OIY%^3ILfyWAm~x#9mzn%@g$nn(Q7qw zw9!yb03_XTA)aGocl9`V12@$!&wW*5Id@e|^OHm&u`!%mR^|HMd2zN>mGxZyX9!lF zd~iCSC)*MVV3C3<=yVXmI#HyT#g~+1v;~ zN^BNBAT~W~9UELo%({ig!JyA_`W&B!|KZ>q`A2D9fKN0V;+1d49#MfeLASoyDBu6- z$^>S)mypgwZ9DPpEa)@{1n#-qu(6n^!tPJ*%Dp?ELk52P|hu)GKDTNW>>k$L%qA)epW5MFy?R_qrl+2etcyU%>1Ww9e~xhojd zKb7{!WDK3Z`2G6R#8ZhLwOXa?t2(o$Kore%mVAs`)oa(i1k?oWTapb;0^ji%XcmfBs+y{Ga`39(Z{_ z?rCzohgeo)81p?TOJ*T8NlFk$ve5(fDLY9RNJqj#hbD_4WdYW ztU~7LM((nqVJn=gBQX86dDKDT)wEq|N7f=-=6Pt=xuk1Ij`OPBM+P z3z_KH^GT_9eUWwKruL!CJg3<)M4pFJ;&b(7Y9Rg)8>7TqLqj!(I|mH4Lr z9deR4Xe6?sG*Bfv`4#HO#IOau(^^#OL%DMn9a@U6z8P?NU>B?1Ub-ZywK4PK+Cy5h z9-i_@R9klg5t&J7ckSpY{k94oi;jlfI};D*ng@66>aSv&a5)!xUSQU6e1ouyvbtpI z?5U(gB<44_*BD!2*@>A9b1U5D;Mo;fNQ28xt|ORv_w;7O9h~5VjX2u7#qD!%12Oi> zd8o1|yS&rxB8E#boG5_PLuajGfMg9ae-KPFXV7gqO;DSOFsD#T5)?tqs`vAc_YvY7H2z*xlY(GOY61}A@ZhmJF1 zBe*=j*E*0MpHnWMTLbXteDJi)`sAGe*A~#!HUu2K@iO*b?mIHC>c4o9%UQw;_LGC4 z*~dKsoR+AO<#a5)TEgLcOb`}|*S_ei6=b^IB3>PS+*JFx*w+Pa&$QNmJyHpr14XlS zmsv#f!fbSS0zsYLH@9-Fgfo0RpG)iOF+qTMEkGK>lU-UXBpu`o*=!-veQ$4XFHkJs zZAMMSXgE0gaXrnMWoMYkaj@%QbM3M7r3q-L!NN}r!eP?1T7M2A+%xhyqJhZftC2cf zWnB@OVVSl||D{7Ai(UK8pa*iy9kPgkh$xu<TNGLmGyNr&^8kC!}rfY(M{Rfo+8JC@tSjt0;g_xA82 zL0p%c=!B0#bw^d~f7zeJe`1_-fj{Hmc9jdK+BCnW3f7o+X; zBH8pm^7;1kD$Ttx@q0RXZ>ptv(%-8k7CRV0R+!$XQO;bW4`!YFK`@lgLANa+2}Kij zLwow1>!r}2XKL^&b4+Hr+wXedw+{_jLrHO{V6w4`wM3y&v;~f5zUjfjN#iOtk&<#E zTPmnR8bL83WC)>zaa)B2w*{tqPkrwxwJ*z9pJvW^6r}en!BT)cAifnNl>(?m& zE245dfvghiDXlNfkkv)8M{4S8yZT`eTU&y660|jpjokV=a_*3-nvE zP9mTCHPSP|cp2;PS$Z2GI9PMj1S3I0fuTYSX8btS9l1T6c=6mpoED<+{$|reEl$GU z_QQY6CY$LKTX&l=+4d!*sb~V2qt@c*h4cHr(9>^d#(NhR78x>7ogJjceBmSP?le)i zNZI@IJcJ{^VVCEAp!i;oW;$E<;&C`1h=)Sh%=e7Gikj1YMs40K&Aq7fj3c$?;az4w zGBn}+)tw|E1u@A)_3TGj?@pzs<+>ZQ_X4z-R#R+_s5NE=c(fIy@GGIL%zmjboa?-m#M^}SA8ULOY`aag@JF- zhan`Y%2pOA_>#b@+tqKPbwa>3`fKXf*#3>}lb3K*o2$iktXA%T67UrdX!MRQ{4_)I z_!z>+VY>QIR%5V};J1!c51Bz@j{340u{P^o^(J#f<5lFm{ zDtT!hGlv-v&-Yt#EONNaq|}{TS4Z1U{;$Ov#6he7w(y=5i=`qwdzH^I{oL=*kyui# z-)L=`dtzr(wR5)CqLsW6__DS|$g_q~U6TIeS4mNsbQpEI$JweiF;D(H^LIu5r@iDm z8d6boPed+1jz5_Y>fas!>=U%LQ{mIx%?J}BPVBL4a=2)__yGF9vu}@u*W9^=aC9CX zi-=#HhUpa(%-M3lD@8SR~qUd!Jz5~ zI66p$Aj~NwBXk@uMR`(XU~ItQwEcB4%ym{8??{Hn8S+jQ{-&9myK9twwm&TWnhjqv7TH#c$osQk{%bx0y>|%502>)sdbYc2&~oL`F|O25KPrkw ztX(C@f(B|f^kjb54;=l`&#^5(hjK~(Z~oBW&= zVv_=oMp*RD#M(m~ofEF_H_~Xe^N%d$;cyljV!{n{*9a4nw)QyQPcw8;=R@Vs6}qS& zr|rnK1Q|RjN1AuJPbm%iUi9=tX7us=+LERt_RKDf93;m;*zOA_)wOOoKIpy8WbAA= z4#UzVsM+%2Gwd-Rn25b26+p2R^9qMNDXFk#+M;~&0j2_^ZhcthxuX3`)iSqlEZI?_ zv)Yqyv72P`KzFR<-a`(#`4YLy`FH*n*p{QZYIhpR4H8n=j1H!)ztaq-ut!x}qZf+vQ^a7yhG# zp8g9u0YHeVGD6GN3qmsiFQ#aZ5#P1H`bGbf>s1E`Ep3Z2x;PHyOE}neeT~>*_vF1R zsLD&7gQnCe%}Abf6Jsv-FIcNVb7I7bKx_^vA#SV{z{55QLyb_*OMnSgL`rso$xnl0 zS1nK{KED$7C=maRcM#vkVzjTE?mWaFAhoSB!R6Sgm@6k-1%?A5_FyU!Qik<@brqh~ zR-bZC?4zq!&?lz{5vwpfQ6|cn9#^s(`a^!?G(fRZ_y~DmSVAAWEvM{*M~*DmbV~^Z zFc`yhFxsm$8;tObg})?57Jfc23l_?!6Jya6&>YD*;o8ocO%@}mR z!J$IhHi$L~hGqsIk7_^zgzrfGR6 zvOr}4{5E%rXSeA@VfC7^pI{amU{9?l2Ced0gsr0w$_;ojb#sVt+7XXL&~v~$@Pkdz z<21OY=M^O{;1M^KHF3*48uyTA>UZ3)-bQiuu+^Y-4=yU1%X1Qlqck3YvCl9=ZY3n+=>p)}E<&`Yik;ua|;(N2m#dM(N2c!_j=}H=} zJkWpxLXVNVq+oD7x75}_oKPuSz;`4@5lAbzaAM)6s?y+ zdv;H8u12jz_YdHbicFC1lZeDFdS53qD0nb)G?@+rN!Qe6+Wg-bmY0M1v!&}V(eJi! zLOi%V5|wd5HxNrVCnFKNx4;F@?3Ce*2A9vtUTzESlRxHVW2(&ZKfa~?9FrAor zad0P|upu1oNyH{JUf9p!5H1$d!UFY7oj*c2nboE!<>rf*K=)g|;g6_1A3sa(b9deW ztZBBsq%r(<4>U-<5$8T1j2^lW_8UA|S!hRGj-WstfgK9eR1-ul67>guoY{)*we698 zI7ujpPx5`Voz@TY6+qg+NIS`a|CCTgPhZx292D&6byvR${^+h4t^o`E6S(b|Tfui0 zZ!p0V0uux}EYR(?zLeHLd@p4cx^d(8BG`%TcYHvPV-_vb8CD^|{6BS`X`=Y5o$o~W zwzS&`uX_%<$xsPlfCJeBhpw4AQ_IGSnJ=(ULkKXge-b1bzPs<>Xsb1$j1Ns_2@#>X zFJAjkE4lUCz0Wz?Xv7x@5%uPNiW9qMC+;%hb7OnO{l$&w$o*tC=4_e;lahxE$FUR5 z4rZ?8D>0=sdGwdZeiidI`fRM_-1Q-1v}Fc5Kd0{7*kCwU{j1su^~We*0!Kk_70TY3 zL6y$5F8rZ znB6&V_T8=(O@51LRBL8=(NW|S#Hl0w{Y5p%bOyfsMkJKE&wC8(FpY@>JB#LGAV@- zdfP+j7;Ki?kbd$7fp8dL1VoJ|=S*Rhe zO{g9t-DG+>aB?nfN>%kZm<3=W`j>b7`SvU${6+;oV&@H6N>u)9KuXQzK;>^GeBMg@ z;+*T56w;Xbb1b!`Vm`{9+UD4UAjW^Fe1`AEc2ly=8B1FDOHtIZ{z_!|S5RwYtDc0Z z8B`#tepHYWy25-Xdmk)Gswn~3QWy{cDm0;~kTX;%d&^4kqJfitZ-3TpqWxp@icx39 zlFF(bo|{8dEEc4?^NIQ2aUo1Ly4bruxcnRbnJjvx)?Nc%*_Uaj+z-_`lzGfK&5Rde z%QAG3d-s_5r~s#yJU)eqY*tE&^UwECff}#4M{lw{fC0K_oO3d5#T25le&6ciKL7b& zlGz!2={ecm?}T{zmj>A`R-SG*J&_orfvYR(GNY<8o0T+>7A+qhM$M|^?xcfaV<=ef z34m=xcC54Moop4@%U}8gYY0{}hCnkok}6tN-R#)_xh^~VmBEPN-+c1rpq}&kZQ2Jp zZnVP5A&R&H7t%Fy6uZan_qJ@BTDK$06t)AcE8!OIHk{gQ7Dvu$vY+jz-lp~#G%jyGUc}gL@5+)7wz;PH3%%p8sFf49#T8>neyucEf@H-W zf8jlYFYPI|XOOU}oQL-f_n&0hl3y}Vb~>qQ1z@skz&ysQwzgd}z!2&jR~7r0Cy4$C zLmZtn^;Uaf0v=$64`)FP=p8vIL;bu(5<@1oiEPjRIed_`!(FW9ERWkd={b;fdZ6cZ zpUs_UP{7_#ZXuEUDSXXl7IPvP7P(U!S~tQQvP0MXhmmm##Ax(WRy>EGU78&P?%cP1 z9lJlkvSl|1(+@vMJ_GvxTRT}&LM{Du}737_>4z5XD!={N$Ik~vJ$M95tG4=Q<`%l;&)MR>omI$+zwU@jA&r%M6on< z;+X0_#LRY|eYo0C3uU1BSG2-{wQky|q(K3b#k5Xnr(BVa1}47TZC%CsM2!^Y6THz^ zciY*(T%c6>JrcO(1Eqe9osnr71?MN;DI%z@5teE6wjym*$ZSry=XF+}@*8N`B=oi+ zk}Fk9PCarsNn0xiLn|WV20ERCFLoOI!tVNuERXHhbV*$d%!-!S1JWI|<}sJJ+1 zR(^MUti3Gb?bMB`@Y}p#ntO7adX#{o|Km@J?`hsl66sWe6MCfmr!)Zqx+KsAdfK-r z@`l#ojkfOQ-HkX_R-8);ON&x!M$;^fC_CXK<{jlUo$sk13TR2H3Y{im{bqq0b0V*je9@5nPTe=L?ux?XjeqcT+E?*VJdK6n@I17z&{-iW_jFpG8ltMF- zQPWZG$!kQoE^i0%pBeIe-fpiy0ug;zyyTqMXd{6>I_Tpgeml5!Pu{;Huy3U_3b6Vq zbaM)nClrHmTl_ffIc&_1HLYeQBv1HQp)0Bdmbu4L@D~?v8lal>5UD3d1F3xoPPnM4 zYwg2Oux4yC;s{`G;$=ND`5Zt0E2NPtYO|+a8+%XToYSIqgni>cInC%D5%;ENq>f|^ zg~YbP%8aTcuQD}&Gt{glrlUR*6ksn(t5i*$67 z9cqp>o-p_Hz~(R?zt=v!$IG`C)w-YMDUR`e1F(*>OqpN5wcOwAnGH4}AIni{-FL2N zqcGb9+LpXci$Ul3-rY(N!S|qyIg7QmD_x^<)Iv79wdT5kz0ni@*Xxziyn_6I0mRP6 z>fW~8SO$#}H~gnCFXvV6>4TXs{JjlMjdnX7B+A_@`pajfNXSsj?l#t04$H<3s5tT+ z_99{q_9(>d?_3cflCmI3e9n$G>+;Rs_B<3z*{Ydb)|MwLSnT~O-iKOeC6SF=j=5q^&;2^<|8%Q@zG%tikqHfEhpI&^Veyo&0zQ6=H zhV7}XwUE2$xDZ7l5&XUeafvLGg_C%s>%Q)2;jTnu;3m_lEcrFo4s?SGP~CU#HPO(r zLc-b?%PQ0Ne>am=Rw-=%)&d^(BdcW8QMHoi_Wk|r9kG|;dbELFA)X9kA@Aec(t{@y zyMzzo7!U&g4v60bB^s%guzhc}pIz#Qd|&9Vua;sjx_~YK%R41dk|+>J;^|dKfI`fV z!S{OK;?uPgyeL*2N0;Z-uej0v7j3Hur#A9>?I+78ol8&4eFf9~qmy3P5eOQx7n#7R z&kMj@4{i=pD?STU>zvjpHNG~1_s&O^eGrFsdcLT6kfw%%`yFTsfGbW(4Q|*g13!D<8$|u`Zym9& z40JNk8HKXp847Rh5z++W{2VUj+7~?92=R7j+L1wGkFyR9+b{FhWmeCs&rF)yD=wNS z5HwNry-aGPhaRQ^oN^N2N4EW)QlCnl{B=Alp@k)@{#7_vMnV8plv~PQyP+A2aV&a9 z3H%h%y}?oGNg#877PYe*c7Gg0u`6?X7Hr}#sF?W(p_S~Jyq3Kiu$Kf9$UIzx?)WPV z{`pzds`e%*PvDHnrygHSS%E(=7<;G}wbP}@F0n2*3gC<(VtG$Y3dDYUljb#-^EwUU ztTHtdD{m-09BB7-!!#(+}cZa1jE> zyvqL&vx)k?uke$)pAHg0DbwZx6+3GCYALeQpYa_*%=iG0vOlyLj>Adu*>rtSMeZ+j zRPmTzr1i9$rtl$8=`F2@KX?%3`J_lRluAStipG&F$(@scRzuBdS|EgZQnncsHsxtV z)gGEFI_&*2aF!s?b|=6YUig$3zaaa>{_DC1gmi720oqpLU$&%rd&s;UGRp^!!$O^xv>1*f_t{bg_Gb48Oz>>W7{~ z=8Q>#-fuHigUcR&$i&xysN;;#=^~c-CF7NtfZQqA(I6HU&T@z0ELgHA#c`+2hw8zH z>Q_Y8_FY00Qc;=e#JPY`dq9FJP7EJBZ}Hs%YF|)+@(6k(wVx$bPb>bx+ZlQUcDnRy zY#)bMw?vDz9eS22g@bMI9+7B=1r=#L=u9(W#QxWkoon5Jp|5xMB>ctrX21yx+g@$k zwr0~n7`oO+^SufD1uQOG^uIiqtWm6}HMfq7_421o5l8WmE58r~7>PqZt2K%fAwS*^~%&(+PPAU`;x zMyo`;RbeNgL;cIH`Zu{@2c{;9!=*`W4O$&H$=bRn65{`@W?@dpKmR>yHn}|6yr1yp zq(^a7#2J_5vKE;hS(;w;3Uc%;wh>wfAJB#?N`cBBe`Xk zqWV6!OuR0LgDx{tvhh@MzF_eE<)Y>Y!u+TYLv(N-x^Eymk`vv#?XV$uCf4z| zyd+c$2k(TKQiLqi^S zlUtN#)%f`;y)Na4wtlb)6<}AWG&dX?O=MNO-?}@%M^?m%BOQ5)p;EsM%4otcYSG;w z;nF=3I|;v)e6nE4MG7+~Y8Ri2K9&TqXR`Mf%IyqWDgfqCmr#A2pL%ak_7(Hqv_InK zHxi?${5L9u=Qb<0cAq^M(m$OT^b-Cy^rCMru(&L`q?=~Da&|xxG%bLz#*3d2=GB)Twj3(J`+*zbTIH$DR z@$)*NdN-~0mw7tBb~Z7c{QANd5$=HClq~*{B9(+&k}&syJ(G>0yvQv2CpykbcX?v- z$WxNAdNh@4VgTxCj5D;L^|P6LmSAJYDAiH2w&C2N2O-7PKg;sLG?Ot5>*?BRd^%3e zN(TvdCG-j11Q~7%Iqt?vlTjw5GczGTQ*_o#YFsFZgUNRwhOE5-7GWV`6FIiZAk9X& zI}f6gsQ{Ou#Wxo~7!X-fki$9*dq5zKo2JuEP;Uv-v66MgczJ9*w}Q9EUH?!^PIKyl zRv_>#9}3&^JbI4xZSYQ3UPnyegmM@&E`!I%%;?7t+1Z)&1yR*E>fd_F99`047JbLk z+%K7n4?nrHH)w~WlRugR99V$FKgGC{OVer3lG;cTZ1GvPRNdDghGJ(?T~zse7k3)b zOb&RSBXK#{F}d;C6D9Rk>0sR?V6GdKfx^#p?*4cZ0Isq2ho2i`?1-a=XcST~Jqyxk z6MgX1ka(NS6ML(X=x{u}^cLwCZ(0+BuwKhdm8xQkK!$$>B9}w!Kdw)CRY2Y%jYl%$ zyfey}?pv-sASxC*Yo)5%4Vjjs`__L z+a3GA5@2p#!U}q{taxZ)ravc3tm-W+CbM%^H{tjp@Qo^QOpFL4T*Y+}b;izxhL$Xb zex_9p26j0cj2YVPmF3c_Xb@w>9*PG|Bcj$cWR#MXVAC)I5T zl3YfYmhau^u-L6^m{MoD@TwJBSJ!FZzn1BK+2vmf5EkPIms(EE@3KkY{onC-m=QH=5OEagPI!_oDk@ z6MQ0AW7`4zsQRpH_!9Z>bEd$kC*bjfrKK$H?AN}w zD3O+-JI=k0xow3b;YE#M+{2(h3GUP*%Jk-|%EZfMvcbp6==i)Sjuz&6=(PTwk)EIKIYTBw18q;0a2L^5gl(4W7eA0DZ zeSXYouKC^FXyyj(1x6nMhZ~lk2#JU;UmHFonO8$0jLE`}Z3>suaAW#VHqjTDo{o3G z<8=diVgvx_%WWJhADZwDmcwPiD%*8y0~d-E+>oSPf_M95pbJRLP*UT z4OrC3MOlr-b5Kus5@UF{{&J6(jk6)QVOnBy9PTN}%8DOy1ot@B+yR4wG}Lza8IM{Z zH$`gP332dMI+*`DA&sn0pp+!$jgE&xO^i$_lKtGbn()ZW5#>-VXm;Rb0B=gxfICix zU@f?xGG`zqJ1vjx4R7X!lO~25i!g3zS7BoJUSuJh@c$fPO}Mh3N|j7g3$*EB*L^- z3(y8fOnih1PNX*>RQ$uVieVXWhQ}@Vx~lOfGw7pZM|?ri*Zw+~(!t+~iz(wQS+9zpl)iiqmsV zPnN6K>5pv&jwiE(9P!3Fqud0D2~CLZsO>8V&oBOr%Qn5Gn-_OG5x|F)&MA6RC%cK7 zXkTUguEmo4&VG|HUWsNPC^XIn8-W2^rxX`v||IKglM$-HO8saOWkxD>Iu zKC8tG5-oGLfuAHXcUVqme3bsl&&yZ-VpAcG94KfQkuN2rQ6fK3)&|aWZyTTN*03TstyT2Ykv6PA7Cy4&)c7Z9QW34&`%?OHRGM87a zu~v6v=7%F=JC0sE_eQ+vzNwx-7Vx}XSLQLQ;6);5^Hw-ckTndiSv&H^-}y3Njd;|q&4SBtNAN`bD(G5!6Y+C7nvw4#Wh0;hD6?wub~cSMM6zN zkllpR;`(bj!c8WME{v7TX{Ll8^!-g5L@=G8`p8LrU!B<+chbciNvltLhrS@|q89Sx zIudrmialhzy7@I+MW0j;6nQiQbnDF!S-bXS? zY_01`Sr)!m_jRI+%G~|?5h0s3Q?3Ouk#Ql3ggfAK{K17)CKbjtpv>wfx0$8=Ec^3F6^#FtuEjBu~gyp*d16{@51wQmL4fOYBq3$UEk?y@sQG+EbviO z*b7)i&u|p_OHy{bXnuO&GSL*m8gn`^dXIqAHbO7jnk#!v!>ya91O8F-A|VZW}61#3Qk_RIZnPV*g&Om%uN)J7>ey||J7g1p24qSgQ*a+Z7AO6 z9R)G{P`Vn`Z1EOCipR-s+Hyt)*C5keO-}5Dyfk#9-h>=X=R#zoY9?X9Te z9n5k*a&rVq!SI35%<}zY>{4HNqhN@2Gj_aaiZ_kv>HR?(iY(Oo>|&!Rs{u7gdZ~9| z)MAJN)H{QF_=t)Zgw3G!jZLHl_H8l!NZj^!8KwmhXJ2kafDFjL4 zx_Z}+dd~-hDPf;aVfSncJ|~6N-zz^Cj3NknGW5Y8UF%Y^e2`j{t z*53Enx+ywlWysBVk-Jp?qe@O2R`6yOPxfAXbV@J9w!azrpH(Vc8tq zsWF$m=ni}pwYE;mUTS~g`15|uG^uV^Y?=9B+053%{2Pf~#?;H*imlC{LffyhGvECI zQ@bHS+d=g@ftkvRaU^J!FSTUj$S?&e%%LLJ(}gJKW0UJ5)Ul~u(~Z)Ajs?Q==E2^- z!p(I#)7r!PkSDwO6Tfvg@%_(o3o&y%z`AJ|-l~t#X*i=o#z8P@jKBeYCg{&+YyZQm z;LYbBTJpn#OB~Fx0WS_vMP)Q=^@7)9)99-u<7|B;* zue8(Dz`o?}DW6+b%9wg_i4l0v0u-d}T0qA%Ps;d+T-0!upJsY@vE4d>Re36x&Nd=z zP6RFKQLPn(|vD~dMW;Gr@c&73ph6y#`uQyO|05^CzWb)j^rvP>oq{^UnA=v}fpuE{ft^%MOnIZP_r1rvCA{+KPY^t+?l zWy0d=;ZU&q`xJk<8nc`0RNK9h9*oc9p|9cjGy1^jex!ZRv82)ctTdY_h3Mk@``98;b! zTvJ=zCpP~Oss~0NRcGkiVH6PRi(o90dq3;%et~#ZL(2o_+j-+Y&mM==Bk=8&h(Aj1 zhGS`_NgYOkyPi`5ok5s<;H>zwhFZJ`wB_gr|GVnOMii(h`vZkUlrWbVip2cDaIQsS zo)zV_lyo(7lJ8I!`c&tEpLO(k*<|Xi{qJZ<*pS%ggKPrgm)G7wEp}5M@-{h9QCSFa)z!)$Ga?i%IEtRoKQ8O( zIcl9eSo0~1POGBY?ti0}y`gp@OXL#%xazuZ6NDYHUtg+DPos&^|9$R^@u%3bqTABW z)qw&bcFPRij3*w~%Xb5vP@6X~l+-K1bFf?PoLR2Mog?WQ)n2z-)^R!(fb|5pRbHDC zZt|bEA27N$vBOT@B6QBTUj1%cThH;fEGRF32kkoip(S0t^>xqI_w`Y2!ud*^sB7;) z4Rz)2O8+H5I1s@-&l>y6^83a3to!u94JgPytIcRr?`_BQK|u$oG|_K2GVe7vuldTq zM0v4+nszj0dlqG~J2Q<`iiAO{u2SGG5a#Ki*mt)(FjhiT6vV)H>NcKzkBJq|)%hBz z{};85&fodme*Kitd>oQvFi<<7Io3{4t;W!p5qyz58IK+F6WvpuK`gd?1<8nVc7)11 z=;KIVoT1dGi^36q0SQOubORC|(RVX&4Q#zJ{opOD;MUEP2)s=OeKsVbQ);(R+Omfe6D|OwwCWE#c_V$(%s0d z-DqB?$u~SXrv->DW;CY(8m$CFD&z(+TTrm%nrbTq+W>t*pq%#%auZ7tc6acG1p}ud6oa$TDwKL~i`D z&q_)c_o~LR8@2y2o@T|}Qxrv*(&SnE{O4yaR#{7sJ1D&MWTCW*ii|R^kOa%_oA(O> z#M@E1rXIjALzw87uxXBjt9skLf$r@WYdStFpcCu2%gs%;7kjj1H4@?ht`;SaHmf}R zAvw9tEzCUu2Y8uS4T*?z>PlR23D?o;POA>AF&?U%kqRKcKRNO)!H11$oXJ#{wi!r7 z`#OK5%yn8{P<_fp%5!hpOR7(1)L+^5t67Qgkmxm{AmW#LR^Ke)d1mADFYFGGd9<4Q z=a=8517_`lyncuz-fv0U1$Aem8z?;$nnD;hJa)#<^ykkYt(J@6-Sra)G-#qdHj6r2fB$$*xE0*U zSO1}mjqud6rrfIt%)sMJ+XsV49MVHEm|x*(>vX(`_l$tn*NI31rRs)`cbqE9kZ&5k zd^(+d+xFZ2&0thU7&LCD&P`v%2nj~(t#HnJ`jRn=*7xhTJ8HwPiecwIC@aZII*c-=H926`fu9v`EEy6_f@26qeGDcz2IZ3$Ek zkKxSj2hS;lLsspSwT-2fDZ}jiwQ098<{}VcD=fW@os1ezmfYgSbCTzff=|B9TZZG> z(+*z|X<)Y0Xh{+o=$oJb*Nsk}lGNTOzob&~r8~_DP_z5CRPt5EdT0AQJe*Yw z!0Thh8vgFvBMUjh!`l6#j+hX)Of&c@N8jT0&y2a-AIDr;ZkVzQgOTpjRGfI0V(5<33Na!&&&_<5yh|zGB}GgS%5+egv%FWbT9Jo3!kT2y`}-^XftyiQj((V~%O;WM zFYh`Yi18^Mi_|?vA;M09q%HbP`6Jc04M6d5xSaKAy=ls)n{c zcy?MN4w1O(j15@zJl$ViR;}6o5kY|Nf7U2jD5$4dgMc6 z_Adj1LS6o%Y_ID2J~8ayN13hW;WEk0cU@B>lz>qo4?JGXSJ?BODDK~MIbFAx?w(sQ zvW3WJprHLLY%KphPjQDzF#MOk=`GU0psI{L1JVRJ1Kh{x2ITlH(3AEoEM6<@&QZxi zhFB|7bZ4H%0vn924`H`2sVDY%2lZJbXLxuES6fW;Rqn;>~x*Wvwqjm@cEZ)fMN0kRg^J>C!cj|l5CbWPi!Sw8vxW)-GN1R z7HObs{g#l>Tv_}i{(zHxApK@{lfJUU2qAsyP*R1S>`M3`X4sf$2U!#Y@;HZdC!c9- zoK&32skl;7o&sl`)rgMYIN4h~vvOK~lffgW@y_IlL^T;ui5hLx70y7e{0uWgonM%AvvDJZy(1{*Ycf5Bq? zHV)0|6pY2&tm*@=Dw`oiC0i<{?Y%cAHDk}FkZL7kqlaB7d9r=beV|eb(Xgx6@f_TZ zCXnX4TRwF=e?DGq3UT^$HRK|ZAvNaA9HPM%VJ1rPRbKg$^Tavn#mtBw3??ycKiqL( z;2f!`sew@*8MEZB(j_}aQT*bc#@lj{zGxT*7r@o{DixKuIT|Czd2h{QKaGDq%y|8^ zQQr<_=J!UMC)rz@N_%JsJrqKK3KOvYta~@%jc!f%p@~AH)NcaY6wkRXTI+cea>5iy#EQmdLp5C4+AJHMLzSt#r;br1g7Bfl&VUF?UzK{yxlK=$SV1RF zTJ_3#cykp=4t$8a@39;S1c#Px>FY6M!7S{MLUkH(JHQ4h1cIrALQ&5q{GCTf)f8DJ zrVzGL5>kjE+`B|Dq9j-miQe1(rQ>4tT88g({IqpATMi!*ZG*Yc{t@@h6DIdVku?m! zWpCzaA@Yo^5b<`bwVd7UA^dfup+akyzWsovG{HT5B5oFYFO{Vs%*M$gNs`=(88qjG zlf@@XXpCw{mcx_A7Nd-NEEM;}8AS=v(Q10TPfE2}vC?kRyATA%j?PnJKnn=^!s> zcyVEr+KL+s`&;`XZ7YuKPo>H|qtls*z4Jq@pJZM}XLw2R8NJc? ztJpvKj_a@+#>a!NL}0JW#gZ%`X0XI#W80%gmWnXs;?K$&v!Ye}^;8K|+OkuEa|q7)u#ftWtU@B6Nx%+g(r}2m zRP3mZV{O~}f7DJI4(rl##u{pb>#6QTJeJ+5F3>=RVQTAy7S01Q<7ve>;+-(sny2?2SOt^)|d}6X@0n*-e4w zyG=zhZ#Amc(=PjVziEG(mA$)?=RD>BuNXX_`(9HJRK*-eLXzn0hkRdlg8>|P2_0ovin^8;PpF#riwTJ`2|l>4`QCA_o^a;3(#J@0YbjZ z>$z;kzydAiq4R2iPS?u;E@<;y$8=-x;Gl$#&x%QF>KtLSMw;i?qo#;(AjYm9 zB|2s5aG=Cps8m4#5xv8*rE)zBH>A|n(hoiRXm|M=nt|L?#KQ6Aw7gw|9E7fn42QWt zhXc8KXLqDby>o=E&=(FF@Z(K;IOpujx^Z4_;hNUGxQJ#tC7AU#mPJ}Logib`#0CB(nLvet}wHu?; z>Zpl4hNBEJ#yXIG77*(tdwLdhHQL$B!azz5Hk(|cj6B%Qcbrn)iKq0cwwkT8>E-jm zEQ-9uDFX(TE)Fb)8<$a32uz~W1-KtCdlY8$6MX0U6Y;cuoe1Mv4EguZN;#bGLbIJZ!7sR|Gtmf)V!nu@jW%UTWu3E20fjRqrZ5Wp?TjI}bn}&MCq!5p zlqCs_Isucqy``2XF+Vz72mJgg;;12%1Bv6anul+1u4a+eBxDI|3`yj9jo})mCi=~7 zQtoJi?`wDQ57abQya#;p#6OBSSW+Y)AJftFu{{)hgawB>AlYyh@eDKLTK3k8pHrl! zMpL5DO;@r-ck)vp;okPPL%y!RE_>cx&sB*@$N`#MYgf&`OjPc3$K3`~_G&cF3Mj_o zQyW#b%A{w;rn7>0iU|2NqvElwzJm`SltTG2*QJSn##$VQ`lbwf(Fne0TKPgjU#{&q z-5DkQ1m)hhmL=mjm5X7r5$ls#V@!rmTyj}_ghrvR;$6Ry6N8q>uu6jkzcAj+S%6z^ zQ>}lCNFna=$t2}Amch|2id_t}(|TPW102udH$}jQUMyWtnMObHvA9p_{S*hQnhWci z77F*QzM-W-Twqo+1HTE_XV#Y#ZV+rcY(P7&z0Y`nK%Q`~5u<}N_;3N=hus{zWy8=T zmws(n;O2ORRxp7jof6Te9gD~^Y4`9fL+We;UW6!LNvG}>pyOebZb8d{;nxiV9$$$s zp%Z+7Z`xu#;|CH89!si~LZJJ=^#CGvlJ6BeU19ZG8SqIL5uL z|6J7#Tl7$D%nsM?Us6u>J1-5sb9Tn9YVM?h{p<=t9m2#PgUW5?y+lCpTueGea?&T;uOF zBH*G>oBfvCa*>R9oQL$F=>3pQ#|-7?I8C|@ku7rT@3?ki+ze=liK)F__Vjv8q;$!Q z!p_b~&4d-29q+!=s(roey}#S);Jo;?i@pGLROse5?bn z6UISn45M+`GhR=YV;p~?0hKxTby>+KWYXwxPqQ`$p<0sU!l6Jk1*7DWoV2u9V0%MS zq`w#??b4{#jjM2OE+Sz?Jo_*uYY0J$u}@F1^oH=<>tmior69Ai zG^HGhOq|K5Fv=P&x|k)gl4&@Z`= z?bTpFNy?I^c_h$AhM)o2k-``tH=W1MI7G!~}c zMyk2?jt9fEKVMqNd0JEHc?2(IGw!w4puy;W&g{6YMyn!*^|bnsFW7|ey{hU9M9IiI zi{uzzU0>2te1|aA1~R|&C4(!ZXk&0;*!^eea}R;dFz2^Uji5eEfE)@}UnqM*Jr5xa z!I~cYK~iE*BJcxPjtgX7%C@TlXzGb^Bndhwh0yp+JZ?d}}9VDPEF^Q~pS#Y?kT@{gi?+!0ss@sGHqg!R`s@Vd67u4NasJi&IJ`ZljzJ@DJ zj)Jl34Zr7&NG!?5bb~B4&WF87g%BMf7E#f9WN5`+sYV0BhYuf0lQ}{H5=TzC@Ge@; zaPU?@8sE{)8Ll76vG#h|FwlzZPd8!>AoIHMQdHNNAtytUSCv+AYRm*&lSY%nf|aS zqZ<0I{e|U>%4(A}#>Y~bn#kV|UAm=<`Iv>#7!A8oU{EEKOfQWM!v1wO1?8|k+Rg#3 z*tZsUOzmxad)%V>7u`^9M?AxcbXq9eI#R}NoG$xaB|G?|mbZ*&p%8-OtQmofG*>q5 z-abAvi|fMYm}82rOxstV3u(FZ+Q?$9NI|+3P!F;sAn2i0hQ_MV_bb6@HHdSIU1*Af z8{(B`^05UC_d|i_ACjY$I-*wB(*Ti{+n~MGzRGi~5gbCojOxa6!u=25tH0jAYf)H~ z>8eE_K{*kF~g^KCKn|WbZi41p7V+t zUP&(pPpfu|iEQVus`vpu{g_0zIddQvQuxNw4N2h-{{XnM`#xp+8(HfiswjU9H)4z7R0}X#)z}R974vFz9flu`%8AmKRSEjZGQFVq?=v@ z>$~_+;#>812s)nRx4PBtJKk$mb{i9?wX`sl4aI#>4WN)N$H(}XaV`C^&9zs~+ zAl*4rX$NG_68VHbROu?{4}~WgmdaA~hL)3)=#qE-N=gStKY)Djz}$kE^?>|X5pvmZ zq!l=TjWDH;^LVcyEG3lDUS@^^1ZeL7mj1B3cx5<1#XPC z*dLNSt*A8`aL}`GJpCFBVvb$oK_eVmFBVTl4s;uI!Q|roiNO_RLKtGL*Be6+PrRu` zLKkYlv%kVd$GMh6Z0cMrjtpk{6p1UA-FZ0mNrq9fw@d1QGi>w-Dmme`yep<@rV1n_ ztIF|O4RX=u)uOK5?LMV?Zp^9csa{Mf5`+%%`o0$hOsFLCX!o~=_-gCJcpz@254~GgIDSxqNAMRbb)!^!<1;vLUxY9QvL0l*c*Z#YVOjpUZQ=l6Otpot zA{*%c60-kX!y#?@cdrO_rc-|{+5SbcDfxMMFdZH@y*`iUvEkU%9^8ONw$%o|xpy$s zMAlhJ#5I}gKM54?=RfWK%CFI!oisDJIf##fb!787U;(pKk1Z|+AneP?@x&N>3|Tw( zMo6GKk1(c%!LpMQ(fHB{ILx+psDlT1|4OvP9}yh1wAeP0XS6;p#Ik@AmUoc2+fX*! zI#!z2R9pHje1|vjB2t-9r+xrBG8ceadpOw|WhHiC5KpOASq~VXqOgqkC?7$l)u!RZ zASSA--_I-GOGW}S1P0cc7$=z5&RLV(hEvX(V2jjV84u$PDw;lmWA+oR$n95-ImY=a z0(}B5#}$`(e#M(}Fb>6D0{uGg`-zd*CkI*wHN%Q}OaDZ7Pc#XJ4ob{*h4>{bNIYAX zq6Jaw<;}k*XjEkhpg@mfMH7O461ygBXJqs1z!RI9*ugz?{J`!IR{CaWX}!EXs9^ z;tB%1VyHjDU}fhxtnhH_l3Jke^qf)DD5{WBn{>>MB;#xre==B6n$`+MnuDZAu5#b* zrwU#%5egUimltJ{rn+73?sVX%m;#$8VQ3-*T84Gq@8(x#sC8btNyJ#Y^l^3|(r%U+ zG4IC@y;BI?O6U@zh^L5m&}EtjQgNDNTo9m`&~%QKP?ILnQU`%!;^~>n5Q)nHv~#Q9 zh#3F|D_FoB<_4mPiT%Jt+XT?k(Os_BO`UjSgJ!OeH;9Y|qx_J-MBKD$7W*J|e}EOIx%=Nk-Pomlq!_;GQwN2HP9S0|BhIGyIE$Ul5q4zTb_ zArB2vG{t&T1uN}b4Pj*4zn&It>x`#$h8?JKyqA)++Y$;|2djEYHXkw2cE8egq>sr{&23$R}aifcUC ziXTpv*2J~4{3J&wB+y^faTCov#e-IfMc`ieRfB0V1a&099yK-Y_{;Izkh$5H#PJkA z{mOBsNjxT=YK+((A*D65VWxEP(~lLuakV(-2^vk*s*lP#F2vAAx5>rGo78r5xF;BM#C?Ki_s&A;Zhp!K0fBsBfv zy&fnaisWEb^pv-~aZk^7oPCH#7Cc6^iQhsnl7Vt!=}hI&M+9r_tU#t^@|AR@W%ptt z&vNMp*K-u>#p&h~g74ifsr`MD`VKUv$Zn75-+0(RAECCWF@FEE4{uekn6&_{J2*J# zOzJM2Yk%?BkMWt`%}Lwq;2*-e-v+b@yZE$?+aw>{$Ci0Hv7ubL3agnVOxNO&mC_mQ27U(Cl zU4r8<&=BLME1Bdpu~ciN*%uX2P-RpxBzxaI_P1IYCkR@#o>7nH*Et+D-7hyKJN1DA zHAs8xv>lMNLktMBf}^P`qQqEYR9XC~w5%>6p&|ls0l+LJ(t`t?VX!1Ot*oTdHz}o< z`bm*fkno664A8;8DOpVCLs7 zOWo1uMRM4++CoX)ap2M~vv1C{R>*dy)~Y$+8WL4TuasUHV}e*e$f_3c_C|MiVRb zZ8RU_%#J>c4-I&wUtXB*Q>Ia?aNu%k3&(4GmBJ#y%>AIz8&a90EmH;zpU&TDGLNt_ z(H>^IxB5KxAora1o83LhckXlU$F(j2`tV?DSzsY2EDRf)m^OydulQ=C)%D3t`{K>w z6}#J+K~roqeA81)5Pute7G=P4J8Dx>%18g8YI}hOmpxH(h0k)(a2uFC$$$%4L_%31 zu%xVUw;7MjA&1!dZ>c5)a^z4o)h8#iBw|#Ac^1@gnsT}^Pu8guG5)vtbq%!rOi%)y z{WN`pp~`y2TGjg)jvh*bOzfvg_O`MoffTd)Pp@P*G$CnAqmu$!+}GNg^3y&;rOyOH&NcKd(Ef{W|v73qp<r$>99(O^)^=aH!Bi`Tm!^}Z$%*1jVz=rKCwaV;(iYdL%lEY=`KHNJ>X618BQF&1969TI60d0*mIQ&w+!4a&B zT>M0fWMJ0?8%3lR6;2_`WF>?dff7*8sco!f5(kRSP02g>1Tt8yoNcg6h67Deyq&ex z15YSg;7sY;s7Ue$lFd=W!{38P1#$-nwMIr((rA z2}Ppu8$;G)1&U+IY4=C)|Ah_y^;8>obvyjO8 zHJXP@Dfi?%VM!6B9yeLE8u!|(nH8^OfT-y%K}r^N8~w8k{^hVxl#$OO9$F~7prJDv zO{o3K!?!V@NM2n1%29?Co4KcV=g0h+LYs+1NF(OxapO%l#Ka`a?k>-BH*xn*zd5u- zgEe*&UJ}3t!{3$?rc*{|_80(%H)l#Oc}z9gUR!-uElIBJyC%uu>*9&@P+8}G#Ob)W zcc>;;STaqBYGR?Ql~XpSH8heu(Z!Jo(tp-NYc!X7#qv6whH2ir#%$iHQ0BU?7Czc+ zQ<{yI)8-&rG2Cr%w@&A-T1Z#G#h=Aj+`JLqXa=dtIeqZne`4u) zAy|e-ttG6}q2&Rat|w?*gy~o=t2yIl^xm#%b^&X-SX&{bJ z1&zgQM`N6muw+Z}FK`D}j=UGyaiBZ0_G0ft+7i!b!Pw-GgPK6BoDs>OX@c@m>SVK3 zZFmy&?4Ogtxw`zRRxGBTUr;bggT5G!c#apLB9ebB@Y1x~eY%A$is3%#lhlN;um=PA z$iPL>38g$_tX-OFcUI88FcAlM6M;lxZY@=hy}@EVmTddXk==?tzkyX?)oz_&onpx=q2;xcy;Y@NrZ__Fe8r!LXetHXb~ftccm2 zCky4UqV{}{5P=#MD?wVhKiq^e_B`Q-*lg^q3L2V0GmSbGbqS_ytU{epE8fA*M(0b6 z#9N915pZ^dEbuYP&=NlMD$X#uX40>w#Vn12sB-`3ZTHJ)uuI*U(*L{TA%@Z$|J>rX z(zauC{O{cCbgyvLo=j4odVEiz{a%#g0#>tH8I;f->^r4t+&eBWi|1osA0;djPWBQ1 zlvC$AC9c^?2I7u#SFs5efE5-MsbPv-7-VO>J>8_grdniv=?3d=Xr6+jAgzH+<8zFsD8Wz`ct)Kn5r--Ql|h0LbjjnDPTAE+ z11?)wj*+xU`>yL4v`9Zg!unTQD}sr57JFF6El&-6GEy#EAOw=KpI|uB&C8na{8O*R zXDMt_^=we&l2))$^K0_disdVzDJz&N(RS6y+ZfJrc{R*2ZUM&0Q8x3G12Nw^Dzu)W z>W)|LYqKbiF>a-%r*1V&uj;boc4r>aCVjT!4Kq@z_X(iZ#9)x^ZUx$BnaYv9!(hzV zfuyLuP6Kz22r-7yqGSSj)@q1WaScgwp4YA%&*R8AUeW>U;dh=d8zdkW^ATWE%xw*o|7D#kFpcmRbi zN&6be*A;(!B{}~U0q+c?8~}|%+%-)xd7vNrKJ0{z-3+uH&5+^qWmr7b&Y(_6(X?V9 zi5_2fATW+qcVQSrT&DEF!YSkh0wM>P^qsUMZL8bXnV? zVKPDSp<$Kd+A-7d3fCvU|c2CU@M zQ(7mv)j9)7=gj13MjQu>|FljF+rCe)sEp&|$T%|j+;5IR7e#H~xXOekDFUHFc zVMI0n*v25o0#nk8m-#ZM22YX(XWqqR{-J4+Fh=sol-()RJFwWsryi)?Z4^xHtlnB) zwO;-2y!!W^7w^7%@L$~SqO$MF{p#XY+je`5v2z-VvAvhnMj2?ucww(bxg~zz=9dNH z=VjP!#!xtvd5~NUN^Uqq@b)f*KxfK z-9k}H?x%V`)6XDP_iV8*s={i}I$@OZqi(5MGew$nKT0s6C)t{qs`B1eL2Zr#RKWUR zd~CkkUTPP%hlw0PH;hh(gO>lJ^T)l{S3TKYGw$D?b4HVYK#<6R2GCye8={n%p3&S* zC}(8K>O(O!TIX}BkvtqjEyb0GipAi@<{ZX$-&bPr82IZrI#Zv}x~SobEU z(38c==fH#n>sV#jg6Fl<`z6E#3q7Z}c5m9VpYd4Lr=AwGyK!o^js=XB>Wz7M+i0 zNTc!(-_o})OPxQ6_gc=A=|vvP3>$9fYp&OUI#*3&G;#pT_q72)t-h~O_u@YC?;=>NQDczuT^ zrbk*3ug(Jwi4r(Rd z81p1Z2(U;YEpa(yAEzTmmTu!xO2ung%DpPrg2HvUL&CO9;>57QzM3ZUV{CPc=lkYF z6MZN9g(-$MGuWsO8PtP?)6>hJZt%eolx=awJ=RUl(~5N57BJ#;?Cjt@p|63#l!;0L zYZfC!QKotsImX1Y@3xaA#ua`&^!KhrO;R`@)<_id>c{ z)?3$2aW)J3p%GnpMcUMqZxarOtRG_6TN@Nl^PKA~f+9db$D#FeYzT6K*J8yuV(2rI zbQv@{!(ob~3TJ|es>0dT6itY%4p+3+xYBC%tQI0~#3C(H!-Wjb60`aWBo3!f- z2fZqd(D$){whAy5lb@3C8#l+~`0DtCWddXdVa1ebKhO>|rgj!3=z*)bHj*QjVyd~Y?Drmac5i~02+}M)h(}W_6|?m` zvGg*-Q!JIx$cE-z3ND=Yf4N!n)DNX&s-j38WI8OfjYGpd&J{a7f4bjoyyx6XS<;WK zo8mzs^}dcz`TxMF#~{YDpZHcp(|AUjc6~d4SDg!xg!PSs7yA{>{6ccuW_xt^&rsd- z``Wk#Uv_qOx2=~)X4{|b2f^Z@?-46?dJQn$pbQV6w8{ zM)8DairlYPHl*LMGvvcSf*RKnTCAl2K>lh5EFvr#qm3Y3#GRUET49l3FtRGSe5c(Q zO-u5yGTv53kGLyCV<;xF3jXcNa%Bv1nl>%rw*(^clhVdSrI zC|6&TNuvUX?K~MIiohY)$?`sVxZ{%5o7@swF(RdmLjj8taEbDt%0#;96Gd5Kv^3(~ zZdv!irO>)ns0nN+5ngjJVFW@O&BI+&(QZJP+PLRU{IE#zxgOPDiA0Sf zs^9kIiOb@I(8L&P#~3vop72>iaTQODg;=D^r^Eii^>)xtL3TT`GVw(=&&!(7`4VY# z6cTrFBf9jnEm!|FZ)A0vcF1_{pG5Smze}~0B3&8cx->g)d+Qg0I za=oclS^(?3KaDE}J$AOLV$d;9=}o+pn6LUXOdW{uF*-Ti4E|HR)JLi%4ZT1&@5?K% z#jB(xK(7=#6J!Ohb)0_K?=r}R(m7Y(NQ>Na+;M1pa>J^6Y8NRo_77azQ&ASrUxKb* z7?HU2u)c3_dq$F^hu?LxL(dnxJzLj);mfl3pN)=GTlBvOG1Q}KFq1ESkiK87yu}`T zwF4F7TH3!*Var2w?t!%G6E-iE&dYXj#_L5xQc(cc#Py+(^RWL&-2?l+^BbnpVbT}5^I@OJLudeS-c`%hzWe7Ep#7hzf zLut7w6ziO3X!+*FOem>G-s0bA`E_VbDH$W`6Noe?b6-+6IZMS{51u;Cj7sd6u`&Qb#kB-i~Tjt{K9?AtFV!waB=h zPaPB%WiBi%;BkHAPZo%nr+EJRXt4o*AoyNJ!7PF!*Wre?LZ=2b5)ahBLrFJ{As;SF zJJZdVZbz1h5|kz`5=|BEA9=oBF5`q0d}Vh^{0Hh4mktx_wP*>7JflltgeJXY1%274 z(=2t*V~-!deizOL4gUkYI3?^EM;0=~ZuPm)rU6yt#_puw<$fU{K*8M-asLducY_09 ziL%LiXnemoA!GAB-NMHwgavts{SA+~Hw6T|rIw7h(fLFpURrt-zN(52aD(j6zIT_B z&M;#hDA_}J$Lw4)@(Tsa&@5P7`a@#}>^GI!0G+NR9CCL}op3$}Rl*44*-mW65ny>< zkaXfU^N6_4s1gKSmN{~zHyjRSv1E0>Lu)$t9qmOx7-?+SC%AbLb&(`4WBUBE@kW>5W6)7n*hv_~UsZ*EmHr`O06L=6>c%qVXXIn27!e<)AO#2F-`VPZEccb`i^7nJ z4cCqRU@gSQ>#C;p{4T>y+_=n#=SW5gclQ=3-Co9Zc0Fg`>)N>+?Dt3Sk##i1dj~3| z{m}6sKd9iTdlLLV$9oP$FTH;!!`dxdXk0AF#(34iUu<6=$9T;Nr{4CWw5GOp>{N1Y zK50S2qYZjspY{(jI;J@TO>WrT4DVsr9~Or0&U+azA)~>mdM&Uy>Xo1WT&6p;D|f=h zGQPZfP2}U7{Gk`Pw+P5tFRxW|&NxOHZ8bwC>ML-r?2%$(NGN&6QbSINOxEue@-vPn zMPBZ=eS1hMh#`4K((i+9Sv|EZ1E?1TP4d*g5#;+$>f^nF z^z>4$%ypjnd)Y7*JqraJ2|m4D+zxCf2hu8VD=X4;YKjGiX!KfJHQ!(&19Z#^gHg0F znRNo>v{Th})p+Ss<*!bBtD^N*GBd}&=8_QIj+zZiP2*>*P>`{uSbyMl@9%508%tCA z^vT*1$M*wl&AvwGmLo7dADrdvUWkSzn1~~~6MCIsQlf7p7< zpg6l|Z8HfL+}#2+7Tn$4HMmP~hu{+2-Q6Kba1HM6?(Xi;$UN^kH8bB-%^#|(sOtW= z_S$RT>$+I;fnD%6bNjGl`+PYER`CoJtN7=5+3!lBfuyrovoRos8aWK}VY-DIggBd^ zU`YItDL3-?xKPooD1_i;TkYgr{Xw~zikxRUsSt^YQ+uj>W*jpiZ`$Wz`qfFDIdW-u z6=nXkE%*HO;yo%f?|5rXMG+gG`1y#G&{lc^I{M7TY;688gDe=`H&30ezR7r!KN&j-QO0CzJ7bI2+$vQ)w+J;NJ7s%+$ zXu!DG=rrNg33y>TnY}8kwBluPOQ0g*ozk}!VS(3QISA+S2N9S0o#pcJo196dN}Cz| zV-qQ_i}RSm>oaM?+=OrADnz+j`x7MU^9uU21-t4z$hag!^EQi}CYD(zc+hMmU-R`{ z61VR>Zjvguenazyf1XxXRQv#ipAZWXf50!99w}!!y-L2mh8%8Hu*mmR=ZT;s z`^d0r*N;SEyNnz)@VjLLo2Rr+jj97Abz%z#dHeT$Jx9~o>=_|}k;DJWQ?>=11bzsQ zTXHpVK)N_iBvd<1zD{1P)w-8P%?i&n{x)X~@BBEo8$XPMg7x-111JR}TM01&K)TE4 zIH=LL8GJ_<(0{A<==Hz-=l}j)MOwpB1yY^+T3Bn<|1+rYg70R)u%K825~2%Os#XgX z-R{5!b%Z$pyIg-E z{MG%plkEFyTy8BUHp-?W`|4~HgbloKXlwWfyda1x#jgH!rd?U{hXbC>VIfg|&`Xz0 z=+60zGIsSF(GSheK+*N#l;i&~L0H2Y@rzi8#f{*-cKE!87V`>pq4~dbG0}#bvCWdF z=%`lv>|r+;qD4c$0kA>}If9si=p}5PXalvP;(wLjp_-T+Bb3m1#7aFC1&o*Faz2%S0VARC! zvTz6j1!9h-Z28y8ivajTWt)R#iZqwBnFSms($rO4wy=RSkpZzi8e;0+-Gy0{fbIBGOb0#?);0RwRYruhd8ni{CuTzmBxrS5;o+$m- z`cm|%Ulwf>IeuEABsFB>%F$Z+ao0(V_bSQ~T_~dQ%s;vD6J3PX5ySl5HDLBN^5H^q z-g{m{)rl)Hpnf1VrSCLK*I)FuLXE`^$qcSsgk=dg;j5eV?quKgO(8nmG3 zABuake5;6%2aDWHD?Hx~?(?#Om{ou@J;LnQfw*cT=iF%AG_@uT-r#4aO(8}me3=6} zp`2Qrm&Y5CVhpUml3N#)%~11N;?0&wO&YcQji17rty%e| z*ld%3f{TLKyiNq>QK?(@KT+V^@`K>^f-k!n;O6c0;xF6hu5S4%^>Hy>ATZ!^anbMP z^fcM|5k>j_D8OLSb$h;&^9rd_EZ;9MmCdk8s0|#=~%(XKP|@_z-Y;H-K%E0%}AZ- zH&|i<)I2m+c6Q69omAuKZh+FT8`Ow^mjKJ#ViHYH{|f}?PeL$l$LVo^?ZHGC@bk-r zX-dB3IyXadu3RwWmt(5%h={A*4=@D9Wj)W<;tw-pax%eqn6Ao@W-0|VAr;!c67-z$ z8eKuQb$)h3pNZSvpx=FN?W!H0(d^PVZoLeopdyXW>k&RX#Jzqws{#MzJYH%C;Q3@X zMmeOZTGTFh5%^wxQ~lo5@&err_T+ewh(e;oJd)-H`G_TN8b6?3AD4^Vo}S4|D=Fy) zzDhbc=)-b;K}A85upjNb=qse=!B-9&qUa9n%YdKYMcm&XO*%6a`T~rsOns|Yzv_pJ zMyJm82DwulbRVYtDqdEI9QQMI_M{~T2tw`_ah&vtPH{Pq1a(o#)2nk5njTY~xF!kT zWy_8a>lujS>~TT}+F%~mZ36p5#cGjBEGS`BYEqF;N6N*JZ7_@+ro~L`D_p$9;F|E^ z!imB}A$sz@?OX?r!BZ2SO3g%E=`0vG%?8KG{PuqGFqzH@CN_GE>q@{5$aiBK#zVq)}~>M8a$0vgyiX zH(cufQZVzi7ttzoenbtp5xx7I1^~E@Q4@3FE;DCFy5YM9lC8jLUqSs$k5?j`Wn-ur zpjN2l2=?O%Sf-O6t?(hwN9j)0UDD(5dsWPhGT$hOUJW^gKq6h2MN13jp9PYrFh-w) zmVU|j<%uDZCrNQr+`Bxz)-5V-WrUQ4OW)B)Lk!LG5@Z9r>JR4ggvAzSQ9IL~w4 z{QcB_`3|J0FT+pD*q)wxAFp3%X0NVcE)DKS#2k?*;u24TY%PlE$d*bp<0~Xc<>Z*v zV<{z~or*hv;QH(HL5BU*ZxEEpH{b|*57jBFgi2*{}hoH2I2p^;}}J;sTimqtm=aH4LYkP(jwckHw5>< z(+fV2Bx1J|AJ(y_22-?mm^`ID;w9Y>ImJ`eT1OZ zuJs#keHmT*MS&L|K(bjlLn3+uSN*v0Z@19+SMQTg5|ylPv~#W2O*Q>+76$P?3`FZz zW@4+=Pt#?&UX&+D%Bf7^Fc0#mHV|`3%W-X3sJIQe+ zwM8kl6lx9h@t8l+dEwNe!V;fhYkgMg`C_g#SQjl)F2HLk|9+3R`n}CLPUH)c#g{XY zXzEHRi%n_fCLB^i5Vi5(L$xj>IQebtR~!f(ZrVsj_=asHwNFe!t2*vktl`bjhHUjG zE5_h2k2m4!a}U))FX*vJ-ZQIn1#Q9HMTP;`8)1HjwJ&9`LdTpF-6q_jf~8AGbeN^I zN|}6vba|2nQuYjNXxt!QjTJ#hs8h4nMxi^>?%qq5J!FxsyvaE$SWduLG2j}#0wvN) z8zi9gyET|Xbska?eO#iDF|wZqp3$u@JC)NgKO5dUhP6YLrRwjDN*H7+x@{U z6^%xuOSxKsnG^){-9sLuKxm5$p8epi%++`9kwUx|DZ2PS z^&P1$5-vHsDiABKHhT`1jq)13^aLT9(nz7nMi^^$D~0^Gd!|mHNE}XE;IR3?{2=*m zlh0NK&_o>WKC4VknKZ7=_)vTvkkXvhPZWw*W&Q3={o7!Q zhQ@%qN`xC}MdIK^luSfcrCk2Z(wBc{ds+jRFhU~d83XzK(P3_W{;0*eLd&6}c0ZkK zmO`kCAL43O{{!mZSxrndgp@UCB&kX#`f<~TaFYKX=U@{21rS#^Ce?l|FjV_+Gw{-y zxD`!@#E+JsfPv-YNbqx-5_$nIqdrwwV(RHG&j{;E7@13%5v;hD){{0BX%p3tNx*wA z<1pHPvu!=5Xy4Fy{g1+o4@}sUkLG6OdtK#ufgZp&wBLvmTv4Z}E>rFdbO(7NAv+4p zcA*?4Z{mN|_5W-d-lBXJw;yuwRf3QDKW--($hR%Y|2M+|YhdTOsyEJ#n+Sk-Jc$o+ zK)@jN#pa1*tOwHyx}40xCQ!)D(BVJz-vXQO;aR^{V6#R?+6XpzAF$V(ahmyd8r1b| z^k^HGY#!IOW9>qFkpy%)2_~SiL*E~tcJ)e)yP@7GQ@k4bhd4xa{?aMXWd)RJ%tb86 zPnl}oJ3OcCVRj0Hs>UY^Hdki}*N3gD#8C7oUR3X0DdYAKheD3NLb^3LI#j!Ou7s)Q6%3oHb1%*g zZh3CCGcpe;StDYPw}UrRFK=%$>2P=@ML|+6oyt#80fwTahAr&-y~JNf)^;)v+CZ?q zW5mLhn>awoMv>Bicf~D!sJ3z$<<5%eg^KlBwJIRJ5u+eL}O*0qbA@E2zo| zDw6GGH0Pj=U*L^`V;50l07jtlxKse*;6VSx>d?o>=l6?ymLjTSbSWt8*4=~?&t%0$ zT0PUt%@^T_Fs{agSjs&cm{^y@n(VktpGaPHc}124Q2;73Ld)y;t^V5twPMmR%_Gcb zgpdmsv=9Qv+zD*0e5OLsD$+15qq1z~gWnxXQzrAOx&wSO3N#|_@5{_z^tLa9S%ZVK+duE|sCzipzlF^oZ7+BBNA-9D^pCwcW+O)u3LGa2rPBH%LjMXYniMoxeS z$)b6cFP8^H+s>>uIKm*1cokz@*l22g&J*18So6Oitu4pd{lBwvZj{vl^u*o+Lu0)c zR@P5-KR-KhUkNo7LqF}nJFO8^d%?7K{ZC|KX(4tX{@KpMCj?lMn=N+ls0vj4RfFUydS$CfI&RZq%?~94{e-R?VW+;&qxX^| z+W0ysE3TbyZBq{+i%uPQln)zb#FHtXvCSqpcM%v8yKg7?LdwdLll8d2*d;Ouxf{0w zj9&ZCoJ2M^!uY}F%)iZ2##O9H2_x?JpJ(c^jIi`uwkqH+@^69W;%YeLaw}qzzdI$z zJMuqHX00P;yaRn#NwxL#7b!4Gj?9X>zL)>V{C;SEKKJ8Ur}h1LZSC`Dk&6~4tifJs z9OvuSI%BIH+l{g#akd^MHxAmD(`|O~V3e+YcL8Nm(yV;zm~XN2Bq%#-nlo_p%`(sp z*(8H*{@VCyzo6bMoKF!l-IhL`wThU{hgbw+BnYgTP={$`VsVRlMzKb`xUVG_CApkh zvvMRwVP)Y^q){_;qCf?Soxr)%Qi<#RhCRf@D5asL7Z-A%z5&t4=Y;sbei@cf4;6NR ziWk7i--lBYzBeG;N#a*j3vN!1I9#~oBQ25Q437xWehrnGet~If%bzDC+I1{s!?Dc} zBTWi}h*6F<^-k>Ob|C-_Q|?N@lbhhVWhE>ygGyH36LO#C-3^6@p*%1K-Dp&@QuH&Y zH=Qa5xzU&x^kBuNDXH8T^ywdE=k_4sRG?={tjp zM(q(SLgEf-qpYm_4JBS<04k|o)DfvN5maQi3pBM0A0^-=u+S#BPeM6) zK|)uIs05RX3$*s+rQ9hoSAg(y7D6bg4ktoM-u;SzTRiQagbgLI99#OCCs_otQ$}A&3Bs9U%GQV zR4o6h`AhK|aKb2da8o=69dNg>F&Ts&tN*{r$B^jXtNxbSLKh-u!3d)(4L6CbpGwOi z2BM*UPTZk6R$JrR-;Q_DQ~@O3GcmZQqL-uTF1E!_o6phMEx+CNP`A>|{IK;t)poWX zZmcB$trijdQ11)$b_dvx_#H)~<_i^F66K_ep8tQHMsE{Txw_BqCjEDyBDl>hkUJa( zRBF2qPu>>DXnutN9~zE@3I~el*jvJOOnIH9&Fhttr*>ATpg_O?{=Fm82E5n^?MuBH zB?b}KwLD0kuv7E;MyUDgL4pD`+(ss5Ug@Z|@BZ>1Ne7s?R#YH-bnGJO-q|3k z>$_kc9K_bf@VvWaIvk|wncvpr=V2i;r0)lzI%GFH-p$@D5POsA!Te1Yae@cOAd>CNrLvkHQ_ON}dDuj5RGP}21?KP-Zda$RtCgnt>2MH(jBl&1+vI=~a- zlexS+H+ZV~PNmpdM>DZWNxq~fo8gqppVZvIBG%DY`S_c_PAmiY3}AB_smo9P7F9N} zoGrC=;LDgEnnVe`A#LT?+|4aMCWjde3@i-EZiL~WRikBgjb~8upCrmOt44m$v5p0% zPCDZ(xsuHVA$RuZRfg*!M_BR^oSyt~1;t=Gv(s-5{R>G^E3H~>;Dy~Iy;`{IR_MD^ zERo0BLM^`ZCe~n{_a;bUU&Ft21Y&4*ob*3=*hHvyf>nJ4n)GijggAYxA$yR4L2#wHP4BGghN$OqC7V4 z9J-z-JBlIA3b$(ac$Z$4+B1Ah?0pX{z-V~?`ffthmjAQeL3g+dC#w}sBuV1|h}>3AoU96yn610SJ3 zy(V!eG5L}h-DHULXdUYDF0LC&VSn9;%-fBdv_WrTG|#)vhi980V&Djpk9FfN=W$2odC=NLW$9Dcu=Ja*ib^@{(-Ls}mA4i2> zEn_8+dTwWMEte~IF`qubecvmzqznIZfvM#zN=$YNtwj z?PXKowejWkInl`h+^@b{V5TQ{Up8{kUnZVrtlxh7nW*F4^=UqDaJw$0!-ppP*h(#z zq=tMF{^Te2>|W}QKT}ge9u!n39?SKg259=P5dvLMS$-sSiVPO`*eNabwscgA>B}S1 zJNunUwt_nl`(X*K1JQ&b!@J--+FHo&yYCIE-L-irO-Fe@qWzv)o`?i>+aUMl5~?XK zWuKsRA})AdvD%B@KlhVWN#uUSOexy4=Es^r(H~jyh=%yp3lrRL-3OV3NKVB#h`>8M z@k9LZEg-?Cq>J+!P?ikd>*6G$R)NqQ(ik?Hs~qL+T+9|8F96M1BooF&p65` zf1vMTx3&UE_9X|yHs@^jX33(V5~&RLoUF&r4B?~b2PT<8DvYu?pDFtNlEvrJ5%1&8 zC&(({2c!`{EILC`R{7r>94dc5SCC2eF|Hy$&%MYp#)=E^H%-C~?dli2vOh6eYM42n zqN%0n6dn@P?vMZad4|86=$0UPvLNpfWx(!`X|=q_{o>NCKO^ZyHZ2@zsgTC}bCil3 z?cDiqI4?g#btd`TltTnfrS=V@z$_xuck)XZ34a zY@t$zlEjCl_ZdsvWdzw-3@M2IC`Kx0^*z~Vt67SOWuv%0amKw*r!ZvsG^eZQ>8&1R(_Rp3zua(_jVkA`NCsLB$N z2iKt;3nB=rABV$-c>=tVNPIaJTVFZ|Da=$zm&mV2MK!~}%_h{w&%SN@)!KArRDSViw!%#W=Ch0b?Pv+jKHV^@Z68m*+^=Cg}2y;hg1+x?3R-=BjE zGvtfv55)bc8SRuH-oa1bE0*CViy%V0S$2s_}&Q80jOdvP5tCYyE_$;v5u5s!BQp(eIR_zu?@_`uQs-LYA zBkm#`KgV#quU$_5lz?etd$irn$NJqmaBqVL5nquw>on(j-BpGL)IV9(FEf*-P+)1S^Qf5}1zTP>4}dyw|UIbMp;v@$c0Tt*j{m_s!XyJ6(T| z76(x@Pfruv?$7VBg^^O2C1m){TfBc=p6x?RH}x!rZ$duhe*i&Wl@D#Z_Mqjp1xJXk z(WCJvkVh&< z(7ownn`L@wSDWIDYn;6LHZ;o6lSnvVp!i7Tf1M;bU@VQYMamdKfkw^RA8&3Am;0Uj zs~kC{aaUqFlVynURLKXY^Y_z;e6$vrBPNV?m~;Q%=o3QArR7S*8|c%4&nJ9DGT+Ew zYN_k7dMo{x8h3;Za&%h@ICHc=)!5`0xtV*1L>vT?GanhXJ;V<8qB z)XTj@EZCy0^+a5E`_0k3fozKRVYJ#vq{xIwNx_OY5(QDx1V+#Gft?qYW9jWhV63;l zpHF!eVO;JqN`GE)P{;ZEq;4_?Y08YA9$0B?ahKJd~++%Qs zThb=;gdd1WYq#baq!oK-@UpO%;%FI0S%G&%_~+p9Pma9P&*Nz#Noc7NogFMykj0cV z+$3raL)bq2g5j`#sX2Kk%_sek#$znm!K#_{a zrM#5%mfsCldt}G-c9cK`E~Tui4zf zX>Qd8^Wn`3E((K&Vj2_cAw`u`_9+YE(dY5_pQ2PezeOI-LOS?v$Yadnr2CbziO5q- zcGooViT&MD5~i)z#BexYP@GTs;QEW&l@#Y70Ju&;#bfjl(+L3vatp?F+aFRIg%{uz z#t79k)V8$}v-cYAj$St+t0Y?Jk%&(-VlK|2Jm~(ql)EmjO201O%$b#o2NuD_d~iT?@RNho+g+pwO4`{QifP z74DALvd=7?tdBzl!I)cZ37)%m=pH*gEMS8wT^?$Z5K#7^zTU2GRTF~wpNh*|-S${u z#sH81QZv;A3rfBvj0orkdQ|&i@{}#Wt95I{jsSqaiG1E~b394@X9f}?Co;;xgtW-ySz(X#O?}!*YE9h_W`c^WAP3Vo@=% zpa(E;9BmOz5HxZo)4HMmLGl_VhI@&_X8K#m>DSRtwq({cvE&=WEO)4;L_BE?Hid7} ztl59gPt;Z?^tR`?J28~xq#4PW!mxSvoGVd>d@Ia;&~XoX)}{FlXYhm)6Zt~-rK%vs z>jT`XIFzE~O{?H>GldWU2+Pb8Eq0pS$$!E0P6Xc;gDcxh6S8eDx&k*bP7kiq-T>PfB$S*~S|0;JNy!S8Wbuz+&Q2%eawbQn< zlVM8Nc|KQ@`40Pc9k0Wkc0ImATY3X@&?oR-Ykv^9&Fk8#-b`2chWd}7dRB|I^$5yO zhvmlKF*ZI3gzN~$!HLEaxTHv0j0CBB2KVcUI^J`mSj7)^e?t_V|g) zoF!(;}3K`7QU z$NDA4RJD05s5!nzG8%5$F>((3YJRs5y>(P4IeEa87auFnc3qft?#HN(WxOXeTAbt@ z32cC4WD?N}t^_GO-BW1;jtyKG``XJ8iUsFo{jW525-x%Gu;y%<&%@StGI>%5u?Go` z)H2aVxb8$hW@1M2tmFEgsa7V<7MLT- zL~y_-qn#=KJ{fBa&w&&|i%(VH;!_?OVlYaI9WhU=JLnAJx3X6jzd#lm=%wA8%t;&qn=Xv^TOYh9N z28Aq6RjYYMWHVOu&_i9;XT464z=uQT!Px7krjLE-Oy?z{=9Bo_>rKy(0IoU#j!t*2 z&NZ?F%#n7TuoDp%IqN!AC|C{HmI?D5ThfL8e2tB%_nobR&UZ3?PmA3O$-jDS7)`ov zQ27nn4SQ;W`6rnt_c`4>Xl*G&Z?UGCk4nRfhB56AH(t1HfB_`i4*cnUe7&QV?0Wue zS=y4)BD(Jwo}pQAnB}~k%mPuj)ww%c&(~?RLZW5ei^lDFKZR))92%ybDWAqH_NEQ* z)zo_`A+l~+L4V1~tR_fr@X%8IO~5aEy(g8m5r>j!USv1)k-y@g=+BQSG@2%EieH(k zWs|=l>6YrDw3gi;MQ*!cUcCgsO`@YQP)cg3H zX(%h_Cwp3Gp1UqvArppX*mY>GNIAYR2;@Ev4zWTHo zk0KKDw*~En)Hx@&S#&?H>#I{d@FEgtNbchJNKkYj7B68HP6kGG&j>nidB@h5FPtN5ao_NnlQRcPr-lE3PvAAC75V-Hfo&4`^%o0v2k5`Bt!_bxY z3AI58VOuD{RWNAv)lOSm9H2^%hv9Ut5&YKIB=)R;J@m)2|J&^EN_A>ybHCvUO!ILB z?A)I6Bl?K`6G~on!O-&4ULT}Grq7qFpTf8KzU~sI%QKHaVe90+>-;Ak9^b>$ntI*} zKpqp0-#NgR09)XFB z&7&B-l&JF>Q6MrjYk~VwUdV|N=cv}Q&2NUIckt#1;Ne)S4iJ$rzHZ~-+e`*fs8HkJ zI|j`ThgC%fT~h=7TfcD?dy%nVvw~Lk-&F@0DFr-{Gz(Q&oi?1?Je$*1@nNfW|0;Wj zJ(q7REgK^>pCA6$V{?vtdHeny=HHOrSg=71-=pZHUVB^YXMMqj#-jNFzXctv`npPJ z-_wh?>yL(if=fh1|F*>|XzZSA>G9Y6ElqcehxL$KJu-o3gT;s-H$c}**QYT`u+|<1 z+ZKKWHY;WkEN6a(>KD(ZPfkEVQ9i}fdEB?F*B#fQi3S7Ccs*Tu?V)LN7f2!YXi^e| z*U9taEq=V>dA$q|N{1`LbImjrOF(Ic+XLGG*o(N8CV>Y`lYLgG#n<0RG6In2d@_VG zM-GU0Q6+HlF{Q{Q`$a$PYQ`iU{8BxkigT3W{$`OhG1t46toXAw&8NXvyK7;T8^m%* zG09<>om?H6+?SwZ{1vvCuYN$-9|dC056yo^mOo*zS*QMt0b;@QqsE8c{@_p|aqWi& zijb7jC%%8hQ{`3=a9@=A@XKp#?-43A9&ptv|B7a<9kNr$MeJpzX5-hh&*DU#@G(kh zU7HZxBi@&mS4oHz?Ae9qQ*Tf`7ciR{1L=0j4Q{FOl!0n5Rl00e)&=Qj55kD_6-##l z8|88-=F$D8PWjQQa=n1mq44YMe;wjJIb|qG+%wD+QF4g+>SX3Wf=u3^6;g^d5{`7M zm`By=drnO4a*eKGs9^sJb=o2x%}@v1OHP>ZEw(gdkW@Of-SJuwiHn$TyNDhp4-7pW zyPf#{4s1X$^TRbuP)U#_N;mjck1(mgpleuomAmTnXR~S#zu}B@^62~OY=o2R+R`@F zsSaq_TxlS7NK(}ZU(&?*`NWL@<52)_{pG^XzA)Ea&%E|AW=p>n(ASS?S7TiIHbTRz zfntk)P!$jP+7b@DNTI+#mrXZRBL%=bs7C0t5#7)-F)AN3PZ6oKyR8@1GNJv&VGtTQ zkOFt}Fc=+_#C)AhJs)0f{%T8_`@<<6~SiI>F=Ff#6m(i~82l&~;wY2wK8!TKAy& zFP{ARmaMHfzcJ{1?)Mn+ptH|jc&_R4!fB-qMr@xv`+DV7uSSSH>1$j*7GU(8g~u_X z0aaG6U?k^q+II&PG5(g3B1mSA`3sZh=Cc_8WI?zfjZ9k}hHmBBs z0xgZ@0gQX>|I;3|5dKeqgdJho&XAxZ3P)h$wjQE|#3Fc2u>nqNq9zu`%la$V?+C6I zNZ5fa@5VoeFQ>oP7{*uKmt3Dd;3bH?>o-DgN&dKAZs19r!q;2Z)jbMd06#Ks%x=DY z@Sn2y#TUG~`5iTc)*IeOOh_5oZcoau#_eI*%!Q^T0Et_&N#wbg_ zDo;sg`z3-3O*WW@`O)^NWC`pTzgZv$$!i0-1A9sSCq{g&S)*b5$zHtjJ#bp*ITbZX z@2m+10vc(KAvzSfL}Am~QQT?^D*&>SO5dFB!iN0HG>aVDCgv$Osj7#=nTL)(_ofMi z9mDrhYMWF2hsv&Emf>u*XDmg(cZOl*n~&Y6ooR|TH?Xc=sS9o8rm!e|i)vvlmZ?Ql zzjZ*OpynZcXxsqP3Rcwy{ucSi1QtJekH>wdJ+9zsv+fXFL-8rvFQ z`NM4j#bxd!U@|0|k2|kE7q!DVD{=QrhXQtAS_-^*jVjRry^P^@t!0HC7tFp)=Ul%J zM0pL2UAKgB%ah&`d=~gTpuV#tp2Dc6aOjZ+w`=c)gh9anbAUu{akL2{MJ$fN#q`dM zePe`2wX5^zRTCvfxpx}p8U=LN33M%Prt7o8)^x3k{n4|LAEi3&a8~6DClTi-Coa;- zTM;X%bBl`l5oK)U{XfdIDWCE1@kPx8i@s2SuBF-qZk9L((wKnV*} z(ohY(PAE3WfryUf4Uu^jXR@Z#%sZ%2Rk_ z_TjU;fyB7Z6R#S*7go|}_TtkIne5*5{Yk_78MEqNP`7+RMNT>5EqjJ9TEprMUg?Db zF)QKf)gH^Nv>6|qSd%`gH=TaZ`n-YRVw2&SW;NE`38fl0q-wN2LO1P!ruuKlqlW^& zZ~7;V79vALQwFc6|GDmFEnf5`#JuA&@VdbBdw@UFW<1jKr@v#OAzE1IUYk#pEJ6ks3DCI*Gik0WQpZi2?U_erZU)!)cu^q3 zBp4eu#VMiXrKl+?ert7j)$E*0OmydU<0N%|K4?pBD};`Jl5oTrWJw+pDKkI|{}(CD zsa!a3KT(N1OA((|rZzsf5-z5prx&1kYo)kJ3i<@Z@{$S)!caG~D`ud+9Pd!eorvorL%xgI>FBekV%7PN?ys~(1) zBt*Mz`H|F*a@pZ+WiXiaOZadiYo9>QaQL;UZHW%~Ul9h7{CsI)w#%#G6qR8&eAdN3 zL$!~0^ww`Kbg>eRXmgAAYIU{prm1p=$4}3ZQ%@Xh94eoA^=EcISaG*0w7lMo)|gL|zM01n z3(a^SY%=-YO-tD59kN5!t7gCHrC$~}ZQk0#Sqof=D91bc+!YX8@P=_VtuMsucmg%q zxZ58JN5F@d|LsoY9D*Ay_DP<1HD89_oGJT$$`KFTuLYamUk8+R@QEE_1U7^10@LF1 z<73Mf_-)~4cK>}td+O%jc(3QD_}XSR3?X<9aDB}>d*wtzMc>Us)>l||5OowGPh*;S z0^*1<*j;~=TT+}H_o#kWe)jPabeHL}ps8p3zr#4h0J1I4tIE zxl<6ea(1!xZx6@8T7y+H%~OfzKgaAoT=xq~^sl@!qH!lX166BnYIRMWZ{;3ny1zZX zCw6Y1G;?OEo#KF^_xBHtpGs?Rm@Vrum=-Xi`L+oXUC#45!8(rFt+#(UKjN*bZ*5_= zUL$<{91@C23E)m;IxN#3>&t{<+YGV2T$Xi5U_^wRztaf{HGdY;PoQx6tUrG{S7Gxt z-;s{ad+tNL+W47}(fSb;dZH=8Vz22X2|} z8&I6*YnRd;5vmu<*j~gXSuXq&oQGbS)Ym0BF4?Ur@&foJ*$(UvJX?a!$+vB;IUUOH zoWo9^Cpf{pnQkYzONJw=N@N9{#~j}n;$xV0DYq+b=`q?nDKEgBXG6w{8alM@XCv7p z+xCsMveJ8nC}=6S)1o|6KIXxZA(2qS2(6|GNBLOdv5D@Jo5zqhWc)x_Ilj#J$>inB z*qbA4kGb%nKj_A*;cAcurCc}gB)n>>`WMqerB-DBt-#<)lD^^njiv_krISNlwZVf~ z>c_k_ZD!{uVsB>T%eF_{4G%Nu4NrwN@Q&{(OWVs!h}-cz^7T#m;(Mnqc9WCHl^hen+v(@4sMSbr^7X*@UZsi$XId2%hL#(6tMqsEOLYy27IRBclH z{)9`CgI?@gBO2hCnIOR-zDb6**5`-a-esFm`=bAa0G%r1W>xuKR| z`fV|;2DnD~?zAAY^zLaT;c4?~OtTfK-{EAsHb*ex=2Cv&iMB;nt3T$mak zYarG`*&qUaK7*!SX*mYSIGD55O)RCpJf*$R;e(uEeB<2F1j<9;l2Yrl*k>JQi!!a$ z5rjape$z%VM>gY^{0Apk-?QJZHSR?KstGsw+@rH*C73Aok8x(+%d@!(@u2c&F!ZKYckJN1*jI4s3gY zLy9F^5U`XNUG{o=ajmJ;bia6EkmSN~uiN9j5a9(+p9_TDj8CGLb-bMi2`bZa!3!Se z8s^M?Yb}jzET=cO#4iU#TiZRI)N{5+Z7##w;@=8i&Bs4r?xE1{T0bM-!tG&6Dy=i%6XMU#G5K_r_@ral@GR9#)N5$HO|@7-^Ph zYH83Z2GsE~wre9b;3b72v1$|nhCB_aYYR6E9(=KQy?#n1NqxzztyiGrQsQrjk|85F$q|bX=RdVCN;w>>*am@MznNV^-`gomEO(hHdWgAHim1 z8!u%=TS>hLw$JHao*NPnxBKUlSDTf$;v~BHOE8o^@2$Q4e4G8CyKhZ$aZW}fP^ZVUGB8;A#p%j(CbRWxt6Lo|erV@*M6=gOvA&@LOqyQ?AvzVZ1O-Ko}B-26h?|xq7%Q3XD(J|o4B+Xc`js=$5uzr2g zs@e+%v7)d+H7jMxDIO3W_7}^L9x?FzpIg3TM z7V@-V1`crPq}zaXT9MjNUA{7&XXX@_;3%eUgl~t8o0#w= zHnZR-pM>MNq&Ar@eaun+CAswV&@c>cEhHTH>#p@y?9B&`9Lyg7I(Pdp@lPI1WIKMO^w*L&ms;xMvVv8h+jvazNpvGHUU=An@^fiF?dZWk89U3l4`o0!-;vZ zVBFvCbrJ)nU+2zf#8q&C7=%G2_T7}(Z|lf-R2O8QBkywJxC5RdO5)e^7jWQBh@NvMm)H&9m&6!Z;B}~;%p0~N-f8!| z&rK3bHONiYvWFRo%;wrh$o>o%?-?=F5_jY$KdOSyX*t$+6{ZPEDqEIunlQ*OASpQ? zUjOVZ53Ol1e4M^!tOt@dw5Ch1o63mvqWD8T;iOnW zy00t@5L{T)HHLdZdY5KtLv;v4Yplp>okP!-Uuv+Hv_kL_#ckk0-X%Yc|IKa!yR5Sm zf9kw9yk0?btZ`Qy(qB|A|0Vgh#565x*^-7JBJ3Id`)g8~5f+Tg$T4)SG1*0(ODAb4 zN^VF+e~?=Z3ySykr!5-Zd5o7t?MwZMli1`iV4tylNx#5)y@?Xsa5Dl&>AqYmx<7Wp zntvY9u?)kHBR%9N$kJ!2PE1jWF9;=vT`FFl&fP$s#;t2-b<4GLT2qJo-^!mB;`b4%^q5CXe`;g7m5&@$Qjs?ZU@4t1k(NO7~Mpi7+w`mfQ6O+O*+ondA&HBaY}MRdf8QIEsbY{Capc5RLRo*>*Ay}wsPnE z)^!NiTIcCjnzKJS5bCrAVS;shi;y`r>elQcYFU%ozFi?766V4f7Yud}5SYIj;O|M} z&ahg78A-MM!&;-dAKsgux_ypBMHYn;JEduS_$on>hd>0h<;t|}w5Vv{|2&6pJP>>q zeE-ycGIVe5vS66V{`UI+%mj0)<0aXkH(h2c5OsH-pex(>;@sraKb=K1qJ5V-OrrNt zJ-A=(&ag7W1V*$5aG9v(Vx6zHHE$!5c zRR~0mM>2}=>YF*PR+`=EkrtPhH>vz9ZY1~1DUPMIHzVgmZC2a%_4_SoO)L6z&D`u} zdC;IuRD*b?P5|ecZqQ;A8RG3&cZm4iw+S(GK^3LMj^oDNqrQv3VYwq^^z063Z6W-R zjWa7n1?l;(uzrYq-D^vX`|n$`OIE6Pd#P4^QRR(@yh9E#jN$+DaNKgXo7~Zs(Z2^G zSvFmWJ-<4&FBP9&N;A%g78`Oul~~bfXofFhOIt#T+{{xc{&FI8KG#WFR~ciYvj-Yi zHx`;2xuG*yTQWG)Yl3$XD3yR0TmsMQ{L1C(5zf8|{Lgs&o;`D~x?P0kx(vnY!Ltg5+O~ z^Ss z+xr3RGI47x%}cvxd=NQm)PrqBr>J#TG~cj`h`%pMEnl~&s|G(w%Fgf3XSs24Qz6Ak zc8%vhscE~*KZWFlEqO&_-=Xg9h$<*3hyS9|AC$=U_5Hr`M{*>dljAG-Nj3>M?2k=j zR^-TPLKCnqJYQm^W?blqci{K;zG%6{FBTVp?^oPzpa({}xpqFeB@$eKAza3u^!hjL zz6W|Xj%kyklW#3^6e_?6ix1B?jQXLha(Dqz#T3%L<1?iR^wdaW&{A{W#Y^otslIYuMu^ASV2K% zghF!0{!Za+1=J^O)dFb9DyGl451(st1z#4W_{cX3bToaSc^&|P<_~v#jc9iQty+;o zHfKshHgBvsM@yfnbY*?T9iv>&AE!qLWt#k39|q{8bflM#(!vo!)JGcC7l)-k#ldWT zVZ-WuCz}l;%8HU^DLJTvI!(b_4?5AA6~CE*h$D_FCL#?Zsmv#S%2^VTe>^L5sV&^Y ztEyxp;_sjR#Lo|&qF@*;MS7AdboSaG(=%6#`ScT$?@fLu(Xmq}?lvAvAASvvPeC2+ z4c3C|lV2cCd^vZ0-mrS>i)=nAn(dzFe9Yr4TaggZIr=%!cys*;u(2oDMx?4`&vM#y zGN#sK3_3I|zHu#QNi{Q7*WC@RG6}9VXpK-)Z5zC@0L`k@Fj8h2wC&h*BH&VS+ZlAw zM@qEyBjPSJd>+X6ZBKrCoolx~T`<~m;#?j-d|B9S5`2EWD=b?0uKCN6Ng`*1Ta<0^ zEEEA6ieu$z^KvtChAu(#xB>9=-ci@onb7Y@=z}rND_q40=d$%1tF9~AnXZOh>9kBU zF8T)S$V1p0lj=KKpa(OgbaVYOh-T<$9-=bPe-i;SaEsZ5k@poVfJ4t-}>PRwQzOvF< z-rRIr-duOubi25+LL96gMkOWHtspEjm-zP7vbSp0h93yRd>Ml?Iz15BYrf0aYqKI; z0hCq!fvL$Idp5 zu!7qlu-7wILAoOW4)>V`7mO@Dm3e*l@Sj2=RV&$t1a{Bb65FKC+qRaADeZmeb=rqH zS_^hf^!{5_%*Gp7U7K&8K_1gpAJYi8+1D$JK5M3U8|YPm6q=;3f_QKlt}^$V(8p9l zhmH^SW!~=E-^!3O+}|0OQ+g?l{|$7`(E}8GrH~TeEjp!jM z$$C&g6aLhKCf`ztZHJqLoA$SEOlYZ#y!S?V%F~D>lbMEar0SQbFbgQ?7N|_6MKP# zR$9VM3upM)_#Tj&WEu?)1b3ev#+ulej2Isw$;|>z?B~IwXH>@Jb==aU?xxESHuHM| zP4L%|wrY7qz+3&t;e(2=6b77UiJ2FDLt~^2j;>ehH1zDUAtY_yV3qjK&Rg-g)UFsR^p`d7 zLIEoB$(s@!6DbneG-bU<;$lrC>q(2&Q91Bm#CgKVCLJZ*XNTzXcDP}ML{IXIUrl66 zAQ5IaSuLe#h9#<`ps<`u3(ez(DG=4^B(92zgOoV|pS_#?*{bxA>Bk=kD)hhc((<+KNFs?T+mwUuAqf1#Ptl_z#6hlSbJ z)~>3%pI8M5ki-ka8HE~cK?jzZ>@ebZHX)I*j@C)WEf~l_cD?opdxVstv1CLSR>zcf z4e8dg=Ohm{nU9Z0R_CzYaPzNC=GF^90P6~W)qM|keKqUca=Yu?^0>&=ax)6w^7Oj5 z`9{6!?8dhmeY6C2kGvCjlp0QiQL`B@Zku7a&U%5~RN!kBP9rm#Fq$LU1A#$$r2c&eqMv(8cY&q4N!C ztO?FmEAr6Ag=)$9BUJigQJm~0ZZpDW=zQ=gtfv*8Q94akP$xW5P%V6KRU;U8RhPzd zh^=C8mAZ4vieB;Rcq#0>6TWecs?4f1aN5s7g)}40p|tL&{0A2m-cC6=JO=kh+vDFv zhF{nPNC_Xf<=&$Rk25!NdysBzUp+Xy*sdt#-~d?JhC{^f;gkc`=U%+ouT9`%M0irQ z{&TR2#9DrBavm1MVjg~YXK2vDY!;&MJd=2oP+8B=@;FHAymd2Y*uHEFy!4b_-za-p zB619_dER_;ZRF&KW$oC)4~?wa4k(tL&RV7FEUY)NB7ik@Xlk!8P-NaM!aqTXVZG(% zV!k(6uVE}6Qt)%@%4$djW#pc5$UYgO^{+cR-&6y+m{F%@y0ikModS&Eagv!a64oDm z{$nS5IejAB@kA#j>~;oGx!<;1CG4B1lf{IB7IFBSW3G)iv7TG&E9Yl7+U%aMGT%y7 zr22!`698RTqC;-K{AL-fTnUH(?TgpShEj#K)>3No+JuR<~M>j(O;t)xj)OW>`Ut`KtU3TT@NY$x>@e&2EaVMB2N1}fK&H3mOMW! zF-xyqd^_@97nJU?n{3L^wEjWss={l-=jjZ3eK5t|^5*@%0oIAd8S?E?6QO-@aT?d~ z`NQ}N!D#RKM)%D(L#2*H*}ZhHHlPFt?!@?_;Ee3hsGbCUDu zhPtK?@`A3Mr|nPeYAwc~@8~yDm_;QeeX*jb=iA+PnG}TzO=8-7^jUV zuFq$)gf=suakn15bV3i5C`fjrVa-UuIa&)oG!CRLGBt%8RF#%!@h(48P=E9+^*4rtQRwXnAJlKAFl1Zsc>x7m{Bdp@D%%esSfy_^B7?we!I zuh~OPuiZupKig0|2Pg?*2zu18qT*cfOiEA$&jux0f;HgMZN8 z>4px=4?jl&AUs-YfF9p3qh*|1#lHBg$;lnH+StiJ3CGJ{LFtaYGn{LoykKXvxtAvl zBD*e0syJ>TeKY_%EM1d}@dso~t%xRVS{lOr(>H8uqcLWfX|Wr0@!Zd5tW>P=N^zI&hs?Kvb@BEMO49AtnZAa4X_Q zpe?guuz&CQq5}CXA}d8~#w3sDs~(U-J|#EkuRuE>z1hCEy!j;icUqn3N!6Ty!31n1 zr0%9{PprK^O|4+^Tt?!NN1y*CxLIsEXu|iz2a1`9t}{tbkGWLfk0IG;Ap20?%rzU* zM#?NQ2{njgQ=+se7AM>6#3pOT7t-laJTPaF%!;uAN}G(C-r=b)cwttV}A56+S#PkU}ZK zate%imdT?nM)tGi znlv%hHd7B!@PBKTr2 z#k|len&WDGh4yNuz)g+)3 zo%Oo7g(Pl7P`(99uC)YxE*abg(NG*sT~p5~m`2mwY!?5CaLD;haSOPjq=a50&p6qP zji(&w;@ao+v!c%=IGipD5B$;6ltPPZb(rvNbiNx&yqFWr2peMLL6;Y>=lwI57M@a! zvhvTNO&T-}NI;Dk{)wRA7$?T6=+4 zJ0%xchNbIq6K}A@W$oo|fhs|MPcJN)Rh|E_I3gEiiubgI)n=c^Y?ki%B3Am`a59Jt zdnoGNySHme5g}!s@*bkE>ZYR!9Wbc6iU2{t~E|!uA3xNKm_oX2zgrXmCCYV^G2DOnp=Gf@NS?3<5TZ zHA1lad8ZV-BqDipn)7Cesn=QSo$?`%ip2$g=VJ7;%q)>*vjl~HBfZaA2v@m#eJgA$ zC{7JLbDa%jHs~XpRM2lt{bM(6+YGMbpj^K`TLV*aDWWa4ty*o3eDqete!`QIW$z4|%6`9?`}5fQ3snVo?Qje(cimPl}D`n<4>gEP{J6alld z5v!}K4{BLqga(k^kJpzYg<8Cy7Ib@ixhr{Hm1bxZc~P?p?QeNJESYJgwgwA8dSij7 z!pdi>t+j8lHvgIB9PGfs^mKJN)hr$~8~KG6C`~v8df(R2!WT%vlwfWDwpPwlr%*;! zyMHh9HqIQkYfvIb1&iJu@N5OhXmeZY{5V$E2e4o{B-u{VbUi;(WkGx%mNg|OsC}Yr za`%(9sx1`-q`|0JCxd=R8ye;LR90`@tNZGU1a|(mb-uGm?)Cf^l=kBFzMX9e+kM7& zyE(6H0g9~lxt^>;jA{@ zRv+^`3#|T7CVZ(57s84ei{)LoYzMn{K^x<@0WdV5+iP9b3vS(}R&>(OX$Q1xIa6eK zUNgicmML`ggzki0ocKqbcTE8{8!69v{iD`8Cu0$$>Wp2FCikrkyP_4kx?d%xgYaNo z5&q~PJh$HSWgdF+$m3FMctheJ?22>@7o^N_<%M0(qC-{g4=i-*TyRqqtr1oNZQ!l7 zCOF-2HxyPQcUrwXAZI9ti^;ibPM`$o6XDn{pN@JIpYdHjjZ4<=0evOzSs^rC5eTM; zq!i!y)Dsi4YtqUjf3mY%E?QJ9TX^Vh4*lRU`WJpz>BL+Ot-!h+_E4{AQ z6*q0Iq{oK4v&D(R`0qe|!=>i%aPOywl3E`(|J|P+jVWlVP)nj;^ji=}e`NQE0Vrra z$&_Q%e&@PJPm5H?GwZ~&bg}YgCIZDJ-szJkOB4OaKbg~&iRNHbUX_-TqH(=G49i}M z`bMc9<`;yf5(}4iqF_6^ml>(57=~(5vfKO0Nz=gf`g*k0xnyb2+C~d~^~J-8zm9*ZU`|s# zF=l@jPg2%5+8gwe-5}eVXCn~XAj*xSc{RxGWB+{_ZL_Z8J4|5qY+)E$So*o#O-Wnn zV~Am!_cn!tfd(+g^r*XfE{`TVpbGd~$Yvq~#3oWAN-oXpaR|7-4a2=ScyiM7O{x&^ zzz~#w#etb{#5}b9dcv}En&ecx*x5vc98A^m1-1$XW(3S!5n>rI+8@m(CNz#(E;&8t`BSh}~B=oDF z$OwyTTTUO3E}}}xZIx3k2oTZmypNCbC&mAaCi%dk1-#|xNO`TVKb3_o=&dp4=J1ho z_{>``t-O>>Y_AJ)zpQ3nW$@#xN16h2`eI@$^O#&=$pVcgdm7VX4RLx+JB5``nY1RM zy!ly9QTE5x1{iXDIUn6l(+Ym4Brus}9MpF`fAeL6goCt4S_)jZ5y)jjq^PO?oQx&# z(G-7`ki0px+b`$c<%n@rBE8dOn5Et_psjg z3~ppc<}xpl9{uvZw>JP+XMdjK?Bx)KH1daKyI9Kc;u@Vf;$1EP;RbYnmCUX4Y zqz-aehcsiWKe5yD4;9;FxA+91%|Td6e8|NXbPJYd?uGrzT(IIi&4U-rd=IDw5+{EP zygl2&Y+aP5v!Xmwa@}iN=#u{gN>AXXe-pXxXFKo2s{*gAVN;BJF`j{-hT4D29E0yt zxW&W@jZOo1bf_Gjo@@T!&>Lf~; zca96a^O~OqPU@8|-#$C8x)`-?z;3-#KRxcGAEk&b1{k7a>+4M-YYIP#R=b#wlceBbI*r07o^z#o3#pGSy?+=ua&1=fpY2taQc$*PzQo3dyUFc00m zU+r1LOS-p7a~%cSTwfUBAro)5?VcrOo7IEnjgC8w*RuVj_K^b)FRuRremw_S{jJuI zzxAOWv0!F0-jC$EyjL3krwS$?kx98n7kFGJE~U~&ZWk;R0pAL-0lzo+=q`!>P|^;$ ztX5&MB$GWKm)9VV7#tYsUNyMw777BDy9rsy(*GGrp*Bo3;F^&){PQ=b1?{Zmfk(${ z2Z5ZXiXoyFtKkKUGuCRpA_D7~2XN47VU2)qvzhjTNU6*dPo112CQG#JL zNg-^2b#Ohxu07$ ziSka|_R(iIzKl?s>t6o@(fhOXv3~x64=Y~i%%xZ-ypEkP`&lSMHBQ0nHK~C6ne6cW z1Fs6nHxsoV3t=kyQALffb7Ds`S}A@{R%(0v^1a;RvZdG8XwOeD^Tzo5C(7IqOS+6? zUIf}hGh$Vx=x^6i+R&Uj+ZX?HhmFkw(6{<*u}4^R_1~RB?$Ft6U3l|Zi&AC~M5u`8 z32g1XwaBD(bJt#?JpcQAMF{#+(PNO`59qioyr7HPd{%|T@G_M-J=#6$#ie^)f$p^I zpbGIbTh+Z>zX=-?baGGGj1dQm!UXBnBe2)9O{CS49~hng@qVj#_pllHt$Pz;jfbSn zZ%>y|^dJ-ycGTU>Vh)Hr3-mcG0J(}~!0mv(V4nAbqI*(oFd=Tl0!ly+*L;ID{$Z$o z58+vPk8kfEa9(H$vm4Gn62*v+%23?xpvB&@5>JX-t85QgjxFdA2PZYO?M=zy+V zDsxQWsT7$yz}kz~s`;d@2Pv3A$NfT-$YJ`2sjezMJo&mpEV7E$k95JRm)j+S$y~|D zwj?mOCAz|AEM!s2Om`NL+c7hA?$`DH#67H@rE)LB?a=Nw%l&en6DI866ea50NZd$V z?PkZMx0GwBS1+7ZBqv*~%dl-O>o<|7h-jr31qUyq=~TY#W~;1S^!?!7z<=?UErSjx z-twMgUSgDHr@%)dIxUSuV1z;g4w77%n zCTI`k|L2n>0=oA`nm$j!kzQE)U_Q{AisS6@C?fqgK_j=$-{;@at0k<{ZF$13%pC&V`0QOFqJsC`t+1RNpe$4iYL?h-qOkEESIg zd(`qp&Ny#j6CQW9ulHF{BmrN5m;1+M%*sqoRnC6_y}sO;8$lIBu|~9dW?0s0h(o4p z3^1yEjbqhIrn^ocHLGbyl&>6D^+#@XO*xIBtdl6=C{KgRU$5@=CO&EnNy~_ZJN}?QafRh;g2F54vxM4W8Q5;-t>McFFj6&5>_ZW*Qui^$Mvgtlc?4dxDpO z*96?lu$|_G_eP}RxDPHWLe$sWZlITnme$UFr!JlX6gZ|tsk#M4jcRjY*9n~eb!t6g z!&tF5=<59i`t~dtG$?aFs>d#IhfN^!)vc@0_86mn;$j_uYYcInEnE_#jKSFNb z4yVgBagS@y)Q+o{boSMj@dX5zutZf1x$|GI;RIaXEM%TtUtd`%$GettBG@>DZ< zOd=w-*0<2D>#JA)?npl5*Ke5F3UF;n=g5d?1itS0(vsnU3a!(5z%l+;rarIx{9;+# zt96x`xsQ)loJ7zxXP%~;{j%SvQeV~D%#&~5%_uTkVOVRp5^VmEq6ztBGw`A1?Uwfb zAn1&2n6fiYjC6~Pc(z3Tzs8P0(gtj024vkzV5rVzosoMrGD7I z54Y+PRcDpLhwxk)e#u#PlA-<077&n#3q8EI<9~hM1o1dyisf7cn11TECca@a=pFZ}~qkDO|+0n@RZ6kku$`JK@%k*l;Q~Lhg2YP->e8*EBAs)3MY_qX-$6d}IlNlTM$*rbTM_;q+ z?i1x^${(P9k=TRAUHUAdcl$;`x@{=Pv+0Y?VHIV@JRLIs!2Gn^+H7AR&^lJ~j<51% zY=qOG7v*Yrng{^_!TEkd+`$7Dk4NxY^1Vxos}V5?&ki(gxf|@QwqlD{sB4@j`Y>9f zYkGcR6mb`DB+RtmiBD-i?nbd$az+cB{3$Qc#9#ey*vH-Od?9|UlI(!UW;_sbJs051 z(OP+gS0dG$;~+E{RC1Wn6T5q-qWo8cnl^55QY&IT5NKWKxDX%h2D8;tDhm?Z4KveN z1fIz}fSjfM6y3GHA`4>Yq3r#x^eB(J(Di&kXm!0&pF269oa~b|)ysUm z+CK(!wD&>b6lcN6e$(>PZJ76TVTxIZF)$1J2>5xDTzGwZMKgJnKwJ0r0}sd z`V$Czxu6Y9Ky!fqM)|YK7%JXXgS1v3$k`GiZ46!)0`!x71c3nWPsiJ497W- zv4YR_&O6Bc+9ZK%fH5gHk~E4Jeedl;ik2m;fQ4EJ5E}LY zZ<-agsIxFu>w}M22w&VPFfu=jV-|ww!t#C|aTrzlD)4pxR^enu6}ABPbMN7v<)Sr>61r^9o{f%a&zebXJX-DXn)Qr}vZ zC(J?ZSmoN%6YZh7#+I`LyFAXHyKNyumO9eD8~Lx6#s==3Mbr!atmWAajRFxD2f~U! znAp*~#ZMxy7+(k(UXEtCHm2>EZ#!T%ERaFv)~MTn1DzPynk$m~flli(vBbJp(5ep{ z$^97yyo)w8sm_=5wk0tO>4_0RXCEd3S*QQVBMMO@=&T7knk|fC4H7mF!`CbRd-dz_ zI=K+V@GHSsG=KL2C1qG)`N2n?&(pB8xca_AT#<=EYz6d_u&@W*2eM;{mc=I58)?Z9 zQhJ2`0gRjm4<6XD{R@A*3r{Yd>=1wOc8j_4^v*9mN$M_|#(`rJ%cqZ$Ax$Z!GS8-b z`7hV$!*`-m?n5J1L0Erpdy@Pj`!=8%0aJ_(Llq^M8{71HuD~9!sB^vf+Jyu z6nm1DNcUrL;~!(=oiUTxv^fY?s%Po>ZSEkELO-HpA^QXpvYmQf>`2~b!gIs)l&w|l z%+CFoxkl&pRamf=x|KqspHg;`6l<8IPRms@FgS#r{*4vFb1<~G3juXjs*S{vh+S&8 z1$LPyW+8dJL&U|H#+yAez?q6#9Qn1-)wI18b=DLSz;@S}t)O+ws7jN}C+KJqm%?r+ zHe}lJvlPu>fCZAD$Y)iD({!zMh2PVqZxe`BzzHu&Nrq^NQrOhrYuU_R zyqBNi;R|N7L?^4i8D<^R`dh~E5NI3`MR>Pp#;77F`d>ew>k4MH^*>loN=dq6h{gx< z6NO@otqjk{12gh9^RO=@VT!9E+Yi6~-^4@T3ABC{-0*t)d#PeTd2~Oc>VrWX?xqdn zLAN|t8&p-!UpgPbZnI(fY*9LZdEn804$)IxsO9Oj8Tm)LS@*vqh1Ne992(#wpyWtm zTY1v>M)#a&;XH7DRvhFaa#E1tTC9UC5Z3?*CS$rdicLW4)|zKTqT@hP`7B-O+G`HI zS?bIozj59(AeHq+lJ$EmOXoU&kyjBr2^OC{jHZJ+4P|*;Fy-d{A;Cr=*U_>-Uv@nz zYfwJLpEb&tO+Uhxp>E>j8+Xe)w#| zazAOU{Wt^>s(QngOh*gdUz=Zxq>p%QJbKM>-UegzfGCNN8aRlw>j=I7R_NTR&aM2r zjNV*Q+~!ima+aY@_11D`QdY+j6V_I{MFatp;WR-%4zkNblJAdns9V2s3W5Vp7XMoO zK-%8^+>xnl)VJA9AiYJxRq=0cxYw85!8o{HblCvo_qDfRU&#O`J?8gzhU%yr8KKmc zcbB%4(J7lM5FptC1qO<_M538vKDco~=lb~TQH7U4D2lrx5`^+BKms!xCD(d7srfUnXBF5u6kYfK)|XC9L!Jz7L2nvx?OtXJZc^9*hH z(BB94mFi8c9Wxi-DtaB9g%4{Tx1I@c-IRtImJ@~Rv_6uk-uhxE%NLncJN7D!XliKi zTwbF5Sk6Oo#H%Hgs%nOLuSKoga$|b6T)JvqWj3Ghd1*xn>bx?h z*A@b+j3-B1RnfJ=K$} zn?KUlZibux9u%nJfLBto>3g#j`q|khY5TXQdaL{iiRV_g60Up` zEO33K_h0pRBoiprU~(IZ|3_VD6?|YvI#HrY;9A~|22M+#mp2--Qs$h?|3c+P=Edp_ z_AG}T;)+GKBiqXXom?y2*xE9gU-vV(G(d?Bs$> zPmL484{b^$RP=4+4F;E*@Pgm8NOwj{*38V6csUh2u1U4J~A#yQ0qKAJkStuQ&Nhr{6}?;p{ok`cEGue>qTFAoL+=j zgU@lzw8a`C9xKdJxRws@ZGrq^ixP9Hdq=>1eJO3-pULPuhDF^bfVSktHtKZ^;!o1T z4cz55)zCzUfL0*#$#9Avl0|A;AE-EQFC^N$l-+Ik3cjFGNoNq zPZEr`n-P&d7G#MRVAqVGeifwrynrthAFPx_D3a>F&|UokJMhBs0!D=E<%G!hnE(mk zu*+yoTheA|X2_tL)AREXOI#dXoP?!18s+<7q`lpDQKlvOHd2esB7VCHEHOdFHrttw z;Up+{&8Uz_9gWC@othZckYT^GZ&EzAs9{Xj&DmVr=YOqxRpvGyHBS?m8-cKk0K~^z zFvXoGa80<_=b>JplCK_MtnpzEtZS;oj~OEM>J84zlRn=yW87Tf)D=|`4VY!5464VwIe)jz7lNMyG^w@BYx}ja9Rm% zKD%c;Z95TkK6o%vAt!N*ebH~CpwY&Ob?>tEQVY%WdVWtU?ecas;mW{3-PvQ+E+ld4 zhrdFfDN&co!HYrZ1!R}t*`QO_Eo%>FpTUdqCp8!&qe!z;o2@1QYM~8~i{*sj#Zv3r z2sbc`d?t|N0XlpD{`n|ao_?VP`BK+E1F;UfxE$mo%UJA{c%)DzA4%du?q*_6N&Lk4 zBl6SS)_)PGu)b;TALU1xUoNB5goRmvPmy+M{3rGd&=K`hQl~}qAYu<7qB*C`EriaQ z$|I23kUu6`MM*oLX%S{x7vn*nbC)tD;K6q4Y6byl(gHrCSCOD@2+L(7kR<&&2ZtyC_ zOkizV#rEZE9<-CsP=;>X@mgV&YF5eDEgw4+p3ixInHUio7pmX3AICLM|03Rve7E_5 z;``pBwg>_#C>PcR(R>$8VzI;jGrAsxvYegz-g@zvjtY;Gr#z<)%XvaiOTZ07CKi7a+eyK$g#1ETZf6 z;!xXc4Ypj6muY4oax0Dbem+2%xj#pWgF}ca<)g+{Q6zU}frWk0YAoqTuy}MB;ffG? zCvZES;}H7r>RBD*DIAVBDRpQu>sxc}UPFCYaSN#P6}X}gA&ufep-gvYxfNW0H=`$a zIgsIY67V05I1#4LHoSErG50S(s8#k%j0Bf~>l*7?<|wKT48Q6h%KHKGmz)PKm{w%^ ziy+fq}$aqh5z))i-LCTu=dw0L@nzBUF&CRqhG`CgMOV? z5|6hUfoo_Fy=$h~Y^`dDc6+r_vHxK-+@;a`=)Nh@z#$`iU1M=TYHJX-#96JOI03x1xsq9jBKW0?N8C`y8C*s~X)T-6|!thKMP`|v#V$FZ` zPM-4YV2oW0rxw(EoX%7kQI@r6wdVocB!Qoj`>rk6w1S#ar2K!Ueen6Bm_m1!Rvh^PCJ%)@gN(XinKz! z;ATmI^oAOKn+2?I8CG4%AQ_QKH})*7KJ;MSK@my>{2Zvrto3c?bJe5JW3I;O3;TPR zqVn>-;eFM!iw}zH?L047uMda44G(|9?T=TPdq?KS)=s+7qp#E{2ukM)NsjK40 zNkHdfbo?r61w)80#mq*!1@TtpLgNkrB41!J#oR}#z6RCKGM*E%)X1lGZK~|3t+7+q zX3F50!rynYKR}7pvB9OLS#Egv#n*fKYSDVZc}BPE?$!NUMj~V1uZ|O`=a7+))2O@~ z=PO*P7jW;;ufQI=_0fT!R4v$4BnMO@8f8__u6cxWDk>yBSm+(2tS9i~pl{|DZ}?Au zPaePeLk($lwIc?y%AdgZC@3hUfHp--rv8?GAr?S^MGa*8Zm`|IgwsVq*X6nj=zyzsqT zwQoa+%5ICeGa@#5V4x9t(7F#YdOtaRul=@?cYZ7@@SnDH_N=0GR_1#jv|Nt$mjj+Z zJw#bo-g!WZm{p+aA9=^Kwjb9AGnR$%eL#JplfQiSJRk}by!$S$LbGIpFM~9hN{@+e zz#`3{Q->Yf0Lw^=F)rwLfb;vhXufQfv^Oy$prPWRFgPg*=6RamL^E0Z#4>l(eu+D~ z*-XlCEgr2z8!R{Y8uN@aQ6+f$Yt~O)*sO|bO~!rweb8YSgeJ2{qXfkP>~jbM_Fnb8 zL{Z=eR%gJ7`k?=|Mnl&=Xd!N0M(p)w(f0Z_=e|D?FkGE;@_aALrJ06QUoIYuJaIc@ z)eYn*UVAZBRR!kOg7fWHy?&qSa_K*<#XnvF=GcWNrs-ZcfB#8!m|4+%cD`KgS%s0t z$q;a7uV}r|_Cgy)v%WVv?n8(EOV=~jaSL4JJ}y4aJPV2$>`)nr2M6Wcq_Ze(p<;an zzvr;6gWCGL|8|>JjxwR>s16IiZ!EOG-7^~C8VxunxEnI?tzYGybfK1a5Sa7Zx>=;V ze?q}%AQwh#_j%zg2&)x;9$(=kogWaY-Wb9}AU1?L*$6F0$)P zpOZ$bkG7u6*K;%o+*YuQw{))+@ng;Fe%8P&V%B{(BCR;-9%AuQ5s&h(#f~t`|jJt~nn{I9M zvCT&QoD13ffh^%-c!|d7W+)qbfUD<;@drA%J4ww#ewI!0SL<)X{-{*dqP|IfdHm5v zoTSt?Pa39CPEi@7)cyrk^1~FR=X0+GK;E4f(duOP_u*>=HJqOBPS~y~4Pv>S6o;JM zJ=YtX?X#;!yvVmf$>aPDSy4=Gmf!c2auazij(lciSN&6_C|&ibIHc;jPV}V8U794; zi-Gcy7BSGiYDo3xFfI#>P^C;}%={J<@8!+qnXHx?8`dQ`$x&#pGsW4(Q@)DxAnd*ZH?FBXCIyfUU4A~f{fkVspuk?84%?$Aex*i7$6 zK_~IQ$IGQyMjo44Xx0F=T3<`!@0u1hE%boyU1HzaM9QHj7NXD>=!lh z@K=tEhKLh{7AL`ubjOI}O<_;%aib^cn0Mig7u+jr$I751ZFY!9_YGR;2QusZ_*qho zndNhXA>_8pHJrsEzVtCPP>e4th30ghgX6dIe4U`=aT8Az=!UZ9+Z;*4w%I>uz1>{- zTy|UCmkmD4`aH%2Y>FSS8mTz)7icq%%H$Z2{e-=$ENuZVizqYCVTZvlYJM)$FBHl; z-A|xq+DO{ZJ|-`A<13);J&dne-0#}X$nQMaigWW4+zL+JeLj<858aY6j-U*ZoQ2fYr-P0E@YsV^Df}ulRrujp+V}~_1YZHPk|F;c%9#VHk$>Nb+2weh z-h17x5+GdIVHV4tU7 z4$6p$V<{me38k@#89`4`#}mZ{q*SWbfET`1xZt9zvu-=Fz+DHdTWLzze%0e~h~pUl zn0+~-33ZL%g!C%lHFz`-dYjUU){Y#$<&Z<$22n%~!hjGGPjuV1^WaTO z3443C7v~W!T1MUG2c@>82IZ4|y;@Qo7=XCw{ERy|KeOJN!~%WvW1`UdI{L)-j6lKA z9nIWJ$o$d#p-lTPiwUqxp`4a3|KRM*HmqeR&2Nnq@Rf!dKR)cY9hf+g`2z!(hHECE z4zti|S1rMJN_$}RIItD9WyM}gvj+8!IqB31@gykT|2MPK@q#)e&LZ6&o+Q3CbnQ`B zrpmq(4b`2r<2G(^?GfBos7rX4z3G1OV{Ii|NsNlBeK>`KhU{a;q_Obh5eL=&cciYGN$5B%ulu&N`vW0efdC!!n)A#P8OVzGDbhtD_ z%{8S~9yxhhDhml%HJI?IC|&m_KOY~;bl=`oXtT8uuD>r~zQbV3x~F|B1Q^HX@KrcJ zn``|;r)oYe{DMoje&^6V0Y}Krcu2AK^u!V4Ip5n&v;sF68BS0__f?;{Gi@O8sj?aM ztG8iqr6KK~n4X|~SvpBLw_V~Dvy?OCTsJA3BW5?ZfdH;&_E|p)cX81wr~_8w8{3`B z3!;$TQw(g3KWXPo@51oPi;9#S1{WxY&^^yvgc{If%io4km@R5mo-FIUq)xm;%Z)<> zQ67Dl*3&&NC7f#4@epA2Zohl#PW$C>@6>Nr#k&?BIuWwse-$An@G@`W){D{DQjTG# zAiRm3u=jb%X*1I5qm<8Je$pSNPTJ=ZF8rm%ozWDEdPZSed;1&ail@g_9_f+Q*^VKA z{iPuRurd6zp_a6lXIlUOwQ0ZplAxA|?49A+mtw&OBw=l5dkFBm(u)mN-`1n|xg7Zk z@xF_)y8J~3N7RNbaB=sW)omVOYa93HFL|AWyqJ^(ibEdaY$Z*f%ELpes_%owaw$)O zLicCHp3nCnH_zgR-B^nWpBVS`yN#*n^{Pjk&M=k6LIr=Jk7u*#a3A5&KgMMlgi=I< z-T>fEMAZHidMHyoEk)-L-J5N57*x|uDc@c(o@6#{h2nrH)#)s6{Y69F2C#fpwA6w^c( z5ngSq`#G?nBnMd*ho!59_xD+EA*s=ZMpiL4RbmyH=Hh16V&zf2i6ZYmPJU#TmX@`o zCwHgUcURp!+vk0rWg^b1{h3bOH}e)gc^2lhDc{%q-Q8{=A*|c|wiBN&{WgC+59m>? zXzfkcmhL=X2cElaH}}7)LSKpGp~_G&s0w*5%ayX=%Uc#^eqry$}wKL zD&nk|c7a9WzNTNMxiidUepC~;&b-7;-N6R6&-EnuNY$esU#&(iV=VYvaY?|9%Voz{ zdu^w`MK=u=Wj5si1nq*0FV3~O&vj3c!;-EjEf!PxN!X}GFelFXC?svgUG?H3 z$%c3T;*t~Rw1v}Ms<`7_pXp`awZFUR8xW1&4x;vY%BSY&;%venqxn9Wpb~ ziFfM-OY-A_YuJF5R6mj8F&Z;GJsDBjJfryrFq;#EkhDIO^b{770_M39J_hP;+|zS| znFvvw!NYX+>ajvHYw1_S<1Dot*!OC zMVsDawlu{KvOX3a-@(#)qT$>V*2rNW8S6)wA=Z2@gbY#@8R*<4T6a0irk5q3xKPas)+SZ;fmw~Bov){ zbL@9MKi+EWZ^jph@9(9-$QWdA5gP9dryK%6V~k<(F7EEx3T*RG1A03jFyYJ(@$sT-gz&j3S`PnrNb=}jXZXh z8?d{*g4xk_yGgfP>F)!yKm7BATYpUS{aya^zWWuRGanE@EG=({ylOV*5tKYv2Wj}D z%-6!-c^gg3g}8*%(*9)r^he)G0FH9+>Tnmtjb6VDuj>HW{C7MzkE5*G3PajF?(88v{_vT`UM&+Xw`VfHY_hj!qy<;FQlQfN6vUKegvSn*6Ove zX|UdZT_1`I>A!u#e|?&3XDth2xxCA{XmK2!=tjpCAZpxQ`JqlfP!|DBm1(K7qt4Me zn=t9;CT3HSvmz7iXx!Q`XF=Vh_v?&?7t|fKokGP=NkO<%ePhd4&7sO_8bUnr+rr@L zXi>4RfTOy)8YA+vvX1OWamRDu3fj!QUF}TJSPc~NdS7e`+0FFCi(YypE&DFn!N&S5 z31OpLk7<|$6s$z<^KJ8v5+n=oh2&Ii2m)VS^T7=v;SUWouiz48VMU^nSX+N`PZ?l^c$l4 zZC>emSYq{$XwvO5qJ&;JLlEF}ujj(q_7@RlYK-Xnjwj2}MnSKNdsDW)rhT?(Rp6FD8O$nGviulj_u&_r~HZOd}8K;fP`eKA8lh4xtnLD*pf znG-)*3K;G&)32#`B_HNuOng_o-f!&1jY`_mrJ0D%s7EjPM9b_cZv=b`CU49bbd>z9 zUJsGxe;$!z>mikK%+@L9!kig_(8=j;<~9~3I7Vp%9~#v1$Tzwq^PO2<7!VRHX8T~- zkh^=vUD|ENB(B+g##X=y%lqC#CiyhdTlLGUh4!n-SWKvRH!Lm%S=gSMZiFLq6ZVg2 z-Z$&P9xZ2Axo$V-k5!hvDoi1tEi-y@Tt=enK$DXkRdc{(e*)OjrnkThr#*iFRyXDm zuV?afK$qPayv6N5X~yMry*gUKx5#w(_BpXzN?pAg53~v;(@J%q!a9bps@7A6^q=tb z5F_G*M1}N67u6G&2n3uTBeP_BtW(H6ctel0s#l@Xd0T{2Q0kcBA2;}cA(`GNyp8wC z&qGd6_cf$VLBlb5k}C4GGe?Tj@S#hR(b z?nd3BZSOpriFS~0w{}bGSMD9P^2ZoU$C!1rjXj&^m>DF@4R0ph`?+@GgLt~Ap|w4e zs80KS($fZlPQhFM%h7HXZ`wpS=$Agq_S^;J>DlSEX;lTSO`((9H!BQrF@O-O`xe&{*%dEigZbyXGVS?yKqr>tnGr~}n0 znEN9o!|B|vTqR5?Ee&2PqV-FT{&^g*b$^rXHKE$~{5X|g;ITVtl%!I3JcCa;+Lt1E3rOPb!z1NmNvb1>p#N6DWyF^j z%H;jC?!1q$Z!4m_y}>(BTW_>a>%n_=dAR znA?8I!nd<7&JOZO6h?d}Qd=VQ8*xi%Vvcc}O5GyF_1LS43ZN;`2S^XLosmqxlqqVH zgRRQ5<+;uCgUjf3zh>LM5e)-Bew#*;Ebk|wFO`fl0n2UA@ay9giXGo}b<5~g?{ebb z&k6Wi3*gz{3rNu12la#meZW}*rkR}$wqJ5NIo}xhpe0Oq;C7$LT45UOapTMK6WJ3` zzWv1s)gJED)K;q5I(l{+x~Q8cW~8s^yr&rohinF<%sNy=~v~$H;=N9 zjBiy(*(OAie|<41i@>dlDCyMYJrDBgQZ z`QZf?(S4gLS%I8nSrJl7B(SPx?V*+#0y5)>Lp8Bp8arkDJAwS>lnM=VlF6)Gh@>}> ziaRo4cqM2Q#n595Vq~taNUM&!3L|%FG^`MfIR(mo=ZKwsJV|U89_wm=S+HN9dHd{C zk;YkY5@E7ouZv73xgiZV%F(yZu3Rj9(CyYYp212P|MkV`gIqo~^+!jCSt~|H$%jmn zPgY5-DXE!$R}pel=QDFNM%!WA7mJ!Hv{G}qgTuPZFg@)Rb&~2WGk+4!Ri{+c{lmp} z0-;q)&N2`%cnf0|4AD+ySsbagTrl48#bPP8Q*Fyrb+%9*)=~1OF*CS(>errjgD2Zy zNc0ll@uQselsEnsFx9S*nXauC(x3W`sF0P%8(B24rMLPPxo>XD7uVnwS+zhefsPQG z>hSti^gkmYr-{)xT@Wa^uUBuZ-S$HCFwKj&DhZ zxstra&xXFWAr}>YCAN8&B-cC)YS;D{bpaEZ7V@pK6+Ydg1gjB$ zD;OPHtC?-b|3i8Y4$dNc5qS_A387Vy)qK~+EdmKOQ|e>TX7#-8*}HGbQWVDb-DpDN zrJoNCSui2>Y)aEUmq}lNcB(JKbt(IO05kQU=hYEXqFQ6t?Xst=XZ;BaTG-XjH1 z!%LDsVVLh+2pjQ_qN}v>503NtAoE2_%S4u_4Kjk5ZoF~~FL+G}Gpp!&e{5DY;{j0n!pNSQtT7xumRTA|I@1Tz zh8d1;>zrKLaTgbAqDJzWjC!;hRwggBie%+yaPM+y2^+hL+C~ILUu%iphSHxfvRkDv zSs8K#^0v4T8O0ps`a{xbr#=?-1DgBB^9(yK$OC5+z5>tC8_4GaizlpoqRs5Ao%OB5 z+0P5_l#b)Y+l^c;lP;pKg!3nqsMHu4r-Dq;wJ?mI{N7A*R43RKfb-ILv75f^ciOl% zXKo&BCyh-?DZJTKdDhx=O0rkSM71KzWM^q;<4SffxylKx;bMM_dgSl+mxe;<@gwN> zG=(my<-o%{jO!Rc%#zei$n8Jckg_mj2~KPDoJ?IvPiuePl-I~TvFZZKP=Vf`ye+01 zw18Z;l*mj0&b#{V>IbsByF~(l%Z>iKmq$`%4IL&fp2rX^J%ylD@r#Pe(gZKRkQ@80 zkJv>{#o^4&z&6|+Q9ZK>P}w$tc9r*iqz;-i&OzjE$)qoYN? znF!3Vm#1(-pl$m-JWK0c4lsL^y#@OJA6Y9NpYYv*2s*V#|G%5pmJ@t-!bkr$M*ki2 z9{-NZ2s?k;z_bYrEV3JbtSq)5h1rpCnFUb*r-? z&o?1N9z~m$J-AsuQ9jR?StTZ!e9NZ|&n|+<@_nJiF5@hZ-m+igQlm_o(K>$l=L8t{_5EzS>3%)vC=wt_Hp1FyI1|I@?a^04zKaXxty^uQ(bM7yaQaNO-a7MNmIaSyc z_T>8!86lgL7SiycrC{Yrg@8)oKffrv^_TEj+J#9Kg&tA8)1R=!u4~!92)rqzCnU+? zcSn>iGFq-hG1i4DQWB`|<5JT@-V2-+a-uheS_qsZIV{^vkss^aDwF^Wl-l6la?s zcFYqj!;dTveof7siCsaHQc_ii9F!o%SL#C^g0<=9QcxyQYr#1e)d_buhlrX@4RB@* z8b5P9xr(B`HNj@%3^WjkLMh-7n7e~!mq(G+@?)15OoZYf#rVKYl^i2SB2%tHd23Keqs6qV!>5kImVF3M}S)ZvqR%3%M-sDKKMPp69mW0ex9C# zUte=6x;hCgmJK&MO`&ja3(4|+(4x|`UuB!LoiA|CRe5k+dVf0bJZ1SUoV4{3wS!EG zBzjX(5RE3wy(;xL%iRZ{qh(KbS;+??Lu7kT$%(u+Qsx1|OO5@bPm=ja@;|g4JW4j- zl!gulqt9+#FDS=K7&|YIw=FFgyD@3$x0eRdLO$B$GrO?Q`!yoLmmVx)4T^vEzW?M6 zX_7rIJB|s3r`a@teZry2YHEQ2s6zAh)lTv-}zEdH3UJ zy@7EyNH&k<)~T&*dA6hS2rzIEHd<+Mj~aUrRoN}CUya&GRP%q4RKmCExMfH(Ht(h9 zq(s0vgh!)kHs3MS6#d~OXRGDuYUQV*&=*M<63*O)XSQwTK`Va-N`2quJ$-1z?sc86 zy(Uv(w;U*?N6lnnVZK`&7zdQuZ~0Hz2>yXp*S8yKNC0i*6Cpz)%S40CA8NbIr5Yl{ ze6Sn@zO%* zbx=~y3NkZ$E0@`ZY~aQJ&T*Hy<6?Vg*r>T?<}mvTu^n?cBJuFc3Ob$iB&&+!aJcokYo7U*jL%ixR+5m{_-|KR zr;`QwnKCo8?II_nn~zjZJ-rg9$7)}`7|xU=Xeu`$58<$M>`gI@z^?^zcRHSUuh(>=0f3W~j|m6pA4rPI6Ex0MX0 z%S4XjQANcSQ@ra?gLxaVVkhQ%=~+j8eN+#p!@vwF)SjC~XNja6A=CWnPTb1)d;_{F zI%n{M$V2~;7Tp>ACHnbRP75p7HAR(uH zchRdV5I$YiSP)fzjNxo(db$9xE-jyTU7gU8%TQgVLFV! zOT(s}-6YuR;lJhHcatJ|g9v-uSEhaRKgOyP1s*36`84j(KF)Zy6cwwdk*@NBYHAnWEv|?n1-=T>&GRR_3a~ z3!^1uQ2gC8F>=gnrq=Z#AbC*D7@rr95*#yP?3j?cPNj@MMvA%&FU(t)+OlIf>Y~(fX*@$Jl0PI2CG$I-(yc0OVE0R7cjE!~qnp#+hH3BZ@4QU$rd-pYUwfqUk7eV=*z0Bi5$&GdRzfh=R363uCf%>h%k&;k;)lQf0U|CQr zZ=s21<9EcDU#AG-BK8l9BODVn3+AJGB}A7D_xXB@b$j#KC=XXhf%?n*KUG5jAw~fi zQ_x}W(Ob$7vmpYsl@W&L7xZ$E`Eb8?8KJEf5KLRO<&3M?SWoeiX#Tp$LqlsrPUsb% z>oEi)*QI|T<5mRd17qUSN*~{W6$_3jH{8_a^}Y0n>HiE>nV!Q8rwgGNcs~evKfMtC zl`5$jYiySkoiUV$Fsf0wEn3$b4Y%di|7rc~UPSVtgyEOOO+&R3u_d|D^YIq4Y@EBu zwaT#yhf;cMz|DTj#^WPAm5`q2#OI=t5(m%O$f+?9?0Zs&&`nF?Gwl zmD&n0e1&kmoTq8zlo(enFmV$L`5;M>UfAXpZ1V~IXV&rWsq^8VmC)M#uAfPiJrQb= z_qPoR!!yJF?*EiFi#<bjlx z9tuX(%nNWP`A&s`TI|I;Cc2F>KhrSD@0QKulk)h6v|Xt!ggsn*t@rA$7+|3dT-_D_ zw(n5Js8<5TOD_^&uz@ewFu+=azx+nsMJcNJUQ%-Wqdg^#}*3}5?=KiM9>bsA*}kOG<(mn{AX4!tXts+YUTdq=ud!am&}+ICvri(~8!y&e_^Ysx7OTXIi2$$uJf#{f5Gr-jjD^2Xnaip%!a9Mv zb6i33V!a@wiYvAm+HLneuRep*DOF&a&Lu89EqXIUq`KW|PHYJofk|ztLPI5|j}w?8 zGDe1+X@9U5#VqBneD)x;CYE1x;)6s z=Y+j!cVTKe(rZusge5)dcP{51VcQo)ABmUKIKJ`I{`*{z#E;}GEBi~R`*&%sBNN;{ z^M?$(2YrUm^<=|E+6*`Cc|2@Xx^qdf^u2eD?(cw!YMlMJQGa&E@HeO(c`Pfn;)BA@ zG4b8akUihrU35>fH*Cn-QTR*A0hE>v5}0<{{)~CMdT*oj%9nMhwob^NowA`S+n zyPBWA1-5#oyQ3X{5~4x^+PwV6gx@0}5uyFhDi>>lww;n0m=h4f0%hsq z9AsirrN{N}yBDqBM5Fo_k1R zgo67dHzEgTiNr3?R@DaXQcHNR)nF9hPrUBvkO_B;34_lb=+R8Hfkov>>T12-yK$89@4Aro-o2|iwl z+UU1AP&eF^mNJ|TZ$_{A@xO*g$YGKtqd7XVFQZGt)VIpzBL!*-*Bisc6+(KEXeigE zCh|X@yPGQI4CfkN9f7*+(q;VQVJFUXF<}v+Or$mz{iXHTCgmw2oOQc zOFLALyyZ{^i0|l1H-XZhIEkzKr>57vvhdH&uSS6BFsf=}9wEhfUq*DKH0MyG4PG86 zkQC4tn;IKDJWQ0piGu)Fqdz<%JyN3VY!Inj@YKOd0~;jg&K z?C(Gaw1y8({S=5iD+mC9zWM8})#z`v*&Pt)_)p5NnubQMYJb$cV`XcqC)xKZvrgFk z=zgz=aCMkbJ_JzIX{uDc4(bj@R3OZ)@+gshBXfdGCjlK<2(IJsaUVrG`u!<78z)Ob zZtjXz2k)n;PtO!K1_Us4_zk<+G^|dK#A-6{$Lib->x{J!M}_X~7!9hW(dy}*sTG{L zFi*_K8~~8*&u@EOnGU05$^s-(7IJC%4*({H!S~VivvLSC?ZG@gF+WatGY8UQ-DhnN zz9%7>&CuMY62RB!z6jH9lEd9?Mf2dH<7zN4uCFF=e%};ySl}JO!2LjlVaJ(j&wEb^ z{dfqDxzDm6PCxYX|lwg3T=$*$+O3#p6dtogl3r1G2L{Hk+fmptq(eHy%U@r(~RR85E0irVMmj@T?H_WrEslGsW=~-l0_&4$1 zCTL!ajCFYNzL)3y4R=tKPitI|uMj#!#UKr{pvD?B zE%o|2S9)w%B(3f<;Jzprwoog&m_zP#Fo^F|q%4K$k=8I;E(hDS;x;_5#8f zoS{VKzET!}NZd>hIJ)9Ag$}l7*m76SoLnZ>>um$caEW}TE#6Sle3S_e`hDGNZSSl? zwsxGgSw^F{hNINJOydPpelj!u8_jh3!aN^AA&LA|@<}u`ue@SPe6YeqQE~I!uBwkr zqpd$6u5`>fOeXm3~-Rcn^4H1*qDPOrVsN&c|JrMz;}X?*y; z)ECoB4JN9re2ac}YlrTw#p*;Z)7$=ktMdOnauENq+kxB0b#DCwD4AL9AZA=AVxC7EVWM5yqG{O-`cvHYDuq z9I;G43@t57`pop#?GOMJTu}*aQgx!yeRVz%=I|CLX}FtZs?czy3|~dD5_=6@x~Aru z;-2mAX{5>4_{{)9^)iWDzSl(2{5Bew09@Y4H3}J3Rga*4pcuy8lMq#EAi4dpjv8dU z^dPT-*{_hUhVmHGVp{H&@}T6}{F%5O>#zN9c@;#(H!p@rVGAE+R-MPGfBWE%dZ;|( zT_Q-4m)wYx*{Ba<@s#+}ms+yfZzy8&{B)L%Kh>>OBzli17W);h`Lv0mnmqsk{y9{l zXd%LsWVXL&x6Cv}O%Mm-PB~oa)lekSS8Q5U_S+*ai(9)i{?lBtOtN-z<0L1Ec>LLx zuMsjgT$X8rJ@h%_er+pjZAwc{hlJtr#|+TiF?@e<^}Lf0Z^i zVDc+%w)6(n(*%J#I3^D>$CRO=P6+GRZlw|>$+!F5p+EK0+YtJqn`PG;by2hbd)58-a{>-!YBE-z6ODH(|skvadl zx^_q~C9&I7x8`y<33F*ZxXgPH?j2TaiP;`?tZ&HZ+dEa5hTH5y;7c`@-o5wm(*NN5 z7iJxQ4h24<{2>h)5~$`SI~-A53fbD(T9z5B29ypE_J>kL@uG@{plEc-dw9UBOifZU z1|v}UgHvN7nK5e?&s^3mfXI=)O94gUp|GlicHp>!ZBrlTt=&85V`6lp0cwi1!l78#`eIK$TR zFhMStsvX<}kI6oZI`zSF!o8QCTD=?jZML7~#H$SI8C*@J3tk&>-w_wwizdE`KhXyn z6F*G5`Ri<@fa$r)P3&+94CFs}GMah=A@@T94Lc9bfPQLl_#@xqRy)7suxx%Q!U2Kh z`E9$tufqNHKrAI0epXCPtYw)>fOjArfpkYrY_djIt_sb0bpB=>i^Y0)rH`ch=Y*Z& zAZf&c)0E%}iRiQ5pkTVjK5Q0@A`L{K-E z2Q9YPr?q})Z@7JrUoNn@rRG8mXL~mOQbBE=2x;SZUcja{T{a}*$=|UkLu|KxyY!c0 z(pH9CPRvDt#HRh3JE97X=-)2se~)nUHA2#GYZU%tIM3^ktad;DxflO=&Rb5-shn7~X7B_O9PcQs#H-r6WcjC93RUs#xQ_;&IxLNLSr>*zwZLc0MIK$8H z)IXMDBsKjSmsoVudygp*QR@pA_eAtloA|7A$fU<&OlbdPp?jL#O*ylLE~^2{Ud?6P?jFn1Seb-FZF>d zMv+7dW(QA4<&ZuP2mRy= z5VN-;awFaLKaVIXl#_$z7RL6|hce4_3la zjs_cBi6l}dO|ZtCn+P3S1k zu=S5_E;a=fxx1DvK~`L9Bj~>3Js+t%mjc*Y&aq~zzC62%Sbnj>ImzWeuJC{AIp7Cp z2+)p{?#-bkgD@J-C4c_xIIsDyrN8rezw-Xfd+qVGe1Q(Yu#sgfA>w1dBb(2YT~Ic9 zB#oz34waj9wde*#BXnp~SsteLUa8F}`yC_iO$^KAq%Tk)T-3FHdPDow4p8zf&dxG0 z$>Ik@2N?+%5V5JC154<<2=&Y|LPo77_6ZlFgG^2#-A2=MbJ@U{_2agg<(I@n`F;WgayX+!2;2ESYzO!I|UMI7CO~SV?M`xZQ8`jzABDk zE*bO-(AFoa*I&9N>Fh?qdtIFrp2ifN!KOIkUFQP?PGA8d(Tc) z=}9;cc$)Mn3w;o~=9`?ihO=R>q>@2?X0572vZ&7!!1mAXO7}s=OnV*Q=T`;f@SsW*P8%*6Sj6f%6QT8 z_G3e7WnaFkr#F?ClcqgR>{De+q9gTVL@A-fpsk~WdG!Okl_hcuUMRPFHa1wEmFCbj zj8WB<>DK+Wr$FupnvmXjDU&7UnnZ;d!hE)AKab=Wmz)8-JIXdGb&())`{`LJjJSty zQ7Wqo53H64U7^yi)6|3&KaYXUxc}sxRVv$=Y$7q#9D29>c8yL2O z4TXY#Z9<)U`YG(ysxv)^Y1(A@I;p~3~> zTmGS{rk`oV7XN+E{qH$}oalS0Bce@UcU098rwB7u@OEZq$1Iv_R?{RBI4&PKo-%e% z1$}PsAIBcw0HTpqIJeoOOrAKU>g%dH_Bh2(!sEfJnIw{t>NRC=IjX-(7m;`}y=(g0 zWcM9KgX?5MXs5+0Arg_lFfFu;WF5Ft116|iOxML)p8Krs&RXlwr=sJ2eeDzgf_A>J zM~#t+eEEVJw%{sp+V))4|9{9j%c!>6tzEZ;7HF{scT0-9yIXK~hhoJ`p}13uCb+wn z;$Ea^2wL3TU5e|;yZ1i(eBU_vvjSr<_>-(>t~u{{UCa0DyEw|7rPd}PoUBdg#aV7> zF@jr$q+XK|vu+npyYp?01vJf_lc5&t(+sIn;~AgEkpWWb7-&4eC@I7TfSa&OiECRe zND25!Q?Z(j%ZhzeJnj#Qcs__z`0QTJ#LsE>=RCeja|2mYM@sj$_RO?UVR1|RNXH+yka>bwA3!&fD;8f zt0*r^JO?^C>3F(%hzZ%tQhLiuAr3*#x67@Wn=PFCLEYG3l0ae=QO&R#H3Cd(Vk|lN zgsS!ACxq_)ki3J7hAzyKHPy-3#XA@PYr+|~wDH&gR`jh5YfO~n;!^^ZMiepgM>_!hDJx8(Zwn@D7zX8_-q|MlCKTA0J>yjUmg*DU)72V^FJS>5NWLS-ZM znH?>#dV_tR=|s74RJVd9Pcg?XC1GMoDC0+SY)2pBe2IwgBbmF`l`qe>samO^akwwa zVB*Lk*#s6?B7ma>f`hfo<6LONCDF3mw%X>*_vl65!_LC<%Vvn?~}z$Iz7L z)56nAdFYn9L5dDRBPhbOC(rry1kZ8H&io#ih%YM@)<%V!XivIUbs>R@itO_Z>a%%C zd>qt6n;YsL)#sBUQ2Yv1c==6rBTfTl+g7HBYSE_SPs%Cs;u+viS!V>_zC}5QqvoU5 zVl_q!fpsT^$?I&`Wc*i|F7}Y#<7*cmIR*}Z>+T0x`hB>BJ0Asw{~fbBC_Cx5&*Hvw z6wUa{?r=;oZ9DGs$OcLAdl9+8en}Z^k#P<;2+IfF4(9RNzr9)E8H+q}Xm@IQ)x>TD zQ>LBk#FLX6TR5<>OnVl+u)Z7b3`VOyLU*~(>CUkvS(fH5BdWa7I40YLsS`sh%#j6z z@|AAsjx%vm8=F7O*6{^FOI6u$1~ZiuSGiNOwx0C%br>7#hK=z@VWLEpD9df?sX{#5 z2I=sa%&`U|Z`=mkNS>qbe`G2UAYm@1j;iSScMA=Y`d)8*0x7?L7qD4;m3q>A`x-&M zmz>*AL=7iS`5CZvzCZFV(1LsUfwA6dsZbb&+>1}(%YI%DJLk1f37tu(PPV_?c4N=P zUCprkEq&TA3`NX0$A-3;GycP*#5+2J%}z!sweLx?8` z1RVPJvm=^rx_43PqEWcf2!T`U**s&(&kFULF!JNSpN01{v&O|yF(&SaxYENV2jb9ujVT^p=6|rC9@zCDO78gfPONfT`gdD~!ssVNn(nSUSl9SLUsN&Tt@2te`N2KD-3D6!>(k@DqoTPLYGNC4vtIA3~y}} z0!g`az()pTK5Bn(b#+x$)ur>@68}2KFqC2NJrwk#Ae%246`&P$$B|@S@Merf#PK%5 zi_o9@0>@$;L^7i6p-j}ct@5K~>BpJ1h7$S53c5ufA{HI3;X?aB7kHhyNnC)1dfE+# zv2oc~^Dsl%BC-#%%^ZSf3QB{&E4-tU>fMmP%)02HlT_!YKnQt!P|yo=y>IBw7UYNH z%mj1XW{&&e+`j41r0-v($t;)L6WC++y%5b}r39&z2Eju6&c0ag@i&9d-7x~o@a}RW zFn8IH(!Rec!rz=z>`I6i{&*%n7g5;_eKMurw!6!8SrYDRBlfm1q!oq1ezKbRG`?2# zC4}pi+tV~n_r=T+2zy`E{eKU-A5MFg8twkmh56^wK@#Web}9NC0fho!D5tkR|73HV z7tdfc!oo{u^)_e-nh_zdBPmPE4Ru0dvS7Ou>9QxX2p6IEcy+b?0w5fw1jlAhmNEgM z@u4iEt-pA*7|HdZjtH?azTnh}-jh;;hTh@0M#B{O==ws{6?Ve_;>Z5$N*5G-QfNdX z9VR<-i*uYVPpQS`z2}7yt+OF?dce1LsWn`RpEMIKDVcNbNWgQD8p7}j8zH*AHn12R zJ}jlCCWwfFP|w8BebNZ|awM4J@QWHzMN$GV*P@e6es^Cl$4qiT4O1f1MGw~JGtXz% zx7Y5j7O?uvEbjA-{IDT%a_A8vKdL{k8QR+8@)P-Kok+#a;+}r(AqzICsK5Meu%Wjm1E1lGTJeapW)QAwb#QCn#A5`@uPaN^moatbU3{-Th*Ye~dpp_8NV9rXg zv*td5Trh7vb5Ln0YEgan__<>1)imw=HiFU$hC$_`Aevci>oL|wN*Kzbm(I9WEWLj+ zW276~f63h=p}u(q-lQbt#pku;t{jb(bD;mI^hjFSev2mZ?8U&qAoqvE1*8!ZrJK^B zka9++Mwhzzo8NN#t^G&JvB|jpo(DOwEh=OYNA?dvvQQK*@fIV$^TJlp*Sps8z@b(- z#V8y~>C{_#ooRWQVa5ZKj|G#xC7B$Qz4Frmw4eH|$`E>Co|pGg1oW{p85xEdF3Yd^ zZm?vjg=sV%6ovVYfl!w$8=qU4`<5kjR#>@oqIJ2q=61h|s88&|lP~wj2O+fwLN%Iq zK$MT0x@gl9Ki4T@@6Uz~HvZH)`Jb_E44&(-m;`mpoKU(ID>F#B>(WCFkoUqhu3QEO{X-qyXMU>3!;ZN*MGz5B1m$=H=;5RWt*(hkX$L`FuwJE)jiaD z^*VxBb1We%>%-qPb&Xck@NNV(P29-gXTyYC3mXxq|IX~Sme}gK4DF9%ctNgyi%58 z(R7nOe`CKPt63O*v-%f22Y8d%BWbQDCXXJ9;9EAi>2T}u^CK)L6sPd;6KYW6quGF! z{UY^TF&DUtP08UEfJ0q<+<8lDCeON2`Bb49Ndu^vMy7n)6q34_wSjNoqR=1q6z88J>Dp-;*H~ETUzXypK$r z@XJs8DUjj0NVS`y@%{MmTH5i~%kiR$aROW7(Vgqu_IB~@9FvXYpT?n{lJrUPnJYdg z3W_&&ZwCHvk;x0r5k0E+x6*)@Bw(3UZq0N_uF9_0K8!zu%q?u%8WZOW4Yk0>) z;?>^_p54eofLMFmd}w@zco~gq(eOK%mM~src_9^)o&4{>$Z$8kbyl?GlQWRRYH>a0 zEhp4|R(5%7#zOV-}sdKIyjn6q~r?5 zg{Pt@A@T9y3r-!wh;Jd!+kZH4|9Fx#wX_k@GZLii!$@K8%dYwvr;#N5yJwdp_7owz#|4i%}V*V_@iF zZe0FeUd{yDnUO@?RC?>RboERk5lU(aA;Y9E$gRefuhmuKpkaupYCrz{^s5MZ#LbJ4 zz{KZ_7~m}T8;uX(?D;_<7w1?~YvcXV-B?Orf4s}YIa>4=^0Z0}M}1*ColA8;cz3b7 zjH|2LSW(rB*ROAFCO%L&ymK3CphQU}5(mL1C#Ov>%d~XcYH%5Kn8Xngw}grc*gy@o z#2R4&VRwdJJD8RVEev$tpM7MFT$w`oihi%@pc4@;xRH~j#`XtLC9xQXAf_Ogj0(x} z0!Z7~?x=jECPc;{(p{(J@SfV}XpORfyG^(auzUj$Gi`pk zzo*OhD0{OpC8wk$?p5~CK85&4!7HNz&`(l{D!&^=D|<3R>upfeuP#qk@O~Zfy#0D> zRH)0(V3lhSBlLHXzcL8P|7$HGs-j~xafX%i?@YleqS6XfF+JZ1YafBO}<^+d4j%Iw)J z=5eJCk}1_Y0NK96WF|hGc! zWl5Q>n3a}PAG{dgM=YV1=p|L7!p2R2)1DRWvGR<}pDJ?Ls6Z8VIVz!FmYR+L%zv+A zM&yv~GmONEI7eUsQQ63*4_I1F+auW-0%x%oxd8U40k)zuvF%`*TzC)rqht_%ZTI!(4vAemehWZ%2Fv;WJw-E4DApQcWHr(lWuQ+RdU8r`J?_z%r zr*ZL1`o=2;Cm}qD$p?OxNG0i<6;#W|Eh^amm`GOhSN-3bIP&Lr`W4a0xrr4wL~uU% z0by2JNa^_Di{QVkB|SgL9^t2lo3ec)F!qwi+VqR`d~UmT9({h=X_}7ilng5YW|-vv zOb}uJ;mTcv>m%+|~ro9_xJFw{B^-j(PlR2T`E{mEG-oNOe_Tqw?E zn+d+inVg}yj8?N#(L^In6VZpHgfcUF2N#KB_Khz=Pynv%f z{sKFl_VwwTwRgxaC*3OMr&Vidv~aXFXQY32@A-=}>)s&ZYtpkKB4OvhjX{3E(E1a~ zO9~;v+uN^T%Lu8G^Y5QusRXr3x<*2YdgLYE!zss{ku{erP{mwAi1*pOx49JW_q;tH zquoHaXUSLFZrPnhZJ#|Mi4&L}i!Orat{hsgFb zr#C_U!=s5@{52<5CHf3sT;O?thcjqof>b^kwGCL6?F;xf|8_r;YDNb!hE3$wmiWa{ zBN+!rZM~l%MM6;5oqE@327hhbcBPDX4A#mcAAyN4FIgfUa5XN@zF?t=Eu`kfd_7|q z1?D1}HnHyGLTz+} zp058LWn&I@V7brUUoT55xoq%riD{B9hAU^u{(#(sS(|94W@N|md2JKMt$1-Ttk~{P z)3L7B)k`hqv8p~pd|*k_0d$oZikIshHllZC(KM6%;nFrTW6=jR*|U+L*rUgC+f%@* zTa^TRAcgbk<8L%cF^^oou-o6S{xs*BIAVEDi6%Rcz^9+3^EBXJVbvI$I7?Ga{&h_l z!IRMhvAiGhKw$nzdA?XrPHBVDOW)(zDSyHNaS(BQpVn^W|8UzZ{`n{+B6q>P_m8;n zSgD1<=GGRa(sm2)G9_Gc{!J{a)_g)(+8YXO9k`*va)50IQ*QxaT4vt z+BiB(+kub%l2&>i?rwP((?2}i?a-+93KNY_9M*WLrmhh>sz6}=HS-fS$+tt(w_#fZ zX3l-mgjLVVI%j36<0r=o;(z@g!KNo0bE3(3;jK; zjR+oC0pvkYM??;o%5|%|&e#dr&5^Z}6U{~r=VDZ7SXy_f4>`T+Hs%FVjP#1azvEGX zA#V3*!)9)!GC;K@R30Ah zIc!kA{cSn81-q(%E2Pq2H}q_Usk?!-WBOc}n*+a1#@JVwx=r$_RH$Ox*HB=w;3}yRWHI8rCckHeC^_y+U8u z2qBjzpECa*ZjXi8rGkcpyc}rExkreDKrdD|DkPQg)l&|@j-!@CO-I9ipV>c8&9?Y~ z7T#Y_NK8)?8hXj2t|dpu;SQRE-Eca|zJ_Ry9LXjp;AjT{BBsJOsG)cytiX3c$t1w2!72RM=o~_I z5RFXf5E&(IIB#($@dVE9HFv!%pxPdk9x@3@(|y0qdc8gv@%OAZS=4;`uo zcLSg#>||@kSi^g`TPJtTO|q|gR5gzrFadap(#2 zZ4usBZY_ilaj)ZexR_9}Yn=6oBIagrk-IhMw#NBTF5V6w9_|Gt8-FKpYC(HML3j2c zIlHllMa;#=T^#ffnSak;mJKO->5A=C64i9=Ow66NZp9@6F+VZLjd6hDh&&{cFA7Ft zJK1+Xb1y8ysCJ~VZ$weckG&$!sCV*BcM~i{qhb~(3)vsp?k*NE$pk)&Q;O{ozp+mb zMAtzhLH&+K$tZ|LBZJ;64?7Ouz}$;G`o$`nd#z9q+965V@?zPud2=d2mn+0G3gw)= z8G6xaaa#heJoPk}!|3_brhy$E?HKD8dlKy{Q!k!wNP`!=8rVU;snDB1DCR=p0<|Fp zpciIHMd7A+PR5zq5H5hC%LxF{zG-RD?}(j-8{d}&1qBiETHLIirr+<1tu3j!nT-m6 z6ciNE&~Pd|)F4Qd`DJE=Sy@>xO#+Y!G#XrG>c}e=W``3m0{XmamS2ZT^R52Lclj;u zuj&tQAig+FKz>zfP5Gh{5G>?+`L}YC*=WP75MxbMYCkEgDZJp#uo0XIcxw6aBXtTu zlNw!~eJI|F<0l{r891WKfOg-lCEeRp=jPAht!a4IuciTF0VEM-Q5{*EsF4wA8LMI7 z@|%yL%F}av0IJHTuB*c3$?1cim?8l_>JuE!tK#7Z(N6yMpjWeR{^O4B9Ib-FpsM=5 zxG$g4VuFl?9INKnUSI~nCmgtZdF@Pg;P?~<9b=_h7xoWGzba`F;fD6Ff;H^00#RE! zqY^4ySs7zq#5NOzupah))~b@G`aWf&$1kD060#e&Bb(gd_t}9&sxglXw-GJRqnPwF z^KsOOuWbHx70sAGEPl*s({@+n&=S{uP7CyW^C(j4fh^KIJwqZ9r`_2M{U#ytZB#OX zCrmSsN;x}ihH;*=hfno*>siRT}A7QCCv_1zfkL zZ@~{Z-pa_$v{Ja^lNU+&-s6+f{Gg^DV{#uihH6yPXV<5(D9~8PR0`pg$v{y9!3o#X zOP$<$RO1eMl_hIj`o@f$AH>PntBNU7JKx@{Td9An-(1Ln<~|tDS+_2V%56hL-iu}z zzj~T|RS?o4t9+q>{z()IMm|gSFJ#$@J1s7LLt>M-ytpf(<=lbUF0Jbf_WVL(${BB9#@{L?4}rCR?ZJ-w5ET)EbNIhf)EgxF<1q04V##y3d3U&suAvy%nre3|^I{9HS$2b6wK9=S)r_-`f>;3Ytl1dc; z)Tv-y@-*2vNNPmPLgqL-&P7|1*7^>y|@D}vx3G{u%ha;8TQ1m)x#Po{pqf<`>OJHPX){$lA;U1;xK3 z9Gq9XOU1EJl`an6gM$NAJ+;8Q76AmejUiRCaJ&E6xkUV-%<4%yA0a*f{XG4h0dONm z)c#vL6laefCNzY=-as3#Z;tyLP4TV49LZsyI&d(B9|#jaQ!N!eN<+b!li>vfS12!g}k76SMWQ4Hs3X2_${Nj#CVIX z;uOJ4hN zgfmwMo8F&5?KuG4Cb^=8cabM8#7)kZJ^ z{UvM7K1nQW6nuHqHF+A-r^_AI%9fJM!+1{B{O|$8C@dwO^5k@XcF8%m;Zg=iI)dRir^A!S#AMVCn3{5*N13lo3yv(RV17LvgG@=54J?4Ckqdrd^13=4vwU=9 zF*ah8^qK}^~$r1R^sD}+NaU`$T>?(TF&|dry!DlUZlFQ=+A%r9;Vg5xGm-IL}(w zIW7dYxq0`G74oZ2bYV)e>uTTIMg85`YQzfn(Ls}+fi7al-0yaa0Kw&vC%KOy+Gq;M z$RN#d-7k&#@gBIP3LQ^+1?OcQ$!?!Bxo8Y=W(wmacnoURlDEs#N0R|d{S98`8;!zC zco=Vd{(>0a;UdKT!&vV( zX_5p_F^Sh2aSu7BeRiPEpxabQXBl-gde>+vV5TcR_3q?IWH;<{Pp7wsl-U=tjnqkK zpJY%#AmG&|g}hM0ZkHEvBja#r_<8it@sB_%{-|bF=G53&#F`hY=ry6S_nCa_?Z7+F zgZkvNyFu2~XdRQ^qoT^1PyoC4v|{V+zMJP|C=9gBd2{o~%jSRl$$@e7DzPb#T`#7& z#!utiR`RJA*2WnqU}O`4~ztoy5ALqNr06l zBcoxeQs<`GDV}d!5~VgV3i2DW)IC$OkV#4jI04;xQJclUZ?vGZ9-z3d5t6$411eY~ zFktVU%t!jZl=Bp%2yO;6*u)D833K8Exjai~li`NUQG#HxqQFk2%iA6nduGDZoGJ$@ zgfl+k;ekgTR7vC87n{=OuEib-VX)AcEh6KneYbW7`Aiq79~t+?J{9;_g?<-bf|Jn7 zXRV9V_*&VBP)SIRFE9AZhJ0S)1*_4Jq!5<~RZ{t9*1p4eOxY8YsCFauIAS&n;~ z&q54?=*(nA)!#bNrA#}_Ouqn4F_q78jPLH}nF;ZDbL?xqP3xVOLI9=k2Om?V4+1*8 zyTeJ)axk*n@^m7H!)b-z1)6ya{*Mq(or?5 z$ntBo{r=d^ye^71+Xo|ri@Up!L!Ajf`m z>GBTY;Wqn6QnQjq$Y+E728#&FwiwRy8u$yi6Q7#674jfJsV9wP;?h0a~g=6*QlLBk&YLh;JCc))=P-+RL6aVEqAXe)yPag0A277+JDduYW z6@6^gR5;2Ig0N`5*_Z&3lH<$K%>8C4|B14>7t~FN#teiJ($jJw%VQ`W#F+dgDrr|o z#Tut?3kK*nQ1BpIT$6@~94SEFr(-&0gy@%fvZKr^=0m0H96yD_zd4+%7raB7#n&iE z`WZsXyp*qQGQWN6a+*a}by6YSFQ-VeeI)nS`6+HPcTRyEe1#nkP3sc7EA#)`T>9sn zSiGwX3T^hhzT7#Tr197oLplCUbN!4JE9@gm?zc)VbbH!%vj>Ynm4B|OsI^vx4UP&| zxKPA50XLZRT2=2RuyxiUbaWGl8GI}K{3X|89I15SE677*T|jYdw^X=ai*&S_Rlt7Ak6R;

      1. {4-HEBr1ZwLT`QxoRP-@oOENRRo2;9raqV2vBD8i4|&4Dah}%? z;1PHZF>Cnm-exK10f?6(T@6Z z^tPU~f;RD-I;@Asy6%GYNX9{5^KPUZC$j_EIATki^)f=^Wx+?wD(E-W;)I7{%VOu0 zO`z2#pNo<62<-joBo*UQcvMu*F^Ef98u-?rJLNbH%wvcKY?mY3Fl&RRSa=1P`loy@ zx=tw-oQcYO6gK^XP3nFq-?R!HWOJQVR@N`e%PXUYS_3J(2JTo`jsqlP`QBP!2_d)L zJBCM6zhp>s4c!e@dCPdQ#z(^0*nSYJ1+>*1&Ze`A=0>j60xWsBJ7esZJ97p|pho zJ1cNx&duewu`fcX;Z13D_pLyZxRK?9t%bKfh2v|q#>eQb>UQR1+w^bO1f#v{%u?+x z;)$9nqp9mnObz(tUvJD{4VPnu3dtX?XG!enj6NFlviv$Kn%T`W!A@Pd=#CjEAvn=2 zTJJ8qOm{JFFO#36{A*!^E$S4Is!j2GG0s1D=)B4)Sh2aTRA5`LvJ|J5Uv6$s>=y2F zvhY9qY6MxH_U+vN%0|uF-ArUZg%~)sO}U6qeLtmK?o~io5)d{2q6@cqw(nIZOn#gL zQ|MGoOXnQnHp=zBK2G7Zj=?cE8}nMtJ-x3q{C?M>6tDU|5|KT%_p3j+^o}Dg@QQZt z_`GSRsuaz?tNf;;M_K-ox+?2pSWTO}bN`$TF%1iP$$IYg*gv?nHa#saqiql+vbkdZ zcQx%tW#2UpZCb$3kfrNcq~rnegs8ux!UP}?D8{~<&3RSK(4!l}OKfMo%>Mx?-v43D z#lh(G^d15u*Pv(b;66=yTC5%I8!uEKqXtx>HQ&!SHW;aD`c|#$T;?JU@a* zJ}I>taG-Q(@@PfYvq;gr*Q{ii=w3bSdW8s}#$3`M5T+X~SW>DH80jcboB!~#-B&c`;No(67r!819m3N0A zA@L`))g0Vsv(SJvk6%9%ym!6qL*(&%O^nzdRvn~Tq%p0)cAHeO#eaEmGD88Q;3gKt zK&2VI#(7oZjEa`=j$KkDPE+UwEn1N5*|uti?4pp=HGOA@`$vW(l^~=A88{X41iKJ! zjKx|F+p)hNzQ}#WtM{cyt)=R5{4tnC$Sx}uD)}DSFXv_8QWO8elxKTUC$Spkxx40~ zoT>}6cv~on%y)oIb8z2JLs2P}@g&O|CwXa%`mQ%8ocrIys2CXy(0Elue6X|=)LXMf}q~xF3})V~2;j{K83tEtL6Qr*;M; zDcltL0ypRoF<)q_1hpyskp z{lVsteir`0&AqY~jtvQKSK{qXz6+Y>NXlwzI(Mu$K^$0;U^%dsmM$=$2NWGuiHK;1 z?bkj81{9eYUvfBgWZlpp=x|}-C%+WV6KWFNyQ?=8xxP;Fgg7s*{i0?Se664@Q{588 z{+Y}D@lO>QSPptuef(AL<;Bqw+JwJefD^5gjlc$(nJ~-cNV%8};(@9|*DE7O=h~_1nVkofkF>AMJ z2k)ELc!q>I$Ch1{`TR3>`J?82O$!U~ajiRiMRUDu!9S@1%=9x!qY*lNKqC96}Fgk^xl9nR>+8p z8z^S;NEb>*Kc6~GPAAC6WY7#{N2Vf^FDE;5zvsv{KeQ$;4KJrplQs4s2o8^)%)h4h zBj!XOF@M=6YGM(Ps^;S^teHqsz^)bP?C<)O=S8Z^jZarH;22Cy4W}O)=ROQsn27ND z#HDCAa)nCwzHE;i`cJgLu>%jG=hB%u-!}cyYuDQ5*|0IsHmNg{ zoylIryt?&FCdlV6!YRG??!>9%QMwucplB*X%?e^rFJpDmwa?)C6toB;I%HYM_q{84?!6xkVXJCc! zbzBE|xqdT1R58s`s1bmmr#RmcS@TsWp%hYQct72exZBhfR(JP9I^@qW*xj~=xchmf zj~4P(vXe}TG+vE-S#a2CLYMPd%T=&97kBS{198e*V{7+(!dvtmXukPdWpp;$hS^hZ z@f0BH)Is7Xu&LYXHuLB;+a#hHLVP;>y*I{Qp;P#n+bvo1J(OAQzuHg1DjF3ek4kDeimBU4y*>40TH_Z(sXHIVY*cNV;EHa z{#-XGIU^HDR8A;TZF5joI9Ze5|fg$jfIPeXc$%Losaei3+GaTU2GSL}}E)3$h=M3ApLuC&t# zd_D|`F-MGpsAtSURqlK9WJ@4pmz@#7^82HCyi%#a5O@3L@av%=R6Xn^PDF*XCr) zgu{C65KEdrR;g^GBQ$n%s#K$TbAreSSnjLly@W;Q5?X))5L;Jk?&~@&sUv{;ASyJi zU)Y_y<~Qbvr|^tF&4)uEs3RTGKwJ>vc49L?MxU*GQ!9*}WhVUI;5Yjuf1ZW3ykfz< zbCAHeQ_rxoB)OY)Am>vC>yzS*`rpq=*k)jHsB4Ki_?8@)b(-fNK}WpLP)`n|WEcA$ zcLM-kxufAZmt{142tIO#EQ*BcZ|n-1qGAdi>T1c#mTGHKC8cLa3V}4MI-0Hum5c!= ztzbuag+VcWaN6=9){-A`jKGx?I#EOZrfkqRgRlZEdOn1g{?gPWo^E}jeciu83rt0= zYXXHOJmhV%M~qgR5*|?cPpAv=NnHi{Evbtc12^I{3jyu3PUo?YLj@w)30s2_lR6>J zVpr*={ypPwsFUVV)cj?8EKec^{63Dmv_()6DWdVM@05zSSYzIODeqnOMwd-*(3I{? zHJ#@2?kmK%^nPHPD?orbY3gFc?yZ(daURjQTSd!$Xy+kGQLjhfz{Wj z@CvOR7-EEv`Ggfe$N}f^*}N`nU{?!BQ!3oB<6kEgC{6a=V=&TiLugSMvTr}>%M z;ZBQy(Ij55n;yxw-!qLP->HqTZpPyhQ24jf8!R%>rjz%Ef>&%lPlpOIC-Y|r;&sW} z#`VDDiEw!Mu24qw-vGlyFgCV7Ik`?!Wmg?VM<=TW?Rv5;&e_q-3Kam23ZIujyX?mg zHv4_76rNj>p*TM7sl@T+5`eB}+)tDZB{7O?I^8QFdi&MiPlVM*D0ND#fxOxbxdU13 zQw5Niod)b^6g3iN3I4F$509!h0$I^ffZLWHw4NcV?}YJ-rX-JAXFCdjHp&Fctvq2Ja9h@Bd(yw^Cu(e6IK z&(SYqr|GYQL_Vo0p0B+ZltcvW*_=;RNxw{w=LP0%5+Z1jE z&RmHGR8#Jla}hPHjyZ4CKx;O~>1{dRl!jL?JaocpATTfW;s; za8oi=FNL40iJm~OI9}JFlh!BFf{$)lUcij9GDVYGr!Gj5 zmF=J<=G08Dnhu2;T&>(*Qo<^+6iLTy(59TRlVj-)=P+{HlhBN}^*V`RA zFz{CK{#JG<a z1jVWC6938f?=Xp_2*Pnlo4Aiuv?bKROcXMa^Bh??UOi^?Kg ziKHxAjY~^v5LBze-2J+^QC2yr`o$T1l95 z;)$f-F=j=^%$nh~UrJnjU#@ulbp;n83t;>7{Fph}_)h4ZhREZje0|r_4+pc;II3My z(|~x6RTI08y8%XJyX&gDinoblM+Tv3SMv)^f6q^H%`bHfen#+cl>wk;-Z_^+tPInF zrNRNs?z_=ZkeHdnwfV$dHrVKxbBp-kh%JVNm$cnr&qW@*C| zlfPf4V>pVr%6yaSR!K8v)xXt$;>*1bVVCoIw|0FC`bK9AP$;o1iWEsr=8Zmd2FOOS zNUBxzQ(F+8zblAxJCzsS==w(K65v|h>aP7}+nXTXzDQBvm7t}8aaNQYI?)V;l)YS6X8ZIA;l>}cTOuqfn^f2q;;h>eC-PIIqt{$`XAi+0tDt2IS3_7-)GpoH>{iRu`tKyPvd=XM`nTO&}Y6jQD>{PQmA z_?yLg_s+WXoeFEll#>j$(uoR59mIA4vb1!sja>;0<)k%c!Re9N*yl-F$bl zG(Y3f!ev(tmS>$UK0X~jDteFW|F|*id0DuF9m_+5`!?VHnjE3lDIQ{`bSE4d+GI`= z`ypLt-U9(;YX=F5OR_+i66I=WAm6e;S+z|<8uIOexJmZrhVC)K1@GqZYW+E}My6P= zgH5h_g>ld{*|sh`}x9%5F7D$`{sjETESUmmwjbh(I_+XhOX|R zL%Htx`1>pFNt9Dyo$J@>vfRkx@bx^crg1rZFTSFf$8oXbtP)An z)&F|`2e+}FUW6>UpYDd>I|j=R|0Q?3=A7#4_Z~}Miy6+^ZU5Xw|7d+`2z;Bw{H&i^ zVYM5x{lnRdBpa;~A*R%4oiiHxx!i8cxlYibajhYU#6Z2$_N+!b#e+YoN!g4t zlE|O#a7puZvUecZ-4Gh0)+7l2BCDey5v-=1{&xkx#Cck#e7lZDanb^J#J2L#p7r8D zErj&>L%}+C&K6pB)SgF#C_UCX{Kd59M>A~LxMxzUs%cpaw{eGsBd zSEz{+)ZrZk4K=yENtWA~rkW*KXxTa@bo4(AzLYO;x!;Jl;E1(CKMX(8>l0%mdmCEE zIt`j##vqM%-l^ScgYkS`=((L(PivvmP?r^BP*6>m82K9i^k6yBzibtX#B3dPtE8mF zz`FIlcRfuu)tnt-vfj5JGil{J0iHno55f)6V>9)AD5=ZxYH2Cb<~T}_v+Qi&~B(A>22txUGonKml>#jGDTkI5%XyDel? zSER&CE>+`-05!+PWh~v@=?|re;4vn##JR|4t@~oj7LOdcjNB5e6?e2Cw0&+O-y;S4 zTfSC(oN`6Dc>{g$bxIh^7F&h(6xvbV2U-nnpiR2t0Ph#iOH?V16&(< zPw2EbJXlu#vVZ7^mL>P1+fbfubeU9>%{BV0guYhudvb`GFF@%qN{(HT_bmJn zR2og?L*?71MbPJq$M0FguuwYpUCYHk{n0us_CQkE;dU8(+}g1JiE+qjng5lt^Q5O| zjcaDYKW(>vzk0K}wmTgD#n8Rc4yY(D`MkAL_Y502GMLz;)^TTP^z;7g-Jo(ycE427 z!dr%nc?r5dcM3-SIsb>Mw~A`BjkeN*L3U-lUO*{}g-J8E*s(PYv7bVEg<8$JR?y1uDQK;-jxqSw;oodu> z#7pLoN7(KJ&RYjj8)XVFREEvTrMR1*kOnxtL6R;K*vY(tzQl?5E$ym)k+;dxn~xg# zlPPY+pv7if?(v9C8jGhQh>lFjjfG6{lP#Xq7gxyrB(}I%Mw5zm{9v`#6e zl)7JKLb1QoT`KaTWtqOrS(9uG71g0h`s-S3SPNLN`8bkDX3(#~U^yR%W<>mU) zs&)N&5BY-m-9Fc;rZ&-HL%-XoC_f#El)!GQyP)L;-tLYP`_?y^*}A7g@pxKQQOZg? zS7k~%uOwo+^Sv7Z#f?8}XEc-mCEaO>gZg>c z!iY{Ysdq^5R})PZb6j|_04XV6shymyFG)LnDP61+Uh%go3D6qG$HC4v3Y$^9;V-T0 zhzRxA>RHuI0-J$n=#Y`Bt(%AWdD3;3u>KECuCsqUDMK4vKY*COs00+?hFX_Jrssay z!D4E?r3NR~h3^J`8r*iE-bN_|O1fY&kwNmnmR~kZb0TQPZ=h3H7y7~VGy!>Zuqme` zYi~ucy8hVeQ-L-MH4!h8g` z_8@V+K8a3TXP7ldXV+vAFF?PZaTpbR^#qrbWOa5QD4E z;|^vwEh3w>FG2T*DsgHl_F>~JE0`0ND`HVTD|Sw%3mqK?{Y|#(KAle)0D-dRI=u~o zn68K@JVv29e=@qkJov(hlo95msw=TJ3r|p0yd`YFA=UmAaqlgefRQQI9d%s~CxYm`>{rs@qx|^^FeFXO;OcyKtgHHW6ABh*x zz92QbuhcabjiZ>k|YUf=IGEiexXT3EdHD)frK8Vn=X3((zogG11YH!MYGn1{aJG-O+ z{+!U)5fww6=x^MZ7Kixx`QJ{)g(rO(B{D>q)yb6X?j5xLmfn;_g8z0Chb^ml&0>D) ztoza@Y5`Q(Z)8NT;Dgn=YZCA|7(@-BmzYnEg|XxvgAj>;L293UKTKQ%CSS<*k=cWB zcsnCw*66TYFy%}xk)@8-J(*5Of+C+`KWF^VTU zYITa*Q8ui00*6G25^+3DXFCw)D9T@pwWwT`AScowdSg(l@}ozIHAr%}c${5ZC4R(* z%^c`mIo%6cN$W$pF|5akqQYpZ4`^!>T+yoPb2dQr^AQ+PV8Jz7qF>?AqjzChzD{-#`69?qNjK+8$xNu8E% z@))f-lkIXk!pca~jbyY5px`^o?q{|Q-(BX;moXl%2hhkB*!N;^7kfPdBAyj>Z0E-1 zDaA*qO*qOE3p*9b?6BY!%ev(&4tU`Bp_Cmf*idZxvZkBa;QX<8(xLaari~wW3)Xk5 zMKf5t&iFr2Xmv>7sbr#3p_-sby@JBEbGpKznJroCI(JRI8QzIqxktP=EbK_!0@3I0 zV`OJALetJ%k*^a5h0mLIkMsD%Gl%I7f0uLaE8Gpth+SU2Pfd%C%kpMF1y(HP+{*U*hfZe-A{TFL1 zV@cs8)mId%53;u@H4G>p={6ak8{7yk&eX$3;JFGjJ3jsyHgyMadgfP+?BqL*cC6&- z4KT=H-sjLd0T$1aL4b~4M2~zuNwAdwO8 zg|muiH=?1C>|R7f;67D9DQ6XnQ{+{IBH)Oc5daQWxLbX_=Wj|@*Vm5$ z8@efva~=X<6~?A}rD~)-aIv}0=gu~+1!;qf|Mdm31eb?3-ugX5dJ;TNCvuJG9Snn~ zYl@~xW=rgzPWuxAuJOoSN2%c_#;_*4g{_l{YFG958ih~e)HW9=rG7ov!kZF9gbR_w zag>{8ym9&Z$p^&@j7|QP*pIbBcB@|-eQVm@x{0rG6Gg8|G6|ytpipI~JdVvfQCD}tC zSMWy;6$3=F7>#7W;A?7*xjQW|=jEXg9A`?@WFUX>(= zc}sYrLJ@&$YNas;+kr{Q1y(g1*WRQdn^}z0%$p@c=!djgElT$tSYW^>?7RRz)hPAG zspMh;y0kGrBzZC0p|JF#P84LzbJ58sr0|K58+b?2!7~+%HY&0kow>;sPf9~98wOKS z{A}ukD`;9qlIW|HF5CPeF3#q1E-LbfiW2574}zuSODHnUApQEC8txQLn?mL0Z^(7P zAm2-^w^A2qx3#ULMD3Zd;4sy7qySHoK}>BrWjdWNJcSeB>Q%Ev`q=)+2(I17;jF@p z+K`@t0;4MA{U3*8-6eIVyLz3sXSA*0DRD)?s+HCtu!H(=dX#{jBD$`Ps@%?Xyu#Wp zyu-!ng%$iSz*Xg`-iU4nwBF@PG9?s%LHdiiuF_v1vggSfKrX-)T^R}F&U#Zalpjh6 z)6P4JUd!E-HtP8BpfYAHR6I9R!_n$gSB&N-c+Bi42t%qg?0M^fiR$i{5f^elExYOX z_BciKSJMvgn1l7?V<5Al?~W5hBx1S23RFGv*@6atN)j9(rS?sO=5RKV=G{yF1!KqQ zQX6YGV0YS`oxjpBPCwukT~LwkFU-9YPgTrtUH#ww!8oT_ocQxSL))XBMb(}?$a-pl z<@y@kc?6zwbGB6HBYuYV!sl7;H+j}XP;oFZVmzI@RrvEGF?H! zv2|*sg#B^LcF_bK0JvNpiw%^ju?w7-;>F$9fEKsbmV8FlQCm7Tp8JI7&0(v22RkX@ ziMVdv#_hYIPVHq6v*8BrSPU+{C58=>O1S@?2?U9W<983RI#e>pgdQVMD6QDg|1W6f zOjidX9)4^ddPUBcj`jt25vhvarKXrawd8s2M3Dj>j!RrF+78Q$$POso|4RG<2YbUA zn`j>eb80dCc>X({M zY$@;NhDJ7So+;Y%woV7_d@NYN+W@tn`X*y5D<6Zivl+FiX*f)Z?o6s@;{%()Oz1F! z9*M~&5;32E>^S7J!YcM)-^kO~U1RB=%P9h{!RXHMYm|dkEo;G`6g_!7VX0o~tleLB zHS^GC$a+MEv5)-jAisQX!Ec9t`i#<@yHiB=3yf93>w34UvEMe5$n92$%GlQ4ca^?< zZG-K?pBQV{7vs5-o8O23+(^*o%q>8VkN*5M=&^I0_;fYENcp9uAOtvfz=S64tj4)p z@1XrxvKQ8Or{8K@XeRg;(2gp&EZBNqytz|(!x6R!mK7oyc?5R`f$+rPk8%7szJlU*w6?ak(Xlb4^~=wn=e8C$pK;-F)0Cg*WBP6!&o(v0%GU^s*)f!`%6?_)pHYX^FsQA{V;^LzL5t^ zw2g9}z2VeFAvsi;Kct~T#fkGc{Z@BI4=sOT^|Zkc80p7iU;m4svZ5Uu#%q50xN0=8 zCdiW(C`Hp}h%Lf)=v~ONEB__mu1-07VYfbJN*Wf9`AOk40f_2BZT`hIbQ&*>ksVPD z3tNWr6PC6i0MF;{BF5T{XQ9S0&U535bHnFZx>CPMy}U@{U%;&k<8I;iX$cn_VUk6w zQ4Rw|-5yS{M?_BXSHyI-%qq9_7KE4${iQ*K6JP>QNB`Uv??6hFGR0{e7z z&TRKXB4TBO7Tu3@I>WwUHZ52LKn%KTuDrt_)dlm9xHfAK9A)8_ey$Tr8S0K?G&i7L zA@UGa{shmQ)t>BW#y&<%?!nx~WGo}Vqo@+h9XHqC;3DjERY|Rwp>xy(^DHt5pYh`? zrRa+62PWbu6Gu)A@WGub9h_EGB*w!VUuB>HVhBm0~xII$Lp3c%UYcxz}0s zLVIgscQ~JUO!MYX&Kcb86oCKULnm0SHVZ*PREjQns*n+z1y@RK4Wf>pdYAIaJPK5a zY8Q!8|GrEEVG?sc^L4)>^9qFSDqAUOsZ6d0d#Rw}jC}Wg-+V6757Cc?he$HtD%p`mn}&7bd38l0+eZ4Rl;z#Ks;5he&fSZMMD1^p^Q;*=spj`m$#m>v zENKA`9jne`Swv%9xp5h<<|qPbnsi&CMcBC`3mZ4+(U&d4jstZg6ct*bKM9-aeu%Vs z6{oC_Qi@&U8+G3OWNbPmb{-}6gBW`XlvUOFTwCctXR=ksc3w&2#U89-6eCY-s;B(! z+#NMR7npfzU=J9H9^{bqLtcjiD{z%|t5c1v@0nnk>8`|CJ7coycpA^u2M*e{aIC!?)aA#wBFV;|;dh4(!-@UG7R2XB|}6uPe-MFpNi z>$_yS;occBr93~`9*%3}mWy?l;Vdg#zZ0uG2bu0=5`02}?H$wu&RQZ4oj~oEN8>m! zy0xR@aL+{>GF;g?TqF&6%--DcT{NmVtrLdcrlA5=hg5{i}~?W zl(pkp=+{cM;W*oTf)r~vUY5n_zB%l?L0KnpMt_(ETl?p0c#Fqidf=_RG_Rp#**KqU zpUS78b_e-?wsIIQS+w#D8o;0X+70h>%e9+?o~`*;k(exFm7!#5x2xk3@OIMU1w3zS zGmIYnFjK;vji;G9uJ!c9>_$XeQYsOZ)n$-=h|9SP6_%^#WEA6aFON&q z$G8{@!CXxekt*t1Wt_E_Jrz)DsKUiYRO)b8#tsptxPhZccgM-TYjp~cY++pbB1`L3 z2sIp~%nDnu?WBl5labL2P6gp*fjU`!h$7ZB9QDMrKn{QOwcpcuon(SXo*I#h!z7v!}^-i$B zHvjiSBi*U@@H@j!knd{{^1i`zmLR+kdOnhmuUxUnbJOQtf|yqx&?6vzv@P{YgBUk$ z?ji1J(KEWQlAhj7u+0BtgPF<|ROo%+6>nV@(`3<62=~K(t#|t{bl2FY}#}8~>8!&!cZKA<`%uHEeMzyh7LvS#IVjeTfcunwpLz ze1-H1-z$wsa%}RqQ>+tlyDxF2@iy6D?%Y`O+AeN&_vsqlEVp-1ou}xK@mIfeJD^~R z&m=qjuf61+hV6fNn1Xp+&)>}l0v9sN4 zR_e^ha{idJfga7;K0zkYM6M@%Dpzr4H>+o^l}&>l?fz9sKr}4rB~l5I6LX}I3PHx* z^(5Ge;)>}`k2S=L0qFk)wn1<5UJ4b!hHuvq*_MKPQ!+9lg5Jfk z=I6XkJKpSh@$tVv{Z`h+Ua0OHNlZ&6Xr`b4$rIdL>J#Nf6P-27uss0T{Q7yJkXF6y z+$EAxqm-YQZ!7IpBt-b-)_3C9i{LLZvYaQG&%FF52N~ZlmqK18JuHiw=|5?!%BDQM zi9*7?^Pc$xE{vV@xV5H;3oT{Mbk~D?V^5G{0Aa^rPL@`c^#u#!UG~mCwb-X#4F1Oc zQM6DgQ+of}rmPm~^=}{KKJ)V0=n=rMOancEk63LMM9r2T;S=O1N7QiDA+GmYH`BY_ z33C(iHSA`$#pLtM!)9vlVDtZkoDyHAzBoKKPfM56Hcy=0)VxBjyv>OIeuM_0Yw7ZA zf%UMYE$XtbH1TU|l28QdP+9{r-FL^V(sru#Kh<>~cC9k8nQi_oSR{+|&{=`nTo=@n z>M#x5#$+t4WVuQKs^r|o*jQw`!BW^v!y3tdB;KQnL8Ff0J@tMvth8y?ag0 zdN$v*y?ZP$kGMbk+CIMlGzmBTMuYlvU3iC^E1r&9oJ%9c(1Kl^jh>bSrUmg)6+|3{ zJ#sRpO0R^2(VS?D<=&tvpvbqmXx}eXOz&O@zYtM&KMHBF85RyUgg=n7{SrrpA7%xN z{0`LEbh+?e{a?7Bu4NZ@E_z-`us1y!9Xs|tTkik?A;+^~87~&_G#SN%%r#n`YP~`E z4!cR$mD?nH6}^K2=6@$x(+#=YEu=l8uc?j7K5oDOi~XnY&{>4zh_46JV%~TOn~&c+ zp9U$p_Pda|z%fMJj}3=c%a4%lJ4Qepe;$lCeZtomBsA{L%56ZIrkn=d0RzgoKYQgq%); zdu6<&KPIY2t~HgZ-WGFhCZvpHG#=-&;K`C31iGoP544pu4Okv}_Ifh9&xo|A{w53M z->CT_eYXI}67dZXHS%d7pKn5?hXVZ!P&vd(MBm?nw2&|jHM*W;1PM7;U3m6{qd7#e z!l#Ke=pFP4Rqx-c2*E6FDY?Gv!WV}uw!TNPib2&oG^VN^e=P`hWcW&e?Zd4t@cU`r3ZDSuoPEiQ4SQhks0A!rZ zWz(?5dx-p*-T<)(arb#_- zPZ!xFMD*AT(DupF^UZc$HSBfb?<$CXw*|mOl7&$>+GQj;xhx+mknYAuLCBa z=R?5~;OI@$)bE_jj|$_R$HNLc7#e%O+F*Nh*VQ;AdIyVW{yj|ac!w{}IV33NuyDtm z32!bpDj5Cy_JvQ?$=0;PK(cDu5hWoln?3Ymr3V}UbUqFW!_?jd1o-0xypB^cFCTPw zyadm)rk4W!kl~xKs6&blqSx*lRp@2TD~*B~DbhifHbQ(>NRpDp<==IJ=?{mDeQCyf z|2z_-UA)T#IdjEx|G-0AMITpc{+#hGctZn{LI(mS9{YIno7ihIVrDBte_`%p>eOGN z``vHskR4YZ?9Y(^93vpQ>%Ypk%`MM>8ub4S&WM9Tom94dX~e{JG@O9Cf3z^yn`Swa&{EhPXT*Kh$>j zH9c65sX4}Ur@hi0^6LRO#0drEav~X z!wGnpfzY`tM@vZFFJS!uM_c3CR{qpCe2-`R>msi;+j#ABzf-r$5R>Lpnq)^>QxEE#TfzlwM+_pX3 zH7T9)H!ezkn!RjV`{Ln1X~>9a&jOlDLUyb58%VW{xg`wuiE-oK zR_TsvCyAr2U{YtM+#_0YG*U?ly*K=x)SLK;^`C1CnRg5F*s7~BD5Y*vd(LD$z(5iy zDJLZ)MWqL)B-eu?9GjxFIu1&aINC2b6OD<=>8A~SCLV`&r7AjZLpk2cM7>L%_Mj%V z>RzSn6S9{g(HZt@0eWMsp}$|ST%n(C^^Wbh`9VoOofhVNT03zbW3oaI#&LhEp}iSN z^a}rHp2!K4rEL9v_uafjj%Xj@*5XI=gQyow1t?x_*aXrAzL z{+sr{U;>f(-0zE5h5fbt&ebdE{Wo*8A0W;&V*Z*Hm#^}DDr;`mGtRI?J_2=2=S*>n znqJ0&%4VN+t2!m7F@mE+?qEx-jukHc+-`6DYT~~sAY(~BoDd#z zj}uX3o%4430-&yUR8Qx*8JDobyyF1wM$CrDW$!RJKEW$++8Oh0rTWjoRpnnx-7a8< zRJcbfM2>+9JtzGc`fPkL1Xsw4JXd&BMPh|tugNqP=0?wGrgXWlaoXCvTMYw#kcvB= z@c|efS)Lp?){l>VID{3={@4N&86Ly+j@{~Z@)3W)>N9?2m86PCPD=ffVdvGusY2z( zq6B1KJP{0vQe{vbW(Pd|8HVrz-KGQuUi;BMJYM_Hy*?wWTr^+lSP~kQgCtu_5FV|D za8$i(SuO@D8Khdtay|~k6?ynz|JeCAX5VRmrzRQa*D=TNvQ$TU-cp;((}x36myydn@c9`)YObg%G~Q_kxdWm&-n6VftQ7{w}(ekG2Js`lj%zz5U{Q;zn`k<=Y4}{G$!uu#6ei4I4}oVjPKUvZa~Eqr2#-Ro!zkfstZ+5g2XKmHa=>V z=lwpLFRN)4cO=gl0d8uozG9>Rkk4bu2SMfzznAO?Ya2!3sS3&882O&_vKcok?dtE; z4q%UL^@Z@hTq|-m;dqmtoL*gxP}=#ahKwC6a&$FHGrxH3B*{`p_^%(J)pWo&fjQ*b zZ-j$?{USARy&5Vf_LS(K{gWWN@LT7Vp{}xL{%)}@a1q?#deWv?`XgU zw)wgTe|))fFVJYH&DeB9_4W`R3P0enXxu{ZHUja3I4T!z$*0w$Z}c)qPRWiTv8N2i zz1Yt#iXJ?Avl{a#`c~!cn9UQ4YAy-2XLcxyMjmgcL|B5&UfBxq=F9U-!q6A2tRrQ) zEFE$4rmJL?4KcV!;FV+_G^!7Oz>+?y&}=EPm_}+j?6@Sb6ybpouia(@Akf^SnGH^F zIA=JliOG0yh4?SBJG0J(c&hD42!G$Q4@@7$6f1nuj!la#A{WK%E|C^HQWx;7=l9x? zVY>TpM^jSKcumD@mA*%+_kP=65ZPmL7nPY_BH+usYeG61yf2yc<`W1F`mdS50?kE?^ChgQ&^Gd=M$mZud=2PRCmNVTU9I*bZJ zq)0Z(lnut%)L!_bNgdz!i74yF6mXXJIO>yiF37OUu^sN6<&ZVYUE~?sGarWu!ev+dmHw>WBKzg*0UieF4kjwMyrEMy5=d8~X{zwr z<#`WS#^&mLWXr~Js3^~=K+bJJd!A>Us)PFlY$WPD1)_ESYXZyt?HyHVs?@&y>*_37 zj^Pt$DbASrR(68}EFA&7FBV^j^uh1yo0hS$M8;OIYHJ!)-Q1X2@t-%C}Yyaiim*u0CBwreyBsVGV))x0=%?ye_ zh*idz;SD|?8sISRTNNVt*dUM7ecj}5qBH07>-$^Y^~ z>@=3=wh}zP^$3~nxUhxg-V~EL_WqWR`P|JJaXVyv%2SFqKY4 za&WZ9#KB=}okF~e>)ae6ETmoVo$R85Q05t`?aiSztOwwuQ#*Vt@;D;1eHQWD{_jf_ z3MbMV4*Df4>u)SD&hYZk+~5_zx7{OgCDxY&83Fx2RQvG{&06%(j!3o zHUj<&I+-gwTByn{Ms2Sq5p<{64>NmPBv#Qw{KCp*ZVTcqtr>MoHu7y)tbIV^nUHVhUUn>YPQG*RmW8zpg2|v z`C#iZ1nqNo2Ql9Rt~=O`ju5VMP_DbDq;z|Csv`dPOO0Vl6f6Ste1WN)R9xNbJ8kE^LL*W>2|Pv8 zIuFG03zaz${?ovH{Uwg6A=MJ*^*LOe9KcY%=;ZAB6H8-aG=N&~OT$qcfn z8+y*%l=&(mdAW}{%HNq#9&rd`c_k3R{dk#DcUiYIjjtk|^Gjvf)KU0d%n0=nF@1bS zx@PKfVwqXV?_87I%KTKu+0F((SDC3n!QGC0{R=k4zNQqym4(vql;byqRad*aBx;p9 z-x(q5UF`~}6(otDCEtGdyc`>fffGmn0mG|sq9k3ywf^~Nl{b)9HltsaCMcoHH?2^L z1n(H9e0Jb!`0&Hi3&0VnN)B<)7a2emDSXk5{g^;pgvNtwFQ7G4jM-||53_wc!iEDP zqEq<0BioRSi*n#CXLgy0L+5QP5o!m&DC;8eIZ4=krcL3^LE3XZ7%|{aQ2jnCt1tex zL!7WdBsnd_JYF2LB+uh57CASZ2Gr}#-;d2twlruhBuRHs6$B(36Cc8;<$&7|ldMp3 zL&ma!&+leA`i7M|uGO=~xz_|NO+?@G=WVrekVFKz+)EYJuEyImn{TptK2qxxpE4hx zw7(a5UW-|3{Yh}~xOkpynHsr<-Vh*?GQ5KEXvW2uSkR=pP*Op&yrU&xHyzL@zHSu} zx)a#em@IYr>D>clIEyj1H=m>Fawy}(yXcOA9*XF92@)Q>NlKJb_DntVIuB>)eANAD zpdy@DI(+t$Z%lm70%N#U5-XOHr`0l;CZ5x1qEDn zl~gddr$mEDN>+t>_~U?bIF|IfM~k#%A&(Z+oDu%6@duUaQ-%DL^JO2P)3V%8`!$|1 zvF@Y?8`K7fk_!ri3_YbErv$*bz+;^*)UoG5&p2>jMjjwm8l7-E7*)Go2#ys;*nAh4 zkd_t<#}t3#pXO)2G0^jJ)#7y(1^Cn4Euj+I&~3kW2GIJ+@n6X}x#yZ!sOLX~sqc!1 zW>RilaJ?5V&x>&Sb(>Sg_K+JoD&;aH-m<>IN#^PBy55j!^)H%n@9+qow6G$7-ZA=Q zbTw`>d%3##B(wWS`W}NkQs1$QpsXCTwA)5R{7p`>!vOtODlFxQM9Iu@Eusnc+MoHU z(U9GzMIw?KJ}ndFFh&lV9lU>Jrb;)P)`cf`X%h{*&419Kn>cj+Rvk??X3I@u=Vn%- z*vouh!c|b(2U;iZ`l>Qzs=xFRLB-@R@!p1eLQ4Jr>cmU>m(S@3IR8f|))ct?D>XlZ z7{znCSTh1wgXro zZR}3~_h2`EU+p(rZ!)68 z+GLp1qvEp7pfeigu|5n>Wss$ zn<_k^O)~eb2y75f=YdzJhZ@d8);Rw8N#Je;d4YqCe+RIn4yST*)^cPG4L=(B?-MXK zSxK~LH!|ES2hz#mT7T;6fQ90zx~m(<$x?bFp6+i<55jLV2~&pmaXr>|zMVSjIuR>g ztI-%NlQA9c{kQxZF7Oc=Vd#a0C9SkY52^=#~5ynHN48Zt(g`Wymx{0%{0@B# z0w&`G?k3Rxwdp&hYHQ@zRm;fZa_AKuSW3BuV3##&PuVlSzXM0@oasSlG}Y5(gwpuN zE*sTcBc#;%k0qqs^bD^<=Pj}2iCw<-pK-<&7t^8L3`8=@-^vwG@yBwUOA!mUqIfUQ zfvi=_To<^G&@RGhw5T@*JbEBg6R}mbwrSU4 z-6kAcO|M-{C7{3u;{X`_kI7$QniX0F&CSi0agCr_&cMczk~SspG`gF4 z=fz)yKAqPvrQf8BL7oVC)fLR5tLkH}3HLc)sZzt>IfaBHvBFq?u!Z1-3D#$fhaR_m zvS!dDsr@sG&?IxLkw~=&cxAbibKoG1T=0P_R_F*taMpZpf|Biuw&;v2R^*Z^mV)+9 zCP4x$_MCdA`CXU8+=UU<4dDC|`_Di3>*qu-&xd8Ag2qZX@siGi?=Xyq{i461F_m1I zut=8JK+$)(J&?Go&(32Pxac(1YJ7nv8ZzVL7`o7oP->@CP*x|uuK4daZWLdm#@87N za9pBDLy@E7&o@KTrtWN*e~c4Q#-hp9Ge@Zm?Oy4ig?>dk+M7sVRU;bln~5|($O|uz zyPEm}*5>P#lk-JbMnP?}g)l(d}F zz?lD};HAcd_KEfvWbrQ@KhOU@E$qroxQRt{Bk*J+=-^;(^_~$|vsMg1*O*xLAA#PJ zZ!veTt=pXKChXB{JDzD=fO>yJIr{drsQ+q7A+w#3D9F8rKgm@HxGUZj-TF4}g?*~L zsEm8$E~73)1hPh-u9CC*l6|EliYWrz8?yM5w_*1GZBFz!@VN9?xfB1tMtSWLw+_0% ze~aKvv(Io20p4|H0Y%@sKVKE5UquE8sv=+!2)skaa(88C`$?%upm?=?$`8+Xi0HC; z%b2BLel^3Ol&klLj+BP`+gTmy>n`O>exYRW7}tiIFDYHwe`{Tplk7fCZKJY5 zkkZ=Ek&pSTy)_7^nHh$zQPmCT?MdFZS0i_AH6}*Nf*X1b{xeG*5bIZ_d9}_PB5Sv^#syYAL9WxG8vnAD2J3u=K0Q4*>vO|G7WcZAA8HEP zK54vRoTYZZSb4XZvrpuL1Ld-tVlxI!)A&M;WjAF=|!m zRco=7l4DCtw#weu*+Di?+%^<|mnN{8A?S-{hLuh)_1;7|L44svRH6#`=|_KLtiC(` z7yOV2tTcm!3H~7KhEWbrwO&6m*vix3 zpzWD!QuM&E)c3rz<}Abk`n+nD=N}FS&eYeR)C#7XF)F9K*L($d5;kv=mb~C*ovq$? z*c$wSPXX~Ba`~pB8}IBDNixA3=&31oqaNmhpg^StC^$F2qq@B=BZEoKOBCmVU zV-xnfqT!?EzbVwOO<%hci%mYQks8nv{%Y*tYm79%Mkz7=uC_gwUeh>%|8*L^K^TKR zbNz1dD=ySlm~R|aQqMF#IG5_pNPgxkB+tri7qqoj*gXd|c^!q(UqTV&EObsy!2#Ip z({y|IGh^{UaRORqZ;jj*T(uR1aXp3O9T4leJZ=FiwTB|3mGF5yGk>VYeerh`uOltx z?vYWJL5L$%a5&Ey*N=wlap&cO$ZmixU{`DE&w}sot4t6CIguty;hvuu%`P_=9rh#i zlXP}=t;?>=e}L9bm3H1D?8=eqEoyEgVjJgv&UNA5BMM3CskEm{LiZ)s17@P~ zT8w#`jlI$kGaGM!HTzg%x#YFK*3a}#aicb0G(X}wVM;^c&>|(F)OaSeee*nKRTSk7 ziOlv&^ow>d!9*fYnO4Xi$0{&zS0Z9+-T9`eEdP|DW=DNtr}XBa3giDY*_IYioWU z61u122@>jZ7bSuY_m)n8!>yT9CIzqABqj9XdsgvbaAI_x$&KL6zv z-jvrp!%F8gjz8_8u807uRE(7u_6xam33U$x5!z~tKC=5vBYdpw(pe%T@$>WZCpg- zr|sx}v=KTBA*Zx<;YG~}Cm1#b?!s-g+viT>5&IXfv9|vgPvGy@^keA1j3ToboJt(F}-n^ZPfMfI?D3!dR|BCc8Q%wCK)>hgCEU+z#t8>jwT&{=rt4UEmUbM9BWe z1}>guo+l!>=k?`>o$BBD#qO`&)DQavwEVUHS@GRZGzMO$lPHH4!h);stLn+Qx1Vb0 zHgN`GJfC=6e68szECO{kgcRv;Ft!6j;)j{7fFYGYk;FM145axvZ@u@c?LPGnlfJ$_P-Vvh9io-{fsh zlvpavFc5r?VX`;(5^May;9FMsQEc*8(pf*O7JCYG3-%m+f53q?x_k|L=W6wJz6f)* zA=dxB^t3m{|s+6sZ}W%aWUOjX$EbT>%7@Y zEQ&o;(biN9^2?^X!Efg7a2oL9_H-E`KG^g6?9_EC*KOLS$Yf@WVGq8Suf^JQ(|1OZiF+c-p1p_Pj7in@+UG{qan$Yv_veXeRb(0)$<7(Vbs*tH3YGAXi*NJ?)`& zr-mGM-x_AdBdPA%91Ukh3;`m+?=%VSXM3ov##uH&Hs;;e&~GxiGPwLpqKEh>k)8GF zm~qN0oK;+P*&5M>1k1k6i}y3wAR~;>sTe}<#Bc35R+c~dxb=$GaXAEsknC)?bO~V- zzT-ll#G{g}2OzR|Hn=_lKhS7$m9iWgti7424wFNfFIuE)}0J>!l&C;AHKY-eH>3;U9(-ql>P)OkTI*J-6YD zfVy<_<^PAOvkHjv-@d-2BB2b@NDkd4jWi71-QC?SNcYe!-5}i{ozmSgfOL1g-xi*GK5u?Aa%DoD5xzpaQq?ug{!N z=Vzd~Qy$pX{Ik_|3p;d23OTRxTM0-jeSaKpbXG>{#M#d}-5Sd8vE2A2MNKghKg;tY z92)L6#G0rtlV`I<{PbD!LdKTZe2ByA+Et+&#Yi zH^e7mRg82pa+bD`v&07*H3~E{N5RGdgrKEH-0JHxg+K8UvHdfQrurur@M#mM)N&1wbUYx1JkrVDbi9}=Rq!`HUQSD8 zw0@MK{)r9^oEchVpVp8`z3x9GL7bM()M&W6k*=cFBV3aeA3#J|WvLU*V~tC5Qe zgRal^XX+wkYOW#+nz~4-LSvdR3DqQ{_MSi-`uR|GiWCnV4iPkJK@eUB>MeK&5dSue zB}ZT4frPq?ssmI>Tun(RN0l0M35)|$SPghLAl?0LN(cfXHxwMED+lyS-eAu--V9u* z8uxx?M!LbUv7M{!e;`OERtU0KBU{SuUFF4YAtc2XB!xo?E9Ws8{dC%X5UgaDf&HV2{SfO>wmfM#g!MO+T!!)hiI=Ne?|j-}OyRK0B9VJXg|VFw)J2Z! zz47+B?`?+vl)AT=8h< zIazlJl-4HxY)&*4?Iou%H2MC4Z*T-HH=j7NoM}Gd(C{YXIsUs~qeM&ak-)Hb7W`9a z&uJKlmqCLd&?%m^vgh1-Fr$EB*(PlCd6kZVBsJ-J)=g}VnchtBfn2aRCgppvX2<4& zrk0KY=yQp*kc`AlMm|d=-~2S0$+^4Y6ws*JZMV6zhS{-skC?(rNP)^WU@m8ixmhkU zh$_~+c9Cr%nWu4%4^qyR#Iq+a0f~FwWPo1l{jw2Y^I;y_e^)&BgSDpU}89#J#b8xS$ z77(77Dcf3pC3KX_nXo&dc49rjfA`t32IF72oqxMbmj4^P%NM{tQbdft&ZDX+Vas)W zr--`BecF~71KtvldK|T%qc&-}YC~%}dP3ub{PM;%TkcGtr+c@-X5n2N zN|bjq-ed3w*7uSn~>c~F4+Og3-N6B7R>C?AQC-KNGiQt4^Zcz64X15%EjH_K95#5OOoL#P-GJ z`#+PdMCLgK)g5TBO~+VIus|6Ysqjq@>4$DUnXJIDI8F?01%(+jPoPUQoNf2iNH*qgg z$>lha0MVwxX8XLDW+5?>coro8uC$CAjFF!--=s{69tZ@0m9$0qvP+q;xi}lZcmz{o zIyRXAl^IX8$2e}9s)lLt^ab=mo<}vaEh`~< z;8p}A1lVq|N7LrvBLY?o@`xYmTJlL=^pI%k=3>(C$De*14KeeF|H}8_;%Y>r(1k)$ zz!9*`OB5%Ol!3IHe!b;|imSx~NJ(`FLcJULkx1^B-X<9wk!0>H zA_+h2{16Vq_TXYTj{)O$EB}%^l+z}Q>zPNgI%wI*liM9JBU;rx7h@5@3#b^)7>#GB z{j1pQe7uipdiL`R!;IMdqy5fp?ERvf=5Q*j$Hg(eatY`RI&q zb8&7T1XGU;Oms45ZkW%02HIbDzUE|yafG+6x9_=Xzb>@jt-h_=5@+NM?qTE>UyG<} zu$^QE2NE_1A6ZmCx}W!9&#rEEpmab<0P39{H>qZ>XBmFaf7bHeUR+$nR#u5wKiqUu zt|?rhP)v{$Cs%Deb8mav+8Mcws&`P|q&sw4+ zp7H|RhF+K3zQfP{Ta!bMC*-BScn15#iPnJGGPTAlB|Wu0$jN5{9@lb=$6aRICwI!Z z@MK-jzgS2$U5~!7`mGeBXoZ6Pj&O%ePm+<&YrP{oWO5yzyxYOe1IIk!Y+aj|dOxin znjU5YOU%}VEeKPkOLOew!_)%4f+V#+eUB~MUT^#+C*(uao#4{a@f6gwVupzPzSrfI zXEOWX%~fawEiG9>K@6}&9k+!uRpO+n2^}?2E<_~WK1`iSB_DlB4DZ>KA>N4UIh7&(n9t2q5bk$S zn1C ziB8oR&Q8g2CkoIl+P(iO>0J}Tm4loWWx(mm_ zoC&e|K*b)If^)Y!2-#uX=XTT1?-3u1QTIswJB@F0QxxkavTI4 z*$O1AC}eUR%nGNX7}Lqu_FV*J1GE(Pf4~DA+!;Ye)L*Qsbl$0Fr&0*-nQ%}2u&|-M z%tNmBzoIp3E$j-Bsb5srOAK_`(NNbR>>8FqFE1O4d-5*VBofeZ!ou4MDwg{sbs0NM zS_H7T*DlaW`vjDO1#u$s-m}P&r&^;{&Nk@x7Wlw<#6YsE4|-iTIO~FY@L)YCWf)l~ zha^Y5gp$R9UNf_^2V61zX~rM+eXGTU>E=S!g~nPS1LRDZNw-vqvOl<%h);zoj^ZJp zv{R{s)1Zt?WAJ6{XHWzkLBgCp%dWoRm|7eyAezczAm0OPOY)5*Mbjymr0e5}yIlVH z1HRqnvz*!w8a@=}1QPN?Ne%}fY_-lD*-X9bBm)&AuJ9u%U-@S!Q7P=o(V3s+M4By=0r$LRIl+ZnGWkk}AZCZWr7c zA~-a@cYHVNA3O@kWrx(rAlIAF9#LjOU)HZf8*jaaDku&^x45!$?zHyn%bk&Q7TXZ@ z;;sE|s@VZ6_xV>xlGO2HzHdEFQTU}X2f`B8+x2S-XD3g&)Wpx$&o8w{$4g9D+?7Q) zF*s$;>uf?HnY+FJv)FW?xlb)WMuGn=JLyCF(csCx=Cy+@J8bASS$znD=#bsNS&eVyEe)~wd0ik)5yw=iM6%uugj4=GO^1KUP$6Df1*i(OrQwou4j+a_FH>s2T3i0ls@*l z2*CMA=7-t(x2Drc>^Lp?NOq{9c^JveaP^>1v2sbHH;;Mc>acU;NvaBdwWaOl0{QM) zu1d_vD6jN8W7E-N6J+=_udc4WrSf4w&o|=QO0^_+q4-E6!XXc`IS9lM5SoX2cyDkA zwin}|UTNvr|AA-8$!$~Ns-UtUrLB}tj6HvN6l|!d5P?sk!kV3BR_rWwl z=5(bNV1&DTQREJMl)8Swix2c(v24l;9q7orzr}=o>Ss)BWHZD4LX3YRn8%qPg_&)X zUsCAXuk#Q79-3-aV3>0o;*f5=M?nf1?B)qh8hL@r=1co%ZqeK-7JgPp{UA|aueTQd znc?Bh(&S-z@i@%s>EDSsYw7%Y4Kr6m0hQp zo0#~Hs|SWO3awEC#t2xVN4a*w%td3w`>U$oym`F>i3lpU^$>c5)CUcOgk<|*K-F>_ zMkDtdc;$ap%h5y?#$S};WPDiiVtJqc#(s8q_1$w?8pFIlqvj2pJ@XLpjf-)-Y`cHb zmf~8zqNkKNkB*~yq=dq{*X;Q~-IJ*b{Bi92hoP1z1C&l+_oE>WCL_dEIZ@F7PPMcO z=)|C3CcENZyC;&Hrc){6x66lXw!yE-`9=@1_@It7-hlj?1o7Ppufu3K$nFl*31K_X zRBfcSmbuy|9AWx{!d3zn$~Vq(R;cP4{NT%nCGf(izuMx`bTCW{U1UxIPN!JM`HIfd z^fH1WO9goA3cRYRLCKai_RhAfl{AY_W<|sK*lJaDQ;m<5$CeHPsRi{)$xB; zteY<@>-_%#vK+A_F+ThX(>OxA; z;?_7uphxw8jOw!=4Kv%EAd3;C`lvWH`0XuGz$L>Yp%|ejN`JODVKncJJ7fo&I4d-_ zrbfF$E;8S3uzATRd;lK@TstS18I z96^uEx-jyW6*x_A5)_y|brXdt;qdpgC3%;*mgzLkmxMGfq?rN=7G9D3f0(WgR-tm( zk6g|7r5j_6G(xhvgisuyg0^x17_10^KyrWl_y|QhQqeF7>I%ZtI9<*F6bu|n+CETx z!omWzlZGYdSl#O4aJu^$o7tWCMmwnq1wC<0;WCY!BL5Nx#QQ_A=HH|3i2@>c^lrKw zlRpYiaO14cN8xi=zAi2rQO?&l6 zVhbUp4;RjR!WX;Pdfwmu<{{8W#!2`4kgRZf*PxngrX=W$2SFa;1R*=SoECd1jtX@? zv|L@kpb`rR9chf%5|WqN zrm{3ou-2gd;Z3lHlF)^B3tZY+*y!Kj3W0GG@*CNLPa3l``f{k~XvE^+vnC0+4m~^& z@b-Lu{bJ3c^|-&_hYUUbG7}_OPLR+-iX6FT-11iCJ<^`tZacM+bY zjX#z0LP10an+w3pW9s8B9{W>_Ru$N6frT%@I;AKVZSBH#=Qz^q~_o*h7^E$4fxuLI15R(ioIB3R`^~Bi*F*kDQlJ7FBTi2 zS-aL;91h!KQa2;=F4B64C-L@|tLK^ql`6aGb;vg+53EejjRBWTQ4N2_HIgg1S5UQA z%-)3yRoJfI0G}>=GiQzb$=8nz&K}t#_(CS%5*Cm528_F4KY_zVfPN=M5hd$AcUC4b*X$Jsf#EL048gasbrT=RbM>@`G{jfR>9z$)LXi=Hu+#a^DwzV>7+ z)@A}CR$&rN>U@O;X{&}g6!oln{2ar~&qFS^-+c z8^L-j0ZQYXA0Ul0s%i#(7orPIwiN(jZnyn!vO2B%k1Gok{`yp*6dtN7iDVz&<@{_C z$z}(?T#r`{%z#dZnq;CS8&#@D)DL592!XTQ5^r?%-evN*bq!Gx233b#3uzc52!-9B z<%uQEm6!D*4%1~a#ZCxVvG7;D^{o%>R;20X3oRm(xNFIy;CrWJI=@|FrrQObAvi730Z1c%F2a+1VPAekr-w#( zU&IW1YucPkJ_`seiKJHx-WYE^+HLo^tqbUUzE!eRe5a#*Nt`0uJ>G;NJFst-8S{*Y zD&ngf4JHA(4*}`UKIhX?^6$fjJD%S|vzj)cDNZV|Xorel_(5qT`$69z__rWMG$bb5 zcKR-6+;>T=v2P&Jsj=6Nfy-IXaX+2zHbb_dP%wca*-T|wHx$Hqybq72xY^oOEx}@K zH@iG3>^^ve&9B)6DvxYd6b?FcPVc0>z&LG|2qAOv?gA1sKV%5@?ou0oYZ9q9BpZv? zQLWz*;e_?i|N7rKw_;)bEOUj)>O2^|3Ns4J`lh;qd_%sGh_bUQ>mP50sW)FadGofT z#qgikR91}Of=S>ha%_vt>qXzEo}Tp>Gi1bv)h7AcV3r}I?>W3!i!>?;D%wal^rKh= zo!+AlWcg2zb;u(bXyX`Bhgc22KzK*i>~}3U`uCVu%5RWPP<{8j?R?MgSz4JmO14{^a$Xh$Y1=Q0b{$549^nU zWj~|E$2uwBo(tF|3_NVK%gt>CC9n16_DRh=W6`hUSP2#Kb>dkxz&pug{@x-G&b1v% zA{Gy~9~Yo#3Pft5o946m%udN6N52tC#38%B$rsi*N7vPs_MWo-aS$2aK{n>wAlPfl zaC~cYT6WrP(r|pE<1OLD>Ga|0GnZj@+X3W+vycs*IgdK@Ws?(aWN|5N=BV%u1;=+t zEm@RQ1RlieWBh9g(KTAvxqoVR9c*u8w_RSt;7solaEiNapr6{Ux? z?Xj_+rR3H1_$JJ?T?nautCl|YinWCQ`^`6??3kUSV`EgC9xtrl>2t>aV%g_m*6k2v zSN_h!p&vsi#_zXtx%NZ#U(?pr!B?z;#RUanlB(3dwZ7cTsZ^S6osmWVg8GF{^E*DjyZ44_dr0NJ&T-6= zEtc-DQOo13SRiwoi(0H4`-9q)%;o=|7ZoHb)TWu+#tu9~|I0{3;Hd$rV*q zg(rt*CDe;EIv>qoE^^&VE~T9Jee!-;GwoTH?s zq%#XV?7N?Ck=U!`yW-PqaLxfZqi7Bxz=wST7GC|C#eV!i6y#da*H0=zQxNV7j*!S8 zfeFqhm@|Pkc>hKKr?Q$E{!U|;jNVL(h2PR_%XzBvj89CQ6>2lcW{3;ki~i=o@tbnM zh&ZgPUb{yiAXv&;-`6zF+}vEgj0?(MP}Nw#9^tCA5*+v(a?vYcA5K|qd@rf2V%>dZ zp+ubMf||IU^JsUIYPF*>6|5oHfvrnqHT)=e$TI3|GD-f$26em3A}=vzfb;NYm`K8p zt$3di@oYj9sxc`N%1-#tt*FWMBhy~fdj%svRx_y7tJ-u%twKcSnww5AWv%{epo-5lInxe*;;c)_g zwa+6zZl07eAG`9(dy2x_(VM4mQBL(=`lNouD)^FdnRAR|7Vo1EO@YiOI6vtQq1fRV%T!q|!$ua~E5 z{#S6~l;bV%$wz)~mFRNr({{6(*~VAK&Wg(AEeEij`z?-#j=7uHN7LYCSe=kb_6)8) zh9KmJZ*eAxT$pQ3JGH9NQ#Jq(rh^Z{fwhJPr=8|1MhEbh$T6i!H$K0gV-SR3)CYOfdSkYtW~`! zsqBDhf4C8~we285ypv!7(NgQrUXb7It=snTRCW66Gex2u^H4eDmQ*7p?%kQHo9BFi&TPCEuT?rWgb=LMX*@+Y(SF#$eBR@4L~?@bZj zQgLSS966+nlK7GwW)H%U+OfSZgl;pt>c=WQgx_ zNPZC;*~1Ji3##jF^=9wXD{(`yGRtgMBi@h1FhxX&sB0fQxE9TAEoZKa%gbk&ajHs6 z6rjOwq7gGwzYAs3e>(3gj;66ot@6j+2^pf^ruE{3$xu8<^S`6dd!mBawX3A3P~uWe zS5V7Gt~cVJn?#`50!yVM%m)O?t_dMEYD1~y=Yhdo@3Kz#Mhqq5$rdgLX@ztd55CTwAlQoDY$ftAAVYE9#2mEI z0o^x$maIMrX*5^({9#4Sh7x9>i%8Y4;QEmSe^$3OQgW{|6k6Qx5RA{Gk&~o>Joz3H z9r#uiwHjHMkQSz|wUL>ryxIH~LHnUb{o9dF3_?(ha3USXJH&ixOK>bHy?c^J!)Ipr zbY$a}y{t55om>2@{JyGOlw;IS7)h!SIHo;jy;--OjDYWV6 zHky>`R;csIFk{t+xMk-PXET-;o>HN7*S`o1(3dg*nL&W)p8vhfwYg{C3ru&G5ajzv z#Wnu_rBOxLy_rKu{HMX%XPc8_OSblWIv%^FC#iLW#qEsyZ8Ai!$bm+^s^vmby#V(I~^WhckWNv~hNoDT~a z%=#O|5UfwbtLlM4$h(_SYI?m-8q*Ui3;tVR7U!cSjP?fxaMGgefrK>SPu!@a>IAjBSCr8aTrK z&6!6DM6PTnU1T_B_`sA-PvzS^vYP%}2EsyJH9@^gy+nW1GJy+M!T9f-nlNc1@>;ZD^S&z8b1=ZFP4db^ooKtR6-w#+XF%B)E66q;lM z35>z!lZJYYJq#Y+0ecJtU+2S^-W+MF1kI*|j@%Fzu|bF%xy~8RAtQfW*GFe{SukuE zpezy{cp zlW=v>!P*UFH+j%QpBN@|&R*gL_p2}O#pR`n>#*2;b8sYwsL|cg2(EgEI}Bmd9$JZ! z@y^*)=5QA!{o)^ud`=p?Tglv-ffd$pP#IMFnx=U}Ap=>J-~j1)SNXV~EpjlsccOc$LTQ397Sj(doJLRPTyjyS z*_o-WWdomXGkZU2hUD-uRdM)hb7?sfvAWBDMLC#98d%aEV&+m;xDC8z&-PuD?0uBh#!^rw)#c z41D%$h1>3rR)JkvL;Q+uref1u+OIhi*FidF|hDVb@5RnPmSJy53yq5dZaVdHtvH z5P)*P&`hAutTS0a8q17Zol;N%P6!vwNQd{;<`_n)gU#-&6)eg>7Y{Wq)+!z+AhaLJz`V zwu)*IC~C_86TNP%y|5I?g|Zr-WX<6BxP%{~$bL)#twiphgoDx4$oc8t^cg9X>sF)8 z>-jK$sniOqYw0vNBPF@ybA571vG1GxGnZF1NJ+am4&m;T|PpHXR}A(i&GS{G>%zt7EDIFq2^0atFSTBM|Z6Op+3!VPKe}TwOw^ z%yb3}4-eO&JsNVE7&mqZyvvq;hP^Z$@5T7Ax+?T*(-RL};#bbnS9-HCXmdj`RD8fV zyRt16${XXbEo(YB!G?>j;K@PH+Ihq6Y8ewKej_#x4X~^~4HkTx6#{l$t?#(0vWZ-o ze2^^H;6;zXmKm7gLUn)XYlL`%VD4UU7q3x3-zyi)aZ7eq{=fsf>k^!NPk2#QY6m@d z_JUOErDNl|E+x9fZr1|sp;0k?Khepq34T5oMp>O-Aj=tDgq#+qe*sT{EhGqU?uQG z3v@E-aCxte(s62D2a{^?lfR_TRrRF~M5)s1q{;&#F*x+Y*>KnR>K;Us^>;_jhMu>t zC2fB}aoj>K)C2cWHW{>oj(84#3v+S8K|491p0|~`&CkW?)WYd!c-eS$_|4%94j5H7DuC^Eh9yNE_}`nPo&~;5ZQ?J%=@NYPep+ z=a9p+on`owYoi$c@WwT7rNrx0;g zk9Fd4=J5AYw;Zc20y|cUDP@0*xtHU;jaV{rJ28kY$F`Yvx*i%o&WWv|n4Dz0JDL_f zK-7jmg5@2Y9=}BsM1#0|MEw|{c zsRyCp`r^p)9SYT*E+8qy*&UZAx^E}$oo}{Qm1-BN!PWb--ax}09v1(oD@Jxd@n+($ zgZM#hB&k7I!_XH%nlA4ecQ>AG=u)_kw_@~XhFg=>b^kMZn+rpFQDewxOR57vc!ej% z=yG(56z$Odbh**4s)k91mVDr|8^L>IxF649e>3n|gRr0NOZ~+&hztk<>hLGF1wNP*#ZMJ%k@wQlFb-TXA>zB1*l} zl^hTMprAu94a#`;iX@zb(+S6qOHPg$Yey63OgARU9vtJ=)-pn%Mz0XpnPr)oQPuD7 zHs!rMqGjpuZYa!?v>c+P>f3k@CSmLp*c;|E@B;4|PMSuA7{A`>P5@*Sce}hez?ho` zN@XeuHaC$L(0f}HSZpak1N#FSjuVif^TG4#_^bSYW~VEv?&~RX%GHbCBtsSYbITqv z;AUh;*WdX^UYpONwzOGLR6Tw`jpCQ-sxJADT!Zst(;>ab6UKFYkX*na;GHI7+qPbP3aFU zg0QlR^c&WoUqjIU%SyDvc0b7#{Ud*m;dow4i{>d)L?+x2N8M-xeZEDGEPoZfE8wE} z5NT*H>ECh#=%bGVQR>%!Tm1_I0?1fOMY4URiL{e53!!MAdA25mKZqJA#3}U{+64~R zxvl$P&%d6%)xxlk_5W(4Eni}*>6^=9X&wMI1BGjrW+Mro{os4ssJm>rGxu*po z#yjM|id4a%2NCD_eIp-roLFZOr&`ca^G%%wszRP(!U05R_Ul{mFDB-{YhZEU7`Vz& z#@0&$*q^k#qF)_;6$xV^NEeAn9KqU58yOe&@Cb4qI$yK^45`EU-c7G>L9N6pJ6cXo z7=#_KwonA6(_jSKMy^tep?atGe(?9VWG*Z_njIv#--PW6grzrPYJvOqE9!J5HWFDI z@7Y9^?yOD8UoOWiA&FPrC1yI2=y?MYAUyo}s-Ch}55&{XXT9lcRz3y|SyzT=JU5zX zJU>#z+vBKmdxBas#URp{@WKIlf7f6>NUgEBxuAoPe%+Rc9GWs&fXow`5pyhKp$~cg9;G z?tj)gLF1+b>>?0`1TyZT`t>tr&Vz+*d3Ehv;}i-FGR+NxP8487ECJ^G;Ez%`q>5Ao zg1_WAjF5mp#yAPX)ijk9mV4oH^%nU@a-<@qy=YE*5jkf%Yh^c+9yDJ3zhR>_XP|ZX z@esmjXA~>7QD_gt&gkU=N7v(+j|<=N2K;;Q_wPRDfy`)VXsC#wU|h6#4H8JQ&U6c0 z#4EWgSz=Z6T?%T9V$x9R-<~w}zP~SWKk90g*HfFWxzXwg6pqFTiKuEqi95%Ez`3vo^0?$Vlo&#h<9JRiPRuItOvBqCn0xeUwC^vmEjPRimamm0x{vp zb78Q!0Nj$Q-kx;4nw0C-B5g;1MOyFN6en%04q!bGbUQ1{UMaR+`*cBAs8n;h|LMf< zKm`StUvi3iRS)1lSFRm>DaR$v54DBbK!{n)4l-cBt-<439E(itX3pR0{;Jb5)J#{r z9eNBk8(B#x6gzZJFIs}NYFhA>X|&yy&o8Mr7``Z{w2vIb^rH>=5lO;{@oj8w^l40z}dGG(_Dc0wNMsb$^grpLxtSL zMM$0NgMC*%2_91ukfBg0XRUgk*%2}XZtR!qV;C#HpmnBD`wh6ZSNLSPo- z*e>$hT zLn>Thz!>X>Qp3IXK)S$qa1wZfvo9Z;Y(=IO*A*U|2*EH4H!DTi54o z7ix^`Q8K|0V)SA1_mhS)0tZcVzUpf8Jw|jW%mDV z9_UX(qjes0jgtAz=Sz~mX8}%+A=je53U6m-*@tl>ddO;088~A;wzwXKZB4m4GCW)E zQ$TIv=!;6J8JY;gV?$7IA?7D6(ob>KkW_LH!4fUiIWz>8B5=*kpJ}@{PoHBxvn zXKnG3kV&)nax0qSH3q z;c!k0cxf@-qaxqT3X_sW<_39$t%QMWeNb&WwHa}t*MP%yJEXt<7p;=(ochfQt=C9P zorp;4Z`~jnK8^IzBvVyHUXQWg+r2V2PRYQ0_EVgW%QiD(R0!I|!89cGacG6FFlMfH z1&{2DTz$~od1KJ1#>Z4v<_)|iCO7~6D)zbeSu)R!i!J|iPx|L@_OHa9|Lhr}>4VCH zrUBveI$aHkJW-^fYJkZw9 znE*GN%mVv@9Iv32u2>~0r3H`FL99Q)u^*IA;y_HuaZ*~-4MUD;FWcph4bxfOW+3tI zXu7B}2n8mT!J`Syln+-qr*g|HQ2=m;FGW@^rzokbn+3KTB|z!wBQI-$;6u?o64FyI z9TZJw0T+(i!$-T!vMlKI?LRYspOYhdTz(t@H|<}|pMzArXMEz3&G5K0>&lhFfrRnU z#ICZPC{$ESq~e?$!o#@=l?cJ3qTF1efv92b+4)%#1|yESd86t6sI)?pBt(#!s%mad zwV)1mGbCo$97ToQrMNgcw=m1he~*MU-}n_5m?fRZl_X}P^GQaA8B?S6;tpMo;-~w$ zkoC$>Ld>0XWZ)N;UcfHF6sZiiLX2`QR*5?*Zwa?Mc|LhoxLQ|o zrSLB@E3*CFe#sKbLkgGpNlRi4#^+%Tr!U{-R{i#LAd5vN*;r@ZBVNSfu)bUv!0vPJ zSoa=EdcgU!tXCjurAK4fZ?m~C>f%KUfIHvj+p*o-@%g|xk9hS3Zj8N->AJ3lH5I2o z8-@OswArQ3|5Vh!p9o#+h5yvszkgc8s0=pb=w0JrFu(72l}3=VvC+ibVxTq@-;6f! zWOA%8ptC)mEm`bm5Pym$|y zRNhd^ksF}`4*XQ)&WwE31l4 zfolXZpin725boC?b#0-58{0@N(m7^$Sfgu-jgKTN^-7Kbb8E0P4J0!_C6J3!uPcK_ zANj@vX|!rGr;bu{?@yI&~a+fFmD+;_MAiGBi@4sa7dB_j`AS2WEFi({gMt`}v@|KY_P9 z_sna4x1YW5)>>0oJix(2L~^|e)YQx?ahVsMPTnY zVJyC^HZt$$#b_GmSQE8fMh{=EE!%Bpa;*JIuj(xIuG}{l6yL{IoF($ddQp|j*<({>&P!j**I;0 zkoiz=tP5x4TNsOxmhCR9q@X`t=ELj8q4Sx)?0l-Y+g150Rg|qPs+HQom?KGsB?UH)V!#@r06-To<@JEsu`W55S9qII1L`L?0XGR5G z?v;68nvHko-d~>e&B!s^9GD$Qh97P*aeoQaV64^WP1m0OULKQ$gf285l`s^R$VtyO zq`mXUvE3sYl*T-lWnMt_%@nEbXc{=agt#a?uqCH`aP~aGAuz_dPQq73Fuy%}Y5q0EL2D(qGG zu2nTxSJh@rZziz1dL~GUaSAopM6@PyslJ#jWyD2>myYf!byydw%^BWLPU6QF>m5jB zxcs@HSS)AwUY7%j_x>UBCMo_&XoTa(HI9)&h|eTDS{P9V9OhQPO=1GqcSP_Ts<3K9 zVOoy<78y1%u%KoZkff=$028~RC_v{SezXY%JVw92&l%%zVvT4|1@6mvIy|i5HhHzu+UWfJfT*TBJj~VP zQ5W6wLfuH>mqOXq;-JAXr=a1ivm!7BuI}iDZj>3_o5b~`xUI@hQj%EGfK&o5Huj>)i3Abl{!oy)rEG3B7r6(pz~f5CJbFqo z?uuk}nlvFxL$e4R3Xsk}b>}rL|LjovCshBf%$tL1|ciuiU5@Ga1-dik| z*^WwZtLP3b`g|~41e^Ic0alrW@g!hkKfs7ct1Mb0kPq*VJs@%_3m!(Z`&}`3y?A0@ zarmQ6sPj@&B}toZON^lctSDNWXOv3PWwNKuid^aOePTFg4}l10q64xneVVJkoqoJc2y5 zDJm2AU4|q&;*=mv%+6~ySwOD@JDOzoT1`CCxWeXU&?Plo*yqtaFWNa~2hAM=t@!L% zPl9YOIm2*G9+tpifjSxyD^3~n;wq(NJycYeV(5mhKRZ7!>D%6dJbgLrHJ zT;rF_)F)8J2gDOik1AieEbI?X;>?zjL8Za3=wagk#eM-YH5-~hB|||ZE4|xDPJ|hx zE^vJ;8g8bOHIXE#>;M0v`e`0?U-9k#FDhcCod@O3)| zx=(KhJ3=S8E4j*?xiI5d=Hw{u2|eQyoTN$7hPbs=Yrkf2EFbvQf9YeTv&%@r=d>ao z`aT-+oh#{l$W3Eja85;MU_b3AU)+{{I@vGi|zt?jjb*pc=5&Qa2(^@!CT zmh<`#g>)W45e~;UEw}{>4#C|W zg1fs1cMtCF?iSqHxVzg9!QI{ct=zizo%3FPP$?*&sM@P{cYkw^F{uLp*gl^AbrmY9 zTAe9b7r^&=P~h0kjIe)XW#5`D_X(9jt{>-ZR?^h4-e^L1M z$+`cD{{8O<5_BB6ZPgY{Fx|B)(Qg4;h4>8A6$Rx>8UyAm+Xzb8%7#QU68X!*_1$Ap-pcRrcnNU|?YyN)0w9 z1->evK}o>nHsZ$TCa!1D3YCtwd!Oaed~N{ z{?mM#DI4QWshr&cjEgpcy?1yGgHS7S$Bgosgqs3pX^C@qWW*X)tJtwgL3~*%)YybH zGbu=(iI zu+JCik&@0+W)|Z({(=mxc|1&yCsaCA(%+gqVTYD{D~;RlKA<6yWys8PE(BzyX&{E) zAc9?lk7JK+?YA7j9YWym6i@yvX~nj$eM5l2zaj7?DRJZx*577dB0K+2`T0={-|hpK^U+SC=1*j@xc29@wwAXiqTJuDqa)4S*vj?itHU4oeA>C>{98BjcIJC*Rg^-@C##Ci7jZfKf)5M5)Xmg|4A@54^`{; z_?CtOhi9U9AL!>({?S+qMKbup8jEdBZO2DY=}HZzkVTqu^GSJu#=5u(m zqwRue9Sz&s&RHwWJ%Rnqm~w|K=_@31UnigHt61K1?OOUqGok+c0B2{m`f{)TV!N1X^Iq-iKlL2Z^wiMw1EZ~M} zJ?p>!>tgZ67dTg@Y^MWQ;8oYvp#2R+RuY+hErfhfd4cmPslMLw zSqvPC+GUq_Di<9qb9(I8I3WQciBELOka5Ob1OiMGEhEcyk>Ps{{f9QA>Ku7>s|9eb z1w0ga#7M14Ocr$0PYru{aNh2UesU(AwO@_qkJGO6v)A@n>2?1ES4I2@-hpl^C_>ic zyc~W2ftD!gM@20Z2tWCKrnZbPtq3E*jUvUBF6I9H_X#pR-{K*FxGX0q^W?M8CT%|& zA6>~awg2m}8x;UTjmvdL_D4&1AjeE4L$fy`2>y;KG>&gE5U6U*LA1vlqbefdppYWt zPq5rq4U-s?I~(tqn@NVo_&uiXYQ)|CHOe_Rah&{jvWa$zq}Rcc)J#!aKZqs1%<3zS zHpFB)ec`9KU&YN>l;WnjyP1pnM-N3rywYeq9;VnWF)Qf8O-oD%vcGA_yCx&NA6{*8 zD!tpb>oOnrmT>eJR^q42{ zeXzX@`TggBHU2tPkFFNiAA22rZDGVGh3@yU2L%M@Ob%CYcJqG{rpsM@m-vZ*@x|pV zyxeAv?<4Qo>kwVbdsWv)-1A%T(AhH#;T!n0*IsY5%B0-3-NyJj zIUtzIdLxu4%f>rMcP?RE{9IJ7?58+i4|W@GS@^FL)gR~o<)s2QOM2Xkl~11>JH4Q9 z8;`Sq9FZSCieR&Dh`~juqX2nhgo$*@R#n?sFK|dD7|0ly{3W#*M=HLRe(sG72w7y$ zn$e|qX-xYge+!|?!h$S)oGLtrj|i(x z;u7>(jOy|?{Tiujz~&t%Rat8J?C7^v{mQn2%-VfI1KML(L&MB zwaSo=Df4+PU#02RX*D|~cdW(ivypWf!XU`-+&6EbVslcW?1rnYgbjsNR0y_eO=)%J zLc#pnQTi_2_`GMz`1UvUOg1Pg7`twdj}#X(&(++<#1;pkX-QcDq(x`{h}eR!PbBy( zi-Hoe`Ws6dx^r6-)jqd0iPkL_~L_s)Rp9_gKO^y>LLFO@>7JDt=zqlzLJ+NWWXCgy$ zaS3x?E{YO;IJ#@Nd=8X%Uv2mnqy3qzsrH*T1)H-w?EV0as3!h5XlG}Pi=)gRL|U?d z{EgIZGAN}${G3nf^V3cN^5qSBjQ+$?5{JPGHa_F;51j{0RMKN< zP8y#?{+!$oL?;K%ecrrJ&#bf*&7<@Aek4^mj$_eWwDQ%BAe)s-ci# zq2pxop>s&?7=4!O=@PQ<(@?+xyM7JYu=(RY5%6@X(j}aSDLVBPEwG0SMdZ)Av|QAk zZ)U>NE3q3jHmW?_##HweBCp5ZbAD5t`4p`;$oTvNAjEGqE!+0}F{*^Zk05{vBkhWt zLWtn~*Rz!9%86nFZ%knMl-_3zoEhD0f(wLGHf2Zu`^}|$o#p@DT)eDH%QYgV_*&=U zZCxP3+|ZN9ebM3ffm)M5QfF7&qbaR+O*il*ROMp1Y#yBVm*@4YOj`Abz15InN$VP$MY(!Xe>3_?gZ(5b2pnuo_3HaY;kh+z+bUeh$Z`? zlQr>j+DOJ}Lm@4@F#;8PcumjYihB1I{jtnNAYr@7ocwK884@N|Pd+m5`84EmJ9-eb zpBXtu&q(}nv+cRL@p?Uz7kK3KWS?IIPhI}V zk~i=Kg|R)KU#{{whx+Pv1T7>}2#OWsxjm$`Mir;XLps(;TasV?3PzG!%0HGxN4*Rc zIV+)dYv#|FlqagdKE5wICd6@YxxbN0tFCkF=*yCAgz`e??}oWEm0eY2CKy@76VN2$ z4dn2b)$eotCx^dnKNGM^;w&2u3kA0rPi9yQu~l7V`T9-qtl^MV#{Lpkl-*k$Yqjyl zvfe$lZYhM*Jk4u|gk>K$!ZC5#Hq`~%*YERNF*`KM#;$SNk4s`gT;!*2y0b@^BQ0UG zJK)f2v+umjb@Ysy&<<U;`5ak7H0gtK2XsiroBl z1f{rllU8I~R~cL)PpanbT_FAhKgx{~$0}P6T-lvdG3A;IhLhD{GLC1@{YK_T&aW*E z?YU3HAiMAu6WUch<~R|0%H@H~aRP}%ut_z|q&XH}tqrekNJ{&9P_S67bTFr?seXvW z&x}!uISm+_;)hhz*BudHyh4z zwO`x>{HbwCsxX5Cxj#xt!9fd8j!&cj6oq@AXD*bK`g*`omGe_ON==Pnka=wX$ZThB zY;U6|3I1~PDJfM?DLNSPe$h~GVA;0wu%Ffit39H=u8yVC;gAe;eKN)82}c(Ae-8&R zSvw*8fB8mRRs*w8wteafHGgy}^mtdpJ`%}gny4RM3)n(l~QRSB> zSD+T#&6MBf6;X3fG?qDlYHOchhoCFhI>>vyzI!M@m3@2qpu8l!$2)t4Tjq8rrg>d zmY$LPEhwvhJvZ+~OjZJKWK)=xM@uyKj>Z)S3nFm09m2yIT3Pb1(xn))sZt_Ee7a3z zSuoyd%~rqC*?!mJD)z~sFU9^$C6sf*YAVFd{!Fw84jzw%XYW!=O5DB50#vvMIa%c}x?lGQl=uXVX&Vh5>3 zz(y>7(y{sAv^EDm-V!?}#w>dn+)?_-m@`vhLes{ik=FH+>RVIoDd#!$O5=(HZyMSm zWnsJtk8Z04>E;BAvgT3wLowSF{x(@WtF7QP6B+B?P@)?qtow8=ZK#C$8W(4qQ<2!N zLpPD&S8P?+pQqAS^09cctd`Mn`pM>;*V?{kP~v-SqVV6345jY|_Z`C=sFS=hWDCn@@^v${kZUFLcR^$FHs{)P~*KJ0WJsAu*nkUBDMCNg>5SGcrX zMWSiDNbybbvVC=xLyyK+3?n7Ww9{vvB*064E{3S$@cdlWa$v6Q^hU*TR7yHstAwS2 zjRxyp!kB9B3du7jN?!Cis4u;$tg1gVP49O*oxZZrF(-4*HNL@PJV?FKA?-v`2wb54 zlBWu-_4UD|72+G=a9#wjtf#?m)~(qZcvIn4}I?ug-}(&cLl{@5G&> z0dG&RO7Ai|w4$kD4e#%PN%IDx^P8G5fsTp2B4%3zDhz%uq`KkmR?H0m9Sb$a$SZC5 z|N2i<)c-FZF#rxWCJ9#=QjI?K1?E!UlxH3;w$h~jg!!QF zPVBBG{Q1fIYAHUx zUd}Lz<;$bF%FuoR4_{-b@F&>HrPzb+&c`5CzC=o6(}5pm{$e1TJ);W$X%bjL&eDSt z|7^cUuT~SAOnH(%%zFtf_hn%k1^xSOK1!nf-WFmB91V$C0B6LQV@wb|%!&ZbXjAkQ6ElENx?zq~>v;e?8 z2jWljjmg(3xdWMnwVlRyb365@;8aMaoObRb8>u6afN%19&ZZ^EMDeni9%v=XGwnx94c766}uoW?|D_Udid7y>N zXGW2nOuRubrYO$;bI<94G1-&aiD&mT6V!6j9$?=CqR_uNfQZe|qcoE~V;kDl7#v=P zypKIER>M@F<8XgWI*{E{J49GMb%l7Xpw=e4joF6W z%HaY#|6e2bHY9-k5H!$?kH_|NTCez=wlsGcOh;a!*X5J42k6vm&kZNSr{=xm2eJiA z&I)cph68ZpIsAIS&x!$nRw7C6>tgNClia0cOWK>Ns;a^N!gM~j$9hIL=8mRJmpkZk zx%urYlBYWJLq@>X%!_=AWsYu`-rpE5-i=U;NjfQN9kSGyJg(5Q`VE`Qiv=1PFG}z^ zD)GS&o8*ubMR*4RV+_v z+b{ooG<>h=f5K~2j@tty>@{y*DF{81_|z~IRp}_phuMi)YICM5RM@KIrg{k#Nma881~VAMkan1@~h)XCFu30?LFQk~eF zX7QC}q-=RCH-CayiQsuA2}Leq)FCLH4+Lid!J@ zQW}JU_`~3V8&4_i;Rd@p3WLQlRAa2}ro@!GSxw~Kz572>9I-s3GLM|%t+DyLF?)NZ zZ|(Z3B^XlE@*0^7@ow&q-&j~!4ps{m9ScKWn}Vz-`YOA)uUF9jB(FeUmU@hdiPulhe>Rj<BAU%{&d1=7Wl%EaSs zx0|K9XsZ|P=t@*5mC)F{`hw} z^};B|HQcT)K9?7nRZGG~3f;zDk-}mg-am?rG5H!|W8DYJM7ctX0ToD~t^7yZY^Fi)d$`=r`U_p%ekCQH@%H-M3`tD} zf+q5L$WwB(aypuq1pmC+8IhG;b~|kZPgm)1>+DO@gZf8S*&fD77rg;sNEYxXy!+O! zyu~}k^bm#SDydPY{QB4A$N{*#fUxkmzth`o`xcy~PBR%lW#@C2z;n@uXFETY`D2=H z0s@(5qwtQ9I$!1q{9<+g)u5OUwGY7B8M)kkqcB4*pv$s`es~>)Ey)a^sd{Csdg%;2 zf5lGGb42fSJdL>^pzr}wh)WpYwZhv67H6MA`$g`TgYCG41d0yDg0@E0W)+nm&9r2L z4+@H!!3ELS0gkdbVZy;=(|kO5ar0h~v%44W67-TZBLnJXl0CPWwN46EUKVOl{51-&!BWjToAd*NaKb>}wglfB*B0^r1Zb`1SnOdzq#q z;6_(j`Q%r}5UzA2`CuvIpn1N9SVC$)nvsm*Jhtb#xcvKn!(bV?rYBZct@LU zijKOz;LGcNz!EpJ>u4H?`Fa$HtD-8asioP6(#l{Q+5ofoa=Ujs9vBDx*+(XKl~AHI2yYoF5Jo)4yfW7&VUlRyHLVxIW{YB8jOE*$@Bp ztqBacIU2)3)VupALBk<&*QX8()1AWlxz_mGr#0M%Z6FR09%ha#w_-t4XrTvvE2pMO zoKC(OzE*42FqQirlN>F00}=tAawDQ&d6$c*rgZc&vhJ% zEPKLMm-C|IF4eo6a1&|gHw1M>|Fmq6)MVVhR`Ao*E6>Mj4O9lf)iF-eqVNuw>qwp1 z{6yty)h>$9n1h5)DBlPje|T@)V?T36b3K_qy!eQaE~qy@IZ}WD^kmicS7YNwN5%hs zCx`gg6nTi=Y(1{(yYG7UZgi4YQww1-MdT?UH}NA5ibnBkMKymH}YP9e%hm&%5*9_N;Cq~LcQJ1zChp}AUuFBVz%KW{3v@X;R$H_+86&E+`rl=xE06VjOgj4$76s`lbh`1jZJI)ba*fyq4A9KM5v@|1)p8-v|&40U2+46jOl zK$e>M1qCU@{?H_avkdx24x0=e)hX4_vhqPknofn@A6fz7+Hbw@$GoDwOGsWmM8OC| z|I}-^Aq1SLAq3tCg9JVeftMT))1>w-JC`2A2I3ZPn;yPA(Xq#Q;+ivIPmHc)W z-wQ{s?Y-3$z{?`*GkX$f`1zY7zHlMh@|hnzV7{ng^18#Ih}kJ;z- zt6uk`_6I7n4WnqEAqmRqWH~`S@axrew5w4dW;IR4NGQFjzPh4_s0Dmb50_0FeM8ol zi)_zzI=RBVa|CsY#+b#1nFa>6z2u|hq-6aWf6(uTA`>iG|4GPId3z$xHUYApLB!)4 zuMtCXN4pNXRDQMNdT1~l*nA};=E#jWKCen*>a^^bD{)3)(SbY6HLj8Fm}}*u-;L~N z)6ovvC5R=RxHvF`#S(AqMPmYI3^C49sEBbn+LC$R{ul$_Q0qeZ4QM?5GHrNp3MX-{ zS_J>heRR0-j86$V#oTn%3Q^KghrQx-g%&xQw*g|3qnPID4uN#S%_^RYcFL@qOH--3 zY^uLwKZ$LL9UPY}8QO!j9(ePhcA!*)HbgW7KSbmR3G6#a=vtHQG}rVJo7)?(9Xr!2 zFZC${6`qL-1Ba9*d5HSN2?Q*DXi&sfuo(Bhaa=#AY(>^H2$-ryPxiDnme(F+a9RqM zqNZ!1Q5h}k#JVxJxdkLxYW=Jz>y4nn^5V9^qr20{f7t+zlz=CAYe-F3gUI9l>~v+7 zz2`ar65nv4?l9DL-`m8*89$>*qzP85No;pzrSV)hTsmL9r4ZM#v#OsxqP)hzn$FTv ztE*bwcjO9}RtsblQIlB9`Ir$LKH9VdUVX+t`foh03)b@8Zw=?!GLu9aQ- zzCW)&K@o?Mws!)n0>@d)_KmKRw#Q)+FpEECmE9Tu9LUH&knc{bZj|KYw4I8o|bUwoJmx&NJttN8JqunJg zf7)v9dZiPKA*}4&r`paw8SBj_uTW=M3e#wSIw;6_5SgsLx^jp*r)$ykDS0zYmRi;M zNEZRns(!5U&0HZY9|2NnN7r+smxoK)leQ3K{*}evFJVQ>ttDICwMLA8i9xL!$EWpj z{HKL~F&Annbu~brojo7G_sY6eRevKq1@|Ja#de*3`=^IH6D1w%wx(QWG)$FP>?wsw z@78PT%v|kdv*h2Zh-+8R7jb2%Jj5LN5TQx(&-UVQ=)Ws)yp{GGtQ){H)u8yufs_kK zRx52Rxe%FzXQrcuhWk8Urtr{y=t)9)5js&{ZMXDs>Gu*7#G)=57PmthE%+-+S{x?Y zlq4#5UwUxbXet`K7ekMwdJvB1Tytjo9-;DFKk#3!puhK|Cym{7NLuTB$_Ot|@8S%m zQ-Qh&^!(aYgANB55u1?`^YZcug!#2P7v+@8NyHPjJw;ER%uEs$pk{6&?~#+TD4Jy*XeR`0qJ%-HsT&7>|{VqQv%E+Uqd!q}tW>k|XNO*~uVuHm}VN*NShG z?Zk@Fgd7~MO?384rHf87y*h^40d&mp_~9?NT<%4iOM}%xhk0eS5$1@|R^5=4Y)@Rd zmwSGq>(3&4HHQaBJJx%H%Q=~d4(`R6ktqJ zh3PQKvH!{GcuDInKussoo5z|7K+hMOrBl)Qa>jl+8BhO-XlkQT0uZvvn&wrvqgW#* z+O;Cs9D8{;r7?=S6 zF=I5F#P0y~?zIn_$iAiaSpVPyYk)sC)92|>HoB)mqdu`h_~kOjSNRk2swyZq{u~5~CV!q^O>n*Y%z6h-cJwtWjDJFfPTW}l_8=!y{E(7{dWSRAo zTw^0kn85PWcejz8hhQ`mJpgQWPF6l<`@XqTG&z1<3N9p^EIQULZ-m5GyPQeRWz9h) z728PGvYBy`m5tWD7tzDSToxul?MugKd)sv+i8l4U9Fo_SY$liO!9byl!_#@PBOUOa-y*qh+8&SPs6S

        p?K*qm(l=tp1p7}KXeB=l`WXy;e>=kNY zs)qjQ6~SUSU5bn&A2d52UH+&0;}F;oWZ^E^BnfF+KXyr>dIdN1iV`U&SZF|nEIMmM zD~avONtR%@mgy6k_{JeMx?>A z%jre3;*o}ao83SzF7O_rKUgZ^e>!3R!0T~Vl4o|_c`#c^0UTJuCRaTyHd+}dkNm?W zpo@J~qL9sO1{WPT%@PzuEXyw@+Bw~xC%_j=Lvsph($e%ynBk(2*!Qz=NTPe#6Z`ARRpfVzL+j5EZ(clU({Pybqls~0NjjU{Kb9z6%sR>q zzv))lw75;0nC<5_G>DimA&>rAY#Ei3ip$Q7?mOkH`we z#RuxC$xv6*36o>5c2?vTYiL5kOQs)+PphwW*)&v6Y0P$$ia&~+I0jA|Yad2tUVQZR z0BKTI34K?Xvz1oYTc>r4$YVU6w8=Ye-D-5VbxzhPI5vr@+INys$clw%infor`lpDA z$~C|I)-hoiGlGf9-m3}6iKv3$hoHxgkPv$v^M7xhuXK%;?>{v3GP`@gX1nIwg0o?cIj#P4wKT)_KUYiVDB8_vFa9-+Ew_tWw^FXM|Kwh*YxoE0 z!{oQXtXEV>D?sn0DR6fzg}c@knQUTO@x$c=`}%>i*=D@8x&0n+D(o06!?%snLRMP> zRw9!;hOQU1=2e#rAIZ$Dtjb4#x>MU+YqLN*zo5!dmL;wt)4rtl!pL)X1O0M+>HIWc zez`bUC8Ql|KBuh{{Lb5jip+cI)<7IgxrLNmV>SIk242 zEVahq<@DivvsoNJrfm|0eV^%zW5avr^zu|=ba`WI)3=Agt=cgC zck(96T7qPjZuQ1HrELmtpCZAY+=a(&D(A9${XOvc{EhVN;oAC2n+=?RTP*8?{NDMF z#N#w|`T+L!?E^b@ebB+bbY4=QVYIe+mW_e4D`+XkNVN}%?A_26-~eG~iY`U zdJcV+<*B3LYLr&OK^W($K}uqy?lOLCAG|`wI4LtCX>v!V*CJKFiITT_8gG_@A! ztd&1&^Z9TSq4AesidMs$g1kJXqdcW2D?BF%#6`pja{p~C2Va60FUb?;j932MtVgv% zSC7uD{!q4p1wWY6~-G4 zNpo24)-FPwA89PN{U_Qbo+|vDNDaCSR_<@?G5zo$iFi&M8%NgA zRh+(NKhynHnc|f>&R7LU?}e$r6-yo>Sq;$a==5KJgXnpujhMk^n}kOgX#7@R=fGmu zF?WOxb|I|flg!=4I|~A2#X9FWbuhmz{i-pOH_M?+N)-tBb1c4OldVq`wy&q0>A;SQ z8Ygu~p-J)BEPfh7j}l|4vRW$ZGho^=nWNKjy*VZfUN3Pi#F-bbOke~?cZ z7IUsE&*T+Gk>UPO8(Hf>;1^nroIk?DNhS&>5-DIZO?xs`T8oZnolf@Fi*Y1edagFos`gU&PG2#Yn`5JuQd_#P zk$sRM?|%ALLCo0A5T;05{#RN4JOUp#8;VSCOV3P4O;2qfL5fTlp}3}^KoJ-oq!M4% z;Gvw=+#DkJ&fWdTxVW_|SHtB#^7ZpT=_y-2d@eRHRpar&;xh^bFiZNse>0eWUTqP8 zmfaoh)7@z~STf<;VfDOg;MSI*vy3Q9W9l6K3RA^BaHOo`tB-`cldLt#xqg4EJ zJ@FzN()UqPzNfujz0op>4{xi4|CLIX_f|OyU9P#eawz-jz%%%0KMn6!!{zw6lXmJF(^54+`dl6^-ak)Z6ZYWN`hVSwm^Hp$a5knb|ix^^aC^K!MS*IR2M_v-x6 zdcz~JeGZgwZ<<56fBMt-ych-c8Ssj;{rt1B(}dJu(cAI_(V$%*VZs;mio2%WF3Cx0So!n33aLbi}4&T#RAh_ zJ3EeVsvGW_&&H;yB%2C((ZfxU+U0)2R1e-gPwD9K>E`k51Z7pZy<%I~7ZWMc?^>Ud z>Ka}Iz~qTm+fR+DeC}v`*-wOgZwJ=x&v)FVm1Q$vy|V>Ghxhu!^X+Y_^DQMRrFN47 z%@O(CDxtgj`l8$X*Vvn$CoiJizFa|w?}h^0J1}69P(zi#a(o+fhuvBfnc_U?RTNkv z1iiL7loKby+1AV$J1{)Tfm`-Y7OY+mqeO5BNihCljJ2DJq=*T|uE~WY58Y>k)08k$ zq@UHVrL&n?=HC}>Qm5_}lm!$}x~fVQ4QUnAp^CDaJ0&s!p?Euy5$1)j@q;ol8ru=Y%xMa08I60@ z=btGiH|d|)v#4!fr+xJZhI2=6v-XQ1#zND`uFd(l)yVOft-}tPlYI-NO!vsh2E=GOO~9P>@hx=x>xKll<{S z`sFnLo4-bm7p0ln+`XSo7W5&u)yj3%=5ZYzw^zsS%F_Nmwf9f=I$q>^GTA^5Rj~)0 zjiEQuSKsxFZo~hmU7^=751QlIx*F%R94td6ylqXubf}w%C5Orru7H4e%7GnjqMZQk5Jyd)kz) zFwE;fNoe^)(vEKTdP8dqV`6&3t0ZOAnrv5TBv~TCM2(caW03mZx;{c>+3&RQkZ;>r z$YrbMW7=x=KJ;B59qZXEn7v%IM`N?nN}td8BhoFg49sG%K3I0vZZI3#VbaI8iW4P= z2oLRTR4Dy5Soye@5<;U2*8eyWaW3d|!iC$TADoRtgLS_;K45EYL zI^D&OoJ$QOQAj;4mmS&iDW7M9hYKL}`3n**rM<09UAYrucbSq2&uA2VYAY`1txkoW zMFQIGK2QAOV9KXRYCl=VxV^p_Fd(DxmeQ5m;3T$X_X~)Okfn+G!UZ zXcGGj8cFfJ_s+8DOC&9wWqZ#|6hHHnARHeU-h7=Y(4q4mL7a_jQ{2op~CZSoL)_cNq5g7Z6^HI!;%X41owZ7AlHwV`pH%!{ze>|*l351b2=2!j7XVe9KmcgB|j9_;t9$MK+DN<8*DKUCt@Unk|H2bsbe5oQ15r%IUbD=s3s% ztBx=J9Yur|Hvwe(Rivf9jFSn0G^Td6pT^ibJ!ze%iJg5NGd%-Lz+0dkK?g@QiK|(e z_WRbGBPgD1l`Jv{_e@WtR*H(aC3@V^+)dX;*HWJ_FAxJZxSJ%WUq|}@6O|b-P(! z`b#qE(eO(kp1oC6LNstier-Y@1yx$S!NKWE&+^UpX6X#t)K=rXKOF|P)HTNycCT}t zi{yE5m&We?o}p(}Lyv=V!pPnoc9dk<*SqPDx0hDn)#>K^oUHKqS_kV}P6&|=^X%BQ{+Q!%+0d;Num@ zUcbwUm;GMU>HK=tsp~(-wpxb1SHg+j-YxE5#KOTFdhbsugJYwkcDqSxh8x{}ZX13u zEY(zsupDJ%k*7Vk5Nq*cWN-dfixnEnfr~G7<+UV*jL- z_iLV6XmkO_c|Z_=%I}~X0=eHHgdq4I%*rg&K3FN=z5Q|!50}vA!5|WwQRo=;x08# zAe48c+tS{ZY35V;2e&Z9Tk7a=wGU-qN~*vCiIvhLY$}UE|IunB;BLxh`jP{ij|`n) z8HV+3LH4GD#;%Kud^6wpST*V#aXM&~JVp2SWup~%>#!ty*3C*F;Sx*NDQ=M6`fp%{ z&uuxc(9H_LG{*KB^=v2Izwx8x3<-u8qBXcGE5Q<{g!NieG6*$HzAeI5ik%ynSl%Ya zTwa~Jp58oOEVLzDKCRw!mhIJ+wqq+WDY&3lwKg%9I`0NKPzbuxXe#O&9Zn7`tS**& z6yaAg#s0{@PdkrXQgKSS*|>j9s@PIiN-b41y!qQEXM1z3@+)&1lS*q-eKPlx?j#>+ zbR>7+!oXo_Gi_L1I*YL}hSal<^_aD0^{nkzI=n{$@!ZlW0JTjN-NKIiCJ^9|u@xIx zfEe+z%3W+^2WYeOo{ex|6LS`sA0j-WXPgCh@66xWpm$BpUtVM+_a3}IM#YgC(q5CbzueF zJ2^F(_SV46iV9kChL%9gUIIPoTmw~pXW6fk0VWh9+u8oZJs@iQswmTH`tX5l3}?#;&Pjyrx`X*}z_v6A4l!5IWiy8EPF z{Y;zcIng7<(;1H2nX92c9wB$gag|&#(pc?kc<5)QHbEi7uPx(SWt!@B@T6v;i{_~OiupaII-{jq`T5L~{CL$(W>+foR9jfr7&n2v3EED_7N4>yGr zC-oG2n_3~3Zbo{S@D_rM_cPRqOEwMuOv5^@lql^``hEBjwNlt5h*-7Ww;7>waN0qh z1y@`}G^}tpGcMz2!aHsN0181O8)4QdF~F+rY;|a>%9S8_nv%2a4=&=~{|&18t$A#% zv&;kvVXnaUC*U^!)L^YZLjE z`mh|BnCpzwGGBCDS}-*`ANTNHfc?f`Dx=Z&#t|$Y`mkUrC2-wD^mLgLkdP5fhr5U0 zYdi1MdbY%^>U#6&SjS&s2rn!ALrC9xKr)`n2tko)=Ukok?Eu^PawR>n|M2#9-(}@xCV)13vQ*FN^SGOG zob<={{dFQ`)_<`j@9&(QiKGgOhWd#lS%Q6qrYWuTsYUFExz1rqZ7@3{@fvQ6b69G* z2Il-Cd5uNAg>9GaVO>o6J6fY}4nl_weROWV!_-Ob%{a-ICZb&X)||f?4|$nMoSd9b z9v8@*6lFU$bkST#l*Y!XkM290AqtwUl}UNF=w99=_SbFUQ#;;*O8DOaS?@9*P>2lf zjK-6|Vr6A@JDygi$B(7o&G1q~dT6K7Kp2P}n5O64#yn zJNem`4tKt>%x>z#J~dWMd;8TXQW$X=YpJ6`5hxQ+YUOiC5r5lE4B&@SmjRK-3E!`v#2efP2| zJx4Cmi?`vB9R)-)-@nXyi?X)9lo5@w>Ep@Hx9hP`&9PUGVk@FyT>AJ1;8CYM^wI{lfmBx6r*~^wp!0&& z`~Eh#rtPN2`rODDp6*9UxqXI9UR(-nGrKUN2E!frhg;4%cBzR+vbccqnf*kwX?K*g zbkf{ZCt>Jqx~LxOYP#BvM@x?>nR9jMv%xR!x1(MYCWWx$2z9hZ=?)Q+Lif$utDuy4 zO*Ym897Vmb+f`38KWz6O>vb>|u;OK%lsbzsgNoxL0o61)bU98zvpBwq%pa?=p62DbHdgyhNP#NP?6>T9(*LZCX zsW-Txn)>QQ?pj$$j*=rwP9JVOVutW*_~%#P-kdFIn5fWja3S3tyY#kzEM2c+wts$b zT>S+5#rYsGj})oWwfp<(_FgB|cJzcKXWqv%$0Y*VN=kdfiS2}ay`?C^SjPgNSNal6l7T1j@0voyJg?nPT{49BEZ3ku!#B`lVO zon`v0T*X>8pQ(M4ok~i?*{?~X-Xp#~4iY_dar6C`9Ra@WJ_=xW3^e;gAaMxLHBa9T zFHJI}N_^nFnHIhT5c^i?l$4ayG`<+?e;L#ktJ%8}0oI*6(e%GblpqX2;iBOK`R6bJ zr+SezP5(zB#~~mNaC0#8F9Db+;5f;-Z%!D-dUL-TFCF<$00)mr`{!Hx(^0u>nDtD( zncU0EKK~FR`%11VvUW?C!a6fA^l|tzIcuYtAA6IPr^E z**bMnZM{HKz0T+ixro8ca$QWWz_Ej8*Y_i&Jaylc$Ee1hAzXa;TjDirSMBzdP{eqU zo_%sgDkDFW3}C^ClAg_ zHNL;$eN@DwQs>Cc$;1#7u7Sw83bAs;il;tTUs`CR#xq~LUXy6p%NZR6v)%BxPBS^V#2?W^PZZph|cdv@5R#sOa`3v;b}nALdaoOL>43 ztI(lV-t1FSUsIDSK^kgKuf;+WA>E-~I?f%@L2|HcSRMiuJJl9j5iuIdlm2X1y*-*v ztER_hyof$180i~gKwt9ceg{|uxGrjizYcw{$6K_Q>_{mstqX5FhhoY_QIHlBd3%Wh zqpYf9Z1RhoSJJ13RrgGN;D#qEXCQ{JB2>EW2~d%mI8!)I_NZc7dl8h4Ea8{z1cg9$dW z1Pfzg!h)=!p~>N@QnM>Z_xm0rgWltxsyZ0R<$oy96tk?1)7G+usi>1n`%hKlHa0j;U`q2qGAHD0GwQqAj% zPp;0CqsS{sYkR@4WEWbrma*JQ7+_bq#0c0cY935kv+|s@Nawbw^IlorP@Kg)o5>gD zc;6l->W2k+=UzfR0>rsm2O=nK&EG<_S{LGqT6;QN73R6?ni_XQVV|CmG@QB_Utj!B zfAC-T!FE0lnfY*cVN@=ib>lOg`u*Q3rO~wE%l3DOa&b0KLVExq6Zfs#_vqR097W)+LQVabGd`X#trW)t7?7YI6{qU=G5cL3lnyjIB%@Z7?zD2h zUiDw^Co1l3x^JsTB8Z)=WE4Px|Leg_dhOiq_&a{m6vp^5Wz3JhmXY|X5FwqMzqwf(DCHyW0UHP zwv{4d!GNV17QaP|#s63G5ZqZRsdusPINH}Aoq82Edl__?+O$*?neBhA5R_(@s#8hp zuU=g|$oOpjZZOZ$r zblZbOAn+>?{pBK{rjyggLeAuPt;xDeykp7mOc-vlBhN*+9)ppvOTcmt8G0M8^Xm0B zx-Yb$S+Vi?BpW4br3QFfPE4+%3WOXB9QDS*ZpiC&TAm_TQH3eZOQf_8v5>#UPkQaM z;v#64yNFRj*Ayn8L(7bV&{)Awia$)6aDf&I4G7ObDVYfmd+lw zB=zmK;roMTe_~m{X-$ML{$LxNdedi{6%7J)D1@GO4EEBlD5T0BiJ}@6 zx|sy{O3u4H+mUp%=u*-UHz(LYRBM9)=e;XmMCoO zbZl_DWWq8u;LEQUf~HU_k3z#*>_|<_B*#SQFWwp&%_UD!QP%YBZ;m;k`*p-)qPUOx zS=Wa<-BcG$ZcT(O$hD1LqCA$ub9(knb<#2;?QG6;xNP8|lUM|a#cv8KCp^96^h3dA z3&~9f7$CK@85U~B$>|&kXXliRmM+i|4$`fGzbttcSL)&JmT_juW>Lc-Mm?5*e$8#j zPp6z5XqD;YKbjB4)#Hn2lr6r_rY|npMMYfHk{2@m8|+N*p~4ruFj-zwoa_4y?(3kO z`FBd3z+_ZX5zs~t2TNtE;KM<}puu}gBVCUar zMdQX*@N9t{?(jKAGchsywKIdt{rI=g;cOH{A|No%IJ+++WlejIPL&QY1O0X7t5v4& z&WN0gj%J*@V0dHzb@HuB+aip8tifIG-Y@GnguNCB{{QY8jJxqD2S~Ye5Lc$VA+ISl zQBhDE2wCkJgwRA5CsksJ1b*1BHCl2%?gVjcp$UGxIye0kojIAf+U@61xVzZY(c=|> zJWX03_ad`5mI6}DAi+Om*ULKkeXJ!@e3(uCXowa8Y}s%^@OxR`uK1GmU$A&9<_e;o zqH=Azpobvh2J$!`a<{<_6Z`XT`P|BPl>pG3cKuf6q0p*7wK<$N!a~Bqg752Mp7Kwr z4B7=3wKZ*rc+~FGzk9rZ&v~w-XjyKUNCvMuT4#9rUawHpOT071^M#6;23ABIOvKPH z#n$|o2M4VD@2?V9%NzZ0=0+O*P4*eRV9!rxuzq?JjV|JV!$-_ zx%B4#2+UqLzU+Eodf(+QZT`8f8Y7-scPJq4{5V+F|9w@w(z(3#Fx)>ME^#h+^5F+#-S7Xd5&z>0663`06yGKB12K_=bNzpc9}8Oe)lH)?U3Ar7Ei* z1H_fuzwUjN`dUz?C;9q%a?9fPs1aP?d=O*JI!to{lorykLpDCCLSxVcL>CVGpJ5sB-`^EBH5Lhk9!NB}qRun%Fqr{SbTg>yMf z1{Mbcky32LvUJG3wf6qFkysO<)2g9ANkZU=e7}%O5Qm*qSZU9z%?;PN-G6)C4>dQw z4dJM0)C|kI7*?!kNE>&7q8N+&y%XTb_l3Z7VfL}R(;koC;%|bE6ovylbJ8CNFypN> z&F+&3f*ybAQG(0G22TZ%A_Z`c3Y54XuT~#8up*&iwr1^=NTwEY$94V4?l80pDl}hK z7?DGv{~UU;Y9SqB9b`g+wn6N%^SNvIuj{Esvaz?r@MXdADsanwoITuGQ%fssDx1&x z#YI?r9I_-Q-Aq~+@ix1dhUP35?7o#5g*lE5oQ05>^4K`Oe}BX)yBJjyYj~e1dX7t1 zrSWZ=7tDknzX)fwLn-%dhMgQeSgNgJ5WOy0JXw+-9~G2M*r(ii7Aa6Lq97}dnNJtF zphTNUA~BZYqezucV^P*OSM2liea;KzM+XnXnJE+tj?yT2-`mRQOH0G+`|NsdxGrzf zY}HFolaTX`k7Ov$1wvP2D#Na_=lp=5Ybk<%_{c5Q|M!oy--HlnTzNyMQj=*|yHqZz zL23(M`q=H94>+~%7u@?Nmo&I(uCvO~G8lv&&W&NIXXZ zn8UhAxzg#!iZ%80=~Q!4qI^UjpdWg&)_SIRTuAaeNOIp;%fG#itSyp*hX~N0fX+38 zZBRoP$amonpF5pZTtq<3y(~|P$)jnvpnC_%B{3mlYCQwI9#x#iC1*z;$YKMVw_l+e zgkHYRN{M#(G_#^eTO&nyPB|*r5nXiND#&HA_@(L(TbsV|H_o&&+aW`=0;t+oSFl0i z3t^*B&Ev9A)9s#*PvNfD6G5?ULv|7Bc)4BeV+>-Se^K z9X-NTE$-$9jT(M2-sY?5md50jY~%+qFL(N`T&TV5j%74Lp9~BQSaMZg@`% zwC?Xk-g{mk3%;4G8$ew~z0hJy68gHlS*z>(!)Du$IaE?ro~7EyFR(H0@3xMR>Z750 zKrF-ItT8t8;UqjLrmR?*92@J!1?fWe3H`ruZQfub67i~F9?+*U58ezSsH1K+d7~iW zvq~hdsd-7Bkfm|CbDB+Ogp5_drc&@rM%AojQJ;v=kT}xym|o5#M5fjl?l)zBa{&Ac z7u%~Zm12qa_z_^i5U{ouhNgPx&w*sm|KZ*V9^1ZN99H~w5rxg_za*RXvdW&uc`V!s zzS(9mK55XZvm!*3&RvK;eu3@D#bOfsWSM&vKH>QkvQzdp_JoTFyU$Ry1P*5s{tfd5 zLO$o@(B9f0f9?G~H_yJX7*Dr)V8D_TQnT4U1~`j-IKR2;uh0pN5JfXcE74U8OoS2L zLzqV8s;#Jyx#e@Wiq#kB$n$-HBFA1g5@o|#Zbu$h<#f#+_^^}uQkc?X*f3LhOX0$`xPhEuJ`RjxoU(yOGk+#y#}BaCLi z+srKT;U~cA@KbUBz?3JL2+NXW?dmK}>rIes1x1w1?q=?Q=l*>D%iHtAPYK@5(lm3C zdINx0bCq(9>=NZ>w0VK$@Q-Dd51)&(&{Ki3UNicO1LKp6d2@Ph3DE3%poF>K= zn`F9o&Aa18>m7!|&++2z!wmoa0xgTXITl`0(WrLx8TuY6VTdU{b@G~da83yo77m5q zY?DBItU%e`1``?e4KZ^qZEuYYT%o93LdW3B_>}FBu&=A}fZJRO z<@`dq>M1<;x-)eX#5&@y{xE9CwXwI!Euz8JLlEeQJWQgHBy?31xE{%lBn%kCUVdA6 z18>JdTD3K+JCKIu4FrB-`_C5=1>ZJh(9-=gIxhp!jBfA7@vj#U@RfDZ{!E|t29w{! zC$F;Y)|RpSuE`d`do(qpnLLZcthBoB0dX2`aSdUr(@CIAi-3?Nr0X1{If%U7pozR} z2;c7?d0#>0_hhp0GUIqvM8P7Ax$Yf-N&w_FcTN!crs6r0Qr&A}WzAeerUv2r{5LXl z=aC63xe!2;73TX}t^e+@&@-xnz>`Uq-${8ZWEAmg=(M&{CGt)0F^G7fqx!iAvE8%% zrKZCzJxzL9wGl5V;`Q}aFN1IDCHbbaJjouxqq#7d;wis+=ic_xwb~Z^OQ2DE-c3$_ z88nd-5L>DMJIawIN!K~g#-{!>&Y`EQA0b`a6DIlL3JIR2#g0Wd(aJi>ASNdtq}>k6 z@q-7*X{hRI(mkEkyIhdO26-{J&h)o6rIUQGG-or?!^RDj zC$0uVdcbrEe+<~*jZe@EXgBeEwf$(dq_fiMNXUt`{OfIq&T<~QCsu=3?nUi5F;1is zRmuysO7jH&=5sQL!U=~hjug>>D8Z!uyGq!Nl@1zPLp`g_!e{QYBOt5I{=3Y;FJ>2c z_kmwa-zds7b?Ng=fzAgP` zD-9{Jpv`pv*_-!1&@{+ukx7sGGEeZwgbU|p?mIIyn(QaigHrd(boFmL)p@%zVCKy@ z9E91t;##u+Rr4rwog%jB{jdgW2Qy7rFU?dN(AptawORTT7q zaTfGP(TS8MdKha<`pICYt6f)Pu=Xv)r22_JVVgw(GhQ<^Y@lbY^tYus1?-%XnHv$Z zzzMe;_qBJL$6k7x$DB6W)BtNjjsv8d^iXuUn}+T&y+O=j=FecztTrTjYVw)D;VS>} zx{2%8S-vEB&)=ZCLFa|zVa%b=)1d<4=RM6$L^*_wz#4YQKH-k{l`M0QE^s`Rd3c<; zr|S9=Z77zw*4)_i3Dz@rfwyv4zSr5z;X@9oKh(tN?1+FssQZ%;e+xOXAc^FIeyAWRlAA+JRiOd@1bO%quDU&G!JQjjmKuSW}lMd~w6)jQm< z#BVi7YKEaB;o)o#wX#|asQLS!TxOM3aW`C$Kb6D2%kEL-@wten|0gM=_sF8Y0&ubj}! z)&B9o$(h^ZgCNUEH$J36!7_Aw>a@t9&&>PSMW%b+qN3MHhHD$prIqoHdG6LOlo-sYlMl;$!MKy-@4Lw<;F+lbGPd) zFaJX>9Lsq>_^;o&)xwfmp~Qo%xHu1|t!^yJc6M;8fd`a*&pW}p=jHa*v#cVd)Ihv5 zZ%MototoPl1b+QO?ElDQRWV8AyqMpa(Heg3D-A`FhvP2XxN$(2|8%49E=jT@&P|X6 z<_SRrwvUtNm((x?mZ3QntN=8E5^laWr%3GMX}bHECc~>OOX2$^gcTvbBnmbntyao- zTtA^Ewn#2sc#=FZNLI4Ah>IEp(A^aik4e=FtJKsKnb}gYy6k^$eXTIq$vE{7s`PV1 z_qsbN1TipL2m2_Sc&C!}H(+gt=n} z_tbxfn>UaMK&33LK94dQ^V!UoQlCqo*T+(>y_-t^0B96J-EdEa{o9c&YA#a7=C4~v zUaNfd!>?wxZN?7E+{;)%U1za=98-TPy7+_bC{B1T#jVfn276=H z_5-^>#W*Hy$&>LlH*<2@^SL>sT)r1|w3NI2+mV|!l<64W0d9}gX#)Jyc@-o^J7ubP zpHT$zkrbGuiscV4Z0KiFe@6-*EtP-%W@i{J+Z2=JX-GQ zNg;&*kN-Wt0s+Tn-iiUWs*(hb!9$u1PfG8cTcOoormM-3M;BQxe(S#d`Xa>4+2oZN z;r0b-8@pPshf)>|9P~;<>csp&_6+{XL%5b zA5!VBLvsi#C?Hdxn7db_vmgXX3Oy^6x5!lGCMOs7kcH2^L_nqc+ir|_#r)hJ~Fx71>TDMFS-Dv*QhGHJHOmjWnA%^#O8ltq8)kMD2 zgRUUA%~C!{G9%eZwN$Qmn}Ezjb%O!)lJ*8(eoWTXRlbB`#SA5OgsE}WeHHlFaQ1lZ z`B?ODrir_~5Q^n5a70sOa*&GuSnhr5meePA!{XBQ7rpJH|#N}O(KF2FN zGVQ3;taftBkkryQmQJ%k#-I1m>dF?lnu)C$;~Up6hRQUE}*2oI$<#FflPG zz3H}@fR;RU+4CV-^M1@B<7fR7ZOa7FPsvd_5>0K$Yqr~2F-l;c1(E0n)GlO=7S++` zX%NxpZfhN)2rbdfYio!|D0J%zl+iKI`dI!1B=<|&CBTUMB`6FpB6bXp%hU|c{kRh$ zU~k9BA0b$acS!1yfM=jaTe3wmdI-en*47B0)G3srD)<_TRo@ai`6qBrE;S}X)F z7z&>M>WKb`%Oe<&5iVi8HeGUGc?~4aiI&G-if|aZfz8Zc%p0$5M=j0r?5@g3>;jkS z*!3--P>;WKL1lUM3F9nwU=SGy-n0`32|}Z&B}B@e?7r~%1yk~bIS+TIl@!?Zhuq(6 zIZ~xCrw5(vJ>BHc#Vls}K3c31Q0@@8Ehux}g%zsT>Fc*+*7m$I2&UiEBsqtpWGRv` zW(5?+@O&xFc4hK%Jr8WmBYpo4L2t;Y8D@YM^xQX#ZE}_-L*E18B5mx zJ=zanMjy`CE3=ZaFWH&f_R%O;9P~YxRQ>d|TU3_DqL>dy_?ZTJEjb|Bl4(2p$d?c>Dfh)kJ5rtM{0K&#vMV_{Id4#V?Y{-5UP>1Qw}&P=2cVPTxbFPo{@A0R zsg`8U2GJ6C2BqfuW8rgE^-B*EM$AHsUWqM{5gi5f*@YI`e~=!{HDv!E9dC}G zJm>N`Rmqy0VzP?aI#jbH$@po^h+?lPj$CPKG;HiV6>KHluAAV@lyk+MYi>yyx%9i! z$?j1p347qEmj@D?R~;H}JK$x1*#N?m;1T@RrhnP1dC~u;>D-;vKut!SkOiMbA#zye z{_(5z(m=7mx3p#`Flqs068}|-hqmE`z!mKa0W>HT%htyUt6mYU9MUAaynY3u6=yt#Z_b&-M`v945wrBl6zNEM5vpop25Ut2YFY}E&Um%6tuexut9E-e0wcR|FjpZ<%9%oNLFQ@iWvIu2sWw9_!#zYhKn{_v!{bT75%wfMcg zh3D>MQFapR^4n*Sd(R7@AA}-dpZZ%AtObeKhXR1oUofGu^<3g(qG9sYW)dbKS+(<` z47gFT+rvp`6+Xz)A4CaY%JDj(<#5kBIT?JL+k$NToqrk?8nCYI3PD%k76vi~XhiY4 zUsQeTf+P0%p2~NarycuEu-J*HddV(iO0(#m`@>9+D@b5?3oXa*VfDEo`J&t+`LY*oL>#L?LnP|0*H*im3Y3EWimXG{Xe&<7JcQVNOu<+x}UO;(geW0R(t+UZ7 zKXDB!x9g5Kr~L^|gZot}2uQOHxdwzt3j{ z0fsOFA6mA!RvV1l=aJ(0n-dZRywAwURsX4U zL45^m+v+i$JK3%<$jvg%Ln>akcv>s#*~xWN?7(#n{U^usZltTI<1r>zMKJ-fRUFpc zPVNV!Uiysqlbg{b={1mpK6Q62a=Nc1n!kZt(JXjY3S)We5iUyTUCr2&jA(Gv|Ak!8 z=R;us;9$?2I=Vm3u3m^Am*xbb$enZHY4beEoRJFu7Q?S`)N~X}Rc%ZVzLC04kx%0| zWv|jDyG3WMF~zER*y}Gh=p&Zv|K(&x=y@kbS!9zeaChUZXt-2L%roYNsR$CtiVrW0 z<-sh?btP(du?U^G`B5?*eR_L&QvPf%`5a)kd|D+vN20 za&wq*7Qfv;*mTEPm*zZJ%VY{6S<$AL$!Yfo1QTy32>kC?UG;)ett{u2nXFiHb1D&@ zuxCpy$Knzi0quafhDEi68w%yWHnR1y-Sr+>t$k6&q?47IEzn9h=1eM;tUBeKa`V{$ z@-&~V>D2F$9F>}ed&+P|8)0&fM%LeN-6icxgJv71SzNV~le2aFV@|WUJab?gWLoU{ zveIh{Jnk`)B-VgJiaufLm0WwjgNAn7@$Drbt_xWc$D_xI_ao5WujC?|#yX*h^mDlR zhwroaUE;K?Uk~ZQ-&)9b3Ot*S5p`8>x-ic{^6$K-A`q~luV=ycLs{m|tw<-vdo7RH zH=HX)^=W8CJ4jX!@j@blp26OjSVB+(` zwI21(>oZqR?-8r7`S$JI zDy;|;yJj(Gq4PXIk_pt^bl{G?{jvpyDuCFAyzT`qa4%r{|-!Sj~QL59s{dUNOXAl43d8h1JJaU@=L$G`x zp#uy?R~#s|J#(sS%EKfFu*(cumgdGFFk8LVZf<+Lxw@_=M_i**?NG-QH`(LQib0`3 z!n)U3f>tw=qvxerkYOnHC>}^VuVH?7oL3XC<|Nl1@s3>c%f zwCd~KBddS7bf8J%@o#;a;(7Uz8ZGM)i#?~+Yth*PFpz{ZnvXWUE2Y~}}9d|_-l zfgKmM7I4ai!2%?Hh2_6_4}(eJ-g7ehA}Wj}LW?GkTDAC)5;e-IO?A#jryE9g%3mZ5RVm>~PfK_N5ljBx8hA&=5) ze!RMKzb7@srDsRi&sDdAri6^g_ED7LQlk;31kv7jZ6x?r0s}9G^Q=FB@hRFQ#&Mo; zuIRDD6eCqq8BE4uQb|Q{p4BwWy=S876d;o zSa1!LhSWnf4LtDX1-;gl2hhzP=I0w6_6HIj$I{IU?PD*lyak>GX=>0bi+0T6F>NHZ?ILOql4hBR($fCxZhf{GE%#MM_8G-n zrM`)3SaWtxfF{FSA(Fan8%KT#; z;C~Qs+nD7B^^HSp87^sR7T~<4$3^+auk#ai?&}p%7CSN6*E-Cy$S-l)+_1hOazDXa z{rd!?T&h*R8LUU#Dg(yerh}ENAM+piHn*B9YU@a`f*hFRnl=3^LCAyCcAeVOfq$f;$-j-`211&w9iGD_3)^K5WezFmKm+QUZ(l(K z>&WLm^S`xdCBO1$+}RisqIqlBObv!M(ABv-!Rkp8DXJ~W>u$Ese$nT)*chEv*ViZ^ zhHpUf9h|Po%!XjR+VTY6*!f}Z1(H^Mm%f?&Fb?o zWY1EbjEkAreY4FQ%Rz9p5thBVQLZBA=|sl^a=3&X4r6Dji6SpQ+76xxO>(AA+Nuw9 zBK4rBmx%R!t~p^&FQJ%PuS8sV#5dkcg^ptjyKS!;{`Gv^5^pvT_k3vD0Jg6RE0&Dh z;kjom&=h+bmHo4XU2KT^R%TZrty4Asivc6)s!grXKarJ=Gid}SWh7z3&;IY`As7bD_ z@y_7ss7ASNkY6Bt_2@cEnXPC04U@s{?+tWY?tgHYh-F@7dZOCD&vzcm@#^AOgT$rz z^Dx5;+z1{2wO+U0K)Oq32z~?DK3(|VN(&XYdmnd`x%Qg*i2mhX`bpJ*cbUPj=>DBR zVO_69W>&*1DVX`W)r2L>Dr?f>0Ga*Zi_qlCWnX`bmwB${{&d*)(m%*7ZyTiI?n9#sn_FKBlh1R2?Vq}7FQ|RLk`UMI041qXh!f6YCq;XF#zo}e^pH$SD z-by5;*bS!b3OM%d{^52tBG$c4B;F}8cqia`JK=@AdGDRNh`3}Q@8!96mV2Hd++;)k zDSk%`FE@HIZE1K;Tdi1me9dv!L^>HQoxW3R^XYa!@DUHawRT}>{1`fKYeS$MAZz0%g3Io0bo z_Mv>=4qc4#PTQ?U>3!|Uh#R9&AK*_;;kVm4Uwf*4%E|AIe=!h4l2&F}$~X9=H?6}h z{+!jxXoEI#)wad}l%K`N6OIPzqi&Je3008y&`bm*td(?BOV3ZcQ_wmU6OdKSvP(x8 zW?W0WS4dZRz@9nct{+@9@t&|g*NX%;)l(u2>E+)XQ=^iLnuxz;MCBRlGd{bckTOdS zoye1s6C|)cnaYb%Dq#24_Z*CXUlQvt3hEC#M@A9zSQMvDADrw=9#5o|^obcyM^=DD z195*6G7zh@+Ju)&ys0wU4!I}O#$_W}kDJV|$Jk?c4oZnrPW^wppWMdo7MFemY36z( zGRtnsqUrkqZgL@KLjg+5wqd8Jo*TqlqM>?m=Y!SO0V($-`3MWKr8V)psVQfpN#i?s zbk?gGJ#W2fOU`JgX6E&cPUiIh0{+zz`|0T@mnf{6;n~Pi;$$Q*a`Qg^ z{|N|0c73|Ft^QB99{kW&%C9dp{57kwQt$YgZY;Vu;}WWDX0P_E`E>ceB5))JGr@z= z$iEcEm8*`$F)O-0>+9Y|wEyUGHjLrr;^Dwpy5G4qSZiPPyog|Oh02zi|AU}FVxmCv zW&OxRMSjQ7Ux!h+3P?L+^fhJE?$z7h)gGoYcvOKDD^UVhKcl(e+TmQLDO#p-{y}o) z7fBtZ%@Wf&0*g0dbVtqBy@6j8tX>RPYeCcQDzJ?ftTrnw)J^t=h8GV#JC_1pFjL(J zRFuFoL}c!Bv8bL`IE4z&yYcw0vZ{d1;buMn@@Gj&kw5M)4|)!(igp9U?@lNRZ(E)? z+!ker>}UR0%B}acAOEyLAD?_*P$V=Ih}asO7m8K3A^y-15B5%p&U?geA&SIr4Gfhe zt`dWa40yV+M6G5Y4h{RT0$%-K4>ox_d`h9sS|#ntlXOevyHmX3nYX|b6*_AAu#L0t z-)=-`#t_KZ1@b`ZG)JO-`n>h*J~R{e`S!7h7zc3s6W3);xJ_So^B2EX97BhBt{WR` ze>L!XDvpVE^Ngw_tVQFop!_5AYN#|ev}eXVPD0behxNx~hWFbjyI+surRwO=4q9m& zl~h@{gq1KCr&EH|x`I?30a~(8yLf>sQam$}vb&BYsSsQLPYrG=S?90fCP9*;G#{bKWoKiLuhJ{j065h*+^x=KYs;-gj01o+3)4;f z?C9(;DGQSSTqoKng`>Phb8ELsF&Seg#DBt@AMeIR^&r=+RnxH#=f-j5$Vs^B4IArf zZWz1hP;0g+I)%Y0o0vj20Q-rFf>EP~f3}DU0=K1KsFWvVxjgF4@r48;>=;!3h%|o1 zoNt;im$Vk9s4UOY)x5Fa;AmaB~xDB0Lq43M?@tV}|z-^u;0|22%Zv+8@D_sMloiIzJw{LxpFBO;2GsnS=4~UCKpI!6>s!iANbTUQ2gy(WOXReT<$QNB{C_z{ z*B|T}Oiwf6=N%rmo7K;e;vp|Y+J!aMCDSzX%*vLWulvT|P~Ex>T~Wg+AehP8S%=Gh z>#LE()9aIU9Txx3$u-iA%!qpsTt_}hk8QQI>!oowMfPhiTm{X0&0aOvwu{j}6o@LQ zjbIK@CpFO@VTPZ_#+j{s6b=6eJ-aUItl?1Na~BUOy|xl%(4C<0KJIwk^mRkMw+ksU z7B@z*QWJ*~zujJroX>2HTH^LP;FP}Z;bq;1W=0z|e^ILAt~VUkxC2BEvCIFslV=+a zhRn-`mu81=ypmlFk6RueSIkVN+=-{Yi-mJiIL8$!>#2v|)T?wYEiFl{6LtARX7lpO zd?lqJtarb1U9%XvtVH-K{Whou5W`@5JwFBXxw`h52B~t0D}N5mH>W+ES+3vlZ*w!% z(8-&E9%!y#ANNKk5J`k2MVhhOa2*j>nGxWS>3@P_NRNXeYzx;8wH~eQ08#KEw@O%- zLAbfh7`Pf03`ya61-y9VzkXAY7Dkos^|Y6)6*Xb>Y8=$+Mq#ED>92NUEci5wf`2r2 z_aiD6K)D`_E2%c)%vPwQ83a@$43^RA(Rs=$x4G5@Q35)415 z*N{Jz4j?xt{Wy0bxas+fXP$$;Z*a0vmywbxG!Z#`1PBA0`aYQ&+?_=db;0FJ*7hDT zvALqAx8LE=upuk)I6FHR@edcM{3V5tszZ7=?Qr7oZwwX=LX>eyxR<|CHPc9`A$4`6 zKze!A-!#xyRH^PGX~wNPp)9M^3Y5_XChK758;y&EXSzJ4)N<51RqkUl$KCh9%w{yz zV|&J2Z6w|^PRE=#=(VR9`!~K9X<&*`k*DIK0DYP_P+X2B$iC-0Q%?UDqa*yn6&jpS zP5Jmb{)Z+OoD%a5F(hoz5!aZ|IQ&IVv(Wt2Onf-fH~X+Gtw~t@AU^k?LQJ znuLL#bgy?2u-MoD2|VQYJ`FpSTluM~of@Jt9NzEmX z1YN%SJxq`v@ml;&oacWAVUUbF?wZ%Vtkjz#bieK)P@C3u!l)TD{h^i~e+;=%38p@>+Ti$1)EnhaT<*!~fw{olDKyMja+n|BLk5d?XK% zaeM8jyKgxTJ3j)o4Do*qABfdIs0_Su*c%XeRoc(1+^@;jv9C-18p3war>IDc-#uam|Lp@bT?W<^NHxzIFj5^%#w{1ZWCWp%^n$04eisBT(NZ|o zzaA}9>-qaWb|tQpF0(3bX^c#rMr`;1jX*)*?d4Nm5-b1ZhiRRBNRPA*S>31#ozU zFzxE3Gc?orFam#(rDEjGa&m%!Gx^ube4d@%;ZYg=yTbHO2DIKo`O`Y5RWy&HiK|(- zUn5tjfJT#3EV-8}!v7&w{oC|UITc7_eG^sFNUGTLnFxS0UI>89pE+(05M}8%x{G?` zBTzA$O+7;0Vrk~n&0^Mx!R|RO8^LTYQBWuh`a@avetiaC8J+!=i#j8g*uJnlQaX|Z ziJGIx?lDd||sN8pIt|`DO5uHb=XZCx5Hc^UW)1(Ie z-AE@hic$J8m?eQ#a+$o+%nxg>Umc(KR6>g==sw;8@&E&*%0D-^#f+Yq&`e*~A z_hJ9xGq7FnM2ml@W$gzZM2*F@7r1xse7l>b@PjVtbRsY5dDrpbJVw!C0SaT(W)=^? z0eV=+7yzrN(k6QGx*~y4j8T7ken3|Ga`W-heyTu$>Y7U=;6K|0!C=Ay;PN@LAV_ly zohZ=3fn}BnT+T11CnHIRaB`-k@3TdA^K2d8#w5_b>IErlJOC4Td6>{#q!{*E$H(dK z2vq1fRTN&Z>rCjPqU2iHIH)rYrD?S*<9Pv=*JL!)b2FB@H!#P@jivqEdIglI3FbNR zLP*c! zOufft;kt`m??!jekLK~DU2S~m=P0Tk&DhuV;#s4RW(|S3><5bfR6`@8a}D2> zyY2JLddZ3EY%H_#5R1IyA)e$6?2@yyR@rM!5#*`nqY&=DslWIzKi_{do`};$JWZvw zT;*#tqI6yKjf8n9x1L6q$ZkPMsX^Ik&~`3D7kxE$7zXm+KR4nhpM0IIM+H;N+jUeG zY94avy86oC-ZuVd5iBw66ZX~jHCdkJD*Z&*$Ec%60cA-_nWGP$C|vp22QK!>)4kqg z!A0?X#om09e7zeDRh}tsa4z+nsaXCjzRql1=bV?Rbf7i+h>TL&LWdo>Pq*Qch~;g!oP0Zqg6(EAyH1ssaA&y zl9_vTlw;$6ez-UrLg>&hrg@UfjkbO?a{!l9*D$n!|CP6V;CDOM>-hh2N#f{L08YZ| zm7Kb{1k{Jc58l7#;B%b?3*=W7_IvCQL{QEW5q9<_s;2IWwtpA5lN8p`X%7#J!D-ek zkr21$iS7a}cGlu&2o7%9fcOSswOJxoF!VIpEiVtLvJ;&f`h?^&05zcw2<+ zFz2dCTDtk52SC*h_>OF|yc98rF=;Je(bgBb(dh;OEQcoWjE#?9K>*!hI{vrpuI|o| zaS@UogbJ05WbB+F`jME z!S($FcEnhhsamfCHg^gThB^2p?AcpJP_N~0RJkxz)G24kh0of-XK3$G7CSl8A>svG zNy3@Wl0*xbaLCLe%MXIVK?DfZOCAR@U&z+Of-dg(b3PT&^tDImdt4SW*X?BfnMsOt#g@OR{ePjxCVog4|&Y~CkDotk_4k0uN*)uNnmi+6KHQ;7-a z6w1_2c(VLwQ{OpE{$(5*w3mjDz0K7-QIqZ$tLCzA^7^jN z)Nu#w5F~ocLnf@c=H9Ypt4NRZo%D(6nA$G zE|h2n07;!eNx+536#@7?Q1viQS6IOfWj^BUJUFUmYYmH5o* zpJB@HL%7mov)qRpEv(b8WUge}7#Js{jFgdVC^sTyJ7|G>UE;yo$vbL(o8LQ&2Herd zu61Hq;$P&SOv#mb9XwcN&78qogGyNffFH5&ARekVAbmm^1#hH9@U+MhMS{Wc(r7Dh z%*ZoFyP{d)ry&~+iyb52gfZMN@!?JOi?giLkgcbDANqA{xfPK)+GTlZZ_M7Wb?OpS zsOt)|)tVsHJDpCF4M}9qd0VWT(cI|N@|fwd=xTLZ*q%MHJ9s%>H$oX5jWhjW7OH^) z;6Uc%7Ln{2mp#0U^4P$#@f80)cg-UMNZK@FFrJESD z7$^QRL65eXUJh%f#(5>um1_aPDsL#1xtS2PD`580OX_se1b3PvxH|K*##dMHkc@SLa*LABrrx(nYJtx>%X%Nh(}P}} z&dCEp^h=fdSjfABPK`ZDdb|$7FOLoP&W|A;rVj&!6W5zC7>p;upS-FYt%;pB{g$Jy z@_b)7&U-F|(V+%Icb6X08PJcQ_>NWFn0vqRicK2bdyRijYd-IxIP3p&R-2{OZE}mo zw)0VC+j$dk((%8QfsNDOM0dkaO&v9M{20~@cf!@E>>wI2DLZ(R8#;|Ixtwdx^LGC6 z;>g{20LnZ%4d76aI=>S|*vs))3o?GaO3%1i(%0>@PGbC~Qw<8se<H|`jTk+0yL30US zp5imorL`jNIxzb;$WRaJdPt*I*C{Q+1gYoK5a`6&=a#7{V>gnBBXC2UeYwGm8+qM0 z#1-C@2N$%wlWbqgt?m@Q@(?rjmdny*2D`s@6Nm>1z|%x(0%CEIS<)#OM7`x{i&&0T z4mk0saVf}YqIw@}ZCH!~%pqx|uxm^njRY)SvZPus<09v-?)pG;Gwz}o1IF; z)hVd^6V^VFyVP474wu?rmw+~)TqJkkU)>~W(n~1mXNm@R(ThE^*8~$cHC4CAzpMSz zYNwa05DfHdo9By;s%l`j-}7IHg?ttDXd%B-y!w4}Ch_MVoa*D;)tjJ1-y|sKTvDig z^kl9$W=zoqecB{GWOwIU7aBPq-GT$1#XTaL9H;Y&$2MOzyU12ZRoF!&($Vu;L?|0b z=v-soJ48%6HjGt@+Xe7O-$DQ>*p@ zxgx9rGgV|hD2IP+`eJ_$wH`)RiWItSB0(&Bh+}lVpVsySC0N$NeY&~th;L_!JVTH#E;28R#iyE2wSb)Lff}!phXtTrF_L7CT40oOgUXt8!| zhn`HmR#}FckyEeFR6PyZ{BFC;@;75+{gJ^K%3}pAzaOjgyu(3_=+?7IwOvg-;2(|g zX|>F&u#ZyDluXN@?tjl#KlGitouN4*|G9p+r+m_ju7_wTk3pl?%70qJ2NPE8yR`Peaa%=Q_z+Elhgh=`6cmAOuOK`fm?p2G-95}I45&U1Fn zeW7uuX#AH%Y?Qor7@<)ER!L5+# zJW+Z~{1vk+MMkaJ&3txdaIks;o}(=Lm8{@bNtUq^Ll?AjK7u5{!lCrClx-5JJrY{E zs6*^L8Wzt>c{|QnsJ;2^XuYEaVBp!ExYzf%L0CUg1F^YCz!vbX;_{UIp1~4 zqIxAUoC;A-Qu~M=&|*pDR1JGJ;`uu&-tp%(5R&V#MKJ@{e-kos$V|gqp_OyW<6T@n zCi@L>AxZgy`aWg(W|p*ulxgSp$tB8Sz>pHh(V!OPA-&>hLg0e)*kRW&7=q zU|7J*GvUh{+xwlHYgQ>`u_Tg0pzGCy?4Wv=c2g|J^`z1mP+OyO=>eOXq$V z^Gt>xe%Yvx{ZSzhai%Iu+0YT)KXM)>JuD*neN>oG;5m**2NnhI?nmKYY!*I=vhLqSz8H)vwblHKA(hl22;fn`2cIW-&**NW~ePlix?iEv4_R- zM;uI=Jlzbvfq2FXPq79%)dum0M%kh7t#nN7%($t#b7d*YpK7eDzvsKf%)Y@~CLg^w;bg{;S-fdOxXL|1SOq-8F2Is8Aky%*@g979-@?m>w zSPMeGoSfKp>1b$FKG_xu+R>}9ivZ&C+e?Vv0?FNS%#k?c+8~Ns8dv`S)V!K`e$!TB z#-xnRHTy2BS($+M3$h0{q|YYPCIt-FT zg?N?4eMsYmj7(2!DBuHyTWQ=6_C$P?`Lx9{#KtLLKCCqrn;tZ?-R>wKS!2>jz>{)k+74y6qBvrzy}*esp~mJ{sSbOWmMqH&i4Xo zf-SOArsxlMsoqI+-2IvmR*_T*t@X-83% zOtj-46*4ki50;~@g{$cYk6@!*Z88k6@+<(O33RH4*b-h^lINo=V%c_d;OY-#3G@E) z{)IoMUQ4VgVrW!}!N$&78Ouxch<1VY zWQD-oA4mRil7i*Y!7tn^#FlH>J*%>khgqC;_Mr zBFZPLI_oAD2(sUQ@chy~> zd}qo2mFi0xJrx9h_++v2_fbGzuS7yX=(NslAKry?*%f*+0O7Z1TnF%EQ^@TUhy~H^ zoFhp6H5McKkDLlw#msw}pr{A$Q+mP66W^C#@z38ZF4d1ime@|VbnbP^T?nKESfXcw zF{&pMHT(Gs!iYgF6gGh%J1twTZ;+S#EY^4)%-;%rd6eh`rlOTXwrxXMlG>JEAQ+HQ z0?zr@k!chPp~;vVCslEz?Qh1&{FkjsG1~rS>LMg*F8Tj(78zIy92&1$!WaQnZ9r;j zH3K2E-o9`Uc#E1N)<|u3S>^(F%%xqv1+C=3>1kbbj+%1W#;;j)5U07hxtq5Zm@(O4 z7&#sw*<5`bQ;Y(Aei*TiKY)i%x`cnD(F7?oQ?IO=dZjP3!}2Q-^}fW*_ZGZ@{(R-_ z3jtT*&F)~v%r*foW>?k3mz;ESHKe6w4`S;dl(NpW_vCUUJV<{r%XXrKwOY;rixlP? zU&QU0k&9*rHGV{_oh4QgzOR?Un356`E7_pCFW9(}uV9|iGG|OqPF4^1`qXbo-D!0& zUU=m>T970N{d>V@ZoE>J>Yqk+tzrA>H(uX>zE>oz=W@~t={%&reK0XxM6L~}Y*-j> z+w%6%AbtdCb@eJWay{7{XY&YyV6TH#3*si<-E*-O)$EWbj&jA=c`=;znORaTSmLGH z;T(_6gm-VxFb57qkN;Nt@Eg*y! z40xb*gG4aji*RAzZ`>pO4f{4)xqmCl7Lo&C80w*Ysey}clQ^uo5-_H)k|Wuicn0)5 z4yHaFt?OWxSE@hSL>+B<&r#OgpuV}QYn8(05)imZtH#?-_`G3x zg>%MzBtXdmy5~*LNw|JSllnu#-=EWIC>G%q4$!pGlNnXUv&R5w7AT0stiNMvB25!d zxmfdy#cudP`uo)?@9nv{67;V(>rV{(X7_)q?HLvGW67`Y#z7uXjep3FM28j6KBQ2? zU#p{b8@dl3dV5E*RYdg7W}f!tIzQs~MZoL0TKI>+G{!0Zdjq=Lb%~yASc4x{1VbJt zQOd_q`arxGlYn_l`_{W>bR7j4H<6|mQ=D1aAyq@Ypm!JT=m{cMm`k;W<@eagj5Bcc z33g@GTI$HDtMVs_zHer^O9a}?`jOA)ZKTOYeu$~5;F1;6z;mavd!F+$*}ka!ih2^q zuE!5=ze}HgZ>D$m2Jc|e-{l3n{PC3Z?Z>+OEU~5^7)tlf{gRpHP*TWHb(b&@Fx~rO zFDJ4%_1#w3J@0Osh*0Psp*I|;ZePsH*loAC6Hizh=xsn(_NG_U9ca9`&}boHhLHLO zT$y21-Cg1QI+s`Di3F0P+z!8&g{5Gi2L4KnRMV4Ez->g@(McD})~}U$t5_rjm0`8* zo!o0s*d&bkV@3ZOG{cIbOT?qn>n%mGhEB>KG9&*Z?JU0&#W+hdDM;hP=j?t@y=x*Q z{4v<(TngZ9-~u-f)Ya6~v?hd{C<|Un#**->ADG-5)|A&9(|I3?UQNo;B-G>gNXgQMo{Vx- zMkPb1)y6_4hFp?V>diUx_6nSGPpQ=OO6L*;J@89v4@{nHz4J~(^?X04q}C4<46Or3 zxrct?B8xS4O1hwo(}9g(=~*h%yxl6bD{n)XcRy3?I`?uoSs3JXP69yDkIGP}htl+j zaqWb+3;R%%yTBycB{V}PyzMPy*6&mQp7PQsD#(%2T13gh>Y?b|kr z+!{}PH_gig$JbJu%aQsL+wm@d~oTY>$xQrhRa&h}RS4PP@g zo#hmi^Y8z^E+*5un6heyL7&>Sf7%P`e?Y625C-+IQGqjKV9nd8$~W&@TP6K7fg`Ge zsg8>p9qx;mze>?0bYMTt@iRQ*o5R~}Er<8SpB&?NI>QCJhFb9~?u+yZ3;7=$kYr$L z-)Cx8h4&q0=Z5*VowF<~E^b4qO~X7QU5GTr#R3-xg&OL@l7pCEneb)=&>Dc7yHe>! za85sxu-UDDv%6iay!*A}lL_$dZs)gVFvpn7t%3a1& zNUIrIdyM(L5<6XI`YHh2aZXAbz;2_pu^CQOnGofF8bS((J#nbi*%Xr}`f5jw!XGe& z-+CZ(XntMN^tFRjBATL(BAVRrRUzB^0AXZwQbx*);k<2E<>4sgezw~Wrskm+KK7^^ ztM@^^NmuL&UJlXS9ZDM+N+A&|NNBH+r%g!|<&};iV2LBZ7n!BkL$@ir{oJ2Y3-H`& zd!L9m)i+w27nQ8?oC_dKV>1kHG4jK>=zI)bu*vWe-i@tdCUNb%ce*OKGTr;uJ2E<@ z?gBdvMr1_h*M_9@Z9Dl1i*dq@@)g%xl6fCdPUMLgpPnCJkja}Es8T82O?r2cQpdAqzOJc8pUae$w7}*{t_i-0 zTh5KzcpOjKUZ?mqUz|LhnD5(2i<49jWS=>SpEFiHCyd13SP5*|$e}zfP+TG(&+wx8 zl7)J}lSAxL&0(w!g&DA+T)8?e=hcc1e`gNu(zlpQL;_ZiH-^FrhxUatYisoL(7O9U zM`+@EMaVLvcsJi>Foz)SzoQlREL&f_EpldQQ-^n#Um=PFr|gX=Jm(|k&a*TkVzsYN z3~Gn3Et`G22`{LpOErBfR6hd_Z2&&my;zM56=>gri0OOP?e?sa(r_mxbp>eVM*KkQpXYDX7wU zLn$36EINFjMO@Qcq?6Z2cxV)zXW)Si4Q5yE1Y_5{&W2^&@0U_(7+6v$Rm}Nm^b3qn zPWI<`Y%n~3>XbNJZP;3~PpPY_tr3+oWT~*I*~xYy)M-DXgJ}E=KIX8Xc! z#|&eZLQoE1;1IX!$Ju1WO!J{?dO=kcTFalu=?oFa+~fupXb#IZP5Ksecn>-dbBAL9 zJGCg%B|VB${?&yqkvsace?|dFyOt~gAZcxrUqTfwyAX0lLLu>{sgqV%m69d`K`J4% zLjt`-?M>`A!}#vxJKa4GBmTBN2u;YF?h-EzK~gP|=X_>2-g7e=qXFiHJs8jwhU< zgvygu{5sAi07uMQQ*!qMC(V1do!;NO|AON(bY3b~9O^~duIX6|XGq?Z=_oLGd59P` z)onpX8q%R4;sC~#jbzJ?wF*+YgC+5GvO7#>TBElwWv>D!xb)78c69y_BgN>niiC{om!Mtt>3a!8}Q1cT@BJQ*3MHvSxeYex;Er~ZQW4k z5B8g3Sx2VJhQh~$bw^ced>BAorrBV6rrL7?PwYS6JW+{#k-m^uE_64W4VjnU5QXXNy(>e-7!*qI4dvZ@QjH=Y17*u6dJexHaI@KQGMHON zAHpK@rKBXgj$jS%^o`euUqDfx4zCYeIW51BddT~}EHYibHqh>b_FpBP8na%jmE(Ce z8n%_;tnwkV8H`_bT0rNLcdy6V)7#KS^%2gOi)5A@KpxDio#f~KM=Z>sb|R>!gb%7! zU!*FE&uuQer`^8qX$P%hK9ayA(cNSJq@OjnP`4X?npw3{b5730U zcRjZXAU;^Z<_aaZQ9BG2d*fb*n+)>1BjnSZDzHj2UVvG|-S>QsOaBc8>g{In=ap&Y zb;I2cx8WNEW2+?JgX#~V5VGKLHbJm*9$(D>qZjupNInE@`o(k6oq z<%0^JJu0koi*g`wGpf|LHRXyGu+{3Sgt~o7%{nE79yQNofY^S^ z+D%59U`?~3i(IJ5G_yU(Vytk` zI{NF*fd~{|H!aGJqfPV2&*K&0qK6AvDy*&bcXlCr(J5Xi#BTd~ZcxKu6qTorgk}Mr zOQ3@9vTS7RQdaep)up;z35xI6PW?sV$W1nI*2Z*sV&_QBLNXLpnj2&uFCvv|FPVDA zCUP&L=zpkH{>2PN26i2hl>gEq`}&pKDHNrrP)zb5wwyIXC3ek#*bZ|9nBS^Dhoeako?uuP)zjN0R`D;DRCyb zOfgKn*NWtFl4i)A!pEe(LiY+yfraoStg3C38-|2y?TFIC09?ohW_?4w^Cbe^SN%6U zPxI46ynljWKukOB$%|DTQmk$z#9rorh5q^B@+&4c1 zhrHB5<72u)FgQ4SJ61Zz(HK(4e}(@l{lKd4cr@9GoyC>LL%&e>sM0tX*q8`eNMD_QiX?HuNtcTGM@h1P{ zb7NX%*aWchyU-=^xpA_9mvu_w0q)CzIG$$(+2SM8T=}N6c|m>1PuNJbOVmbfs$)_X zjz#%XKha}a+=fH`c%hH$RP~GPV)QrhZiIGr!Y(W>ZS5v(3|=^N0vaW0nqcxIz9-$0 z2i(y>QL5_8jLZKlpD#@kJKvSleXWN$99dWbfI9@JLIRjZK<){c-HB}mallvp0EoJ_ z>wd!Xrw7F~Xsp`DptRx3A}6)55vX677pt{9S8S3Hr0YfH#bNVleIBa z3Jg}c>}Nqzz|1ftl*F47JF-!vv+1UTzJ#V(UG-dIIYdNYCXVAu@a^exIc`<5GCwI@ z?v+r}K%MQrOXuy$H6Yj7f>u%*i!(bZ=r4Q2D%X{AD3+k2CeWHRya)-@BS*9GEx-tQ zgSzacRB)}MF{9zr3MVw?=uhv?V2ryX_W7_=dd9bpCi+nATIXsq=p9*^pStuE>OL)f z=|>&-3k^Jgy8&lBLzbkC9s;dORy@LWcVEx>bJkkIarQBs+gAK++^N=|2XM}eAnIYt zbErd>wO-h?+MdZrSOJ==nJ36*f^H6_29zgjGp}n7@sgJ;e$UnNGmCbt_o;@Y#sCFk zF4$;dwz?%0-Y81)CRtrmSmuU{nRL2$`S=QxB!Etq*En1bah?gp)^SuHn->D;TS4t$UZkI`Q)W&zV=la@f2PSij5A$Bb%qoxw$C`6shXsC9nQ~?Qj+o9pWc&2 zZN6SQobj4O0xltqu{8HP&LERH$earxb-(!G7h7%ryX4$-E{6C9wsrs%RbUCt-^efW z!qdG;xzlVJzA69;4>8Eum3;a5L{UoUej8y(B5)Eqjr zX$s^?C~QV9%7dn{gO;&1sFGC1RqI&oKiG}{Pa3$X{Gt=x>IS(R$_7fA-vVnlPEg=* zpKjsNOL4p8(>4!vf?=Y_ldL79C>rb44K+f%jM;{V87sGR(<*$JH$3D%@KBKt9{?Qqj388=dAsNl z{kM{&;jyu3UCWg^YzFR&T70Kf4SyMe#yu>egwhFQaWSmzvg^uVOG^O{v}5VK1TMs2 z7iTi0dqvYP^}H#U`8CaWQ0%N2Rc{;D^t4y(E&KFp+;zf)*{d(-xmM+eq|lUWuf)U% z%p`p*J!=CmHHdKmGL8H1r~wNj**-`#sE0q}jyS}n)#*MgXitIsK;eBGwX?QWRC^iz zBEWX{N)XJlBq@bxQ_8xX%rweIm6ehZC3tH;_L{QYhW{=_?2hE{dz*wfDl$(>ZAr8A zJa8iMropAS>TtUIyUe_Be~JwkaAKg8tNZ(eo~xUXN|rEo-pFf$NN(IHxqkszILZCb zWvT1$*&eNYz++1l8ZoRmE1`%7OhfA9eO_m;Wsr*28ce#^9BUGp{8s!q3qGcGz z1~wrye9Y-4ZFOme7f#pZ4wphb*mi9BL)KvB8~mk$aRa8>)LFn{6&xp3=X(sh<~p3m zzTc(eHX&(f$RaP_{I$x0Nxm6xTu?H5W8YE!&>)~4kw#%T_}|t2pF1h+2Y))Jo&Q#h z|GdLOfKcCbyj=2zxIN3dQX55Gn7lb-6LEQ@Mh$vfxzk0_hWoBkZM9g1z}i5pWNc}3 zi~Sl6G9h|>UA*}YNMG*5mjySCecohE%WJYx;^7=$+UQjeX>PNs5Y=)+J)?MDBOeSc zEifn-y*{CJjo9^j{?STlPkR{E!DLQMbhNw$_>h9@BYq~o*T}?}gtkLc=w|?1Vj>$Q zw0oQBGAZsY9d2~|B@WLH+6yf9Zw9EYC9>TAb(^NAN4)e=xt-2pcRiia1la&ZZ&VtRy2ku4#o6zm%AX=5Z^} zWSP$qG8WfQdl-%*{_@iMM9IEGHuhlyNC0i%czI<2vBwfp`TfbR!FXdqKZSF`aP2*J zqVEA@6pGpx261u3@2v5=ny#_)2>OJ9dh(m_0e(Ny>u~xJz3)yUOsR(`KJu#kTmFCV^9w#$>A^=5t{M%Zck zUgb%Ji{SHK4_1sTsSCzh9oHn?5<6We z1*Ed)#<O zaEpbYR@kYkgHHAUqu%(M6$T$NH*E;ygFfQDxeHUZ=i$&)zDX2Ht^qXD-vz_0-RI$R z9DMCpHPqTqWD0bz)Y-X0Rq0QQJ6*VnTuKrF<`}rXUN~J59#Ue;C%Z|qC_{IYL1|)w zav=14Fq(O0F*Gkc^~fl1v(92ytxs0*WOnlXF6-ssh3+$jEPFmG5k&rkN(~;)-@+0c z(`mD(VDkEf$Mbk)_!1hSlTx^0dUeCBJIF-t!Oi+r01GVJjAI;uj3#( zk5&|JXE$$y7eofITl_jQguxF_Kd&G6W1^X9`67HtA znK9&&WAUS&*xIEa$vWkNoesu?`k3y+Tt!$<`7ykPMu&h|Yiqu1?)NzvCjWco{at)P zG+Y1mtNdp%_TC}!kx62S<}ljclWN^G|41vF5!9_{1335rUC3wkj)e0uY+XUwYb5qrp~OZEk4-STHv|Cn2=7m0_BU4k_ zl>)47;jiBe?<63YyA!U^&^MFrkH!wUKgnyeKG^q#7QUDATCvPw3)a>z!lD}$AhLmP zF035D4i;2O&Maag2WW8T>w$)dAujR0jYP?bF74kG@$xF&tO}HkN#J_@*DeXzHwTCh zc|~1+9(MhlDksaT0{}s@f&5*P3iD-avG=H{tQoA2wZY3*mC7^8I`q0l_`psRkYDTY4D%$ z=ABLqDkA1p&PefUXWqwjT0l{Tv$j7v?>PVNsqp`9ajk>H9f|&bb6CvGM3h>`Cw*#N z7xPY|DAhq9iIz;d7TUj96`;#%eOJgXLIMA#>oP{+Gb~?^w|&ZUYkA6(aWSa~U9#>M?ejm3Ck*cYnMtrjET?k*tHIqiei zXx1+XDl{cz+=se=7X5G!!<|ksfzva7c%wYe7d;}%AAfQGC5b-V)&|5u^DjwTHoTes z0z-Ghi5=rWE*m8q$Zc zE}H(iTa*th-&lm5S}EO@_PFeKh1i+8(3M)>{Qrt}B)b1wMNpclM1J4; z;QwW3xN`^?_N$-%i&Ct)x_bDV>-A(UFF`3tzZTgX<}m0_cXTiHosK%py726m$uFtn zPJ>cb1)lRnO7nm)8#*YvDaU!v=Fn^_(G7ByleLh33=x=V+G@w zn_y?{{@(jq5}Ca2klzyxZ29KH%JS-4*{ZYv64_7_eZ}NPaUDJQ@!w>%Q1KvT*Z)jA z69Kxq&i$H4IXhhhq3Pg6R>YzD2|9>NRun(T_s#VXOZ3wB4R+#w_9!5l8KygJ-zj`M zdvZT@x>4Iz)oz!&<`X%KW;t_`njMR!Qwkm#7ha^nX4%SkLodQ@3f$Gjl^a`w;z-To zhHhqC>2&bu;JSq+5OuDRaMn3a+wprzDGVK;*6tIWe}78?moqrhYEKwTY)o< z1w5QVNNwK6EcW$3N5+zmo;ktp6_U`gQov^$AZ8N^*;hD}Ey0mRlrqYMo6219ds#`Z zGwunhKb!!eBhG*G9yH7L8ROH`PNEpLVz96G0k|ARN3-@fraK}t#zcKV&B-2J$!9II zP^LH~$9nKHLL=tEh#>h4^u9R`fhuT(3C2S#u55MzcFr8ytj5u`-5FsC8v#;;mIlP< z#>)8m(R6K=6K_t?Uvb`!icL#m&+@-&;NP+s{Qs0iF(H`4)x3hDqJdEw$ZuM6d*$zP zGp;el#LsL_NLCvg&G$!P^sD z1t{@5JBlT1NtUJ=e8Mgr!>zZ{CW~6ye|Srkdqb6UqaXxOC_|u=qpY|#Eg4|?BNzR3 z95^aF;)i@T9QH8)EtU(jq&sPST<}pv0ocT|SXNOr1B(tOMwyR}cNV)9Kq0+?A5S9K zZB_|}m%{*d6#)!ot4zq|-4vt{gvLAW8&Tzw4Yol`&QNy7V5l25N z5H?|^o~3`W*i`XH+F#$>W(L2k=v=8B%%347e=rA&7-)oVN%LDQJE@He+5BX(i~XZJ zjFtUM($-E@ua2;e9@)%6uidU-L|E{p$BM)AL3TZ&k#qn4T^)EAlH{TknOQ{XVPqD&C(W&JN2(*#$hb0=h=ES#aX#)E zj9!Hx2L)CFD`b3Hdk~NFJBX740-XQapQG`kMGuPl`UbHU)m{@MXv|yRK7MZWPTVPR zs){T%S!S2TTw{rVeN(8oIFjqmZy=RAr9&inC`3S()w!55Dy(;nchIvos3;#HlZ`O^ zyGd>;o_iL8;Y9{~%r{aE;~FFKr!!sxwyqaM7Z=x4IYwaZ?>5d>Jb9!II)gdX)GOeA zE7KUz&b~?0*LpfQY4v4)U9iOP3S-|ysARqS2itgiC{dcnPg(*iGPqt}55Z3% zw@4etUEVyj@gg|5V0~^Cln#w0_6Q7Jqy0s`izt%ZL`W5yT9NX32LJrk6V$8pky_%3 zGCx||B?U+0J(E->JG0@fFz#4tR1< z1gFE|p4^x>4RR=uBJFVS#%4&n(B+a9ynk)#D4d6%AoL1A#2~D(6LnO0K3!%WUZEq4 z{bCD2%SY`*ZD&Njck@|&Xx-bJR7t|6Yim`njOPjuWIv~fjY9>E1?JAo{J9b0qCkm8!OO$?25Yp=gY&+r{|ik2_xkb`jIYUn=LFpN3R(Z@R1PCOn1fO{V96S? zI%+NZv89u-qw?Ir2~&!jex}$yZj8Kebot|itKB@pqC`SZd{Br?1@8NHh*{<&@zRzI zeqIm@@sj+tI%Kg4!>2?Fc@p!ReW{Q%*daMeAd0xWiGv1);1pN!%Jxfgij60+s)5$g z#}+TsT*{9~DFdQRR3%dQHR`!((nrB3ZTLn|<7GYo$Djb^BDr-3VramL2Dc0R+3LmI zzqR4<(*s#Z5qpAb@1I@a=pbi&Y1$<18V5Zi6+Gh@uFDXi809V;`SKu zKE*&oKd*9qZ1pBlQ4*CWv_`HaUQ*-a^hb`*i(P@V^oAq%@gLPAxmj z=F-qV_=ykE?YBLcUuYeXI28}y8)!VE&T|%%f}QFi55R*uKC~gx9Unf_7{|@ikwvby z+mQ%tS3ImjV<(-Vx47FQ}Rh8j_X&n2DUD>(HQ-&KBTKbfJKt-?~!jdiW zuI23sUzgpZBpa-jX|vKHugeKf;ulRNqwJ7d7s#~%T~MDf{>EpK2E0}RNLfCkLpvD5 z(*c*LZl_C=qe=Iln)V-jpCo=X`sXH_*EPtZ9-2G^;TK9AZY%%Wz6~3!>HD9h*^LX_ zb(U=Tv`{%X)ti_6&RDwSFM{R=wl&4p3l2^3WZTyQ@cX9BOO~K$2mcgv+0^aS1?ncyF>=9ccG#ep2lD8tywO;{4q-#y1drBB-*H0cgKjx!x`s{@BR`2X)}X0H z{Mbptj2jbt=aO^-Horbl$8luQ;^jg>@PazBf;aI+sjzB2;06;Dh540f+9C~vksE#0 zK%k&SyQP@Dc-(}dM*HwNB%s~Rh9gC;-CN&+o)wVS(wO^F?P;GbQtZEz!W(!eG@HI*bfMmpNOc{UqA zznKcf=Q#1nD|}eIul5^Fg{lf+NkL5FPt=4`EE6NE8g>kBKldQqio~7EqTjI|Qv!D} zB|l@OjE*FsG{|eQ(msy+zc*yeyo9LkVm-Fz>MgYrK{9$fkLrur&UWe!NR;4r#29sKUTsDeG^6hCX zaw?^=S{o_v!LL4krVd;hOE|bre-yHyWV?7{i^O_(r~&LxSKwPn#0k;X+kUrRhd08M zpg*&%orOaYi{BcMwhc%!h4nMF$I=pPRD@~%g&K?N`fM`?wPgKpn!ERd=Ub7H2Pt%< zh;P3t#%W(AAn4|XIWr4>smdTafwm{&@w$89i`Mu84ZhEz5rgd}VMs*$_g3nm!p%TR zPJi-(I)ToY3GCMUczspvdMV)5xLmK*Y0bM31Ax4rAF_CW$i_CFQ^P+Dz1#R{dZ|Iy$Hp&0^no(m6|CMCU+&_8k z+f?~&u|?`=@$ut*M5x90iXaa;hq^^KFj?fFJJm)W5bf3op5plrgvE^@wNJ!6d~)bU zKnUyQ5Pc6ea#>i!SvEn(tE3$f8Z=&3T^Xjc^3LIFVJd;0+*k2VF|Bh5jzL@} zZLtXSBltZappo-yqb@Ekl-Kz8uWGfP_06kx+JyAWVKOAo)iYj6e66got9_)rJ57oS zoTlG2cP}nuHj2FB1c;O&?GVUn%2GtbO1=uQUyo~L+&&6gSQPCBzDAh!7?DbT0@bTI zr&#RX&r`+fNbs@5s;VA@qP+_c=+5XM`r~s#^RP!k!w|Fwv$%O2NVIi3i-60r)md`R zYAqB_p0l1X4OC#ywbdG;>G^%qr-jk(-TV*CXH>|w%w>P z8k$9s9ox1V+qU`N&pFR|-`}S-?lIQ4wdSRJUUSy_^zx0#Qm$MQ&3^m! zw*S1H z8O%1>6S+E?-ljD70SX#W$YdXB0#spWlcW7pxo^`T?~cE9VNekoJ6W#9zX+Mh$Qs8$U_{&ojo02#T}?`5cZagRd`WT)|xUyP+Wx^Um@5;lME28xOH8QXJkb8V7a0Dns(UkG22Zm`T$Y7A6r z{G_11$z9OuaE+v7+CY0CAz=DuZy6>O(l+3#s9_OuyB6w+FgEP^d(2+&<}JS-c5FA; z74cweGnf3T9r*THiomgL;_L@~@@BfQK@cVUes0LRow4%Wj9L0!$w7M0w#wWbQg2Gf zyC8wfBkQ#;6v%Ri&+EijIA%|FUF7?@Je3r()V{kTEu&*&4&N{wfT4B#_37s72KYV~ zrgfieRnD3!xnWuw}> z%i};1Gb{Nd4kydfR)Rrl;HwDv0qLHZk*KRD*ki;iN+1K-I=; zxQm3yhVOVstD0?)CBvoxSkVh3EVsL;w#3 z8b`;%A4~OcYGn`iy*`OO7&3t*fBLDmPe#)d=bqp!!LJPxAe~{3;U>9DdrwFg{qgu} zv2VQJ^oi|?ib55)56#lab<|TKz0jI6A?}H3vU;5eM4wjHb#pVnlXjpF#&3P9V^4P~ z&mWX^IcNx>krcju$cd*qfdx@_tZ*eYKAd+Y+*dz{zM3RAdr|uL+XMV8_jsl0ob*Z1 z1K#K8KER0{veD}w{_{@Q!$X_BD7>(oIEtQ;`WW4v?AcbXu@7*p@kwP zGdx_D)qWc?l9(Hx;$82B->-F6-DibSWA1pG<>ZSLL~Uv0A7qxq zWB5>oKh_MC1OY56VK_eTJ9ay9FSgq&bd=hmAu`X^An^Ar zOvUS^=5dNg>kJRQaOMuLSU*1-7u8m?s5{^o)? zQ=#hxBzWN0VDKCT6~BJM{E-jF+y9Tvu}(g%|G*T~CdIMl$gW|PnQCTt=;N4;UZeT` zawtQ2WxPZ6%G26F_UY5dt;{!3HLE+Z)kb?teXFJLmUE;!>g_`rYE=2+sWiD9p_w2F zn3cX!)RiA?Q#VQ<+=ek0<}k*2Or_U_&Z`+n}|)b1UrA7;GfKo)p|w;741 z>xkm5goEh*C8-y{_81odyCr)xj!uY{$uZzIFp9@Wl6*plEg&X~7X$dwclEfz?2TuU zX;1eRshstW>~}eV?s>6n^V5i(JX#!JC2j-e0vz*d9m zr4rj5qFoDYvo+jW8fj<naFG zlN|%s4ztE@OZq98^gQkwCp^%VLgk(Ha5!4T_0QJ|8|8u>Mrmrk{)vL+{^(2D3Wvy5 zpVM}&N`JM|3mayQ4mV{e~4d3zplFeUOR>-qi~uD6MKpW?OAKq9(Czs>~Cs8Nnc=uHny zklPvom7<;V1=@mGW5asOGxt_3=h;o3Ni9+PQzSRm5f8bT0TjmhE=`RQ@ot1`5BW`6 zNVu-U?Lgmk5sx5a5Ckq{?aHQnxu38e^Ma||Thh=oee8W=7%b(cOXiUqHd~mjsS0ai zVxr;Vo4y zkRQ{ad0UldZ;ls-qeML&_Skc<&6B64a-3;p5YY$ZYbek7U3S#W$6{)A?ze`44-v@i z1Bf|6$d2mgNRcsW*!_B-)aa6wDBn$tU^FzfwZFvOoSBcD)#?E9J?;pysXF^LxQ4I3 z*}@rdc{|U?aPl)5=qvbK%bG1y#!^g4)Sq6-)i$RY3LSKRekp0HM9XpIhiIwqCB6TACHxEBW_z7#<0a+* zi3*3kT^(St?U<4oG^y)^vp)uBJhB;80?RBJ7iA&H%~Au2yclqnq!{+xCMhR6 z9n7>Tn@VIp=ZJWdPWH7p2IS_C$~z`aQCk>lQcVyLd;Padg9QQxQHqKKZ#_@u5=$|V zTP+|xJvWuro3BVd%YWpLw(0AaxJyI{E*`O96ACsJEI)0?a4DIm+(VgU(rl)07OoI_ zYpew-x2L@>QG`X#&~&J}w>85%;Sw}n_LCUXO=38~X%pzen$xGYi{Im?wPFX zj;juGu23kpKKd4TRm}_T)sa>qI$WJd*?O%oP*}E}=iPj%=gB);%Yz)-32yIz-ChO- zF2A%sEao7?Q=sLFTT(7JdiyU2OI|pQOf@c%xab|TF!u(#gz>}ag-xW(bp1k<0eVcH z8x`Tq=hYV8hPnt;d2}6tRk#SVYvmVr^W2UcROBo7oCS2(%tGH~s8V*>MlLVr=>XZU zOHLR^hgf|ccyWs;EQ&9tccmG8#wM?cGwIoyb|h z7^_sS`4EryR{_cpG7T>nwA?i5;Wz|2$yMRcdP`sf5Tul5eSbAJx-;{?*&U>g0~+XZ znsGcq00Ew0Ua8Q2oAjFJ)9>lGe?zZyS>cR?Y~_=_@t_P&Lu2jKL`ZJVH2>hSQ72#z zsTd56r^KPTNKv_Pz%Z^SxIQ1Q5T&8tI(10&#LnY-#VeX;7(5NAZQ6Ymzj~5o?opN^ z3O^AnF?Ooo)}v3+IwxbU!@p-WYCWZ)McwDLS4dRil)YF}pCcyOWg+wS8L$1c zv`ns<;dVDlN=zQE?culDoU#GWMk3BtX=<9i-&6$J+z}hTZLGOe+>%MzpWIntl^PCS zcW;&!XCGtoYu^)j0LkQau*vbZYHgRWBXL|az0LhQN&wi8}Cp|ExT-)ZpXS~Ji9b%>d2B5 z>EdK@^Femx$}FjrTUnyhA`=YXJ;hsi^nd7uC0G#qDSGc}W;&SiQXwn{!fiM_s-FB- zBab~wB!{b_h5~ZuuYBKYs*q!1@v0rz$$TbI4 z)a@sDVv2Abu(!t}*OD+v%|DiGavA&mMzscrX1LE~d{16y%iMD;4$XET0`*!?e^bP7 znYy5t()tTPz~#c)+xtSn8ya0nldjzYsxL*)Xsplmv0_h8UzwU;_ZuiOw=UlZZ;4u& znwkr;i6V?|gnu_ArTYVItaJv0fX|AQ^y3SvVnJ+fg?>Ytc(@qplgA*Y(^&*+MYX{x zac`v(B@V(bT__TF=#?CtV55CXgw|A6HhT>iakq)87&Bbg+0=!_>4W-Uiv^;GP3P@o za@*$DXU&Q6Q8zoEr~L*2+ZG+@Blt8cxh;VLX7b>10fo`Fp+8f@1*yEbDLf`LZgI?1 zN(?ppO)lqfCMh>Zi-i!xAwGqUl_=5D`f$HY6@G=6isk$chCbuGJK8dL_{MYUmq2!D ztezc`nE4n<87EUmhF&VpHlM3=Qn;rz;uemAppjQ?N)rD4YfiNj3tAdlozwFaA+s2r z2H0eo4FQh_B`Anex+sn4n?@ew*|Zpi!(M2y_>2n9x(Ka*&|er#MA3O}rTykKUpfpl z$H#^o=c2}e5ut*R>&#;TLnPW>0G&(~SOeoxKfXray`iv^0DitVfKxrm18{z-t?ThF zo$2%qY5-|Gw>$@3RFU0lN!_hRPlYV^f`~oa3;N0%J3(iP)Ey6HqEa-;?lTpVu3rKY z{D|l2w=uy7xjT{G2VF_1->Ybm_wi>hhB<~bcu|KHd8y^)fPbb%XR$r-R5N0*lBFNe_0W} z*IL$ljDp&H0p|jDy9o+oHH`>~t~>O=IXEz=Vr-B&yNW|WW=(Ydt5Wxx1GXQh* zzX$ippWcT|)TT>1uV#BR!pD%*<{+=jC4!@#Ea%bbtMls?kh=-y)C53@{%0ryn4yHAlgyz1DF%_3)a`+!|mYQqW31H7B@9Rk?- zs`GfAB;2>q`QYevK;79xU3hBmIPtBidhtr+N};Sph}C~x#S4ey=O+dJCmLP1c?1HM zB6v(cGZ=I3?u?U}AlpvULRY-1m~A+w${|vF+lXEX^V*y-iF=H;B_>FAeB~{@z|wl> zRDKJA37{w6FRKueL8!~Nvl6u!Lowq@)SySNcYS0=>i~-cDMS9Z770&XqX?;fR?NTR zthPOBa%n>7f4@M>JdtQ?FN2Is1m_oQ=5B(cGL#!dw@J_94@m#XGiy>X2D zZN`$nw~{BQ2dd}UIWy~f9Z(3VW4M=R<)FJMV;@d$wO8J?3N`p<)Ec0Fs5_qkI}?D=&R7^HdncVhJ3i?06$vlW5}eEZLdJTgw#ZT8 zf~OW2BPnGywk!Haujcd2G%x4T1d|yJf+S?s4ZC~H9Be4Dn6+rH_7>GTf7sA4(GGrw zCX6m+N9z7fijEp(5vMX~ST~ayDH!bsHz@B(*{f*B%X{~_-GSb87cX@IKN!Bp<2!z1 z-SPVmTTB~y@Rq-7u<<}3nOdR)(F_?}6-BWlV8(Q&2vJo9FsMSUrm`+b2xE4vbfg!G zOWv^kI!m>4%C0zYxkXNaT&OF#X(sSk-K45WRH_Cy4vw8`vo?Jkf4}Utdt$-KmN`+Z zqP4rm*zmJBjlo(N?xtQ{LcgkLK&&)aC$kQ3^prApHcVa+jxW;FeD`*`;TuZ7?u^Of;^>{|s{eQ>U8Qv3z_t|F>iX zhE-}t9;Wa8197!%FD8M{wthzcpcU(++xJ+5JZ;=yYSk6ceI1o-qhS59%@pZyRbNm} zV3GZxEC+Ot4IEW-Q_)pfZ57c~*CM+@OZ?suUjv6wj_W_YLuI%e8DQU&IcwkD59}Hg zzLD^{jb|p&)C{U)7hq_wt=D5(pGAj~Kp40gXUG)vB%qq(IB8JHmZNuA0+)tySN=xd zumX)yJ^mQ+Ssid5%QnF%OiQQx!xy05*5#A5qLGhk7~i7?*q<*I8+CQz-HF9bSN!~$ zHaATlXsD;J_erCQTg8AaZVnU+&!;^{eaLG!y>d}p9F@2)Ut9wd1n0bxqQd(J8lflF z2uy3D5!0=dB2yO3n@%NK6GV-w9S_vKhyyU-rGS|FFHucc07{H>^ksM17#Nt{2h1W| z;;rpy_eUNPvetY>I3sR35_(I#YZv8K_WtAacon`UD|-kW>JtL&XP zIjXu$&o##UJ&JLHq8}P^z1LsaJLGQuNa2ykl9;ciP0tnD@afy9o`+k(j5fLBs`~|f zTVn2cv0&lCtrEbH0+mx)(KCDlh0_c8!P)H&H52(4*exY$%3Q(jFqoc_VmPE#M9LLP zu5NQ|7VP(`3>*u|$v;`X$>Q=q9~%$JJKp@tIEEUGOhF1>z%=8fyrX#dic#D2Fx0%C zcL-59E?8aoH`t1vb=1t@m8`OL>#MHYv_$*G2{K*X#UuKd zugGH4xx|6R@r0#~tdWhLb%@DMa#NcuZMYNLIhA#|88*||0DYC~_PE5FW;5TPvs0#w zMyhHjGi3GhFdo{A?B|LrAMYiNNF2{d@R;Y{+LysIg1WKly}#?fNZ+$ryv?}C-4p(B z0XMK_*YYtW0>3iBIa{d7sSvHn=8cVFJ%Eu#0iO@cM3z2lalN~Lp&00cr{VPkr}sD! z646iUi#Kad5N_~sq&K-+F!Kx^33{Xw%VDUN#KEj!%i#6uuJc7k4$p|_$!hA(72Nz7w}mj%MpV~z=UdG zp5quxCEHpJJHQ?ACMSXEP;>xWWUrhK*vb&qL%~ix)EVaS@GRPX zFP`7JU%8MJAoAl*@sG)ajM4gy^cCXqU>w=#Ix-+uq44huBox64*TU9};+TZhEZ6Ms z22wKt47R7527U zf~QvL5GJ&5zt>{CC(R-|2uz|4G>hDYYp~T0-m6-tFsUPgiR$s^Bm#5G+hKwrR5)lK zW?;;p2Sh@m5OYeJFrWz?5MDpm{!R3tiH|sD>_cUo`Wnr8bFx@lZa9$PkDss**@`OC z>{83-*tyzKjhB!djUy4-pO^Y^93f4eu#BwQ zzN<?Wx47I zt#DtKHO0forU+4T_Y?!5ifbINn(rv_Om;uz86%VMZh?-5;VCETqE(ezQAFdlq7XP8 zk!aRgD_KqEs-1F-2wH-)^5sqHi zpImTgqi#+A!n89GGq_|is#{gwv$?F@tf5?ImmN|e`yOU(NV8wT&_n#;mA}qz7yb7A zE<8}6L#)(bLgk>s^#dB6N^$nV&$1_?;?9}JZi0bgcP;A%OD0`lmQ7ednq*gY^AtUJ zGjBG;aBhm_RUenMowYo}gxS7N%KKX@ha@ z?L~Rs`hn`?>iQkt>p^LA&vZ4qCY&zQ_v*m@$jm_fGm_2uPrKf9FeUBqi|h6}zul?T zw_h^FDoux~27OQ1djI6Myqp}7b#hCAk2#aaC*+Rsfr`7KAs(|`ZwXW-A+tTqrsv}_ z`__Ef|78 z2)NQ)iU2~_lZGJMRzVF`I6i4cQ==ku4-MgIovLT}A zn%`WFt{XR22@}$m%F=)mLZIaD5BRVUAcnJB*Itj}-Z+*Nn0}~b1JU zr}hbeEM&g~c~5x(o878|HxLo!VOQ@AYu&x!F!y|Pz4W8PPNBB^*~WMue!2g+@F4hK zkii-~H-X~$Z#{9(zvPA>J0S#-CLNPdbCKqCf)0aByw~S~Xya~m??nAoEsGDEyyH$5 z(Y50hVcz@35zmMEm(V@boXXW>5bG|A~4I zX@lpaPDerJ$OSLJlq%~MRDScuOY@B6)J2@a!$XWWW z(Yv3xOm0@Zm6ivL)har16KoS_F_E!-WfA*Yn3_$#Xl&4eE(NpE&=__&_LG|B)_5^i zcAiL+LO12R5 z;#YCl!p{>Htfl7cDsg;j(E`w427yopC3zZ$4ufZnTe!{8anj$QSOWF!Ry(f7obEG@ zqzJtcgnWi6Tavy?u)PAW5Hpeum&z7$KV`&S#dKwq2|g|$K9J(vM(_^k$gV5FCh95~ z_8208OgD@(WK3G|#sgp_V|!)X=6@>2nRY{)R)Y#w{NRyP;6;TBy4FuH&g^_xb*3hIo&2I5tP>3C zJa@Frwn~^_i4jNQg#^C!U>8J-g&oAoNKWs=0NDJDQak^k_&(o68M8|zh!rP-vd9SR zfS(Tb`H8#wXlI=wUwu5%J~!B`hc-JRiR-SL5E;bX22SFO_CBtL3>psfi3R!_ z=Pw%fsbH8i`!li6nB%kC5}HBkcoi!h7KH4Y0S{?M&&p6e)2_xn!ciXNd$z{|>~9E} zchW3?DHhu6%w7+M2V!4=i^3kO6t9ySogw)#{HT70p}i4qb=4mOOgP(0M*$rff8 zKI_(pM_pes)cHZK!NSD&3k$i$72>B%-}a`o=OWz?HhlHW)#o=C)3?Coe`oVUwkKc* zk(&qf5F(bg0Zjn-l+2(XSy{<{XCR6C>_85jW zXUExt+j0Jf4lFr#HLAHcHJy;mTA0E=bYaFx!|2jh%3D`gczKMURkAX-p*o%o1E7I? ze(;X^d3JcyR9gkfvjdiC7-pYz{J)J2>qofdzl{yCrSEa>8(qf|KA*lDT65x4$k>c{ zjDOY72dwAOm^2%RC5C07ubtkg2GFGgTtNvfGT2%zGhWHB%zu4-ffgQgjY$tE6MB`= zeJQNk8L0As_I-UkxXj8|91s?IFe^8x9vW`9LR*UTKwE4~h1wEwc$Uu{-s~3NM22({ z_1em)+N$8z7bPQ_4$`eW0d%|Hg-iUj`4ua0>xB;1u5J76Y1@e;i`C(0%2o>BvU=Yq zAptXyr{uHJ@|M^KjZ`vVFQqWJi^>bhh94{ID)U~>DvPXVz97wYAR(X!_Bcl5bC^Xz zBw`!{g+3ySE4m>&sk{GVJOS{UxP-#tDC{ zZy?ex2|(}?3g?QH!VAV!b-ob&N!(}w2l>iIC4>pZ8s}WHrjnheB|O_CU1h;^I@(>` zKyJ}+7L6vsgJEw^3hW^e7MzsU0^U=H0Hy+BSHH~XmcYnl%=K#SAJwa}<%yiaL$}kw z3~y!Py2dCCRl#3&8%nq19d%a|4a_RD^qqXZOEkLPCsyca3(IxHLPdsyjq>E~M3 zQ0l77i53)0yR?2^`V9eZVLK8MVvK%gXwpX*iSHL_eun%Z)oy!b%Jfqo?uTiC*0(Ya zjZEf%qP@TUj6k;yd3{m%jMTI{hmy;Iv4pm~uhgD)EkfKFjyz^ROvRDqsYcQ{eeHyZ zirNW{+=04D9egW}ppJ4iNf2(aE=$)F%}wT=jE`$1EHDVbQ}8zHemZvMCQxZCQoE)t zR&_FO{_GhMnHOk@eo|Z#y{Czd{e4g)MI|cv|W0CWGaa$m}t^Z8p}&M=G#v!W1I-h z7K|f?#^m^#>u&LjRIC&aM^ud6c@r@kWFe^*_p4@~rzM1!cJsgAaTl6ASaj;WU~OCO?cBWA;n8Ab-aF8W zGzR9qWwiHuYFD`UKzic2vl+;O!5ex2Sf77%h)#+>pt-%@S|1P047!;o+fanFy|IYi zZiM4Pzh$Adnk(y&r$0K5TxW}rUcAV2pmmRejV}WpgD(jkS1KBf_rfvp4lcN6i{xi7 zp%Fb!b01@^HE%MrU7_ER0QaR|Zc{yE$2UP1%PwA}U`K+5 zb@~omR))xk$*OLN1Ee0y+A_dC?cc|yKHA^B0PV1b9kLh(BHv2H#*KwV@T=PRVlr3R zo~iEM$|>P?hs_q3Iqlf#4_jd3j}*Vr{{|oZHOwp@4o3f9fN;M=qOSW0WAKD`-stp7 z84L#cj1OB5-8$uZf)|TCAw(02?k8S0prQZf0eaLB9~j)xOZW9!g*O)5;Ng^gUQ7Q| ztHck3y%0v#sT-{HTi$G6U+ZqJj@OV$mg{%aKc}g|(d(y&2>YDYHodh9D^K#+4K7!5 zaSYt=ZEw5Kv$-oX`KSu?N*u(;v+c@odz6+Cl#mftO-4Yt`_L90THA>-EcgD^rQKoT zyXpH~O4&(8-mzs|4?SBP-8&|ONds>iK)uFvmLWjLcjdNulNNMm$`v^=2lGvQFyHX7 zzl7ihHZi6Hg_4{}+jQHiu3&2qxwqMG_Pm+J*r3J)aYTk&F%!#^LQ_7iBq zaZ^OSOV(|`NrgeT_bEB`*re}XrZz2zUyv#+j#FC-JS62#^=Aq;*YReyc`#lKF(>$1 z1B=ei^N?)gB)h}*69kGFRtg$P8Ya&o(c+m&w-T2xwn*DkVgw?8_mb}z3k+TYi6|t3 z_$?iiOZJUi-cX#b@s9$UT^+*uS3OJJZ)>rO9=f%^%k2C!~K zkzwiSLnE0Z(;NEc!B)pn`AHW%_(JQA?3 zVQwhp46@q`3ZiBi2td|GWzqIp@NBwGZR4a7Jf(t$h=sjFWY(V6oqwiW?Njh9l}_`Y z{*L2u)5iQBL9-ZVB`IZk4g1{oy;-diC2NUQI%!OFt2$=nWj~*W$VVtVB#Zh0URj{0 z&692GC_Y6;7uPS=llYD|0e^qkC9kg)b#@SQCpG|CX%e$7!CTN#=RClq;c)z^>7BT9 zaO2}vN8tYQi{|CC0E7PJpX6g>> z=cbT}jAw%F?4!%n&Nwks2L`wA4s?k@L*8VA0FANttKGtOaq(FH@&YzbDSt@*q+6B6P;zvX?d%OzewwUrDzr-uFOsHIhWRTSJ|<429!tR5(xj-Q2xY z*8bb1>|b1VCm#%zD=59oh>~+$9^Y^*GS#B4Ro**hf!A!p(E{aiK7#MMgvJ+me*4yOY32U_vc&QEMWxV?6pY=icCVB0X=mb?IP4j8X3(M& z9XK>ElsrH(=@WY$GGsapxZ`k`QnbB)^3NrUOk*K*WNv}{^7ZdA8TXA#Lqo|>KSN$d zztWwExSNU*9C8#7Q1Z8`o?ehRGG2_)7qm;W^v#3Hlmw&GIngnbek=!r!n6)a$&25V6*+O?*yd0Y25JXV2g7)vgSbBPK6W+-eBN;m znX-bG_~h}}v}o4{Ydwewe+hF5^T;VIftbtE*l-`~mF-W2R2sdRO7*lr~` zfQd#i!zMEnRYf3#*_)fYq?3wK!Ckx{wkJylyX!E*LZNW_AF%1!W_sJoY z?_Urr5Yg_;j|w1A*A#|6BTH8A6C@(@6DEnrh&^=;(=ZW-<%OftR1$>5i-wTsdUN1; z{sM{W{{;IHeP;5mc; z`O-806@3W`V_w&LiyCA!twOzbc4TYQyCHN#$>9F%PHlEDcjuIoq(iBFPp>HOzV0!! zs=>j{&7X^mMV$%o&ptWPPd<1(^X**Kqf$J4$@o)R_;Ha8pMrxN-JJtHNUWE8QR3R$ z%`VIOlKNfOX@cY~yLNDBbUO{3Z})-T@NtTTDr%+C7djfpv;6-|K40JtfIN)<4keH) zE^;3-1Sx&-|J0BRLE5ntZ0RZcj1dUVs)`K4^TT=EQ~xMlIV)!PAS^%hdVwOaExy_n zwgVWqPPTAkZC4V1jD($KIJNXpBELLh_QL$n4P+(( z_>s|cI=a!?EW-EiR0`ecFktkaPVV5|J{) zXL5_lcs9RLI3}5c^p6YL({(!0X)dh?N|rxS$)}gwOv58p0ai%InctKrapOnM9Mp7k zo-(=a0%)nEw~(NOI}B<4q5fV%!>L&(#68eS2#k$*(3aRkaSJq=p$VQsLVO-f2-Qug zE*jW1=m#ED_>Ubhe+@<_42IonmbVB;6o^nEvK+qtcZ zA^WNtQa8+Mkq#&Ge0_O%7rL|6RWZx9I z=AWrqeDXAaI7=0ycp6{B*LKb7aw{E4$S>A7?QoMStDq-_ClUH=K_YO7p@y6l6n{-R z6O&VS;KM7O7Txf5uEHQBNERQI$COJ(pqk{h`}b&A0_EPiH#HY3mCw1RW2eT$K+U|^ zM2^4ydfj-RNs=t91!_~ru7hsjhW(NO>|CP?+pcfW_%&@#Aux-fsD7CGg#o(E;nyNP zmsHDCdo35CN*G1u8?Y)jA2ckpB>0HbwwEE?)xdd@nV40Zm){Sobq}5;K~_z$6LAS2 zUbZ`Kib7kax>Nxg@}Egq-A6FMj;3Uw1`Ip7=6P6eMF&NZ0G>sqv~U`Z(Z;a`@6a}`f^Iab~ zb>;5NXk=~bYU{lTg!vWFw?_GJtG^_!9!H6(G|iL=!PSIB-P1cNqV@1HyQ zMa{;qvKt;qD-Gpw2pCAIE-&f<6#XYsC2la^zY;_HJ{hSLFXe?fw`Ox5686O~sRb^x zm^_o+YQoz(0KJr#XfS=E6U@)^-q+vzT=Fc@de*%lBzK3>0emrw|#V$!%(N zCXll%CBLFRNV#GIlSCoK_d)x&GQe}3 zU4*3=vZI6$jLQd?#Nlkp-HAO{Nv7<-!-UK+P_sD+&+wv{nE zuZ=L#tIDkt^~XrTj1KHHh3hHIH|xQ=o&P&K8&x!5b9i(<|0HLWM$fdfgt-;iYb4mZ zooPyzyT`Y@GG}fZbO4`BuEr($r;7D10&#$BfdrjhkabHgJ&*o|;i`GNcKTs8V>)NZ z;`z3;gb8_+6ZePE`h@pP0@uDc1wTUWv568ZAbwHD^q9oKcxtQ)K^uR;@UKpc@yP(? z;>=Xo0yejap10VaEicxmahVQ^PUZ!_<82zr7(BAG8@>FmJnjYG8>+Z?q)qlCL)fjt8oHSKqSNL)t8t?4mn#j$8OMrzYIDlKHF6lG<7yKD|e_ zA6Rrc8}nO;Pp&lDE%9f2@8eSJ^1kKtx{e-nUP2)d@~Q1Kt~*4urMSGkti1Gt-A?aT z=i9Kd&N4XKm=B{b58`tRniNfU!tI8tN$oy}+3%^>1aZeadzUi2a z5BKt#njoQqB#zVi*Zv$&tW*xZrerHK!ad6wtx>XG#mj>9} z!Oy~n?!@I6Hsi`-F(!H{7e54NyB#+=Zwo6fY&Afi01g7+FGtEEJR0j~d_eFMg7X~I zavTg&(JOMLj{{nd$C!pViZpb=dBr${lO0#itbcF+t^l)&Z@`ki3wzHysV%Z&oTYIO z-NUJNXZOkMA?A+s$qwngv|tqxn31g{)@#xXc#;J8?@T*Sk|#S&CDLIK1mxe@42n$c zFp+LccDI+0){q9e zi|=0M9{tQn2(3o~y2=WY*%84NcWejvyGtp_j`|$VZkIheux&Ltux0aeAb=g=*E1gW zjM{{;(eoPx(04w0Rs>>XxRbfwWD#GtA(dw-309kD+2E6}r3oXjLJ(1oBRL zF}sPZ9`HqfH_}I*j#{4~uCB|t&SAJ$2*K?|hyt&9o;05ti z&vkbXug4yE`+q0^7ayo$o;*#2$8y^J|1~5#fMcWhqOy-sOYawkk~! z-yaL1k=6C#!rIykJ&hj|K+6l{$+kJB&e2^Z9rV6BnHL}UZB&yOd$Ir1$!-r{84&-E z>H5WrsS{@n{(v9!HoB_=6mff`aq76m;Cg+{IQFK-kKxtW!1dMQEm{*sCh8p0E!id-l7(HRsx%xh9PTfH6 z+w@plqSIuB%+(s8nEe;naf<`@{d;EOI|4IZKQB2IAIKH?p6^dNF~;c=u;wlE%;V^K+)T3Y`FrY)^u!j%&1K9XyIP zhI7Simrnzc8NnhXp>7QR#l*glAkC0k6k9{9Tfqb<2|>)JYkFXpWyqjXsvd-*`nnwv zxd4mX^x_ZygN;M*raz)|LECd@x@<%n4Kri+AuBqo(FiHH?S}hK|I2BVI(gC@E%d%F z*X+cB!_EV0uOkVEjievbuvj~0?o^cTM6`z=Pc|L7*UaFZ(xV`f*gjBPU)S+QJk_Hs zm#Q@d{=RGA&gwEPCNpflsAAay4yOr9A(;$oZD5%GDE&te2RjlEjLAT>coRwF{J!Kj zkCy4h#lYMnCGsR8OUs)HMdL@AFmj@!Hs#81S;kJlB)JD#Y9fKf^u1ksKlp zh1xjq0war1?d+|Nm)nQ?XWU)a4XPQY6@IJb{z=K(x!Z|gOtYj>8`tl8utl`5$s$> z6YD;1bD(mBp^)iF7cF=XiGhh}G`!td?KDir!ND=&8LUrD5K&l;`c(!_ev0BoCcM!4 zY!f`?Hl_d@e`;c8FlyD{xUSiknGO%%;7T~kW;E;3;Y7$-YEST!-h06R4f!kYDjZ5X zYZ0EMkJ&K2j(9S^-NSB9iY7a%szTC$y~Ex4N)?UM{uOFzPlc~^nIb(Q;Q?ahuf~Zuzu`Z#dwwVO&T_&~BoWkeffWO-O?mKAB`o>(c_x6{RDP$p1yP`){ zfKjTzj?(Kh@<-oq(Ry$@J;?0y%Gh>!D^8cn;g0BKU`F!5bTHxiW#dZ2z?)Nn&yq{5 z+x0@wpYhds5C2;K%=2Tn_WAF^)q>(j4El7L|cYt*Oinv0)S zHvP4eLMMGfJO~6lC=0rt73e3E;>bc^ucdZuMn>YcieUwzJq)j{n$cK=!K=kJjYD@= zx4k=sw&oI@bt@v>`(aXrKcs0R#@%^DZJ-ia->-66nt{lK5`Ms~!Ueu+0O$(x_9zBP z(r8`%hi7lr19vWnvQ$Ugdw;uI;dnx;nJb(cn6Od*O7u_Do|wX`-xDYWwC!JR!J!*@ zYkF+M1G`Bn>vO^lW?hSe8NvVKEZtM8|2Fy0$*ePWu?BXOi4XO;D*fVf{~oiI9)@J8NBLCP}~fsuM~0ZJi}@7$_h4UB;1Z~+7T8P8jwqk%oUf)sjHKFpSjMd zt^IO$hhJ?!4rhL**J&23qiHrH1decdMGaUL6^MsNzofW&D+(h?{Gr&QKNXu_DtYbr zG7ntMrlZO+CkyX3Jz8UxG!IQwT68Riws7JNb5(=IOag=z@+$>MH)eeZ7z_Z^u=;C5cqK*B)#G5$ z@5%i2fW*c(+`MF3UXS+6=UeIGS!s%GhaZxP$8b=ze_}z`kb8XrPqXb11g;3Y$NRQy z{6QGEKHH0bT!!30nI5gI4fopAe)?9LxLXp48BN2Z>Z?t>59Y2fbg&942FnwMMQx+y zQuze%**NC(Z>OxH*!PW9oMEkZ?vc)KRu1%lJ{SjPS~+8d1uIzOs>HhyP37Mv10$t# zytKv%!_2^Id3@Xh3n1rmxbgLQ=Go1|-pK~{{qSu}DHZk|xjw84Pl0zbDF2R#Spsv_ zHu4Bf?ShAPmbmoWpnTcB=Fj-ue3TG-_Kn-qx`X&}Ggjk18nAh^?!n^#B7Svq2a!-G zayLnk<#MX(L{QwT{c!0fRhpb(*Ka=@VWYe{poF6%yn2Ohu1RSLqk=)La(z~cQwEEo z-zqh+ZQIG`e>kyl2al_6-ul){njv8FfD}WV*nn#2^77W>U&W44%P$7vJdL8qvfn*V zJ4=Bp>Ncl1;l=y)zp})Gk)-Mu_mBhY&%TwzUu9D{)s;&nv>~gMGUQ!9?_xQHeUn^a zV!qox4EO_B9QzJR&{?&o>C+_C1TnIFhUZr7{^8q7Y}fJh)$7_P52iTA=Sxu&?Rh)b zkehUSH-OdW^+ecY;^-iBTwmbh6#emUOh;Hn#{5xhTK>2LUDt3B<(%);8s_F0uVsS= zg-7Gm&6uzTBfyyd`nH~XtGn!dyYD{JK7=rmS-alfed;S=F;JLYEJHtwp2Ykp=e z&-D}=0Z)79qL%>-z?|S2HWJUb4Gi=D@snQA=)3;CTo4kl|DfN|_;1+B*tA0Lis}^91c^1vILVWjz37+?cX{*p|xX_Ki$c zq{`x46UIVTpWBpN#uSGVf82oavVR-D^iD=Z;CfiHPx!hT96_BvS;jXx62V+`Xt|#W2kYk}J+pt(Dv?X=BPY2< zmA6Qs&C)~!V1?qHGM|N$RQep@8n*0Rv$ajOa6}9}7OeQf*yvxpCe!4_5;yCczOLJh zxFwk}<|Xg*jkgw>F@XB5q=uuNJAZ|dWJ3=iT?J%5)?lTKq;^#O%*LM{rV$27f|F=6 z2u?~A2DW!qb;1$g1cs!eaX7Z12Mr`E;;(}Qy@Q#k9Ry{QNL;~AmT~&ZRHaLe{W&K! zXxN-X)@1XxMy~rG*-PQ8mHI4wxvfM>0{06UCmEct?*(Uoyi=aYBQ)#>LiXt=0AjHJ z&JU}dG~ZYR5|DSyy}-XXM$fyQ$WdR)Gsd3fdK_>Tc_6ykr(D^Q2HEgn{b>R{T_iXA+Vep-u|9WYN(tM&@&nrue^M7xCw*6YS*0HUp-L8zIqrUw%9~ z9mal~_^HcyL3Zt6Rwgh^pzt{S)f%MqvXhqp+)Fo3R^x{J?aNOM#!?{s^srGdVG@6g zCHL5Mez;2rWWLw|M-KZqUEjX<7&aTk?1xW2p>nW4rv-N~KL(73>YKd2-D{iOor>aY z|AP$&OxASvY}{8?f?qyEz+&I2d^Kutb;LR3rTG2yCSUKpNvu3^6_^C+iTb*TCBNNI z{>Bkanh@f-<&N*rbwr2Oy#;AL#14Fz&*OPnrxurxUxP=xK(F~=r47LIa^8-`p2$`& zyomDKXFu$-bxBN^ApQO;TC8Ahv#uRFn?BdJ|JNTi$k!a$!HqB`yxO{5*9=XP#~zt- z@CFr}-)@orZ(E@0O1chI{J(xm^G9!X&=b1fazqOa|UF^~!b^4>x%Mq1MCX zpn)e1mWv>jgtb=B?2Vl>Sb<|mm@TVy3#>uQn))4$&i@IB2{Fn(UCp9F@cPp#st2Bu5ET$rQj}d#Ddkfl;V) z6^(3N31oWT6S4)d0~`(D@I?R#sbJM0SE>Myzo8l8c`@5a70jVo=U&)2rKFKcdaGB? zhzd>38~Ony>uza zEyQgawsjd9+$oYPDlAl=;Hdlt5SalbpbVli0WkIBmIot^G|hY255(qegN@RkhumtL ztj0#7wnDTP^uw1j($`R|{pT=@fbOfkz7s%}gC8P-o32sw)X3wP`?H@SA$T^|#KpDm zP7x`IE#s(Lo=2RAZAjB7#WN6DF4*!bj31(&}-w9177RU zW`$`zgz-#1#Ljk(f}&2y7E+byvrJw+xviuQf{Q5e7H6#C&`->)<|&lTHTx|7?e&!i%CY+p`dDWW-A=RkqsS1Rc&J2; z(O6kd(|}Ybf*8w|R?Kr=xwOb!SfLYog*hrj_Bbw)XMS2ArJ}oaUc=v4aXlX=u(bHf zuu#ErZ94Q|O2So55=Ln?1FO+3G8)XOv&w@L*tYN7@c=||>E1J>ejUAVHBmza#+jnWP;{%K5n-)V{OkoqjhedvP#p%4=-J`u0)-U{PHCqN_%X- z8!&t9mOe|QJhm>at5eNOnhv~c_-13{QqvXacjubdZ(WubUvuXpa((HUv#`;RyL~C@ z_8@8Tb3Y{yV_m4>cV7b3U%A9~?zHOI?acI5Ucak|UmOmx;QWT>)A$coX8t7a-W{^` z!nXr9nlaUD*XteVliFIq;gvGYEEz^sy*Xo+7Uu8-F=PZX=ZgOwJBa=>c1$06y&+Y- zpX28&KPT`T1gVL?QIA=YmVp=LF9wJ50;T)cxbJ=utNM&25gFY+USmP5%Hg`hHwXtO znQOY$&-({FubtZ~PP|5m{ictOCNG(;95*Af51=3+=u8Mj?HjC5}-*`gUo=BErl>_FHeKvW5-0X1f0;+!%71SnFuC*0~G`! z<_sS{PVjv(csM^l?z!&WP{S_zyA6CGEj3T8#Gk59bs!*ok;)RLo zwR6445#R+iC2Y}h!?|-affeoLr{E25X20w8a+&@kP~ zd@?c2F|SK6%f)t{_sCLNh>xUUP^5L@sf@2{twNVGYdawe#Z=qCv^seLcvf9VPU7=_ z3qp45n9?HkacpF4a@^-8b`8@%MPDn((W_mP4+fG_OC^I-;SGaPcUpdNC{%(-OvDy1 zia(K7rCg^wmp0gk3pzY034o-Yb(69J!F@}YkY)v~r?dF(`eEvn)M{eVcYrj36v>>d5q58g=US$z;k!*6tBqJWR{5RFAqf~+*)?j>7PF_!CBaqVJynv ze2yCmV5K+Kg*?UvmMGcRy53gx9p?LYHe`X6Z~j|F85|bB_Lm+hu9JbSt|~%GaNL9{ zP~iy#p<6FETuQ(E;0ly-8m*otYA#pyvJK`15bs6*1}!e41Hul!FwZhyUMmJTz{!Kr z?Du>_nneM-89oad+TQgD+;pkiiPpI4Q#Wc6AJ@QCI7A7u`enfTz(B<7gKj3Xq*VG` zGAGmyerdVbLH@3H6jTBMos%z=gtgA+W3JoCGXe;1UBa%W1BdlKr2;k8e~?g&vJ!~j zZ|SRaZis-2gfIk9=y9HT%+x)t$n-gGb7V+P*j#LZ#110!>+b z&gd4Z16Esq`?f%nIIy~}&_@VVw9C8Ns&6L91@UYEP^Q@Y}Q1$)?<{RdMDH2IIKLeRGR&f0A z&!4ZOx((UPuN7jTeu98K72b8P=kB__+U_~0$9h+er?SAs%kVruGv^=}SFpykV7+KjT@^swAIxc}ut8Y#iOFfG&KYt9 zNn!6fijwicH)^G*B6D(ySG5#oI4>vULhcVw7^s7IAsyy4mGYb^;QuZZx@=3phEf)* zGaA0^g?NgP$@ZuDyd2YS4TUTjYtF(9a#iW4-?&0KL0F7v8^71_^zBsXHnj|0SVuO- zG=dhyDcR%jJBoewIJ428WN!CP%oNmQ1$Vs{AT16?KzOjs81-4Pn)-n3w;K zJ1UjU%W<_1FFjzFN&nfF z#?h5+NW;Y!G*^ONSl4n`seZLg@vZk2N2jZ!gF^w0Ac^_bPHnc7zk*7{jp9n_-jd)T zw$o1{vL-lTtmqTdZ`YfumjjOjTodGouspeGp+Lgi74%xQ$U%++vO&fb19&*N8;`FY zGq4ObNj{7}5yQ+kM>B6rj@T5Rk|XIMZWiFKqH_;~K~GW|`m)|bseu8h2-!y;-o(W` zaz9F8HZ@tt#j6mAC>rEiWv3Q1$u^0P!P>ZNa;o`6-ZFQ%YhpNn=wR+w91G?!KQ1aG zo5ILz#EH4vE;+~>xUcOXsgRMeQDrV^)EBp%TPZYCF~Kz>dn8mkBJJGyCfD~|1x+$V zDJX18;yE>{crp@kcgP#g8=9%IfBu`5>dec_$zT_`q0+=Ibebp6-mEqzYTWCa*t}HQ zUMCMeP)OSs0H%q9Mb`UOVu&yBnGQYzI$sm%I{>BDbL2M!u<9H^MmQ6^p*b%y4MZowQ_{Gp`y*OtzqZwDX_&TT;$}C}gBq=E}gf{myX^qOOcTG>ppLhs8b4(J@4SM|43WCy*p7bRfSjjC*}d z2kAiWM(JKSl1AO3xU5|x8;lLLJfiZDVk+}Yk2}!@ajzjcHHu@GZV)Zqbiw6s8XSKf zif!IM98X>{4#qNCaIBxlF<0@D9Ey;F^8puZ2P^mkmQ=s@6Ud@=C}V}ud42Zw5t_wz z>Hcl7o!+p<@R$GTta0?E?e@zSP-Kr5(B#$fiVsJq&WESC9nt+Hx}P1;8|RM!8zOYT@VnqcgoXN1>i*LH)%h2$Oc_PzsN8u|ar@G^C>et= z;sw5z5JEhS_Afm@AOd%uT_|7cbP98RL6Fol>mCCiaJk$QmvNe>8TEkXKsR8EfbaS* zqKB6u!dSh&SR>1UMR6H%ZPyJ;*YzKEA!w4;iCFBf8K$U(Uoi2~afSuQeS6L#8RAVk z^+p(byaxp31>?S#c+#l^h!S~>S$p#Wn`~4)2fT8=Ko;;iUlm$+JaP?zwT>KyFpghJY!ABr3oh!QY+w0qsxCWH6 zr)NS3RG&K97PCJ@Ul1a5x-$rJy%_pYo^a~Jtby#rFtDQWkR5oC)UGCIeh~8lDD@BM zlXR)A`e0=Yo(_D0!4SVm#Cg5|1$JNIlH3%zfj_JwA!+NzJL>dU76;ve{!?a zd&kD>aEVK4d;aG!sbe{zkhYN$0PWg567F~8-z9EfZJ(kih;2mwap%-bef~mnX!CQ5qSSt*Jalf1CmL;pn{Q+&lQP`fL>3lg8|IM=7zzbk`aL@!*$uLgQ-%-tT;> z^L}Ka-`l`Kgae;NTu2RW8?p;ckaA*4$9&9LZnyG> zU<~b6%yS0x(P(O-Ntmc5v8lRJWEkU1a@dbW;NyD5{T`LDu$3 zb^V>|G9~W?IV=on21c3Tu-Cm=Je+YJBTZ`}FU_cy{FZnLI8QDJ!-}R)Q*xm)Mf(0y z>^_GMiPJ3EWU({qvk7bXHg)xw?*7+c-aNaL5_g89CRfY{4)PV{gsw%%7GkVZ9LaRm zbm7>*S@38?72O&surGI!Qs3MC@msHGm)}Tj0{92n+l5P6y%y`1;DR6EGEijg2jP(h zqsp=?$gEo6;*o_0lpD^HwQ3D__yj~IUJF{nH_aP8nY8jfDR1AX9vP=b)f1`QTcF8m z*Y*3Xlm_7;#`Wf;!XTNon+gKi&Oim>o4Wp1C9tBZthk(v3|NMV7BoQCKvW-MN=WUN z#HpH9LQletOPa|8%8Vd$h()uWl3Zo51}t#I+0Q%d@9ZFZHsVGL(U8l}dQHxnS7&id z@#%zb2CQFMI;fTR`cIOwO|vMPKm+iXpqoK?~3xP z<)&C-NFd_0uNtNj$mw|7QpE@gkTtsEe1eUF8 z>truG?LOKqG-jEFELBkJ3s&EPvuuV)DQ1{kG-!30>niC^vyj%E;yj=YC-7zb50|Gp z7q+wayOV>ELYHJ{1PG`S0JVp^{#!%dNR2rM*?o$WWvg-PwyM~Bci!vu3b^xp(FY+9 zWLR<~kYLOaC8D$3tSgu4|X~( z&f8uR`>?b5T@LgG^fpBSbOBd5dCTYbVee!%wzlAB@i(>26iOK?EQ2d>f^FU=J3JcE z_do;JIFUTEj)#Hinbk(f-t>H0{XyOcq2*fqa~mmc1p~%*VkRvC#P#JAS*Z57Q9~bE z{aLX}hqU+9j9E>6oqq8o$`bPjbsppbEbS|=H=gJI@%=0eK}(J1RAw_+6nEQ8L=56p zXZnsZ20>W)L?qVC1_8C-Qz% zMUZ@9DGR)D{5x|NGy-?- zs&++02!YSUb|1zd4gg{{Wvow+*#M||sp)LXTPKmr!ifnYxH11y`vZZDYhd?i{kAf~ zypRcX^!W}Xr;LM3A814#cB$;D^lMR$$eetc*{6gq%pi%XGFRim+&|Qz6t%U5$y%PZ zHm>ONjP!jusgVA*FnBL9vVBb?H@Hu0(0${}_+;s9Ts!NFHi#eVsw8UgLVs0pbW>`& zS@yHWNQS^fNVLmqfT%)#ZiT;TXnaU&SdMQW?W6lmQxTF+TnHJiz~!ld8cm|IrSp0e zz1i}}?B(O<=Nd@BQLS81pTk@cVlzB9nF#}%^RvP<{}46SAY5vhLckF{yG`4GprdX~ zCPArDw6lW5s#$gjarbgBR|QRTGglvh_26>PQ;Crebb$nA3hy*S=f>q5w)Q$Om+>;c zZhYYRNk*8#?W=Dm5zZ>L?sD#mRQ&yl9oAodexA@YZBDG~kN$EGX5U4Bj*m`ze^!eZ zHe#6oYwScV*q;{N=a4ixtOn7Oy(Sn;<8%s2;jQkPO1+rp6{CCCX!=oG+vT{Hv5QYD zZTE^P66WsZBM=gPrk}cU$Y_{c_iV<~2-8UD^Bwjb6*x)7`(q*~(BxuxKwOmE&$@>< zUBN2i_4#U+IVC0LEZhHWkbt9HZaBeg030)R;pDmQ7l%B!Y@D#fe(?jE#BWAP6OXSq z3v}USnSIN5SUqz5Op}5_fjv1!l2SiCMrmgEB$J>o2Ke5A2qywDY9INQ>uieufsrQQ zuKIvm;)gC+(>Q$;w48T`KCoD0;&u0fSEtFYwab_0Pjf9>lnyF$8hbBfh@-h!I{^R8 zJ{b4C|KlxUw7?TL4t`>09~0KO5&&!OWw0+9r~4^w)j8lMUtPyguQLaX6;T)jK@Kd0 zW<#;F2j5f}5)ZtceN!OE8Ob8K{GxiKEbR{8g5#j1{(t0ESSW|+~vn5Vr zZJAf}_grxN{8isfJz83~n%;dfQ9lL-_UH zr#Q}yJJ+EFQ*Z6NPUcO&N(2?Lt#Auw>Q00ciX){OW1)mltF-d!c9=nads1s}d~Z(w zt8?+;&Oi0)sH>NRJ z7@X8S5>mw88A%>@TyvJEGBvf%Sb*oO-YC6n%Be<1@PAPUo$064Ok_>4@Fije@=IEg z#?#pba4@za)*N4i-&}5|!OzC;n9T2iF6C9g5&z&cove<)k~iLl$)?h7~pA2QONwY#_7uVt?|lG5@O6R?Zd1W67l zouu+HrX^X?j^8Z|RRL0jXg6>t>WFSjsqc?dP@bdN-!V|HRy0IyF}n zGSE!A=t<}0eD~jj+mt2y-avuUJrNl+;pKx=h(O+&==lyKDIOhzqNb(wOJ30#OKK-k zYvk>q(ey6rKEn#x1(MHv5GTc!0LoMh<0=ib2_+iEK&oVjMHr6yGOja1!tsa}{}?UU zKu+SAOB-fZ2BN2rx*}_T6y&osQba<+F#>t`R+;UM;V#$F#_QB*u@R`KeZL?hWsC~< zQ&S>H8!A@2a;Qr6RI$bkh5vp_s-eCsFFyUj+OBQa%hFUaIZD4tzW@27~fmV6_84#1CWI-M6k7@ds z?nv5NS~i>SB9|Y?ydO-^x{WVi{rjRUQMS=+b5o`}eHZV-3#G^*@i`RnnP0*`KIV*t zZ8{o!{N$IxS)$Xq>Ni7ZGRXh$%gVTK$VSN6zu@|DF|*fZcIn|56`}fjbYwf^VHHU~ zjU1n?QJJ>CF`w%^2*%LG@nG0r0MI|=P-ookKQBXKalSpA5!^o$tGUczwO#f-`3;tQ z3*5(Ac-=;(AAYmCnoOV)ajAl+PjAnV94~dA;UZRLs|@XuD!sc&fKcI2O)R4AO}fzNYZV7d)Y8c+i{+TN3!Bzl3E>yCu6#tytinIY zc7+$?^n@S!QZ2#JE?LvIMx3#}-ycy^j&Q<9U;iiR-BmcuJQ)~GVmg`~t41^kM+W%r zN1#dCH$oXkphHVqC{Ga0{O}`;%|qi`@||W8qd(x>%MRzw{p|CIrN$*Sn|;~e{ysEM zk@!&!49y~qipE&k5Bhx7{q*b*nk`P>u*he2&wupf(3ik%$ivqwEN0_s&yvsKn^FtD zQBirYDLi#zzP%WYZvALM%>Fu8bOe?_i;+1bQBT0#r}xbM@Ub7u`kQY^HiNe6?Dqvp zolun8Z_%jPSoCTwUtI=#)E|1;Yx|JOvV$dNBJmBdKIL8Z;>sy7GRio^!to^M8x_Vb z%h)+}v^~H8X3dkvXEapg=2o<=^?#{h@L}htlhuk>6#^E2Xk7@vvpLQ6E2^H8pX~UX zb=u|G*DK9j$cL}l9O21XR_P?PIy4nht*uRatP7m%icraYpw3At*FM*f+sA6gx$<5Q z*hR9~6*?@YOK?A_{*3*Pl>*?Y6%aNiI1VTYN@{OIfN^TPGAVm}8spsG$uTOg@dKi8(&>G$!z=V>h7+aOG@j~s0u zF4}B`Hku+WPe+XYAdj}!PG3$oI3S``cpnpSH>Dl(bZ*`9n)JElC{5Vn8*r| zEHfMSH_xJv=*c25-Y@kTetA8gSy*bK_c`-Y|5LND(q@6e_S}bW{?zrl?$iBn=h+?8 zk1jj`v5!7I`K-Hv;vjI9AN}4dNVWb}*wmFTYY227Kp6Fq>#g;<%=O6^BX7lTn#Wg~ zCrwh@Q!il4EQbvD@N${Z;kg~fzPP$w`r~maVkFf_zK@unRbLoxhU?UqxuGsXl>crx zw*P5o5u^OO7*gVzAjjqye9>9x1mscb*f*kYay^_a-P!LpTXPSbfy?zQe5yj>e6f8E z6FTXBmi@>4jhS+e^P+1kR7`OzHDBkNWiK;c0 zrkPJ8brmV@YR-$^R@9mgQ=2a6#2l~@}U#BRY2 z9M9V%W1TVEPK*i+t#O5U@xIg+mWBsqqRxLZ!Iix=bhg#)2uSD5f$ zBGfRs?j_DlWgU#&XS+VAT>v`%SO5YZ*NE#pUiDP-u_X-bitZCW)O3T8aJQXoNfssJ zWM9L1A8zEQBy2%Vn?@}J-rptPD0r=`l%C$b$DWq)kw0eBu*J>ukSP;NO;Z83y1LRILgtjKeTi1VmOC{Bi*Z(lujVb*8;ua7h3a zsJUDhMu{Yhao3Jlmo3IcFa>s0q5M9wd4N|^V(2Xa)YN?-SeS(W8IYR#qk`c3bxdJ| zQ%lbgf-6xiTZi)8)Ad4;k;%ksVtJ!1lqMVX9!}0&>iWA9y`QNs9qtc5!dn3l3V<>f zy`T7(jHDu($eZbI2X?ye$I8Pmbd$I;NY^oI`t?ZBWi6AM3;^|D*aQE29F5~dahO_@Q*4*Fi^@U{eTie1|W|% zVkBi?=BA3kjoPh%5O7qwa9o$!;Ie*gQ8g8?zGnXHMMqj@zowSvO& z{EqI&hF_JHDDLj=$1CTrn=VY`(T)s#E5Dt^i~_;6%D*feGda$blzwt9L7cb$f7(fV zjrw=?H$=KxzrwJ49d^uF_8o^vAY203!X#9YGKy*-KYsmEKHV# zSS*6qPUbkyaTktqekbW|a6cdd($xIgaa|)sGe096^&&Zv!49)1Q64*2!)59TD=Is@ zBl1Oo!&VWyEk<@~Bawt)AlW=2T|9EJBr)uPpa=q94-uwHNUD1|;?P10JTp^= z=68a6_h>uJN{EKpMHb~${R#xbI{~AHLBQ4sv*Q^b zz@ApHDaM}!XeO!(4jr9P~r(raU@A=92$zert{TVDcdJ#L6M!A(D0=cAzQ_8*Qe)5 z#VFlZyYmZ6ff`#?mWWM~A4g2-eiYWXq8P^Euq%o&X87%%%oI-dM)I9?Av1dB#HV=% z2|fXMM#t)6=WGVV;Pq+5jtVpvyC2W#Kg0;4Fkh?dJbd^~^%liHjP{tfs^%9GYmKw! zE%?Ure-De%0{(fdrOGKxNB5!SgxH%I{Su(Faa1Io6)TYO4q2l-W={~+W+P)on}dKa zJG{}_46!@Bx5rf1Y+0ugY@3mGb}%Afp9d~hmw6$q%a2*DG+cx}7vMf}7AYqE@7dkz zr!|snJb>Q0`Vly$9WZVmIWlFxn4-9V)r!hct2_3foX9od_A4()@`6XsPkPNDL8vkA zJ|1CEG`kj1ptdb7K+dp^G(vFYEzt(EX^!JEDD(lS{X*%8=jk>+q6`x;vgE}UsVQyA@3aQ`T| zNP7`R5hm7QELq=;nfn#3O#}Da5#!MBKRI4IC1E;ke!P16Yd+27^Q|ndS^ftCAK{Xj zrq$w2IjEDlE+>?@#JH9O;fc~cM0Kb5sYkxD-J^XoXM$49KaAap1&2t_LX72W@7E-B z%9#cCv$sr*?$_|yzH=rD0uZvKJ#ET4_sQwFqHLQRpFF~O?-S-kRT2?t@DGE%&Y2)? za)Moh;wk3bZ4WapjF+3m9$(rtu#qB}?DOP7kd+>x%osoX$?7m@@fjbq`AjB7H+YZ! zJj%)Wxs}|%79IyNtS`g;bW{M8jk5itb*!u7<%QeJY_s9pvRVAX5PXh4XB;@yws+Bj`*#yN`Mw9Ph^~n1X3EIL10k9`H{i+I z0KCUMvpKs{j7{AG_64?$h}B{)Swo5h zc*4`GPmjczQ(*7Z}D+aC@Ha2f#P~AQ1A*L z?JPjR(xQ1C^`J=I_-^;>%Mg~rSm))lpQVY>Z`JQo_L4*;3J>(Xpp-l`7tWM|GHmL? zD4%dpZUjCsoY+B5WVOhwcr(5@BzKA@;4z{b7zv7(m(Pb+U}+eAL{2Ojri7X$X^+b2}gq(DX zCc`9vo||laiJK6{uZfl*UJO#Wpc}xIQoWH@5w+8At}F~vs4Ny>2zz7~uhdtyNLEwi zyqu^W(L9t(pvNwK^>YbFC5;9p2$Rs03X|f5mu{ykIe6$Me_m&^7E!^as~cs<6&c|El*)!Y0fk|~til|p$~3&*0!e9Jm3HzxyEHC?8# zDk}RlCV2)!OvG&nH$fnu@T2}4m7zZ3#g4`pGIJ4KhnRywd&t_ZsDZv(>r;mCxm|w;oz55eep zf3*$6Qj}MHq0n_V{)Wr**SecNCqQnRPNruJ|J-dlUgkbM+|~x{K?=0Sy$|vd68v94 zk#{_xQG~9p{s#LMZg|w(5Nef{x&IwR;w~aWaGL(l3baDqhTj!kDqQPndI8f)!nI+j zz{^WfZ-E0OUZiTZ=bp=XjM=})HDHP|;4(o+>eklG;ltk>o^m$D8xQ2asp2XvhK8(! zm}Os0#3d5=tTlMo`-sebmk%8-chm&PMa5On)ba_#6QLNry%A(ljNA|}r88j*t4eVh0%MnL z_TR0SK?|G|w;G&ruOXnKo12`Pff#D2O*kcqLf^p-o|r)$Kks2L6-x?8OO%ZDQ>?-; zi^vHOuba0vWtdn7J9H*DC(3&~C~)f$lg~bXB*GMvZJpQ|3axN?d!iK|Vke-~!*8xP zfh63sdTpPtVXndKP*pF4<~VUIeyl7-QJ$DQ34bXs|1|_PKm4_Ch6h>X7Ev`wS~rXx zp_?Dgu~c`EZ^wXC3gQdYjri)p49yiV6smyN8zjFE2osi=VGrba&d3cH$CszjsI_>F z;$^t8OZ=^_Qi?A4{(;4CJ}k_URaR({ldF$h@5e_Ar_)nG0&a&6WVsG5b~gtB(C2y# zI0iN*sl>;kB}OVmH;SbO=-haG)kH5e6Fc=BX8(StXa(Vxd-v$ z%Lf%n#Y_dn9>K28`%z{bRpzY7T(#5`*Mk>v<2tizm+0D*_4-P!F~nb6 z>isd$6^NfLk~i7jo;{2&on2ksJVA1I=j zoSps+r^Gd#`$QXhQ@`(>90HE6#?`2%kALnZ6#lXP;X3%cSt-|>?BjTZ(Ek+hbsxRg zBK}+Il^7586rvpO%71FS&Pg1+dPjgru~X!NNHB-5X5=_`kIqw(Q3QH7=S`KX_8v`I znb$Yb(k*}qS#yWl-!>}{hXu$OJb&R&DE_jD+wxi(2yCS%A3FXqKC?LY9kzK}Qn@o9 zm5d7&QqwEa<+pc#c}D&Yk5fAFU0kA;Mehjxo3O#xY3Ci0n6|cCugfH>%ZU@xW$euF z8CE=V40CX1tSXX05&DXc3)FD<6`2!%v_($}-8cIhzB8_m6k;k)b2JuPZkG%auDd+L z==`w>yWwQ!CBDEJ5{X8MbqYZ_A;DbYMxI}8VvanVzB{|?%}ymbBogRuGG<6C*I#AX zxv!1jOe@F;T0?t$F*2imu5ov^r9w6mh*vyQ=^0iBU}OZSD($4ZQXFb0aB(qhr^zjZ znOnTLSBqvzF^qtV%LsgQ6c63as_RF;=crg`U5ADsBg@9B_SZ+hp!pc zPZ|6sU5V%4w)aIXD9&zRO^$%(K#pG49;LYsCc^Yc1Id}doRmJqP*EJ)9- ze54?@4JorF^CQKe#0-S#va3ujM!-o)55c_)*2f_vg?X01LYNn;*0+7LSd6{>Q_g#ty6=NTmX4s+u%SQ<_w@~GtD z)BeZM*&dp_Obxa99PI=Op4L&t4&xR>dDkIkO3sLrmx_AvxxTw>&LoYDf_{;G=|*vV zyUYT9>e%G%kk!Ryv4DY*ZB7WH5vWd2Oyh`d^z?_mrZ^tVa88uaMwyLr0%JLvAmy)v zf>Suvree{~3|^-CRSBRWZjhYLpd3wKA(0shqaYWg;|S}$>x5F|T?=~6lsoYzVfL)= zFfQ@dme9=H(HKDA=NSr49H8O0Vk{o>iB7zUlhUvuGSW*O$hj8{vlves{nF(NIW^pC z9(>+RN+4cp+jwN~j~S*~rnyjZImD6&35&nbin)wh5b!!cOFfFG3oxMTX*=G&u9@)P z^CD>e-G1n$cK5sE#TonMv|8uon&V#IO*H!fx}wop-CUH$j6>52c=ZpAmG zmkO24Bk_M6F&A(z_zeGdr%V$KH?kBm_JVw@@6tkMaa0AY+x}56-h-(~9I$x*mQ)C~%= zA{%_-t(;k1hjm~dfOC#UfJY^$+9aG<6i#lD-c#a;N<|`|RDvH*XCJP9f5Ra2vqV|s zQIU|hWCFHIDp>WI@(tp%NUBL`$s!TrDk_l9#W&<$Y|GN&OA*0ff|Z8Cr>wn>Zy6lg z&Y&R4rZP46e~xq*BK#B)82s{EzOTJuvguU@Npl^UzL53#+LM;`6fFkLWcSs79ecF3&??8&1$I{`jH)VljkCm* zb;P|ZKI8!f(Q1hjQX2N7AipOT=4{5ng`)Ax6g_LT$J{l_pg{6>rS}2>@J0 z*ySH_WVc!=HqvxkfJ&V*wdqdBZl;-pK|Pu*rxGaBS}qnO$pBas=+?ySZ^v~EFLNc6 z5>=th*kG_ww-J`*KX#XQaYpsVd;@*Ajxcldkx`4snyQm~OtpP8i13*Mdy2-{P1|gI z{3y#$A|GrrC6CLaNCo$qNdh~oRa8$;)LGH;k*|pEEO@PbmKbH2JEHebC^%EaI1&e) zH5D8P|7O=Yab0Y5Kw$lPB`cZEEyMJ1=~73Fe*x1ucu11O0cT>DN0sy8r&?kF>AalV z*YnHFEL4{@=B6_;yHO-xhDgrMaHU_i%{(lwU$|$9CavD0A{d2OBekT|0C{RD z8P~8pnV{+rj%HK*QOh|W<{f=0Q^1aSz007Bfp7nY*KP^kg1eIRgfJ=L1x2em#Rayj z@g&|?zwl*r+eCJIjjG*V8}Eb;6LUWp%v+`2(wYjdmp$cmm*FCv-`}Dp47DGuHrYF2 z>PS!J0|`8dQZ)WCM!Z4-H$#>V3Mz|8LnBa!2lHM;y1=hnz`7#KBA>6-=DcRZFXs>K zr>gI4r_1`KUr+~Hsp$%3HesHjyI>$7QG7~7?CgEE#a5s9?^lERQ^5wSX%8u`rmO4W z-;M-)Pl%71yNDhC&DZk{xn@WG_a{+qsdAb!OGyB-oU6MJ!6}cJKE7i(;JWv1t7QnA zQbD>&AO|{?B=P)Q=qYkuLRzQ>r&lB382yvk+=F5*^?93nRT<2+u^)0^`*GRB8~+bJE;D4=v^pvqMod9Y0ar&8sV+@p5C>>c2@f59sV2{xEYKn-yLP$pH%O$bAwjfU1c z%`2>fM{EpyUm@*GeuOQb6B9P+-M|~m{oK_H;&eHK@;>q=i7`oS`O}}~h{T`Go*q2P z6GLMLeK>-*{4KI+1{*=)4C~u{-EK=*ku%ar_S{q$tDm2LBf@6e&LR1XnfOECOxPDd zxI%(P%^4YPoD(tQ;wNW>Fh;;vSihTfsc8Csb4vcbp1#%RGtq z?|*I6VWR$0ph?=sGY7gUY@)y)UR~*18jEVUPqjL=KOxM5B-IlU9REw_N-iS_2fLMj8VUcrYM$}fn+#&SLLbdQ4M0uC%P!ExENu5@O7 zbB)L`!TAe0X=dqC^Gx*2j%vMK54jUz}w-k&`V5G0@tMu^+^W85(1VG{8 z(C;LKcFU>|YflR#wBeb~NM9Uw4LgF8?jpCbOwLHKM7_HsYj2~!eb8zQwMBc?WKD7x z5{Gexmdu4SlOX`>Xh#se_SS&PzwXDM##V5d;6Yd`EJVDJD&~8&q6TX+5InRNf1{RL zEl>8qAMh5+49@d)7%oLS8RTQPB=r~RdVI|T6@Fstk5mI;qTYJ^9QeTw1siM=U^4Yyaf>r%SpLl<;mPrabUs| z1cxB0oA7z!-#KwqJpKy{?REC0tdYN)e*IUF#ojw=b;5cmgj_6zpigLBXqO_>a32HZ~wsf0q~5_t{ZoGUz}(;A*ni>}lf9zvyot)9r2f6u#fenJ;dRKuX7M-w8ro@2N$cdvYs(=M=*~rSf=H1kATK_@f5RAm zyt}l{FJQZjfjsXo)|_O`hsZj8mSN&CQ^52bq#_?UjKWjaC)fG6wz5YByZF)osGR=;p~nweVih_fPiif)nEB3YY46& z4<@LWVyiURwASHX7%*Cm79pLMvuZ;pmxn1W0xlGLP#x456)&-_zn%zmW+)86a#P@H zBt^W(iiB*FOg<@8$<_<9OoW5FbG_B7KodhWah9G?BE36-|262tb3YC$9Gwi;HhaLw zgL2KoJY@pV_hC>E!}z&p;&fSB1gplmI4j+>=A!uLHEwZ74T>+$LSR^>fT~~LrrkxO zR6?(jljnbC=1(E6rrp6*f;a1oB&8U()Ui_3#TGfd?e9FYQ%!mRH!sE{p*2S6>9a+ zkEcFHu&3>B4qUuVe6AxE@fg`?B+P`d)@tJ%DcHQpgZCcv&hf4;=tEZwp_E&@@vm4Z zMOoK8y&_JhPr~%iPyWU1w!>V6c6&A-7kKOz!>*JC(WkOq!v!|+yFEae)z{kX`{xVi z-+TJx`8MwJ9lB;W2n5I@r!m)rPY@qWqD)y1UA5JccF6De(-|e0^kOPaXc`+lYU~fp zgszr_%5`fbP9w4I2{y>uad+~+-X@6BT4X4}Hp9Ggmk+62&le~H#HE7lBqd7M=eahmngG4axg=RJ&g+gty z{~4Ii8q2Dz`aeZ#eT*(VQPf&kh-h5RL2D}#%PzjSymI*Q@J{0_l$nfK5Ic6j0cxMI zSrLqKa|b`t7AT4^5KRW1d>tE?{7!LehRr#+VayTpUSYiCR9&S?af4e6gqSv@@trUw zX+}G${Xc0x_}`5jV>8^J%g89$W2tb!WWX>j&4e?>+{ zjf60f@z-0I$RI)VoG$E{H+7NGP*QmUMoz$7Kh*upf?2IgPmUJ)v9R@4Drg!L$>c~F zg}X$RVCZ_-f1uq=(iU^rb%CnlInsDEoO@RXwF>LRO~7BmOyJ26D*QXYBlbvtnclIb zrn*sE;sJn&;}y9SPLNc1#c`#X#%taO7^cU@q)~izC$jY@!1}B2CTKKedoPS+*^6kO z7Z30`k1Vr4)ZU{a*#4@>vBybRI&7`j$6U&h4)A*Q(^rrtinsLokb6JkSS&yteTf7@ z$6DGEX!zkgnK%?2kNc#)+8wqBPp-uUkfuqNqg{+YUZ6H5#v11CNwtaRFf&XuUQcx8 zca#TRTp+~XV2BkRJG=jm_2)8_XNJ<9t0j5N>eX4{=nB|b0-oY zKV$Zz)4fXD$ms<>)A!I?iqhtMn=XK3t4Y{PVSi2!a6Ob}ADOt(E4%IoTQt;W4v;}5 z4H~Y60eql0QaE~+H-F)9L)l)z=}oDq&}wN#N5Nz1?vEyp4;$D9UcE3ljbC_4^1+{7 zPkbH4VPWdNm!G-G0w9O7AMImoP?2?N$o{fD`SE-_u(qk7d8O9HWin`=>ANw&?$R%Q zd3+H*ZaC9_)4Uh6bUrEE^sCSza()C1u($x_kp7pC;O{av^Ktp7FVI_QH->PV8ryoB z&9DM>xnZHb3AtC@^0>R4%%rsgMuQc^yyz%W*1TQ!^FwCkk>My|Dzs_E;z z;9n_<2IjK8x*YYUxpo;c5ZFI;ddz^lE_-Gsr>mun1j!OtHR!iu)&!?~y$YkeIEQf8 zqX@Y1$ezyS`Cbq)A~>o>g6p5PI07oaPg-*)4}s!`lYcRC64435a8sd6YD2_u^P5$) zun%ly3S0;&b;v?kYp})bKHC(X_qN|He~Ji*s_c?Ke82Zdd?rS@nt#=6-AyA(l~4b? z?dIDL6*U#=sHmDiPI8-Fu-X(iV9#*Z-VRJqOXqm8j=cz8w}0G&wQ;Q`VHG|-cC!gj zQakO0J$&re^dW#p7slK%>RhuEn!}7xF%llz|Do%bZ8Oo8^DWSiH_wKcB1|iFXgF=K z*)(tvm(-3iP>H~HwJyn>6VXFm z;e!J;vLnYniFeDo*fjohhPYIW7&npQfspQo(FB8{3Q*&m2YU_=*9&)e{`~oKa&q3U zvQjB4kSpW%uq_l=R?x2hv_m=YlC{nURa@eAKFzoss*a9gutL3nxkmRW7H4SgGM4&p zkoftPd*CiV{~#`^kP-?oc)1sJzkXesB8?8GF>Ki$rxGqjAVIc=k~!Z%{{xo$A8PjH zTIhe$>_2t-h$~nJgRiYk1$@Sa(!a}g;;5RXPw%Wl+Pa?gz8zAn zTx5_Go5r)8aGHLNY#$*0d~`d&=JMFx{<4>M+kaE$Z~!sSEsO`+N8S6|XNL9D$W@V) zGjyKnQ9eX%(^UcQ237rV`k;(k`wO@_hham)q;0%GxCq>+u)dW5h7<-VCnKhwK&9?k zSS6Ks8N2q!gC5VH(s|~LjVzsTuY(F4d04p8a$n9BvX;>!9@J>eH|GY39L73r#f3h4 zbe$M|&Wb+;K&ekT>`$|Gn1~^>uDHu`#?aEe<#OLuxy2g(;uPNf8yWNypSKJ_$E~XN ziO}croeQ+61q_|%mJoS={1Nh5LP!{(=u#k>(<6ry9=8n8zhBpv}O-C6Fz=zb`J=x ztyD%|v@Y-3sRo}m-VgkXivQ=S`yzP1QT{)_r1%^+qb@gHXT`Q*KCf=Dl(n5W(x+dB zM3ErzZ(a`QFC)=XXC?(MwKj)luy_awC8%{w%)p7#N80N+OtkZj{Sb*w(#S=`?-|SE z!>=7nON-KFI>W&}CemY@5Y$?&fXq_MaesE{1mWyVQcj}_+p83GfAlb^U1p&VbY_WS zwlRf@`TyQnWFJCZxKv)b!0gIM7Vw8Mn2hLyHE1``QL-KpKN~90-DHrwm zUu*S>(O;4M19>vF$%W`0ef7(1&ToTlrCLVm=@lr7^)IYoCiU@u#9qvT{oVK4pqn@lIUbbAvrpI#ut-UU7FLsvQ6h5OzxZm3j`QB0Qw1Q(Dy=c?jlCajBZ*GPE*o6ur zAW4GFvq(=Y>}#$@(is-%%zysH#Jy*tgJW} z3%rDYBV{?aY3A|mf7}Qq+rY~I(PaErb@a;muXpi3=Zm!{uDXM+sV8pZPfc`7oq8;0 zPO2FwtF3gWVK&PUJH2;*A@+6WW7E6qc}{OTXQb+vaVP*@6@q zKD&6%^|lfM$#EQ~lx^#?@gs%tN&}csVz8_-BEKEhvp!kCd(q|>jjyPVaNK4nlue3x z90;Y7r@^}Usl>N}1gItJ{ni)MEi_|CcO{xX-?gq!5GvC@J7vMdp-PJaGECYnPU!oF zTj`)GIS26V<;%YH(z1Em?4P9$jm(jv_)pHch9hd=i(x9QRwLnr^f=w*MlXF_C3fCm zDG}S3#Q7+V0{Q6!?vTyoq}%8_ZoJ5nEbAbsf^x!L#i2cvEmNMx-z0yuLa7~Jgpf9m zlB_0L$G1V6p}MgW?S}YkUU8ZHqs)?JGa={8aYH-Kjg>+7(ZpKVUwv<28E-$9;)hvR zTYMU`;q;d{$84OMjGBQRaqQh91*p9Kt8g5>=C-%@G**XeBQODqf0&l7AuZ z&QK8Zur|ogQkRVzscwkllM!@Uf5)TE{m5!zYR9kfF>YIZhaAXZ*=I~T-~31ezC9ML zZt=lQsj%%nY(-44H1_N|lcw936+13?d9TbnjIzk?vHUIy$o;uLCV-}~{Y7-4x}t+? zhQsrxXoy$DQ})5h#b9QUR!DZ0a|X+p2^i^tUu1gY^T+O}MV}ZQ=L5XYwl=n7)`|OJ z0;vzHxdfq54Cm{`NLvWPz#_@z>d-|N^_}EZ>kZ~i>Z|1$>Yi_JHm z$Dn5oVn_Wte5FhkA9m-W4Qs|iuv!uPe_wjl`cv+D(7!W*NC>5hhKiR?7XTfORS%x!JP=&cbDDLlq>RISD^m_21gL@} zglNwo=6967v#YR{rN)yLz?Cd_g5~+kEF;brX8*n&Jh(D8sSrUj1Uwipo2_uinh?I0 zE!TSFkPv5O_~gaV`b#tF`=tA#{C&US!Xn+OZZko;#wTlDeHjaLo-7Faz(jvZ4Gtzc z{vh8&p)IteUZPeV6{nE;NGM(8^xi8RS4}o{P611u?fVD(8fS{HcDM3^deC8oxYZVe zbG@|`-MiAi?o7G&fq8hg-m@zm?~hVMf;Dqmfn}-fLD?3_aBw~~28)hC^nl4pcw|LK zVEUh2dby{4?SV)!^6%D3Pnd`wzI5eD5Q7?rTJ^o?q;j?7WT;3(Wls#?lvzrz{3U>m z;@$E@rdnW%u);E)T%VPUFc;n*Yjn00*I>z|#BlWM`ikCKUb4On*5!bTn~}+dbufVd+T24i0}U5>tPrPGq79C?K(3cs(p zImWSKcZpK&56mmBj|f4OrnhFRYK5`-O3}hbTL>bEgmA@XsfHR-K@6*Db=xi4Vb^ zmBK}1nP5g_`^!w|d68LEMEifv)c-p=bpNB4`LA@)7}yioVD)!%LzZko$**_o1dh)$ zLVI}yf$tB2j+@LYu4X`2;bj)8TL>b-34qZ5F zsk*`zILGSwz5>l^vfcxWr#w3r7ljOxr)k@p_m>RbamC^!j3WE``|~*^ASgO4*hO6^ z@irE+*?`5QRZRd$n9Ps*Nh2$e3^`Vx=-FrA!a@$EQS8?qo@7K96pQ84?Nja-h&$0j zG%ylImbez8`pcg^dUlaVs~Wa*l&IB~tJpqcQYYW%*_fAm`enAt8yD?nWUAhjy|Fwa zG#LfhV>PiBWNIhupMA>Xd{Z#Bk|^Cp)>qw4!LMGwl{)8f7v1#Jc`mlZTnL877!wix zkLTx(FzFLlYfTK!1er5F@S0DKMp{Jo(iQykLA07F_WK+1UY1=A>*?f@E-M8p3)^sV z;E{~y6;ZkNWBL4RQPhK@^-?`1@z?e!Tohnm1n*h@u1i&3VIg7kXb!f5lRf|+#GcnE z*K=(x;eaY_0Fd2|6MxT>CfAtajih;$aqld4wy` zxuN_Teqsl=ySs+{q6C|yI42@O7x66HLedtIfT3sW zu6{*8ELIG^a!f92S@XwyLvL4ZVe(LoymV9j-2yvsN~p&;Dcxo~JO5rlBzs8+(3>tH zcaOZ&7UH~D@i***iGp|1CgWzf-9!Y|9HXkGCW}gV(yHxF*GdUznGig?gaz7*H)q|G z4S7ke9yed4GsZd(bzW-XX4L%tkkE9#YsIRNz1oA`->6T$`Lk3}o|^V1L(5 z_D+C8y7?RaC8hrp5f1JdZ(mLRXLadiZ~s|DVY(1-w|3WH>q9@Yk3NXNpV`( zDF5=&5uB?s2$GKKj_CNp{oAGavb3OLQI_sMB9 zZseXU>s_Q~aWFzzv)Er2YAxYXzz>)yoes1qtj)wDcn(TaCJZ^v z9cOYu7o==8U|xAuaD1mS&0tqNV|f}=Kmf&#;B#fLDaRn1T;UP&CEDEJkSJL#m{As(fAJR|C&37)wE z>ui7Nc60bRpja;9_#sXl(~{rQL}>al3Thl6|GX`zxjwM=jQx7^cdZ05(kVHB5V;=g z$YY1W&o}vO_M$`#+MNG1xQr5lcBm+y|MctsSJZd*{KrM`pLe{o5|?=9U6Tf$$W>fg z`qN|qhW*)4H9G$3jHqs3=>i>s_Z}Guz@nk>J2e1}Wwp&Eqv|F2pwR0RPLW>SO*}Fk z2`2|(&EGw7RR_5k7?V1B4NY9C^kH%$gamn3BcWp0L65+&J~cV&1MdFN`U0E9>0mjo zT<`oY+SCzpf^+$o7(d9v@Y%<}Wy`Q7QcIxhu^1L2gaV+i;*}573Gl)FJDDrPU=zf9 z2$AlXwv6C%G*U(ujt@e1DzK8HZjMeixb&QwV!kyiu(hKQ@`u5#P_ar#0Q=O`)i+}b zPf>5mMHN%?%eBb-g! zn>;#z-_?XeTSL?ZF@E#uUoY^4#0iaAe=cn%>|!nP_ws8-4Hg#^V7|9Zq-0#gLw96k zp+e4cmphqlVGv&Dq%!`<3FA{!_?L&%%Oh-M9MYli+3C%4Kq%FN`??1pe4TK>87LEH za_Yj6tky>Ev`94}E2=D@Pv{2f80n4)?N>?Cm0duVck)_ZLJm_fOtBN7y2dhi8*iY<%(b` z;oKxT@Bf*5L_+@0LksM0GiV++KsD0_w!Q6TYlD4w6^4NW7a{cG%G5PlpM#0ZX|g_9 znvR>Q*Wj3~xz35s?Etq|qWr&3I4WVOV@Oj1sq*3wrE%YP;+JaR#h)TZL?Ck+2qcS} zn}0as;W7TA$Cy%i(zP2x_j4&BjAnX&U&+|pyUdmhH*!E*knY&0^?y&7|6s(c<_ zbwU_=^EAybm2YWXe%AM>2yL3AAL~kSZ1kp^DnEP^+zk8F5fI=vYx6;bE7dsHnChfP z832~kfDjzxoD{GPENcdOzRlAXsm~|KQGcoL7KjcdwN-~?tM704qYA^Uq9O;Cjf-@I<&lci`+8doFx#e4;7FN991K?gf~vDdLUcnUhQu8t zJrtc$#uCz!Su04^%gezbDb$TzH-mh#UovsRcP9U2sdaz#^wh8(k;{RlV?vex1O7|j zpp4P@(Yz5h!h((t3n%S#IwREspyUYbx83F8CIr=;z&Pohl1+ej#$QZ?Gpz`f#11&& z#IrM(H9po@p~9u`@l&Ue$MjX>v+vF*j&^h z>&mHYA?$qZ6+It2dm~wU-KetvV^9epdvn0CZQc@p-v8@6U?`jIC&os-Gp6Z7wy#Rt znFH?QmsU;xS0D9XgXY_LU-s&MQ+7&IH2XPI?( zr)E?cD+Ld)YtIRFZf4_yf{x>-X4&8wf%3rAg*at@BN!^Kd99aaP1n1WbYlfy@y~XC zPLe-2@yKfH>Y|&)5#eEXizIahOcX8;fh|_x1T_p`P03b6FV)v!Z~f~KY*cD-G$}qz zF$V`0s6%s7Rh5LP;^$MiKRWPmh|$r2t`A>=R5d3~+{q$PYBA3}raF~N=Tl}?3)4cq z|9amiX~F?X>>3nu!@AQ3sp8$A(PHf!MHggK{t5^QeHg{4Vr4q;xv9oMcBc^zFS!nv zRdcYQXNyZIAk*JA4aGu-Q`Nzj_At!?9fg|&V=05GJAUg6-%Qq*S7X5Oi`0mQ|I#%y z`1EKcRBd7o7w_E1cg>afu6-hnswm1``ZBb4u^5^;8W~cp z0=D5))Cf}Sv3;u2H5q=*r=X_Q)26c0ZKcv|5l=q>mP**dv=i&aqvDWqPt5!a!Uu#G zMWnxt%Er=V;v`N{**s!yBq+^NlAs=fit&j-)f>&`vL;a`^+!iWC3&Hg;XAwM_binN zS6(V!NjY1x)P2S^d?JoIEUw*ydJ-j8Nj|bIF&1T59yVcZzkl{VI{Va*hTQ4Z%Q`Nd zkdCMT`X6Rp7#fR+@s1K?&I{a4Fu|9YLqs$OU%xedd7Af6tE^GuH1hGl1BVUMOh_|) z%yHP>-QB#dV};oGdJ@pS9P3^a^AY6QH>S){HBt99sH&(0WqTv6hZ!sPFy9FU89dtx zT}CQo$xJt&wSK+_GG8Pkx!)&4JD(i^w`(-BT)Y7MDPXCLH2uwmE|`}l ztg5(D+~a}hgSUe=t^D>*$cDTO&3MBZLM+shMJMyGpJ<^sqQZ-h9ZB1nMwqyF-4`uL zekC8ebANtgNa$u6KaKl-Y3#+HziaY)v#58yFTYWU+ zHxQ3MCR|Qf=j@6%J~iucbx&PQ{K(&fw>S9HqK) zJgZ?y{<|0arzN!P?uX;MCcz36O-3 zFwRi;Rx}M}icqxb;<~iWHk;5(|0ki_dz6x@s*tr_G_e@fPn+z|7jvCk=lRMS{_lA8 z=uvYgsnXf>&E}^pB$vEMW4llG@_8iBwX3{xc%G4AE! z!9ejE(e$wVqDs|c804#7HH1A*zh7&C)0CpF#Myy9!uu7Fz>;fLlH0PhFrZ?>hJRR! ze%SZdcMYLO6YhcWHHo%remJP`Uq*lB5oy0${;*@l@$@rF8cXMbhq8f{>bPuL$gDzb zxl81c-O3VABD}j@^E9&Jt{e5i0qo#4~glYeoGPyf7? zb7r{F0}(*z7xG@bR+n}xP1BX}%Xc^NS10e?>P-v1Aip9Zsj=H7-!?5%>MGa{h;0Aa(kGdia6%|h7lEmts#h!Ig)N80 z*5@HfDqWQ{rx6o1q~=Qbc3`aO16%%w1ZRi}t-zTjK;yU_Fkj0yUo+o-mOYgpDZm{*CjM#6d;H zlxOxnV*t3i93vV@w1^dTy|-$PoM`JpN=+eRK!8S7PbYNwnEdc?v&1UwQ=9xvtD0I8 zS|@ApsvZoVeeC!l7A>AKIbfUp3qZ|Xg;aoKqN5!?R_L)lscP;f*G1h=9ltlnwiDlz z%$?5B>FS155(^!|$e{UML@&&S*NypJHzMZ^ntG=-N)15kZ$ zHkUm`th@%@@UWOV79g7sr0IJ|ScrwJ-yy`|ydRD*v2G2mUOQdEjGZG?P3UsCcsK~B ziTc^4ynfTHfbf zVWJlF!Ph8Q7Z+z)aD{}p13R)$y6@^3szEoPmVuUV3fj-CBDJ7)z}R4NQUflk+#1AB z12romkU+Tp9W2PS^eO3)lW*0{Us_GLYC5zvQ3J)3FG*6 zRv8aRe4+E@&q6QD#2jb3dtP{^Hirp&bz|B)pyY;hM zBdosJJ~xu6r0k0YLupQvUeTbyJlrquGk2W;`|wuaMhf zj4j&V=6G}gnx@nd$qz0*{agq$Vxg+Aw66s8P+-(j0=^YY&ZkM(kYc7j%PV6d*$48! zh_E-1`o_x27%=1pPN^Q%)9A=xQQwR5!QV0R_v zP_S?-M0d+)#^E*i=Eq53o(W<@C(96X-DGrE?_Y}IKOKlP8IBzOf#H*u({t^?9X4PD zZD)%9lC7Hau?m*RYV4Rj{fP{ppmGVunfKfqADk#06zl)`_)U{I@zu$>9a`ohzj+y( zCcX;=+VddYBsGG6Qd&GBaG>ei{kA#ifyA+Ek;Ex1Q5?(MXO)$mvA$HHC z5A<}~5rRQqsskHv+G9!W*()$fzh_e(v{+b?C@U{gJqb&4;zoD5H(qZ`4N73{vrVt#g|WrIE%ITgs}cuJfTi z0lz@8g!8mI{cGkzw}UpoDaa>NM9iC8so&dD_X@Wmtlxza>{pQ>1oatK4K=w~WF1fN zK6hmb+vW-IdQaBr`NZSH{k?Z@aJ`>=#OQ953r0qVuX?!gY(DR2Iyu#XKO*EPRrC&X zHOi&TvHd3Tg}6H!5H&XR$lh<}rvatlJ0M?O)j!H_ztJj@SM!Cml!5dB_F zMCfMNlc09S;=_T9Tn_v9i_HhVgY#Y$b#)ePkJ)T(y5CP*g0gUYy7*pqB`!+7pRX4E zy4e28QDdvd<862*>xc329_*#RIK%k@NaQ_>DE&Q_&p*bwK3)?C37&exz`|psx*oD` zL~EY!5m(80D;CywHLQnOkj#n@3RbN}qOi8%nH#th*48=BwoRdRwj&#O-Qy7vnJNYt zuRZToOiwE{-^}T-*+NN)?+0ojUe{By&0CF2nQ4XXLeH_jzsk!|xxX-8oR)PaCo#Kg zYVnNNKIz6(3cEoO5C5rfO|2|mSuy|T&n3(V$@2RmZ~MffivhBML}ihK0s;m`Mu&+N zH=PSbLG2btn%9q877IRH)SGGAEqFMo69aWu#asT`>h^b0RoAU|19s=z%cbtd2P9sa z9oV?4whU+Q?3L$N1o51yym72|Z}Fze(U6EHxW!vwTD`}NeJlWVQ~CW}9V_=J^NHwBuSjO-OY#{r_Ye< zL+NHw!8NTKvfVghUwoMnZ7F>BFWF$GpaCu19j@<9xjv|e8|t30KA?$>v;t}t?_XL> z+sO{GzpVDGuTOyDZ`lijBMCevSvA5DhJ4w8@%upjbJLqZS(cnN_j-y`0#35t>#p7l z3@#6*jc(IxOd41DqW*q?&+cbdvrnPJ^D`)M<=hX$#x<1jzvk&*E~r(~z67_+z)!Z% zhO(G0K!=SKbUd;WfEcddyg5AqY>rMagA?yV&;}u0K*JyiSB#+qe1w(OUd9m>uFUKb z=~W8X_o0NHMPTlEaB8?iRJ633#7LnbdZGd+e|L0`1JrnFTL@vlFm%;0(~(0u##_ji zf!eSockBX1nqwD{iTZF|epbO>poQoQ!M6OY(Y7DvxTq=ht7EV7#kp`NMD(;Bc=vYm zZQ1wE<$eIxw_oyZEhfXZ_5EJ9Cr=0l*+-titCUSucM9r)_8{=gXhul&*qBS0)3&6K zAz`b_S!oL+w>CCj2I z*?CZCM8`~1wx+fN-k?%DL=$hKC*P@KV9ng8VvXu7{%B)iZ4(mA$!57@G+I?Tx%ao$ zm}4W$Ei{^vUb)8hY2i zcPg7Z+TFx)D*orcVebUBCmKH)^K`Y`w7&2da2hTpp{bA zzRR#)XGsO#)IS;MI}Gnz=&spUSw8F7uF-d`?>6$wgc2WIALh+fqsJ!M*V$5izPXmz zax=1?3Hv~&VZRsIsCp_kK`BH*$I2L^3j0EEmq-~!m>JDdDDF&;lHV+Lto$ce-9awa zX3^V({dTd1;9`{c9108~UgJ7A-LTYjzP<+OY ztfB2Y4&-Pq27Ip2fAVIZ07{}j->+D>tjkZ#}{gFaF}_tI9+k%JeC*(y)pHz zJ&PU`E9ukGf$ssv-eLjZs9u|V5CjI**2a$#1qIEMA(~`Bi7IqM3f+=^J?SPS587z+ z#!`6b^X(rbAIG1M;5?=FZKo$KjtqY z2z(5}L~_z|1k>AY>NdOH$DQBxCAfIp@3v`c)jF4^TMwm*qzrlYk7?em7=1xgm|<{YwN9*^!?tY$-&sL-^NueI#HQ&P z3#vM$j`%ce@=6DNr5~A}t)fS{<@lPQnybnDWxl&IO_l+u)Yk2>Yy5(7Kt69#mAR<; z_hYNTXb$I6`WE%DKyo_25n|H;mo7$W!Yu6Dx%YN(_cpuA*_}4aNu^0VbSWUO zCu*dEChs}&fp-t6mZ@ywSQu@ zpJS`iW;Pc&q3rMuj`Bc61+(V~a9ctkkpRn|g*8GH46lsQm*~@wv8smca1gm&lomz_ z3*?+_p$li1?BTP&Giv!%b5@zfrerPZJTX4+^cm~%E{vQ&ZrCYBN_R2kR6%EvYg5g@ zm?_BJ0ss?i+?N)&C_RPz^i^kssvv;@kk^$cK?L0ByGfB}Ban#7_Re#-;n<3Hmf>(C z3v&tUhZqqOS4|)m%uk3-R>>*_!>Bql#~2@nSs!x>U_70u1-!VOQE%yo!1kvYHf3E- zRgA{U&C4m}sYZO~Q>wI=+NDkpwy>uQkfy>K9Zm*NS#M}L+0K*2co-XNu#N{}MPo(K z(+%5$I|tj788z4c@QO&$$PDHklt0i5#$#y1PGgL>=!zI%w`j{>pB!R6IaR;e!rc$0 z84Kl^6(6yi=wbke zq`DE8;A2fTizNlNCAL-+EaJQMteE3B9C)f9qS9OjT?&Dq1dfm8%F{OwMm{fFJ$p(i zQM~@%uJk<(_~-+y((S61okxEU!?OZt)Kf`kWMA@VB|beBYWmQ_y_@P|YP!dF zhq$-MJgBM|x`3sJ&#{|{A0rKl9`SztgVBV#m5EPVi66jCt$kr zNl3(;q2pT{cx=s>c?llW$-Z{RMEX9~mx?h}NnFyqFogM}So7^AGw$Emw8U^V@BXhe zJmR{s5lZGNk#Z~HFj!igec1QwE#LLwatAuJ(!X8u^`$jAut@pyW$VCWhON%1BC+I=0Eg&)xSm>m{9f2YCG8gsVDW@A;9X8J7S@CsU|qo(%_poq zxlgt51=|*i0CqpB zsHM$r#WznWi6ghKeF%Kt2PI6iNKsOhjts`D4W(_fmq`qWzsU*k-qIB4tM|dj@CJ(k z`0aV<_w9w_CTF6sUN77W*5>lT9ZJk zAHC^VCmOP5_*Q{^(l*dqyVY0DoFLIwNgke=$NMKo(Sw4L0jb;0Orf^yK9gvYgzPY;$ag+zt?aI=;H!d}=5`Ii|o+dQZxq-XOVydi9%@ z*q^r#+Ke1Q0>^1Yv?c4;BEi<$n$x^>8{;lrhRXXyllDz(l|xa>_k&g8i9Nz^jk08b3@Ds411WLOmr9_e}v zN1q*XQ*&lw52G0;2*O|o@P1jP8$4Raj9vb=2)oT_Q7)uA-e^tT8(=&s$eaES=T-AC z7~vf-{)$n3HYlU(F~!bzQjeperbc;XzRHh;`;JFDzY)6>00b~ zR;%Icc$?Ky(CrcJn?0DojWt&xRvfz8kBbkrC_bXSLhG;j6k8Y-UuJS7MwjGi z2Y~^1n4teIR6g+sI*S;z1Kz&zNw)85y?UNMoj#p)p7k-E6nfsB5^%X!hu|MxsHepE zos9#%x1SpSHynA>-?IN37y+qO)M~ON)%V!Jr8To;4F!VeK)0XU5OUZI18{2V@olAm z?vvus;EW$FWfE%6K)eDMEA)n7)n74=)ZaG?|^?i!%DyL*9R#idBG0tHGb4owK| zPH=a(;>F#9Q`}vGyX(#Ko_n5i-;ev#9wQlR?X~`M&fk2?QZ#`a78dS!H4(g71U>bO zSs}{B$)Zj+L{%%5`^A&Vru~!pcNH=kG85RrpvWzi!>z4YzPA<)-krf!wI`bHpx|xj z@}j>tT~ZsD=GH{5$|>~3KS_ZQ#u333kSVup9=^BYzZo&&XdOAaqPDf`+;8+t!Obrg zkSOw0C#~6ZPnBRdtHf5}hsjB(Flm2%urWU*;VdxC8b#pTR;pec7hgqL)VIht!ZVq= zh1)~X21?H*-^!4I$*|Ci$gU(GRPEq|WjxSxJR;v$3*4N6A7#qz zl&I(?{p0FZHg_H8?h>VkDz}j#z#&=wyW1B9*)(`Xn#%}$bxvCgoC{mJx?W@KdmKIx z_smPux}4MEFiW#|tM%621_#K;Pceu5kaWcdcvFx! zDND{rxpC~rlyGw)owxe0k5jxc`H;WW*-m;&Ux*3Bob(D}p3cVU?{UjsfqMqXcK1Z< zi4)o-&;Ds8H|3&!S*=z8U9QKS!-{J;JURb4a4XC58&jG8(%5uT?6^yxFc$Yx^79aw zev2MQFCK_$=9|Igtj}!>e&+RfT+uc{FQkxaCB+Tj+3d?s;CD*PP>B`9WGLs-PqeJ<j_uZRpq9Yek~Yhgn3?hCe2*t)OGIA>I-es9lH0PL=jxp|-#4C@>@v6b`uOG$G?t5q4B-bi# zmnV_r;_?Fc1+>5J+9o|d%GAR152fk#+Bu08wTb6F{cKW_X!R>)*EbyZlfT4XuGcdp z-iLo0Uwu&=mW~^?a>F_MeSF_$7>Y`uP&tLPV;>w2Ra^GCFwRUGH{UG3>r$`y|4`75 zrC!%PVL~FFfnSQ^>WNv`X8-y``wfCf7WQ897IlEKLx+mh2XMmZtK|M zvVK8>w0-2a?!?cDVpN%L?E0z;&UibNC7kh6bgOZ)D4Vt1rHRqVljAo;|u zZX=x318~2}5qkO8wPzrNzEDDibM>VQ2K0~}Fu@k=B%K@1kpDBExP0snVOBsl-{Es$yI};60ud~EI7eO$C zCiYYMCi*A>TGaFcM0sQpQnp=*+`5quA)AX=7M~kbM0%P%Up|yc%butBcaC3ldwXAmF6z=3 zKWjkdd;Xr>^mq(4e@j*ovI$~$60=4*WKdM&$j#wSZm1`QFE3V)n|s|K#YNen7EHo9 zAI3l(+_HKpvvkBZt}L1c^pS(T&m$wXxGw1#Pw*sHyU-;}Y-~6DMp2}~6+GQCo&vq@ znLu%ox>c3Zry7wpu*gh*xtz-X>^4hF4EqW*$o*7X6<;_gB8^E?LN!4PLjg3a>83kf zOzchMB@qTpk}D|9+ULA(e9ml_JeWZXEDPnrKzJE;&%d6h4$r*fAODJ2RH@V1}V z{Lxs8?i~?^E85|oTScwKB_3K4*E|d&`;^>1<;7X!pSgF92>-o1I{fT$eM}^F80$T= z$kd)?oM+p1y(-drDJ3j%UyA5VJUx7?-EJrvW&C{WD*fNVaX}kM^MNz}fA6MI8$H41 z4_7zO*s^vw#|>*JsH5&(4(VY zm`O=VTZ=Z8GY&Qpl;UK>CLYy6RBqe29?#cvWDK{f?x)DFOrw$0*N1a9ZE=ihvrkK3 zfAo6QLQaDAY%1Hs(QmkCqzSbPtwV2Ks0bR`u#=763pY5jE zi&P(@2r}Gt__I?$7yCuTB)x;|xa@4OjwZ=_&_(4w%Gy(%w%t-zv>vdOR}L61#dr4N zexz-@U%5IY0DfOtD_>sG4{eB@jt344IF2TINcSkt$y2(as)|}-ASZHs6cQ%) zvd^2gZngh0T5cl2M3DW>$N19~6T`~KM7F4vpB=sU=kdEcJ600*IGC9ydS4q@jXi7x zD7~LZSE6UbW^&~yP$>Pc?k@4Ue-v@ENMv{V3n#LrhQsA4j6?#5BL{C{*$wbUlHV!A zKus3>Di6fEY7Az9YTc9HnNWK-DW@%{A{k$50k5DVQoiY#PS}PXsg$ax3Wj&nqZ9x% zKY<$59Yx}AzBAKIDv*myyZ*0=?}u1dFHV_3p!N*#Y{moG`xn-err_{|9lr*d={%@4 zhby4IP`hrE(!ap;WywSani_ZFp1|Gr=JavzHHe2;LHAMA;3onD{ ze!5-&KuS26kso=0YS+tK=tH+ai11MOTAnpTw4H58AViplH8ki!#N%ed{cbdY__Oz+ z^50)-b%OrGH!<<+uGm3=d#onceIpKuSi)~%F^4(aZ_;L7OW-3qZG7KmuSz5 zT^4Mw(Auobk3BjGuVyRfmbZNO-&U-Aojn_96n{LR!yp%y+ZAEBWOnBK&0)lc4UJf$ zm}nF;@i11HtW$LSr_XrRGZ^eD2T_$Ok+D?jlNzyF4F`EF ztIT)r2?0NtJI;J?yB+DS9q)*cOA!P&@X(0P)>G#w5Zx@pz8M0iY?+Ryzi8gE^=UAl zo;H{~68FEp{M71@F?@I$CV%mp8gIslDK|8tjl{f$_no<)-}wV`OLGmK9&v96=8MvS zk>+-a*3A77Du_Qcaw;oyaaeSCcMCdnLp9ncjOJ&WJ_{uABM1EXv7l3K&_V>u0%o>* zzZd{quO@^}pDr_C*l>z3;qGW!aPd?6ly~PF@yWrRkUa6E3e4e%H~ZuuLFjl<OR_F(W^hpWqpI`J})(!D5?Y=rkZx==(U&ooD=)J6suRv-Xpkk4_O>aNgf{!-pSH z7P$>1ygmf;4*pqN@zPx1R__60pZts+TNfWe5s0Ky?NFsMkK${rPUlM19$JWmZ~wzr zMQ%iZrU8BrJ5bWcF_76ZqO|Gbjv%UB zQCF5By&zcu0u^h0 zW|;}hKsIHoRMx7&tJrR?K9Q$wPjP{8X{zctx2LfQL%eua=JA3Elf3fBA*z_t2juo3 zYg9MTi0U+I$M>g5V$y2E_A0i2 z`EhQX7A=AlK48H&Bq7U{L!W_GUK29w@J)dIryj8mrFTMRYlYcwU`=z9{r@uLLjN$! z`|Lm`1Dze0yUZtw5dl%;b9hU?I=xy5H)5wyzNuG6kF@NUiGd~)Qv}BvqTmDIlVvWG zbnMutFF9Gg!lx&DmkYdtDtw_Kt?of)4`C9ZgFdzMo2AnM+b9U`i?y*Juc_xnQFaxQ zeC8c*y5m^j-ejb_D_H%@7vGltSKL?d!Al{{VyT!jW2WPKFZZp{3qwmqz9?*l_DIoJ z4|cde=SS;T4If$?zfHCVH8vwnO-m#plm-(Y-ZG~QaL5v#P^OaAQ%J%kQ7+g>xaPu1 zWBM=eLj-Byn;9R2&gdsR!15nBKjW7Tle+iGf>p-6H_FS2bKnzO&nws2`djSvVb1m+ zV1au!O2_S(#`SJ={;?}ojuz!MpW~3H4eu9}JZMDMkj2_YIQEH?rU8_2{cPfRF6~ra zYL%bg)$zWGBPvMlvQ2>CYBO0z>0imO9;@PZYTwt^HX@tZRNDPJ=PwN$)Z4qsr=ba7 z-j^G)uMKZM|DG+$h)FVUpKJUliWMk$^*wGd5zS%s@rQV`D;BlnI7A^}byrjGFGEiH&WVHoS2G*6qD6u@kR#cG7Yx!b|~;Am!!yK7fNcp30Bj(f;rg)1DK~yY?}# z?`YHa9(=_{1cZe#an!f~Oe&3{#&zr)Ilk6>e}I4vPq8J86q3YylR~>?iP9T zuM}dTGub}9zrdp8!xw>D@t@r$l0&kaxzYbl7~V-2pa#+?e42yrApYs!*!^BaKw8`h zVGfsK*@%GR>`qqi+>&3~bn=^*3l?`hSubH|(5VFZ@{3_1htm{F2d2(Y=eKM2QGs8p zT@c2^&T+~ORIr7PgZ;=UMc+mFgLl@82fu2J3tB^{E&8MYS8-$Wwndtx{&bqFfKQ&D zIG4A`9=L=B`I=%PVf_6rylbGdvtso?KRm(;AsPfUq}*TKv=;P&;uz<;KfoU+s$<0r zV?(vyWO<0_w?kXQ_3DiKgK~K@FsEmF9WFC&H$t{lrFDKs)tLsc6I9{Q=58kKpb*at2(ArKPh&iyA!Ker&wu?b5 z`=@B19)<;1yv)4S^r3EMN%~fc@9SwJ9hVI&rTZ17JuCi6?^6G)$1MRMl>yElT5LO0%CsHcDN{nqpSL;L58zKx{c+8(*T z9iGqjV_Y{`<^1irSn`axfYtyikBhhMcL$@Ry-7StCS=krS-v3!Eaz%b{?#o^wB7uMS4E&9fn}rAneO0(gip9V=`}(JR#S z-QUHC7wk?N~MV!aD`A(^fEiwN^1uzm{pCj_op?@DG92R+B5H~SX7h}=+^ILN&poWIT z`HouX3I?O?&?<>*c2qqQM_Q?I%1E{_=(_gUxQCfvA7H|MxjS!b$ZyoDNzSZkeBCNc zv)94S+jhHuhNTo`&7MVla#Vazc@LGmGP>Rg1`dytYNd<**+O$*O1-}q9t~W+*xLwB z;lI06LM!)uGL-cCjn`H-gx>AD|LSJ*hf-HI2y3L@xMgQ}+-1}oB{v!dU2rAg`;gmB z)_vOZ>gKKzryg{g;rm?ko&A%B2H_eFf-0Mx*uweDG9IN=A8pA%mDGaJw^M0MdrX2z zDvxD~kne=T|7UhCX!~#Dm#v(I1%0#YVbJ2@SH=R{r<;b3K9iRVVn*cFyUp;sEvnZL z>#0IvW@I$;DB)caL(oRx9URo<!`e8}aN9Ol}1+h3!DZK$rr+(cJT=4D5aXuMS zxA1nfOx>|Yo}4uqBzF;h20dE=u35Lz&byzsolnS933IR8-!A(D8C6}(mMF8CuGIx!G*z^VQ*;+NrIw&lC}s_z{=k#buVwT`1fgHauqdi}U68Y1`gH+^hNOB<`oU z_hKS2Q9cp!ls{4$U1{F#IHwX%0e0H9QPl3ozP$Dw?_-u#>;akoY`B`OV8YdZ%(V~! zYAnc-d#2sE?&r}s5AJIDA&?5G zo!O-~2pVUqEhn18-H4AS0+F+m5_Aiyou1X^2?K3`wUfrBemx6@&=t|{mCapTX-g?0 z+HyZ0dhrzwRf*MeQhGX~WxC&(I0e^FaLQxEd_z=gzoJBjclZhZSrC(zhvzjMySr?O z){~8kpnl9OAG7b|-l1ALqf^qNtygPZdC2G`$|LN+6LkrFc~wltXi5ugO?rv3s8fDp z8DZkeEWqcP9!%h9I-r98peb(wSu7BdEw{$M@aiB{gizmi)m2Pvbs)lAg%FYrej^V6 z=7Kvngf1s9Vx?dzi#rS?HqMa7Z)C7x!;wQN8X_67RiE#5XoEq2&-&-O@C|~$N6@6p z9eayWv%7bnA)|kJgEw$Ovq3}GMvderRye?F!(CxU?q#Bd5IueD9959RNDyY*y%Bvg zg&H81swx%DikG`mt*1TdS5yDpBVWQu#;no+;$EIup$4T@Z?fdhI#lj7C9fHW}r`GEWd zIpWP;%-tK$baS5m+iE?u3oau+IH6MSghs_VzIPkD=VL&!$@pCID>!50Zw1;q(jDgY z_&(7S!;PMhi!q@S9~#4#DTzIu-8jbtI;b{ykhfZ=>1 z4{2PhjHXUApN>)))(Qg2r9=$O?i>B7`nCeol)T>oI$8H zabo3k%5=<+)%SMnQ|TGgH1tAhoHk4qB@p9^49}mj8cVk8e%}2^VVjuX2T`v4 z7U+rP!Bjtt_iii?N1okI*fOo}SdnZ>PW@n$-aKbUkulCpmxsOGRCV?9fQ^^Y7mRS- zi_hN%hrnz`)kMRIaL&?>QkB`gW?LesNzl%4qUl1-j+1=>m`=Yr;GA%beqT9G>5{{Q zZAWi)8eTF|QwSb`X=>{x4&Q|%T(#yAO=!|8sdFdNzFCiU7)?`((~j}0wjGCyT3a_&r z5@-5{RVzt7$Sx@dvRjOyldm1R1uxRMWI`_;wOqQGSyl6D+%NL`jYH zAf_Mn@4=x3`ykoG)5 z5W9No<-PQHwbxV%*Jae*>Wu#iI6qt>za>+`|apPQsrJ!2jzKFdj1 z0`yG^JZlE2941V?Xvm{6=E^_FIOAr@edCGmg*#u&ht&-S^5(arL_vswUru7I&b2uX z5Y1y|w)o<&CD8(n?~H%QF1tp!>pYT&bGQ6Tir*RHL0oRa;JpE z_3mSBCg|-c`cK4AJs+>}(eI;p+zjzk+r1mJq|2*u!-+?_tf<=k-`ls+)t|fLl5&B3 zA|8KKSiMYpxpz_`ot7MaKS&ZUcuRJ(a`p2$U(fQidOypvK7K`RXJfwS^L6fBVP2?E zCTQ=zLj3BW1A<@kU(5i7?4#G`hW~k7K!S)}gy8=a6y}<_i67}D^nHvgOc7ooUaQOt^$rtDn{CigfK%8{f+oK&h{>0=hpRpkb~^K2%8}n z@l>H|f5V!GZ;4iWe@#I+4n+0~Uo>IVx3lOBhuL>YrrTrgG<1%#L#13YOFPKTE#~Q; zUL}mUs&rA^x@PeH=#0~NQHe(g=?8#V(8K4p*AMq+?p}gPllh-*%8i;n^5(m5#_)Jq z^I{7JK5P8j;tCL<3hdX;+~r=?8A0ZTNTS|t4qULwc2p=vkahtX-yz9;l`g@QOi4n- zO3eF5y$dLbwR65qZcp9dcgV}gv>&O~lBw0b@jKZ^Y4M1{cpCov+@^u&&wwB1BC`lAPW`w&L?fZWwEe7Gh zRaO~PXqaa%BQe^S#;$?tBE4YKRdX*i0lgqMP|2G>S8zer3#vzs$30UJrzVMygz&>iPd?Ax+oCV5y5={2P97o_;>K=3 z`j`6yO|h3rJh6uh8nKtGKG1o_&fWU3(-T(-}4-St5rTcFvA~o{lMLQVttA4CP8LHo+22Z}SQ9_ESj!H{~ zX3KfUVc9RZNDb24lO=4$tM>Kps`b!z4oBU~lo;ES8=};Os4|*KPyhU%?78*h(f)t) zG6tQuYu+6i_IzpnP%;X~UR<)>!kJUATT#r0B>2@zSF#BgILbfwqcN|fqN4vTw%B^F z&yY!$Ro5MTc~p-SQlQ_sc>Ia z$l_Pxe8A;B@l*SYj_KG)<=H~;__y=rN?gdS6Z%5+>Q(m^`iJzDcMBHoh%p)pbR(4^ zN8xtj?$+{ntG#3d?u_Oz1Wbj#!)XTHj~`8?*oGomYBg*Fg!o2OtkDaR#EsxH5%9eA zL2>@Y9jEc6>8QN&d)gGA-J&;85Ec*p)>&c1pWQ~Pp`ei>JsS?f8!lCZH>Zpnik~Hy ztBeZ`EtBu}+dds$C5Jn`UEIFuWt97Oh=Gz|ZvKf)ZrQB0FS(s7k_IoTElrLoc72A9 zz;QQ7UarJPy8A$1j#0ZjcO^Dq?Qq&ZhPlACMx0j9)S%8J{H(07#Sg={;#;7_o^@2# z2vp*XrjX-p58Kww;4!+a$giGx`vc2lL>{f>e8+qE=#KPvpc$OC)4Y5W@#iR}c;#ku`x+9xji&0QTq zU>Q@qRK$>4Q$^XtY5sjTc)Te^lwvr-Z9~JNCm2iGR4NheMMy)eS;-&)641NF%*lek zg3Gdi-X#0HF-Kbj5KZ|~@jaJvm{_$7+hpMJ$EwxE|bkob8*DMFvIgpu=rO9pdo zT@jA>nw=5a=*qIkW~QTsvRJ3$4+OL9M!WC{^4#69ce@Pqo4NX%?+d?MZ%$9oF7~m>$cX>cIL{{Ll+NJ+@pS?CtSSz9vtU?J@+ry%aG`tR(r*wBAD zGW<`|acX8eVT5ESOju%PAOGWk=&^6RCMqp0mGt_ub^cyN-&edzY z&MAO-NWBpb1=ryUGA`g}iYoUL>}yZ4HAS;u7M~3QpI8uL%SnAp-2IYpoT!YRX}5viSvT>bD@uhxvr(&LufawI*npXnV5feKw61cRJg zfdKbZ6XS?drZi@g98DB2>SG^>mb#xPOn}KgS~AMkz)y5Co{r>P<*PzZSZc4}BuANR znLt)L{x0kl2`C8LiAr>A+ezl8wKG7z>0C*-cjJs)Ds;D2eb1++v^GViWzFpiHr8)wkv#5ZTdbGqG>qJEBE7LSHwAL9;G~8+2F~WQGr3!K`PVFLo>blW=dz`xt!du zyGjSPKXu8?4_ybav~vt#(gcKr6C&mTY1D70vSzfLegfsbzC0(Mm2l;yWo!8MU;%#sj+?BDp5 zAT|T+Ia7J}u;oOT<3&Pup^nP4y>&IoXYC$Qw5Fz}dE46+{#J*v;D-eb56Km=;H#Ut zTKNa7s?yXtt|Bf;_K|!0s&9^OB_5mcvb?_dzNbpu8YI>+yJ;1PPe5{9#w{3ay{k*e ze7^bp|1l@go)2&akv|fn{l6>wj~|rxjLNxTHt?Po4#k*K6;t$YHCdp&tyQ~Y+f5L;D+lwT?bPs_<<*fbQdaTOv@H7c9`NF$>b9|ot%#2`sFy?PF+u(7r zHF8~JSHfA{a-imWS#C!paqg=F(Kpy)FPtui6XY8D9hL1*fRonyukeew5{KQyg)TcV zZZ_b428O-xiETv5>&Z_Zc@08i%- zAV^M)P=H4#(kZEQw7+jXSC*cyL=b8gQF*x$TLkY=5Fk6z7!wfg=4BUSY$zngUk{27 zK|YCvJv5U|&ka3_Xat%*)9fuJtSY8I+$WH4Qicim=%eE|-aV*QRV;=WBIdk#IbRkf zsh=8qh>C#gU-Dl2n@vKG@w8QTGfrO{`bfqFqln3?HGsFwnTq|+Z5I05u5SCE3T zGC?0=nb3M5tJrPX9uXbvHd3uq7{MxMn%vEd#u))4r*$y(S}hs~G9J7WA4N6fIV{MK zyXt{&cdJ)D^Bc3K-wXBLKc09ax{5d?v)`K{_D2S)4EhZ*F3l=60Vw)QFW(gUzh+{F4QYz? zhuPv0<^E8i{QaIrwo(oA!ulce{T%DzwW6n5#|1)ABp}Zm%1x_8G}aRu94VU-p@vBP zsRqsAHftPu;#o+2WW+wh=u*3=$KX1c71n=px1I)`7VOn9j4#X8xz41&HJdNsFty3INdD2^9#tZ12?dSdQp;`68aX|fx&fKSgGR$MN2{3b z-?XKXx*L9mlcHW`&xJtCLeKh@f2v;GtyJZ56Yi;bB_1%ajV{m`>#vX8`wLjIP@mi8{-*M1hRzWM=$QY=+ z^?gshxHi)-y%yi;$3&guU3RmURsXalh^fMcy_Sc^HCszOKEn-S*@5)Nq?Q zU|lq5e$X})Ky{~D<~FwcFY8{(`G0kJrQplEEyxyJn|Cy`g~8?de&ey2kD{lom&o$^ z6Edn&Qoi^$Sg&)t7d!iyYl(;eO2JRqJOm!=8rWPOlxC%xkJg>1cTYAGJT8G24aDVc;T62xSw^5biil}{nIQ(bx zdTKdsFGEZpVyTr{sGGM~?+%?!yI>)srZpZjC z47N?GiaQP)VVhlXnBztRhr`t*qfk!o(RC^f58`(Osuqgr+giYm$Fe63GhThSFkHQpWYthT|~}U{g~@=CpUgGx={N zF!qxo+khNC;Kp+@$Dll$XgM*x8kSHS`?LsqtC_Nl90w$b#3NAmjMwZZM+Y+RJmIg4j5A}Ir@SNZFdnE(k(rhY0uGJgg2*~)Y#^(|R*jX!D^8}pZyOoN0?|}JKUS-v>1h+> zHqlGILtFeHcrHHwn(aT~y^ixKJrBu9BV>{Grc~i$w+EDWY?Pn&BR5nTcMB7Ws?8Kd zU7^rNKlrHX2KF@t&L^%>{d2;AZq;DXK@Lsjp~~-sCMBE3Z^hwRnEuuZ+q%9Gs}Z4E ztX-I_X@m{qWinsb@9*!dt|kcA@|U)S27ZXxR;43RD1Qv(oMgC66Hv*pBWHk|pY-s^ zDSY2evbHq(p$!Sp=dveS1wUJmvH}xuvCSsr^v6xFyStw}*R-(?<4n) zEMkh_O;fuf4W#G`O&{74!^c5z{lT)5`C_cFFV*YQxcj{Ibj5DavgspyI@#yA^;_3h zxf?$=%k*J=ERD1C-=-R_LPhjJQ)b=!zxpG+lLxCHc!*c8$%!<~X~(@xEY~B^!;4hc zE$M(44j~UOQlE?dWGe%3bv^3PJHE~38i$AjIl3x(F1J^pdF}bF<3{+C;p^X&^+f;; zYma#C30d!%+t1x2-askbiDL17YB3lZ9FcS1(q&y;TER?whrJ!yyY&|?+P}gbF3nh3 zDqs|iYF(4n3*C1@CDBNufW|}ZcS2jxt#$tfIJ)1Qj4HFu(YL=hm=a13Y!|ugGj|HZra1-%xles=YWNY;>4(Xy zz$(feRx{JkYA;W~u+E_S=ZDQC;E}I8vDvqdEABpnp)tuO9Px*f{oeoM?8%$G6Z)UA ziby(qW5Lhzyh*{g5fx+jIS@@vcCysK3HL;1n-afNPQsOI;p$z0=heh$l+RD*PU?=w zl~V_}ncU{CpWMDzMQ|m5BZ^>sBwZNaABFss{Ad^=`BJ=5FYP-}V=+99k9oiTe0x6E zax!^VZwY@-S7k+$T+ge=0dwn}^yL=LB5P;PZQA2W2UUhBa8_kPiKCsQOy`f&$=4S_ z-m7@?e{RZ$n@NjdpA8#eU8?1t>26C|T)StEs^!A^FK;+Vgcd{pQh;BQg&b+%{_)S+ zU(&Y9U1)W^JU5XYRp-N>v4xSnn+_$Kw)%4KogD{-8O{6foW%@vR1v^8C+J~BKTFH1 zew`Zk$$vb3DFt!5j|wC_u0};h(se@*M6jh1K8PZIlBTp)Bnx7c?>9p@EvV~asW ze~K8Y;_Q(??3?dL>7i^uEk>kXSsCnHoWHOZ+8un0vEOvX4}5{)0Y$1`QUin1)nvn9h9W za#GjCQ&g3VI0pYp9+IEI(?x>qW#$wzO1LT74?~TRdirZ#slq0|8W8v!Eu&LvGuYdR|k*cj{)0wp=%0Gj`%&QrQMxp^@_#8^_r|iAi!M2i=>R!#qL5!{4CfMkMg+T65osrjvh#o~uP9%e zr0uOUE~7^pZCG?71ezJBS)XP$oLKcx1zVN0QVwFXz%ZmJM>jA0?G+u_5t7TB=IlD9Cf_Du(VUh zF{spRroBSur=7_oel<>1{|zYSSU{Dq%BvGspN(B04!VXg7IcRx=m_xg+b(KN=e+OE z&Y^Xjsq}^nSF|G(Wq48}y1b|U$AYHccs~~DF)JSdCBj6*I8&9Qq8sE7M8sc-2fif# zv1{6vI1TKfZW@XCSYDsQT|n&25NA9+L;sKI{QFSwj}d?HYMcX)>^OI!N@78wPtRW1 z8xroc$$lPV0^}b9)uEaCe2{$d7J)%g{gbk~!>qW%YjH$SR zI?A1inTNq7Ct=csN_tCdhu;?ycyKv**zQ5r9dPM3bxd>Mv ztir@~%kvh}U8+?M@_~R&G>c`YUcxS}j4Wj<@~8a9psb3!plfGO?v*-={y<0Lez^wB zRl#wh%O-);$3ml^oy5(XxjO4lk{B&phqoxM?aRWOWK2wKldkIObj~a`h2>gSZKoCF zyBlEU_;4HFOZ&;u=8Ymn!P~F`uL|Z`yY#=X=_F2D!q4Qt4CcbO`2`4+NNZ>LGVTk0 znTFO;XVDiF>@Bol%S8bES3MuBsTM4(u0{*YrM`b->RmuRL2X`j#qijr=)zfh`?dO9 z8_7*@p#1Z4gtwnFoqqDrFSa=nl^pI}Syx-cLzdj)QpN02k)Xu~f?P-JgM+x@#Jb|` zyy#H*^$GX4MXao>A?jS&&K7LEm(XZj14TWa)F$1Y)Nf>`uCc%#!j5*zj>j#Kq4%Y2 zh7qzl z^jy!KI&6|ltEGHjNfoxmTl?M(9C&dj+;bgxkrmqghnMaQCQkqDQKZu+NXIDnY-iZu zH5}Etn7JM58BC#<@2Nzmd1orOXJUkdF0IdT5Y&c=a*SJNKxIN6wc=G$)i z)NU5BMI!-ksUVfy!0Vx5PIw-cm=JJ5T3k{p%`SjbrFrXx%BS!WH96 z3|N!Lre9XR`M`Q4!?Z5TM8(JvM&PBdA(q|$|npgwgjyH4~ z2X)5;?KR1?0o6OHFG<7pCbSgqWz_f_-54j9lt-HOENEl6bj3K%8v}MGT?WY^DIOF3 z;5N{*y4dUwi9F2M{%~szaZ2_fmy)7t-+S`!<$Kg2$H}ZL`)pa!4(6VJX7Llic&eoR z=3gtf!G7`7mF=AKdM-)W`del($8v_YzoQU4MdA(BnB&B^c zpH)0-|4U(RoQrc5wmtWtU$iY)pXO*m^_Qb*`~sYHS$w(dA*Sp-noKIX?6&hHWIJGS zwDaVMG3oq$HaI@XO>Jm#C!J@+ZCCt{lEjL@LZ-F<^+jfNsN47T^!tqm-pf4Cq~9vu z`jv_>M(B9?yC{f$UWK@wm*9w+=iRnj4haL^U@WV_)&nYkmsl%OTVLLvR11e_l(50E z4&;eitSoNA=7CEX_=Vadg1k2t z&N2+uwf*u`#R!WsTq#w>FAdXa=1QzG{k6tLpaJyH+q`4_)>c`;Q#)pv8?^l&aH4O+ zre#~?BNhlH#bJ06i#v=5)hx9!%5jFvxB3R}HKyy{qY0k3{bB!Ak*VTYS^xApJU%9r zw{PX}66LgYJts&3ZK0Lo%yt)%$Ky;DRg`Q%mMH8&f$jC>rGkHB(=ysjjepa(evs5; zGwjZC`z=;efW4r<>uID5Ykh2p{{N4kS{QtTWdDyjW75=tw+;@6IL1qlh6hi{g8@z< zLHh`n&a1khbOJ~Mje!#q;r`-Z*4^=}N_mtsXSgjxXgAqhWE-_qHABR7=d<$>+N)IB zu|1~e!&Mht%yD&26T8{V1MRHA<9hYqN5(|AZoTjPgWQe?AXz^nZvaxR>%J(PVgC2Rq)VC^x!N)a-48y)ha>qGi0!)DmHri?mWj%+dIWYd#ARE%U zPRXm)0C3)>@8njRh9719r3)Z$NUJC&@F8jFxl#Yob}c)3?_Vk!^vbwvWx+=%BpD$D zL@`&FJq|mbx-33x7X9uU&PP52E%ft8Nq#zSrP`N5oTbxz ztOSu7{4mwvPdg(j%EvNt!e2@i_|{YpU;KCi$&%}7V8-@o$%U)0Z(fzbw?6Fg2m#$n zU8`un1P<^y&$%lIXl-W>MO$|;=53_ea9dVc6*?kPoJSN{+FT|xfDVC+o&dx79XuMl zrwNHaq2DQ6?0DO=B0uQ>n-RM>276g#s^4JklA6h8LfON~sq%6A_+j!x1DTquEc!Mh zyvxhwk4&%)|AM&dP-yD(JE^gdfZ&%@zurE3@V9R3qC|s-Nvj>_F)XCh;ssNWQwHeZ zJ}Wycl$eWYbB9H&WtRG;8f)U%WTWEGE>9Mq%%IXT=~vlca1fr30-{&#wJr(qb?mkf zO$ahwwZ*LbyXB6|&8oF&9xXSGBO%h?FARF1|7^&uIWrEq4KamnS z(NB#;(cnL9Dw4HXZ@0;&vW)4kQ;1EI6Q+m=9@61t3&zQpGpxLYHa)Rq6ax(F17)Bc z-Mmg1Bd){NbfQ2d%Pf;!jraAiy;iE5N$~)ookAF0IDn<(LSwd_V>80d878YC-Hz^X z^6DmECF&Df4%$WO?hH-uuNqUHQra*~+YU3kEc3`*Y-ydn=qDPpThs@4qQ23K1*Ubo zRm$`jGcernQuR?#x%h^N`t+vb2N4(b%LIJZ>fkqJff zZ^D{|JI1|9E1Gik3M&0iy>cM>HZ|OX!apqSeTN!`3mM!;nPlfDq4tXQ+|TaCWc1j= z*yH4T1?j$PhVK59p1zL2yZEhc_mcAYy0Pt|b&oNOrcR!d zFg3r>bD#Nk(v%0EW7VZ!Bp^-^)b{syh6gdfx#piw9%uF)x)pt_dW{zg^zqrwqNk`N zEP5NdNRx_7UOCK5D6_<;ovRV@GZEbGMIIt%xZHjT+qS&&vHu_Dsb;GYSpQtfbtn1U>JL?=emr7)qFZA$agj@ z!HxLBaVrT1GNWER0Hl?>iJ1t%bPx)e1o}5W>@ebesp^VImw<-DlQ`Tsc6J9IU#=4h zr?ERTFH3DVUM@mdbo)hx9#8%huz?qZfH0Muy!>&E$KeEjjiXS(+ufty@;W7J2~*EA zBC`550^klbeb_%{y9W*pEa1MN+YO(Ws~0G%j;3$P&o7!#)OyNmzKZ6Wu{GI9`|toE z7y&Q6#1m9_G{h)w*ige8+4E{Kyjs0#_!f4}CNat?v?_CMKbCC;-fNm_;@hrtU~|2a zIpRzH6YNy`up@ue2|w&<$l-=OBQptjbJaN`VcY*BB_ib;&$fkX?-qH?Y}dP{q{tSH zG0RVyt4NR}OE%;uJ^ib`czOHxIE^MCTAj>yt^xiDVqAxa6-Klz~3eDpVGUgD( zfnd6ez+Tq;;w!20Zpyb-fve?KppHZW9sj*#oljp1;i6+U#zQs?4xsG*X@Ph#%R+YL>;K<{+LD-{og>iEN}@`vXqI zM}K~%O|Alm9J>uO{Cry7;I`)%Vf5ieOq+q?u4T+sJ^5*B5jkk0ght-LETp>UBx;aJ zLCNkQ%+*i&EJ1)CVLOMv=4)6b&M;Z6n6cp4$(q2{DPfdrJ!m*-SnvFub67|7JcUlln4#iGx7%ib4=2-vRY{_C_0aPWC z44Z~tTpOm8;;wDxo-xOv&>z*US)u1ym*$W=A}$lE!KNjQy{biVqX1OV!G!SJ!=|T) z>ffU+W0DW##crq$p#ZFq&Xi*)TH_>({bH1g9EGpMhw3n0wM*)U4UmB+hm*sIcZlg) z&?!@oma30^TEr=*C|J3__HvthgC0(z-^bm!iqI&Y8=c@-scHZ)&kH|f4iE{rj4d{1 z^V43I3o#47jXts``TEAyaDfA1`>k1~{8zEw1UF?{9m1pa-_I%84CSyvkGrdM@s|Yz zVWSdm2Tml^(UoHbhwttlhI}TB*FwAfU8c!|54um+&|nIdZ@sYT@a-p`^UjgOE=v-w zHkws5v~!JHR&O|#%Up1mNF0}b>|`5TxqdrlV)`?4HRR}$;>?1tm;wYLmEMuGVS$@N zVWY2Uv-!QZ4?BHb;;zTVD;=L)BD{DPJT7%d#?6Ss=10Bx8F1)54&M`v`?f$<8s*eb zQGo^LYTDe#vs}LQarKmh?964;3*U;IcS+0F>C~6WZm%|!9|nV}!fcgzihXvo70JFi z*{7v%z3u^~SY{5$BtCzT>fGwC1`ZEf*lAOX7gXt-6VDz5H7hJp07W&Ic*C<<0V)8z ziT7mAzjGc0M%yiaYyL})oKVLW_VYa7rb0N*<7t+gdso~;V?cTiHM1mR_LD)GM-|4m z8B8Uw7e0|98oiB)I?=rQwGY}iMaPXNX5A0=c3<%d?NCR`q&GE*H_od#NU$sEDZNAz z%_c%$Gx1=zv`y8i>jomOR`al&OEe3rM2z1&3q&Qb1`^(Tr`MiHr=qRxhUBT9%cPj( zjSV2ZH{la^b)qYGV-Pi@aKEW{6>qoC?orrf=~r%=*!#(0s%bl`O$|z$>6e^eauyUw3X+yLs1q-FzM#&G zH&*}NEqcn^rCroxL0OST?3-imj1HE4P!K34(8hs};SKIxbz@BCvpaBFud&n~oh%wP zKgCu}?=B?bw0&GWXz>86f2Z8lN8!r>d+O&s2^hj>j5KR!bnE9_ZoAnYqyBETc!ee* z9SV9&?!NW4$%G=DxQ6lV+GeUB?N6X4rH|#7e~_=9QBH`wE&h+=Nz!Hv4|OyWlTLJq zY;-}H=em1G=J|<;`KKY?GC%1B3HGZs;g3TqXPS6HSFe6=GP^zEuHUj}fqDEdhQ#9z z$OVVk2Q~?Oh`va}mpU&eSHV6$A9un+_Rsd(y~jXt$L|+ zB`zIqX+#WvR@{^6PU}02gao+!w<~toY`%oePB**YV+-cF=@R?u5#b0ggMf@z*WVZ} z0Cr)`$U`yzkC)vZn6rGx5xpA@s)7K4Y@?pn74#!DVEtr|gSxi|<{SNqzCMD|0{g%? zmQdKe(toZ!h&FYaswqD&uLW?k76EgXS5b^j6mJ&Y;OI6UrbDS=ht0R33XRXP{7M0L z!2DTp`;>Qiz&{m5$@$@u`FbjZRUjRp@yufL9f{GJ&fpK%jG0b_M zZyv^o>NNC}^FO>3sFCm-ds{C)7mAyK6_#)YNER_AD8iP0ZC|H-5QcmYYn(^XjhACO z?lGY=>l3c;UW#oN&o7;#e$uRUT^54f^uEw+aIOMjS~1?e-?!rw{_*5>>bs1dmm5q& zZKFF6fo|6zHt7s=qN=bWs^KcWpmeXSu=k>E>9`*#aPCCN1gWcfXkQ%p*lvDvh^E7C z_Wbxk&+!mfYVqJJ8fxe!I!JRjPMBC`BpkUg1k%D=kuCP_C)H1TS@PO;W;Y#Win}#` zSQ;{EuIt-LSys~UP2ym1WrdJ`;0m$(oV}#>r~vQqS0rwMJ4)kjEPHp$kyY=c@IOXG z8`E6wi~FzJu|c)p+_X0I5-Z~--&TG`d8Qo_V>1&+43-<}uE;O=oXkDXQQ}c{;CNr` zY1r-wZQzmChUe=V*Q3u0>y!G2I(6Mj!Bv}Ve-RVY=S6RZ1>InNYuoICSyg7OEo0_b z^@)K`!|SYs-hJCJ5tbDmwVpjoq$?SS0&-zB{BXArqa*=At@Gi+}};zuP895zetBi;g{7GxpNO z#%Ix@xX&?TrL6Ar8~dWI8>CFz7=l9sD~3BXibkfDtlp!SEc?17D{pcbIy|8uPh9U+vDP@aaa|O$)N4&b#(aFi3s?8w{OTuCiK#MS@tT1L;zd&@+%D%0$s<* zH?smt{OhYX_sUpU=VS|qT0?LsuBwYv6T6=dSyW~wn+5od%1PP;!( zADy+KANlmsaAg+^Q6(#F^h}JH!D9 zF{rUxzR`^otDbq{Y@>dw7Wiy+Yih!m!t3Xj&Ym==8YlfXD*so#wau$nql)0P2iE;I z*prhA;jIz=z~y@fRV~6N%8Tqa#DZI8KNrZ~4wIg0NFB{rW=HL4KtoeD8q*>!tG#Jf zX3ZQzAyk37G~|(7cni;{`&SLtuse})7qjS^*zdX7I{N6_?-Wa$?eYcGOQTIG?R{ww zNpm5Qw0Yc$j-TcSe!V2s0Bf7m@C=_aM?5Tfi{6`gElaiZ=LXl|b+OQfID}3Z23qCf29#YbjHv<3?Kg7Gu}}%?-sCEROe!bq;2@o8^lFW>mWK`XfGh^yF2YpVi|XZwssQe zheAYdWFUnrqSkNRo0cQLXg|GmxLOVnWH(sxLsujgeS|Jgr#SY~D`C1GH!t1$*OCP@ z&BYaet=poR%GnaOq`f<-gR_|&rt#4e=c=bI)UGXilulXD3eXp|hjm6urX){Sx6hZd z=vTacbU#4%6kTUz(yvGBi(_gVrG8Q7c>IA$zgkm-z+m9dy5bOKa_6@%r5?#%#o(z1KE+*ou9{5#LA41dCHU#q41Z|)eRda9QuxL2@^&~VMyaj^4PKkHEt)Qamdk$*-C z^{4?Kc=z2T`Z#>!SPq4LUF5SVswlDsg=&>kuO`WApMr5_xl*IzC)G(ZRNd1eFLfBc z`MC`cQ0%TdtYeHN3o#qKN;25^k}6C@o;FmFw$mxcQA$%X-frgL<;E}axPuzQdm%=G z3zE4llqUa1rV8hfH9_4SZq`PoeD1$C|K`gNMOpDDohTHzy$t~wP#Dv-Tfs1-)ytmU zQ>+*ka(C3%5b%72Y}V9|M}!L2sj03WO0P~})U(oQ8PfEo>KwoHcla;%)S>#GNk<9M z`SYa*iW^)Raz`Pq&g|?G(v``o<&^4jD_H`-zps}VJ@(-ERH^=$x0{8@R!uwL=X-A- z*hv}=MRQ??tPQC*1e1TaXVe>?MJLeBVN-xz-eYE!R#e>ETjX^RT^!3@o2-o>Zl{j7 z_hpfwH^b8=9C}y&i=)>%j$bsA9V`iwy*+7@J=_U&+(9nMuAhjU$r2lWyflUAo>ty7 zH);iYDDhWgZYEEneu76$8Qzim!+HeGcN-| z7xTkOe6x9ilaB3z8$fGL>2jeeZeD)AS3d`O+w>p!8NINvb+XsxobuxobE2q^h_~Cs z=lYo{;bqY+(Tl59_bmT!a~1XJ_(KC}=};)txV2`{xEK0{eY2n^PqPjqNE6cy7_ioj zsf6;Gi-wZaGy}lL@J7M&j)avWg7vy1x*+s7v`f8=B_Dy>K+ts3deTo`JYRAwMePc} zzt<2tFFzU2Kk9p3YiP`4sh(G;6Hp>@t0KH%t6m3wY`r1Vt}*40x=D@jq$%)b*B;IR zfl_H-PAX5%RcI(DyG)kxnP}i(crLa>={CVmY9Ag-RdeZ1rB=y4O=XvYygosM%>z%K zzr+@Yc=rsPP_hmM{M2d2U433T-Y$?ZkRM<(Wxz+nx)pTnB3ul|dK<;@{2UF{%XOs_ zosh$bfL0fyHKg;!=F(m?j^uUH=hv5cSN?D%Hy}(A#VUIo=HVAZG4F8E83;Byreb+q z=jK~QyoijB4(J6Gw#O3Q)y~{Uiq&}hYirC);Y=^9r#UfY77hvAse^Ud%vBTB12dIX zUh}w#huh(WQ{`@aC+%x9^=p5u${xi7-m~m_ZJb%SE`eQ^?}Na70x~Vph4Dk7n_{VD zRBIHM0-_a1dDW(FSzoSqWv`FVcF7H{WJDS^W;S(L_1MU1N$R1nr`xe1@S()j4LX5` zb5@p?R0)QN5b(ONCbLt$mG66!CSSsft%lrkfuN-NXAFN{o5#SDkx9vj39#KF(g?)t zykE||3ib}wW$K+p;KiM7q<3+?CclsHMJ4k>5gklMN~5L0S1sMF-i5w zD&HY9X~UlMtoe&Vj#GM~mSuP>t^O=!b}4s-uP)6-EZy>UDuO8a-oy0OwEVT=BEOr^G#Wt-EyZ~yn0VqfZu{%!EBPLd{@;d$hf8$s`6$IXfXaLxH* zdU|Ak(XfC^CwGw1m1s46`8E5hW)}0em5!hUA-D23a{>T_^#_n}Adv9KY{lY5luoP= zgZBQq)~`o^xWt!^KwCo>#YNi|Cmp6LMWE zjt#sbNyvS8@G9cIrHf1u(<{fVGJgP-C+J{uGH)rT^DP3MvTf5A20T*O!Fd|VtzMK# zla2CdK#h6N(1#qR+k9!$SKybb$~c9E`(fzhO05}^A&T`aHf~kS^M!hrs3_uvkXX5Q z>yc*R3t*jNEEhObXpxIx@nvri-6T5@KZfmI^)2>$^Gwu){T41()Rxlnm++`rBZWVh zr_G9+YLlv_^~Fs$Qyw*U4k}bTh9}57$Pv5=GMN<&n=^BJt~SUS<=>RKR=46nlebm$ zl`Plh`bc0%g~MWJb%-S<+gw%FNQrgjB(bABTmHC9FwH<#lAy!WYwh{3A04_5QXTCo z!|`Gk>8Onj&jATUrud2f8M@*0cWbxDwcoig5Bmx?lbF+DTb3f}ha4e8i%eep*!Y!I zRv?4}a~u7u$dhd|A>SZ(VnamAShi>SYAUxvj&ogv+YWf)A;S(mkfn&6UmF z$u-<|`Wpc#^2(oNIvaww==g5L{8OXBK{t%Cc@uVeF=tc%puGYuFXsp)&AQBdi#G%b>JA?Q(gp*Iy&GWm01yIjVleE-?LnhP z$@wnteRGXl=ybv3HDu%dR`_x$WJuKIz*?VY1Er^Ye>$^L(A@+e8QDlzi+*pfKi626 zl}^|0DH@L-txzQ4dchmzh4#$zNKoV5R(ziyG(6mnMWSzDiOYIKhe6VgrzK27K1qIAyeR^l|F+zk{8JcKhpYw}L zFM9C#IHhz6ezF%kb^c>U?qkD*Wr$AN!}CGFsjmjK<3! zZJX)8$F~}H2`6)dduoZ!WqL7n))M^cOtIbTFVtkja-Tu(-ze=bPkgvjq6v}@9@tFAKW+XVG>AEVltUwV_?G+G(&X^rA}Iq-VL z#Ae%go*cvT^7HM0=A{o{Vb7d`f-k>4!-OXbGPlNUp0&NY-TPNzpL@aB^51QHl!eZJ zMhnbp1E|G%opb;zf^tysP$=2+q=ydx+StuIO)dW-&}&KJwn|POa075Q$HNjh`I;u` zo|p43NkffS%|)C*XGi}nEY<7cs}ujwYE11l;#Db_Ww)1Tl8U{s3y3#{`KY zo@8v&OiB2)T1WgbkbHX5lU=y$HfEJXodhmP3R~(Q$2uk4I&ba6vNe6>JAcfx%S5UBtiG;WN|t{ZduW@hU8ARF1=Vc4iN(O+6$6Z|jY1R$qE@)nSyt z1dyzz3PHWb&&2J}6GaO<#u@O{sNbDazq!i_^e5nbq=tY}rPrh3N<_=yIf4{bA5Ppk zI(TtkW=Cx|L0y=4O%>!F=}13k61j|(gq2ad@xbF?@^hz613J=zZw1S3_B;2ZMGQxk z9}HiQse95?9>VB`Bh7vR!MH4fG;V3OTokXRV>yci8kes%(Z9%?lRADDN<4+FCFYtd zEl5mEe0IGL3raXsP*qkg zv?R>4fn8rv0kC(q1^yH4EUd0~MT~EnqS|Npr>!0(Y;V327)&c=M#iSR@Ok$=BZ`Aw z+zK(e&B){?;IyAJMdooBz&Z5De?jc>tSvGSp*RNP2JSyK{=hYyaH^_AbJ}xUASxY& z`bzez3$5uk9ZfY~+hqCqkr|5yU9;^V>PgjVYT4uN*+Fy3|3FISp8m7=$|r0oV~|PY z;Sp(R5Fq%o5R{l%Rvl2g{fHqn*nhG}v30(DrRVDuU6$E{MhJxe()LhUF;r#cw5bf@>Gk{La0Xx2scD-H2)2wY` z-4T8odDMNC(_i9>7+112)^0P6PFcp{Eym*wf}Sl{cii2VmV48}9u{0dH@UQP!0iX-(z1e#j?>e$R%YgI|UQIOz>P*H3b}Vxo>Vz4xhJjo3Y6;>LZ}BGS zEFm}ZGwha=dJ5OaJ~`OQEb3rGz#&N!@2FnsXg9RQ;`i^oX91*6$n}o9L9RmKczy9p z&=L`835k>@i6A)bsu_haktqB6!6mJ$eL8o|^=FkG|;r(c< z?;SwOs%z=ah-4&F^v=4*mq;BUi6Rmg{wo!1I+zUPEcU;hC9u=6(2pGTW-o5%X5SB= zVhJz(OS6gF55W8T(~KqEOCZe}`KF>WKJDQwx4W0)Ju--{k#W^(n~<+qbjCp$aAkwV zUJaHtJ~z4?1(78s+^pCS&Gz3vyebt4b32$^^)o0 z1u%&QL2z%-np_B2Z71LNGOPK_mEs#rPu+jN)Efh(GHkzNvVZC#OSWUU)w;ml<=F$& zVK#?7wom}aGj)Be(5H(&$_}NzKSsnz4wR4;=Vow{U^XcGS~Jb98s=`{kz{(%KzN)Y z)P8a|l)z3p)O7Xy;dJ5kUG1M57_Zd(lX}R-#>j!76gf zN9MByVoC*v)0|)5Pdi;U+6^1R4fgasR9HW+jm>WIahJ9KL&h|K8 zioi3IDs%L8xv2C<=}A$Wb5kbG2;~H1ROAkA16&Rvje=hfeddrI{N}1P(I0txaC=WR zmF3~X6^DA|O8c%_{~X5V-u&Ml0(-dGRq7snmF)9y4R~TZK}f0cSgP-3=nY%0~)?FpPZeu>yR3PylR-| zmlp3fNDt+8)zWy^-G8#ZC#fzoSVq3vtO|0y$p#-i;EHZ&V2XdXr0wu*T(4==adjH| zrAOYMBPfdAxK#=w)5SY=mR7W+!`HxW&*j88I&02dsUy&X7k;g%)U93*25)`#r7!$t z+^$GErlD7;F)N!i;OQTI0@&)Id58hrMKm>ZEB|2dn!V6sRszsK_oR<1f-77oY1pk> zq0|~zQ0Y++{_eC<>~=flSDMgk$mJE62S<1U2Xg#bg9@Za{y2eGx-?ftWWadA2&Nzy z#o{#P`}s7|lFT^y17RBNpS07B!Ojsm&qki8rvCwg?L?DN70Jj}^kDWk9RGH#b^D~TFS@DSE!`omQ6NV$*8@||l%1~)w- z_6!yU9(4fG;oLJiIv(Q6ba^VK3W?7eF%E)ech+OQrvK04;-G@O#2BHQiW!Mkow}7+lN@2rvK`}+;>^X zf2;-1lxfbX1Z?A3vDeg-aI*(9^I!{aoek2rMEo?mM@(|@@T>sP`F1=F-JsxL4BA)~ zv^N3dSO{$A(OO|E@11WZXqHUa%K!N-HB-d}Ko%%T<;z9`8q` z<^pU#jVdzJ*1sH#g@1|h`N2~?h})(2g0nD?`@6UxKG)l_(#H2Y-=c~}VjSv+$0@^! z=$g=FL!l>03_h7hD&I3#kP<`cpA}!7hw-icOrxab#fimR|Bn!(KO_|VG1=ze%GSmt zm_gvJ%YGFuD8gpuAY91!z=fW6u#Fffb?YlYmkC!`nMOs@7DL--15>+;b zYz(!^2JBNDwzz-!J+URNUgeoYAF_N4XH~pncid9htL{S!C7C7ls{f^utR0Z7QiLdq zrESo&$=s(Wi(SVG!JEkoSvS&E#K&iW0QB6x<8xloyseU^CMhj8BZOUt0W7&Yes9wkc-&oCG!N7`;S858u}hsqMnb!D;Lw#JQ8J~ z#U?MiJ9OH2w6t(pZYJHUUwT0uIX)tll}gS^M9(pWF=y&hl5ziwkO1zc<&FOi?6e2^ z6FJNJSQ>s87Z1voS!3P7H#PLV@T5uX{GyGn(nRl&)Hy!##}ygxO_$YP)bA!Ie3Q<8 zKl_~<%PB9MJ43|Kj{vCzr|!qQV2M{T{uN@Z7;_c42 zJii#iCag83gvDD>Dcg>>CHoTIVn`2HY4c(pED}k0jHkP7y8{LZz)gJfZ#e{gh8!S_oUA^ww_W%+Oj6SER zcYAkf1uhsEwq#ek1Fp;4K6hzAAj=Z#TXDt3Xr$BqqnOodQ-0kR9p6n11e3Iklcj0J z1sK|=GsGmadohsJ-r{@mEjwj-8uo0V9bbj2?MYE6J*Owz-^iBvXqoj=SyBME*7f*~ zIPLdigyDt^U5T_L2e5QIdjcR6Ep zE6)(Fed#!IbHMe!k|C3O}-9_gySCHL&OG#^J z9NgS$jI$8-=X`g#ap;MT>o)61k+kxsp4*3dD;D@>^uh-(W85Iz#?87zIth!fL|uy< zWUF1ImGiLO&S=>}%REUpW8s|@cD&7_->s#KkTwItZ_9f{7YTpkPyagv%U=C=@$Ik7 zfdMe|6-dw3$onAEka5?IPOj}WX*DAVL3Kiro%5JIbUJ(_E9%H1jh$c zu)da#k9vo3Dgmeul!7Z$Sm*v-d<=h#>d~9(g~FXCM&BrlX<5uJ#HpyA2uSOVRD>Z` zbid4-ggyJ&%9eUH^%0Z2j58`f3$zryE|0$w8jUS}y@U6f(_({BzJfz^Y29IaV)7H= zJ05jJN7$u829}-9F?4aY|CCkYixM`&WJ&wI&wa%zQf}S!@746iu9L8KArpt|*}m$^ zY`1wG2~y^kk*cvmxtd018(L0%)5oN_1p)0SvsG)l+L`*BSq6mRAVoWTDTC2FsO4A`v?z|7Po;ixMzhjA&?hY`OCKB(0^GQA zrO#EY5h{z{&tvg4Yn(~Hl<0*4mvn(`y9H$2m~KJo1wl)|elW^n8sRp#dY-=6vRu0l zevBAuwY;6u_YAJl_aR!h`VuUB7U6&aH26HZcMHxSiu+pcnvQYPE8rw0`_=5e&hQ3j zaivB>H&F7_8)ztILnd)2di|7yQckX~Is}#E-;L|974&%f@A~;mX0vFeLE-z2n(RJL z>3r!oKd`KL?_5Tvouaoh*#<%%NV*gu6DSYhYtM zt;DAnTmFt=JDob&&hZ?>mZf<^D%oxM+YXYM*R=q`XKKK8dj{@U;d8r$Ek;uu#(bD< z112u2ij+0=7??8$1!+T|Nlm-qj8mF#-)uBGx}Vb8nL9G*RuWuYDJbqlLM0FX#1WJjj+%VAcnv|sn*}Y{ zz`Wi3sb(E9V}%+lq4|`uKT_h~lbqtxyg5J0j&cQ-0h@IPq3H*X#P3tP?JFn_ws#Z_ zndwb~i3J0hhZJ6q-JNz3%GHcWr}PPt>|nanUxu4rnPk=d6^ACcNyx8PIlIE0Y@90Y&u9S^3Q2d@I~9;fXna7cg!H?YTx7PS_ zAW4DM2u@J+a^LuUNt`zHqFJ9wMVT)O@)b{=rgJq%2r0CPjD%{XrPkuHpSQ z56_@KwRZbJY@#5i0*_OP(^Yc4h6Cbc08W28GoQ5S>VQn3yGp`Kt3=3CR3X&K=;^H> z;#Hh%)>q~4q_P&ZqH4?WRq7dm*l0diteik~pKvaYY^qnRxPxFKyeOsAyD4C0u)#MT z7NX`!F1dW(-Ko5p>c5`aWOYS<(QwE#Cf9ePEg@KNAIa(tpeL77ru4gb^}YR*k{E!! z;8jmA@T3u(cee{@FlqlZOLZlLAY4$J(oXPtr;5ZSbeaE(?i)Plz-~?|T=&<_&iI&Y zI@#MjO~QZt?@xm-zxxm5|34bHwI7xw8Dft+z4E(cR04v->N#S1VHE48-;;Rpw;5Rl z`hcPlWd}R)k{(w#UaaFmMuSr#Y{Ndnxpup#jo76^XJ^UO{cRkt(-uwh@45ZdCjkD_ zfBBiP2H^;>Mn5v8eg|57hn;QOE3N!^g;)ZRktSnBoaNf1a(uKx-&6?|{(`TW6Wgcl ztMCo8n}h~ERWvv3!VV)^4vTEs9UPl%i@KA3Mj32hj7>&cv+(%*z@dJ*BB|QE-Gg~q zz3Q8FHA|h17Ctlz-E6)>LH&YPsnF*wnqBLs8Gd*t-O$xF*n_oc#eOiN`5yFgcPU~$7bi0J`oY;RzvJG(qa*)< z1M>S%UZHt4(!OFMWnML$hlv-;IR_%*O|WqVVG=_X`bii&i?#>aUqk!MEMo;okFna9 zZ3!VFr|+dgXC?PIJ|utS2$DSATuN5QhTk|9RN_MFe@+SS$Y~krVIZri292F6_K9Q% z@pRdBa`Uc)zF?750yT}-VdE@%2nT(ZPZ^fbl zXB&#c(AiuM<<{6-Gdzsq1fOo>eawAOGpUL9Ve^P z!~qLl22Lh_^^*Gf>s!i&ZUc0Q8U8fd)L8Ol>MR`vM6Mup*-q7yZRl;7g`#*F8`^Xn zeLtB;G~{TS1NAJ5EQUxb%uuvTFC*l=gBmZ%bDaj0_^~b@&+%c87mOzgvMlaZ%bfWu zJd?~0an>=TLX!jI**s+;;Ey7%CMme*G)H%ghXzNbky`zfrvq+ZtId(ZMNN2xn=I6; zc_hlS1ERhW_Q)VG1$dJtiu`;O=MEg879r5Ck}jNtvovZo^sDvH>N=z7na&HOzNlCd zd{ISYb~HYx{N4#Cco|q#T3^!RlVz}tPRN3|Pc+3VdaJz9j~el&C~rt0y2$%<%*#s_m3v>pQpC6<)0bVUz=<;3hojN;1e;be*HRAxm+;Um`{joK3*C!BL;$(d_ib0 z{9H+d4qK=pc<~W(u0g_g^^xwJ`%YkW&B)@AtQWf)pkeu;WvpIO42$n7bb;_R52AMI z&>vG~&xo073>KL1mSTX0-J#>h}@tD+p;-pNp{ zSVENN*m#IYwAUaPs&eH@HNsyy&T-=(RJz5WmG%KymFdoXX(nh~;rl%oBb z<|2v{R6)=utBMoyV!O*;gE+T&+b6M?$s$(x;mr#x(|w*d{Kbmg^aqH#_4%%7wJ)3g z+l8ULZu(%(LAp71Bgz`)3K0@>-#bH*TyyoW>a4?69?E+z!-glJVUssL$s%}{i(W4l zd^YiNL&uq|c-PnMY)?GPMMSiF@(|1JqYB8UJr&)aQE6W82a8~XEu~Bo(%Y91`10j# zscWkciN|p93AVNG6WXUWp=3DOLoV_NffR2B=25DhaG5d9`g0zy<$yx=ZFRK;R!k3S zRtW5bGG_>|!Rl<_jEds4ef6$0>#f_T{yZHEN;wz!%qR;HdI~iB^e5Nx#KgocfB8p& z``Z9Fit$e^;eXyL%;x6iEx^nYSbcwXcFuD6YA1l+r!%(5g`x?sukIP$3g-J7%(7F3 z0|#|;%|&aA?-3_ilBBZ<=pcME2YwrudbXN;bs@kdIAEF<%uriLhK+i>Rq@ybRNN*j z-uYp$;i+Z%Kdm9zRS@+v1Ry zMEP=5(f)J_5zWX9wl&DG)TCNE6J#cdNF7mnFcd!N#A{MX{=klL$T=vo>xJIXhW#ZK zKZY<;>Ag6`&kB)g9tT+>;V*r!nvXKjK6G-Z>2{`E5)Rv z=#(PM8G1)~=+x{{q;iDuh>me60f6B4w0yF0-;FL(=r%9wm_&F@*O1Z zKcA&Lq!Y1X;IOm)tpb;Tu!uXO4mF+R2sLCXHVoD>Cy5dO^-k4_$Rx9~<2aiIUx}IR zcCGgHo=1i8m`xg5M=tPC_vm!v#Wzu{*@Jd(`M*DpGo^^0pkJ#lt}KKc=hPEL+|=nM zJ>%Q1W1^?;ywV1D*7{<9Vm0{Bj`r_ik>&qiU%#K2wRND^p7b)Rs#}FKjp(PW0r`{w z=p0eATw)^vlSf9TVnq7@OV6~TW*%U<#}@wN&SiJ1fB)>m5YxwI%eSmSWw4wRfZROQ zjXT=$62tB2D&){0H?rYf`U+ML5t_j=>?_~uTBb@_01?4!I4>Qqe6I4oXgjA)=fL&Pu$X;;j8wfu>(f&rFq<`N zzL$Xr21BT;lvTj->$SlUi)owa59r}Yb9RmWgg?TMx!OY#-1)cfctK4mJn~dRKD{tbAAL)b)7nA0|vsSM+RdlGo z5t=2~u$NddN|Gz!JiAL8Ebl0azMdgtTxHIorV>q8EcRjn%`4=hzHx33^x>1*6CF#g zvzs*{s$QOyMm#jE5V|PMyMH32Tt|49eT}n&4@tr`Pln|qA;{E?W*h#Oh~xJP#@+ka zt9R{nMr3+PIRv{rtD89%WcV?xU7$p1Gt!5ndlQ7m=D^iTCVHXfm`rfUj4^D<+#(pE zhBfFBygI03lqu9sul(_51@K$Ay^!#SQszy&T(~X6X85*C%Wkj{Z*`(WQAt|!&MR3h zpG8m5Y;b#7J!c%w+Su;zv)}$iLxlIV^2aBRAMFs~ zziRF-fw;%1c|!hqrfrF*q5*L7LQ3s(33^i5)JH3R-%x-s@l z?PWn9+h#?;Dk>8y`e30O8L}E2zcjTXPB={pfh2aTiYC0fpB(;fV=dluaC*!;!{V;p z(IRc@l{y1*#&38*_1GBBuJP_($+4D1GKYY-h_GolquYc;cuWEK$W`m^k+NEM#IsVaxb|GzpChK`$86cP=R|9Z5(T2 z$)yfmhWz%cPdb|MCud=GviWOb-H7>VmZH%hE1rY$g zvnv(;+57kF@jrj$U;G2T{LcYjtCSuo+@k~CCw6q-!p_NZ`}NfL&Zd_HSm=WTMzM3`eREvA-5?nUgr4J zgwbR_Iotj%_}gG8?b{Ujw;Jq4 zxJ+WUWZ9_ifm;D12=~%8lQMs(K&+PP!Rghhj5nvE28TYW#Lqq_?Ni~kh>_)mlJ{r@Qf{MU;=0Z}Lp+w-*e z8}39I-0nWUta2l*d1tw>H&zetkJnpN?FJicjtsQ%^IVH{e>x@>$^OUo8*k1j6fo?`Z0g2Y@6>}u*c<^!G*oOmStVBFbv=}|Z#AHX-&X;}S^}gC+Ne4(pOAD;fs_GU8 zci~S8zWLHoe@})bN69r?H?8rW?agn@a!e##e9)}Yi;zC+BAyg{;7Lf@%+uVZ;3zAy zO|#^_&-ZXQOEe*Ef$wiVX!NR`e+i|KA8_2cENX@wLM{#p!@n0dbXt6I7^2I3ys7~0 zV-J?U`}sF!=3?p%QzNbxq#li=FySQqKcFIbkW`Boe~H2SdkmI8bTHTHD$` z9L;t9&F=sE2Tc*Iz_BZ@rag3AoiI@N_vnjh<6LEP1R!dkUOy8~cEf;nykjTY#oA|) z0Qqj)ily7=MfDbm;jN#rf!EN`Nae7I_IzLe8(r8w5CK!l&aNsU{`2C3-_lPttm<-S zRVLjC9;~m0>xLiOoZVFaU-v8T_5U9pix$5tDQ@KM_{o@qw{a)5G8IB*G*hwuF4G03 zv0%L(7>kd*h1u0cWUoS!E6{zIAj-C*rg~Tj@%2wo5=t6gF#u2rZO$pEqO@oMw@ z^7A?2+j6xY&ZRc3Ke|kQZ!*hKy_GE*6FW)0%;Up$LF4^=KT87ZP4Ztx z{D=^0ay~`taO;CfNx_ynF#dBal^@y3Tq%WjWgwqUD-Q)h=nIkC+O6L#SIEH9Z_Ksc zr^T5_kb_YK2Lft<+Q;A^lcylesXTe5J6>;WpBua%-Vf}R_a-|2E-AWl$Qq-9rE1mm zWbV$Kt=H{3Ohd=Z^|(2TKBy4zkFTI{kWbMm9I8VdoBgyEr{ye(YuktEJw;f^kpP9z zJ)Y33q#MP2xnkh1`{u!gug~NVQ(9@X^WK!LpU7lwe1I!0z)U?ID*H0|0#Ya`{)M-A8ZzlsWb%l0)j#ZRhz# zH%+Okx~v`$P+jWnSj~o)z$!27TuSH2;9Qv&DDJVZ?2&3rV$T~ioRhHl`LjJ=xj~1x zDJsL-pHbsc=43kk)=I#JB}=%A_59|l+gjW__IOc`E>5(^rR;CZ#Xm@Je=tw_{ig$A zk$e_GmMlb`KFqHhTXX^&*wkMOrY$*%qNEDmc)8#G{^wy=L~LMM+?m9$Bo^M{+nYNW z71r!Nk@j&rv%-(f%}ocxS6|+&fg7H5BX4 z&B}V`0zAWz98Pgjd6~MyV;}=htit_>&N0UrYN&?4)%y4L7V=01?X^!x!T=n7t_mfe&WwrULq(V@VtTa&-%AQNNcK) zCf^6skxxu_mnPH$!NUT7S)#jR9U{F>gq)8(3z#x5|H^M=d*WH6VsC7hXm)%ixLios zcikFSjrs8CD*Fcifymq$oAQ@_U;&o_B^;<%zTX2qqjdaCq!s?ruekdl7Sd$pTXfdc z@#%#d9nRW^4CZ(s|5|eO3(QU-)#ct?MK-B5x<)CNXaC466b;YG+TnP8&bG&Z>ypXWHA_Ntck7S>yAr#KGjw@Tuz z?z&>8xzyC!z4}G#zkE& z1EGT~%Of>KKmZbmU#k(7MGK&(NLyD|x9z~c=!xEhUH9g7Ipm`G9y47{TY{PfR7T?O z4Zz$v3rxF8&R0pWHoZu%t;3HJM`Yh?i z-SpH`;M@gseNbB`V+DMR2v}#Se`hhvVISrfED$CsW#9GS9Sxt!`0c9FlqsUgWV41DOI4Lh_D4k9v_W#(JrGanSxP zauWX(+V+^6EU&55e}idigBO45p*1ftJMm}1r8-UQWZpJtp8r}U8x5Aa+)`{rua}i< z;P!eCPz#!E9r^0nUQ=93=Sy2`cz{l)Xm*FQ7{lT4s1BEVy1E~E+u=137Y_JVYF((; zzzOiYjP$4dI^Favs;$8Tjr}ngEP-NzI{$_kP&Mr?mw#5J-Y$QiwV(ZXYSR>EZ{sQu zO)4DLxvKkzB-LE-C=tGY@+USTA=ykF0P?c%Ju+jLj95s`m-F`Sj<>YK^-ekC#5FsE z>GCyvM)E2;VS*EAZf-8~T6ZV4E0b|~`z(XvI=v}UgBm@9af z9=fad+WpnDF#wxP2LU~UGvWSq(oBS!ipgx;$*ed+9&tK@BO~TFdI<8*(=wNYUpq8ulT-pnzQ*V$YJXy>05v>r(!9 zHqdeEzMLzK{qzRgunI3W5t5(YBj)_^*nMG6ZFHj+UaH5w!Z_UI!$Y?Rx%-}QFI9{A_ z@LHkM>iqI{D)94Qaf$h1!DbVGw8fKyP59hfmf(Qiu*SQdUEFuC@4)I6nuHymF3_pa zGpIakWM4*g)PQbvRBxYF2<(I>#ANd>l>K4)M{|b-GiUiuOs=2J$2;>G;y$zyPIQ19 zKdB9SVAJrB{f^{Z+~|$AcW&df3ck}cN#codZS;JA51d}RLvO`Ju!^C-6j6a7eF~U0 zHi^f(nok%!lMQ^iw<&rHz~;NgY|OoGDg=O9npjEi5UZkL&Tsz-IV4!i{(QtHl17A> z>J0fr=%eC*LhYl{%SaCuw+kjDgo zCuKg%gRb<&v1@S&9o4RoExDF=0}%H^F;<(>dHQO^qvmT&j=rolWE|V?mP7DkGmZ1Zkq)BQd_G{*#muAIlcQT zm<9IhYo%&!2=Cv2_{6Mx41y}{;+ctt#{EbT=Sq0u!>1#OrWPUL+Ee~H{tts(HXmHIRBL9C$`~OOea-8Q?tq^&qmO}CcljhkbD-W2i(>;lR=f868hP&5^xWtd% zPNqEOqzj)R5NS1>xLtnm5ocqF(`O-gViP6#r%6nk{>D3}p-v*yJSl8==0Cc&7!pZU zVUG9=VIthSB*jYEL1%lD65r)Wf=l~4>^cxdSiT1gb99Lf+VMaK=Yax^m4k2Xalmzj z78N7)2Ul{$5sgZ^W$H5L-8f8?%@b31UB;JDMyQ>Rx&(9}2I)mAQ4Gx?{^lfUpORm@Ro8rQA% zkLJM2&#$aF`o$T3FSxX0nG;{`4jOqk@AHd<>LCle>oRy^42=&j{2`F$NVvS}*@`^b zs=*pC$s3sAivFzfiE2{7bwp=eNHg7wimG6$Q=C}vam+!%+k;?0a2C7CyPh^6VUvOAyu=fIv*Z1;%6#z)+c<{&KnHR+l~)h*7F5?OG;d+ z8(o_t2|NW=2C~{R9Ixkg3d>h9Vd`67W?&54U|c)v2o6*)TocJe4yScZk~gzt%JHt? z0_kYO^|g)=C8rkW_7_hNQYQ;@3cCX(snT6XWSc2G-=ymswg0Y_-%953oqTxS|9Pk) z(y>sYysw`7uV3EHE3Ye?)(%~ojrRR&@n+DhbQeX%O_!%-XT)76U4@WGpR|2~aA*4N z98lj~Zn%=jfBPa`Fz+0#GceQ-*Dw7p2-9P@XM}cFC~*JQ!+R=sOI`U{>ON znr>F1jwIkFV2wNt)fKqQ)jYQfvS5}l+_gU+e<1cfT|FOO!}PkLylal>-sOMaw#WH& zGF+;+6rji)crhF3!sa{6)!eCp_uf5g%{aLjqY9b)7+0Q16R{zwpPOXh87cUB&&&-sV z^Br_>;~qOQtBV0K8p!VZ&8oWO_(8LwkFnpotF@R0V6_t>{lWFIfnPc z1M;FhKq6i5#ld;XUSd0l?#HiI?Les)!Ism{D+pCj!6O~s`@&vz2M($_dKQ36heb|% zf@Qwig#i+vV@9c>V{neo+TXBE21>NaZ{ArL>0T>Tu^{EHkGURK=I)2#p%+i3oy|pA zqz&S)Uu6dL?uuVN=8UeW&}Fa>HZ6jWImGVr?+Wpyyc>_V_Q)x8r{{h;pp$ucGYQ{0 z3$J;D`A@yhRZy%y>9&E^&u_G;zHWwQ=GmAQI{rPr?u^rlHBch!I}TiS;1^o78IX)S z9_eEp#2h*@jer=KaK8TheVq|sWZh)vsHlC`fuhtkwrnhLr=MRrXRs;E!OP8n} zZ2LV3zGb>t_MOzK0r7`NO;O8SY25 zfQZNv>frHLfol)Pa>~j%4)tbes$IiQl)X%LF|EFog$;ss^q7jhJ}M4;DQjJ8skeWb z#ODlF-N-~%5Lm)lfyz-=8^0A5t=9wy!F}*Jz*(t*Hs3W6ihUP^rOt(&3$ex$gWI5` zH@SirpH>5LPURt^sXG4-K*VZ{ERF1-?LG*wS`broa3FZN=^#{!YDX3NzNAbfzme04 z=DG)`y+W_fbA4R)zI{R+kSku_8`O2w%snH03)37EK{w7<;b;{%`1p3;T z$RO)(jWKasZX?@Iu+v;uk3FhuLCQyWR7h!r?QVKU;M`IxQa)!BmVRB;lbfdmD;9n> zbmKLJbvibryKi;GuwP%1v)SH={qE{yeERS{HaX*~n>$Hi^{*$|>zBch!Ww|=M?DA9Z9^VJJqkX9V%m7BtAvRfzc6O) zi*`f35|K=5RHQ}mf-DRZvV4nGlZz5+KMWC+dg@P{9|IBA0uj%wAP7ZnR6{K&7?a4Y z*+mbblER6a61>NS(8`M6^H8CoXIVQp0LkK@M3@?_6(Yi|eK;b*YVc)y2f6ODkvuP% zS@2*`J=+>d+~mCUL>o zAojf)mo3k+Y<7GlG%yyFyp>plDK+@_KXnbP0{+tooQ${-Rt#H42gZR>%8b)TR$5F$ zr(?pm2}FZVn>o5_JnP!#dQzcpAcFfvQOfy5+u7#Zst&u@tH7JeZ(AluG^y0cP1Gg} zOSGyPmU2lR$=het6sid(dRw9M>$f1c19;u9xv>99xc?Q#DdMNJU;h)|TCs&)FA{&# z68@`Rkhty?2ZU^HZC%`oyb|QS9S+ISWTcodHt+O!V>dB0%`868{=aOCbrbOkp;ZG! zKTiXg;=qaxqftVeYHWs$au_(>Qx$_7Yrf)r3Nt^g28UEiiJ1@<`^Q`K73 z>KJQqBJL370I;-OgAXWgmyX)-SMGK-^dW)SlT8nN z>XsxuZ6?2l^X<)3u3XQ6CUGP*ZVuinXES`i=e+#OCzA`{$CSZmi)d6DDt4A#XqyOM z1QO%1oFGkqn3cqi3V}xz$mi;J#91256lHi|OuRK>HBn0EEYG5%M&gHq059PnXHHaR z>&#^Ez&Di>+)qvgek2o<3E~UAN&N|m763!gdt#=>cXCw{l97?tjfs-iV~Ufx_4FTM zOLbTw!Pc4|5fF@~y5aU`3NS_{Gk-r8z3EY%;0H4_qxLOfhM4lC+%O}5aim@sz`a_-m zz;oG{2ff&1&mDo?-%xd0AcrOkx3ClaPq~0m=35aB`~OMp>93%>EA0P#XPhWXN3xJ- zH9Pghnls1>c&G>F4d;WWOfLYO55CM+9U{bLXI^;GrGKQ3+k+a90<2iU6w)n-QiOT^ z1yAAyPJbRWD$Ii3H*P3PT%X32Pj-d3a&$^><#5aR5WO~&xfFu~BcR#A;HXxqW5&RK zb8*wj<-QK@#V?D1Evx@(T&IB%=Tq)kl=K@ASxK0ec1A;jms&7jnaMT=Apd$P`S z4#b2K#r`3c0#nKjk#9|Qt7s|3g}e#b0cItb#GQ4o3c=&_To&?3zudnaCw^Ros$LxSeQ^_uk4AWl7EO6CadY*-Js?C~I9c>9N)Cs6R84GV8&O}~V zzmHJ2!PJY}`Z*uXs6wcx3MGyq@bzm>T8tc>dHPdrZ;WwF&8oLHf(wn@5W|8^hR`MpId<7dMP1 zHK5fm3@L~GE?ec>jGw?t=|1Z5V*<`*{XCx;70I#X1=1@9%Mxg7o%R%=w>bsQ2Y=lE z)efG&Y!5eA=?hT*>xywbS*B)V!y+ret%Y>)h(VM#my$Tqiy;D~I*beA(0=_-|GGmP z&KMLGGn!Aq_5$o(40G7p@xA#k&;E602k0&yxhm8f{lF;Hlx|YD8b^g4jbB7;W)Yw~ zf~OY&EF!sAg_#QOj$OlJ?JY6vdgs~%fk*Rf{hk6VL##d){Cf&IGna62RTXF~?B z!KhB7MYjvUZ%2Py4lqf-yyyDQ^+p5t99r~0sFITzXrP}0bbJ1r;I7+$utXV&WnkoN~xTo#a=5bAu&56e6MR*11hpy7;{f+ z3zcb&O+JbB*enIXBmD%CGKgH4Cjyn*;Es*3Rmr{FKfOQV5j}VbRI%U1RNccd$YV$P zxvC-|-EP@nbD&E7?~vW{+|YS{N>sR;2NMhiZ&~%cVF5rjkp~&!C;RDq`275QEG#Sv zW3m@+yFC{DKD-zCtw95}YDRcS*b6#U?ki2^sSOi9=&J;2KkOJrt<7<(`^0~5^2B@a z;Yrww1;ci!yz&cP;Po^uD7gu}C1AU;4<%+faDjuC{pFrryKW!R)Vy%im_y`|>|uCh zthaTJk=^!ESG&myJKM*bt}}y&SfKGGN`INhWCF->{*-ETXMO#}ln_-6WkMp!GYt_eo$9oIioX8K{B#83>WiU6^m=SZKUIf(E?R7&&nR+)Kt~{%m z;;%4iivxkfi;fszfc-@?_VJnMBu3G6hY6qT80s8TKa3NFW(;zLq^tBS{-XTNRL>5>nr8z}~TT9&DWrq&5);R@%wPZy;qQu5zDU-|cradfI-ix$`C7)_?m4-EVb( znXEra=m=ZFRGL@Rqv9d+yp!}4d|sH<5%b*MG57Ec+J|~Hjc9&#KR45xiaiS2IuiJ= zJuA0VnFa4{2Rc|;tR8uicp!?EA?JO4ZRoo`up@IcGSoFL9vB;PNf?g71cS)gBct5| z*Qc+XTBcJ@3buLXsR4Y|`n4R><_jl^iXx^A8*zR%)r-w|oRjh~3r5A5$5uxZ^wVwS>W```9Rj$MB)*CJ zvFTYPaipY}*oI>G{_w!qbgfUydVajw%xI}Uzcax!RDNAc{Wp@Za6V}4ZYiw%yz3&O z0SH*MUvo%3)TLHM?yipeS;Yj^;+%+7IM%zSO`c4RB42xW2N6m4?*eNFZ7=XrOHDhh zb_q1jpZ}~vkWXe}9~c88G!k4b)EK4STnthL>{(>zK;F1N#OyC^Y{8evV3uG;Va*lb z2UN>=?k7sS7cp_mWmJ0sV(lhu?~z2H+h+O>-}~%WntZ#?8Hc2I7L)I<_A0IpX1b$E zyGL0+tb3bCG$Xyq9BS9RSnsezEH(Id`Xps6 zpC8wc=o9GCdSYfkpKpnyjqAL49Cj5hqJQZ|Ng%A9=>l01FvvIs`wbsm4WS4-Rod94 zKlEGvU-szj_i-%zPx?UaV|f5%kJkLz1esHs9j(8id@PD!Zk^}_17L4bD#iRS-y4za#sJ^s zxXM(E`ns&=S-kK2fvHbDh^ZF`C2u0%BBs`4#X48J1l-=u&DGp1EKVx=YF})^goC%A zCY9ihAAHc)T5aF0HJ6D1+Alu?lrsGBb9{o&K6gSe5d?#P0@pa~ij6ZXI7No;FqgSB z>X5UM*tX-5diLSWh`k*XBHVSN}5ZkG=#b!q#l9_+`&) zp3n06pP3lrsgo>_!8(TfRev0BjTdTN2fzSTx7ca){cm)YBKfV>zfmd`&Vt_hk7dGX z>hzE>QunwRV0L{b3*X&I_8?B=-M=pj;6^IfoQf!+>1&5io%}fUa%#SCb?(gfj61RI z;+*pZI=6}6uJldmrb@ibg5X=}qP|yJT&Oe(WIPB${#?3#X8|mmTy|BbTDh{tM;93=v8LNV+hUPIBJouO6>Nt z$1$@&(RL@M1u)1Mvd8ihyX?3ot_VtBZ?>id$|&#DwD&H@hyA1G3GA2HRt^Y9g@PnL z^}2B5l(t7Cq{HOSwZB-K8;4x+oh4ndu`nKqs)Nf>*Jq5i{7s1SDO)giRTK(Y(VKWk zG>;j!{h7~Ar$tXn(6)V*pWSuoTI6gw_daMyeI6G~L%R4T+Ew*ZO43e>A))qbAwD|( z+I>DSV_;YxNuut}44LC?1R^D$sbC+zAL%IrN)8?!Up6RHm(w%b&3%v@aXu9TKc|(EM%hV2rT8+9L)5JqqpI zPTzx*r~E<%oNoK~2FD`U<78}7Qt*FVyhWyHUSq(j_+mo-D?J&LEihrxoXza zg&fxLItJXXOCBhEkjuVZGfHUJM`N6>C#pX3R~qeoa75T?6G12A&|VI4G{kR>^#|Z; zmk{Ga<7J&q8jSvZqoql2ewKX~mmvHGsoOtGPYy4_^@6Jt<1wK(WEM6%c(yTCi3xf-0oGn+pYjTA2~mGm-pvkm3KFCVrq0I` z`_4!?{RYHtdpB$_7m|^3D*#4taByluyK1%2PTP-IYF(iUkNebukN;-0*}$FJXZIJO z~Bpx1@&^U?ZqCNK~GJt`2=e9P%ms) z=rMBY3TA(MwYeqWh9R|5#vx_dlPRmz4>P5iU?kLbh;Lgc?*m$i3R<)zv(%df%#DJ3 zAd_hQrJ;{o2e4a{)3IThq<)R0?3A(-3`9M}7!sSgp0u=JRkMnGz5eeGcQx0v9Cj>L z(~B&S(eZR{(V12wBo~t4IZ{^0K2s{}+FH0CAGy(YtM+b7PfmwK(H2$deo(mr`ccmb zDquN%Wy`t$572uUBd)sf?vp7`@zb+WeZ32cRZ8f@qFhanN1bx7)cxNw9KV;2BNbc6 z@4s>{btsJL)1OUeb8s%4lG8T6N-^l&RiKcHC1e{)R#& z`ivMLLz9rW`v_JnMaJoUOjI`BtU!z;13TS`z=z;7X8Rn|cwG*AUhp+_s*Z;wx15Sg zUY#j1^>EV$Ne7G|bHawdgllxOi;t_sd-dO#d7;H{&)0BCyz~yrQhNH3EQY=oz6WyV|C=)DM1|nCbht;m4xwRP4EqgOrHF;rQFLi|x z*&0Y|2ZCfS+OWfQ@HZN3kYWe8cKUtZMzB>M)@*U(YA1bAX9hAk>vZ?|gU57d#HtrEj3Qf^qHT zbtD9x7>k_T{_e%;>GEoFp~;Ok8+@Y^Nh|=6UN9a6Q`$U->_OgY{Mg^1ENssUcimd# zpL0K$(g2c{US=+|0?hcb;Ai^NSDM~ZADijxh^tZ7?w99~5`r3K^O?^(b~930tO$UD z)Jby4cZCIpiD1hGtlZlQKEc~e*wA3PMoTZ%TGip4R??$t-YqnKF9P32SYGGx{zAH8 z4o?@~bDxqrAGo$j7_Fw)`8eT#)wFKM`@b*=P4ESK=6_F}iN=#CJ+2T;vzz~6de%>5 zGtAENgyuXs3-VJ!@ zo1R!t$eAy<7z-N2`SbcMTfA|^nyaCc-ZWL#rqfF=V}V#lHGP~^V<<4T-YhS5vR!5z z^}0@P6fzqhwDo<194Fj**?C~pUJ1Ib)YU8WA(VniFq0Zdib1r|E|1e}RO4%f^--Rq zDGo`P|G1R>{yu5eLhi<#$&aC8HFH-A3@K@&YemNBtO*HaWrBb*!M0T(pn}vj$1q58 zPHg9)16#wM_s<7AQ7g^T@7^VUv`r~=HC23VvU=^BsCcoOt8_m01}4JevPd_iKQmNC zRR6j3wlqz3iW+9M8S1eTFLO)+S-&E(!JY{%m-C2^F$@YY?`#=K6YbwM6xs9>;WeRn zKLyZ?Wn5jQM3i&%q<9>I2JYjtLv<_w(GG2WDADv}!&-`V#LVZ{m|}a`O*0)?(N#P* z;)aH?eK0(d{-NZWT)_^h-v?8q4Ts!G&SGnoSG4(;KlN(A(({x$&}CWG!|+G>0JT3p z`3mp18W>VMpu2yp@6wN8?bMARyaM+F*Q@)EgXJ&odE_syF)Q}lKN|RU1w<#MN*dL7 z>IY2jvJRx6rfiLpYbv*zrHaoR_&D*8BvxmZ5Hd}&wM7m_BPm=q)zg)dQvJ*K%58Ku zrc|&)Si4^&6)sh80Gzgi>3(=RG4MMd_G3p5lwY=xzYm~RF8i*Z$YOx6>B${&s5G%| zUO!W#c|SBD7d*R8g1Xxync-pu%4*&c$$P-YjC+x+TJuNy%M$~`IQLU&S;nV> zd!&DpQiA~OFr++g6%xQoI1NS1#K9~y5r!gB*+%2dDD208e)=_-;Ttv_| z+)+rwKq^NlIGj}kB5U6smLw0x0c&a&Z;y+S7_7fjF9uC-6?eLO^a|XW-ZZ)2CbaDT zsSt^RdoUR9^>C`!$S6{r)hU-kx%yGol_H(IOcOAj&)e?7Sp3FD3#j(^EXZ2pl36q( z!Xbt-AnCO6x4Hgp9$&O^Qu2acv++F4Zc-E2^!|Z07~UmofdL8o>gxTq$N&x1vNE9< zQDf}L873;U%aim@L-TA0=T#5I&Af-I`PH1tOW){-cEAVM+(4Tm6*`s{@@B9Hf`YK! zQEh!k8$3U0f)-FVgAGTy%|_^MJAL5oCAq8;VHCWb2Gcnldf4soycs-u5y=q&d+(!1 zYc$FlZIg8W!=Oru^6YWAkmjhly4{ST zw%=6B>Df~fq(vRo$QNUmuU1|1mpx|j^1(Y`)XAQ7pFqcT-xISfS!oI4Eko06l`xH7*> zYC~rU8p0b_8>X561X(o`?g#1-zeV%dd1Fa3fK+Ix=KJSnSZJGt^m z<+g@fD}HI)xq(AMXJz(COWi>sVNyJl1)$6HGgBF>!1hd7>M}geWp`Qluf&9P57?lD z)U9`n^QAGsA3lhaQ8|7Y_HD%1L^W&y%argHtsqljHPUoWYk%5oU*t2ToT%x^j*!C! zVglgYFfqoau(i3u^y1(s0L&kOUHJ?My zZ?%%YMdC>CLQl+$(i6vTdz-)Gk%V5UEaP3Irx7cbETJ&*fCDl!!P@S4r_HxU?Lzk) zkshb`dg~`r>SaH~M>H;&=rmg2laah|Mis!{?bmzU?O)xy+drgmo}T7DX138;SPFb> z#M;?xRTDCeoQZL}SaXkYIkm1TnVk!(emWd;AGAo>R!k9e?yw6io{gSoyWgrl9|^jh zeqHNvw&x%AX{{0muKYP8BeKS2-$|%G-y}|$ZkI<#{9$A=`>K!&upRq8=jH@CctI zDXv^Pr)rw*l?qi6d0B3@!#mVOEv_x8lm@M~R5z3JBA~X`3Bk!U{{HGd*BQp3w6(?) z`yk(+q_CpH>*I|2m*pNQ)U~>=OwFR!ah%d-DT(0<5QBUr>?9<)zpEISb4_BUj`nqH z;JQcL|d_xN{yIY1R><*j2 z`#S7AQ(8CABbLF#I=*Qu$)%V6`-3ni6y7=s1^208g6cZ4r}(nt)uzRihf zl8NZt$PN~MCUP4s82};=C{Jo2;%NN9KHRhLo0c>bBPT9VQ=U7T`~h_o?2QY4d7zxg zUWttSXW6V@=3rq#!AOlwFU!sg;zusYhqK_;2m)@lh^bOTFOfU~-yiVVY7;90^_$Ln z`J2*4YRciQZXWM=3l-Z5CVXOboAl7`1Db!$irk_RMIe%q1s5|fQSg2u>3n&4t1J)# z#Gz)j9p+gB?#{Cu?v@J#zisA`HLPbPuhXxmip8}A1)pU9bzBJtNu^Se@JBvUY_BA& zNXpp7xOJeE7x3um(m1My{!UpPK&LIadwwromaR0L@0;d`|CY=B!iMOuM@ySYro*aL zsi+uGdW>Ln24xJMwF&?3uKZ)FW47(T=NN(D2e;VAY9#SQL<|QOdlwWe-JR4= zJt22ng!5)hiN5l>VPd(`PQ#$}E4qB{D0lUG^`ftSYkIE=G0v7jYd`Typ}sg0T$?_RHjo^d^q8C+q6p2Ig3kHXSRep!*hU7VO6UY zY&e}t`8zKR-8z`+Q`lfo>+O?Z4L%9>*;MuT?pJSf!cV3lP|3+o-H!nWZzRxxG;GL% znr^M{qO^AXJ{QT#l>knHswr7`xDs?AYp>>3hUl6;inUeRJ9VLwY@r?(8#|TiiW~wb zM0NeYR5cYg!K3;6W|5^65l$&jmUEOS8 zJ#Qa&%Ci~9>>F;DC(YE?&VpF z^U@*+*GYTh{n8jhVqQ^uQ^2Uj%ECWa8F&j=4Fr>$%_XC`GTx@PPMzLyI~pN+-h0)))I2cw50K@v5~w|w*T5V|Emk^)kWIL()_=w>ZJtXKj2j`R@0qV zbM-mm6KvHJO0~YAxq~0n^p5sl>qK3!n&|nBdY)|+kjI`Ysr_KH$=z6O2af9~TmUrg zXj%fW&nVvPCXfH(<$5+yTS2FMu-wF2uA#O&Z!wnY@9re>Y}{LX_DxFYg_nrO&gKr! zM#XsFBqmP~42{#S_2$FDiTIJqAiGf55mW0|Nl&O)0u(ycntTN45T;lRfah$sGHQbz z_3sJXKaUy8L}mSO!MU{$N-M-aOF^!bgrwdVbbEBJ4LKyUfMQzDUt zy7%2;bnxbdm@Cyd52$u}$d&JEXV@VO|K;U{PKzH6=1*ATsp=lAQ5E4rG!kf1#OG6c zYl#q@6B#_36h8Zp=~Ia*6+1op-UJCW`FeeGaIxUxq(uAzdc3#q4iK3j@;B%t@Mk{i z>^*&^jm<8Sz>oa7CFYL2(cD1J+^8paVxnhbca=CJXlG9)|+*GWT=oMa?L zFx%#LYZb2Nnltf8V#U`T#~kgALf>-}7-Et|)8ocN70*WNQ5&V;7r9;3T2oO(RFMU% zQFNYb$B362>t@8lr!N!B*L3!1os_40kJug1%-;A1!N9dSRF6XL!JN&QeqcA@| zipy4Pav&seTVjsZv8(;6$axm|jmRN{dJr$Ktcq7MN^1DSO5LjoIaN_rmt#SC*wkJxcl$U4pCHjufvTcx;U-lm_@ ze=HNd_;Ui>t8yD_XmTnm(VF+cj66cLc566M4@t{dSOh`eU5E^)pwv^3H*gG--p{5~ zwz*Qgr8#2^L(QKtQL|Pwi4Zl(T~g>OrFN9>9zj1^{!lB@zVVG65n-m4=xvQv-GA;U zjbV}4clV>f8t)$MC$=q>r<-fsg_n7fOkUr2AY^(OxrtnlzVI;x+Re=whdT*=ocP32 zZzF44rkl~ zg-DM&pL@>riS{ta`_~$X(bn(JJ36NT+UfFvgJiF)74(Eu)YQ`}3lrSMK};2`Gc%5j zd36tn6n9HkO&b^VTG%gKhY=ZF%9}7?{434ABt>0G%1$EVu+t0*+_sTU%0X~S?rAc{2ff*GQpCRqzv@QjowVi-5RbIVkKH;s9NTUYJN196 zG2&1szK!-aJc^7O=rnSpyy{cgI@~crMUyHxo0riQaX%Ac>XIWr)~eLTKI?q#L{jIr zT?xBj?J(7Y`#~U}snE+2gH9TOYs1q1j`!pZFE8-FfFpl>YNS~LT+h4VB8hnvnNIYW*B&}pzoL}9h1nd1cRtJc?8}SkkhllfeZc{Ycu7&MDzi1>I!A~h>7gzNt! z>MX;WfZM(;CDJ__q`RaWX+gTX1?lb(kQ^!9(%r&9x~02gjFfH|{m$pP@8|uvj~vJN z?~31fUic%~i+SbvI-c)6hj<2msx>BL{*a~0Nai@de;Tk^DhiX{2{g|ixS&CHekJFB zFSb{8t@2T~+(cIN3iaWZ^jqDzyycfKrnBH9*x!YAzW5vLaysTR_jQV_FV~v_mVV@T zPESpZ?nAyEZdFe?gcYKhYfQSF)&Q}*TXtOY$?~ysl(h&$PkCKL$Bym57++Ube;dr$ zC@~-mCE0*bn0A#ffpFS?v{%k79=X-hkGJ;Cq!bMX%KeouNhU;pYh zT|A`ZEZ|>fbp?icUm7fR?sBx&`cIDPl*O4=DEjJ?n3tQ(Xy6SfD2LLsxquPkAu9_f ze<`45(<*3O7Ka7`bzTv3Y>YhcQm}oNFtP}vhoILj&li6v=H5ifB1^3=;X<72^$P#r z#OappjUHDHJN2jgTTJglAYuv<8 zub&^L?c{Nr9bb^Up3X5Ao?G#!=d5`TdAbdftbcmu$bPtOJvBJE-@c9|;SHngnE2gj z1l@sslOe(!8uRm4$a=)Zs20k4aa>Q*P5KE6Dvwgqy>_&(6# zSl9otSWS)fK8xM2Hyc-o9>q%Mr4XdseCULvD6j|1Rnt zC+4Ss_-Wp5UaGR0e5&QETQZZu$M16NrFdEVj@>LAF+Grg)fj)23c^LcQbzzOfK@+M z=!R60=#DMTV`~ZLy0xBkM*ZtXp%429M)EU}Mfh=2#O}qKl|doKTs%!}$9~~T)8XHi zWTL)gaF`762>y)XXiqj9W-NxEh7YKv-M;wQ)VNTwR(KGVZ9UCF&IS1m+5B@u)>M5>$ONe>iH_5y29jmC4{UYptTk; z7=a~P7~BJAL?iEzHSX1u*dl@6>gPzlHY$Mi#1JvaV_0pFgu{ zRiM)=XMb~C|J}Q|#C&G%+`69rd!Mq;OKdf@x_2y5g|t(#^n^UXc?dX3)OjUXZ;qi{ z{k(eqRRNXai1;AP0Pcw&8wV$N5}gWBoD{U--`MgRd);-VycRGidbwdc1Xd$X@7v}^?TZ9kBilkmn_(d1CEzroYSA~&vK*0 zazl88Dqd4&o|5v6AL2HUaKC4Z`1gKqe^j@IJ67O5Qp*87!9pWLolT-EAtKsm5~5X~ zOP?Xk-7ia9iVS_mIx!}(1Re@1ssuD=w$+FIT(&Y(Et6VM6Ku`GIkh zkzcPT_KVmsgROC>7zVu9^Oj2Dz%`VaqiytwG!|YpN4acC2yKR^2gyXor z2+13+NMZT6Fp*d4@CE<*f<{uTI4v-f%xEQK5>XdEi2Uc?6o_A#)jW#BZipE_o*k`U zUBm0|gK~2*(4DD-4jxD{`IZEX*pL>4NTk{y;2BqB+gr`nYv}xghhYnkq6>=m7C_Ls zniD7)DI?~WCJan`m&N}Q3)W#DNPKQf{DB{T&9f0VkkKd)ad_@gqO`)IN>vM&50e=+zVFG$5AA8GxUeLHjwPxpQmOJ3C7GBtr!m(jCaOM zgw5@_aRT=6WAP~0W?se6eZ7m;_8qcb2Osf<%=$95sQpn;qq-5|V+W1yFcRxMQfJ1p zZ!!1Ab0<<#FEgHcvG8y<(aA$!?l4nx1^o_b#d06`0RH8jW)ojSLZvt@cdm$@&Ydlb ztj#Y9&Nw}ExZqyq`oEHX%onwJSbgs7g|i6gl|xD3f9FV2{=I(Dfgm&vcWEWKZlQ> z@1WsLH8>y(9c?byt_BCoItJ_|nj! zHOhA)^Q|!lNdV87QT1EW$;hBmz*%o(sj(!|ZznyyjHONwn!Nx)yw|E%goEoKOoK8A z+eV8kW~K!^d}w)0NsHH1pUq-@W8}z^!t~lQ<#wN!alVicW6fHb2rM)%DE<`Z8=I*{ zw!t@{WRaM=9*R7bh9tmaQcqVZM39qy{n?E!uKu@{SaMzr>hIuW^ayhnvkeYptM^}*6*5|SQ!=KA0JZMF{h=XINT0sQK$@6+u?xlGEHgTDy$ zZdaE43#c|S8?dwZoiyRe(ia$uBwbUjmu*UQd%4zHU5MhOT)rL){0)RYB2y*5-JACkBpalssx?9&KS@n;rc^G+nuXwL)@MM7-CDVSP4Z9=4*y7{v3ExkjEtXo`NVY)!C~${UyhE9hv55yv-|kLJC3dW=Gh)c z$&ZqCP1zxcQk4F0rXE*ELqM&U8?G$kA3rJ>UiG5=40<2i4S#-G$oU}N$q8&qOq4Lp zcBK?W)zr>2`A?rk2iOvmeg+-zi`Os&ZjLj8pH;9r-q={K>wFzYaK2B zzVqJ0;UtC|wO-hPQUkjpI{K7IX!xf%UNH&wH>C!8wTxeNJ%0v@oMT=0)iLDuG;(wX z=kkML<3f^u@ETlj@P|$xHUUvK;zv)10g#*Zc37#b>C*Evr^k#U)O!3wwwMdiC!UCl z5Z?)Sq@LC+cH_N0mi9lR3%0BjX_1(7lH42uv+lA%-ia#*WAq^89?jZr3FP@6HXxXt zFsCs)Qe~`nS(jmAU|J*vA}jl)S+^iEZX7>|{@%h|9pZVFDrgv9kraEmU+fMtaG1sY z1B83qZiK0mW>?j`0QpUX2D{{Zdt2!Vhm%-b*3~P6n3S6v-nH-&MT2}x6}m>@#V6TY zpxU8r^j(eYH0kX6bS7OdYpdQjF zxs1zOHP+9Yo-K_`$s|k$3Ku#Q?%!pGEcI9-YC$Te*u@yz5h>X3op z28b&y`5nT1?2%-UfI;wMI2%gXRROL{bZk`5Ue_X|JC}{8W|p?PtBdlG-&S@K$q7sL zF64AP+{4ag?;1rYZW|;c-uvO zhAeyEXXF#{?KnO?^}*x7`IcIjW)jBW3WO@sKEu}rGhNU%VpyxyCdQ;FrGMplH7DUW zGjkL4F|`PKUUV^{YHXc% zK5T@f{rD!sc9G0L2{V*X2fRAAG=3N$QEm;6&)=vr!QPmMF6h9)a=Bq+Nkjc7k*r}q z-;Vb?^cGO~Me3I+=-yP;cWVnw{N--F(d+o!+-;5~!n(sWzfUoj(fMXKLS&+nS2kLa z;io48;+(o#B8Q1|nnto|&@H@Ho<^Su$X zCA;+rh4*IzC(KXx7ig$F04@$naSkf^KwTbn_4MAbY~R_aG~*KhX@z!en0oQ($O2s_ z=7#4$_%*B=Tmq4T+0sK{N3uiBu&&ci;s0-!0G~nQ&&Di6vb-%zzhn13w$L@|(?70ymcWWC zR)%cWDHorF>>nsPd?xz?9#;3^gdHvKDwU$_biZ3bv|NKhX^;=c4cL2W%1Nvdnou^p7^t)d_2d=XpmD0DUQ3}Lae?UCbi;8Iz;`zV8 zHw|O4t^NwF&5OSdZq)_195lTHGSZz?FV=B6{yw45tklD5I^>tBJQ9k!A!4U_Skt3r zfY~$i&XD5S92p|q{EF}}1gg6Eb{sBTeiSn8 zB0%y5H&obNK?+6!numS8@0fZ=C*gK@l1$#z4Y$t`eV#G zUYyqq$ekTG&@=c~=RjtajUO>#7IW*YN%=4JG_wb?uD0|!jfuI5GWRPx zdi(qIz*A(wGL>UyjBzdH=sb3K9t(f(T@I^EGxzwN=JYaDG}eVrDsEeb{s8lBJ)6JM z=;Zr<$fe|X!Wy$CkN3T&UGUSkvZF@3>yuoTyf)FbYhOsSUi1|MGC#FexK2hKSqgB# zMQ{O7LroYI;a}10fxQJTv3uap`~Vc}Pp?(uK9o8?&L0Jm>M$!<>8qr$a=-PHtGu>7 z*Y*HR*sjHow2B>84bj*mun@YQOV&2LowBai++ZsiQ#4_}JLWr&#d5d6v6E^dr}~Mo zr6eZ<2li6hPW-D4Kie$UX0qfInb)-vmLp!)R5O;3I5^A{UGx~FB~=Uf;a}GyApTd} zUNw;S?c28hZBw%gz&HQtSqn0p$?Sr>iNp0sP>RSx5$S6Ge$N~KDQBu(_=#K3dvKMwQelC|0Lt&Q|II-o}S%n}?>c)R2^zL`1ceKUZ$zzek#5{3mTMSvNTol%Q z%!Fu0qgZwL8nW5TOId_T4>H&-ugp98V8A~qYw=NnTJbTjqayy zs>bC2wXG|pcb{j3Q62ugmK7CTi%9}Tvq)n7?q77^GeK?CxM%(TN47XRMP{wP058sM zZ|)PUK_T_HVw{eRml`oYqO<=bYjzzk;rLSA;H^l~NTJ^Kq{WP`FsbdZbQlXs5!3Fd zd8(=Ue7xQv^^g-L5%91c8zCzak@bin9l!C+Wk2S<<~t<%4h<_!=)0UOq`B?1uZW2o zb}xQ*s%c*dRwET(Bt;pmHg8@Jwo|V`y{dV=f6gKV_}9rxA`;FK%FYuc zrw&Q$>qq|@{Q~Nl1e-XTIPx5dKd{iGgz>wp^FrhS(y}Q4McFDGNay7_;FCH7pxt?0 z@5wSceJq!Sr19C%gf|!cNXp&W?>=Iv+3;tJeN)6x@-Gf#H2;I9;xFq$j7AkPYf{a$ z_ChwRLs!IK$53#l^)M#O)o4wv9Wo_gNty*h91E$GJI=M!X}koJGf* z-ApPOnPb<4X%fZfc^MgXR}y|?$85`CQSm**7;XzmuqvyW$On~OkEo}}H8%*i1jWBg zXc6g*@HY|2>`yRv&4UY<;oR`pPiHkW$B7>(c;Mq5rTm&|>+JhP_f~G-Z|r3ANIRNv zvu^=3*YQbdvOvsz`dJl_IAa++qu|j%ozlzwVcvi1%q}di7RfUU`6ZAK5eYgXy5k6; zP`}fQPLMQOrnt|OzM)uDYLc4Y2q~M{<-EP|sypAOgWjeMKyUX4pnLn^^S%Nr-Sb%| z+?RC@#S8L#LiPdy{9Cp#wx8R6D5X~g#n9U!8KUc{cUEklMiNlvndr9)g?v1AWpIue zS1P2W1#3?X*h9}RW%iR&Ts^8WZFvZ#oMCZ|3%-xi$0~$W$t~}27poFD+&QVcx%T?% zFpYMPV}ML^%(k&nl!Y)}*fs903CG8iVUuCNKzoOl*_^LeYP7hQpwhmvxo)T|n$G?( z=w~QMyOWIC&qpt$^~d?E)5f{B0)3vpIjqiU+Umnf$pZQPZr)`3GVZ7Oej_APZf;?A z{{p%l9?Dqr#`@lM^Qaah9?qb|=a8w-ErZAAXaA?CApAZ9`T1&?VEiF#&_q5GRYigM z_h%oASs$rK1}1E)v=-ZBaEMLn8BkSqZA$CMsHapjjE?!@3(4Boa#3pji?Tef!j z2*z)RuOrBWNe?3*k7_%6%Qav_$Z~W_L0k+{K74+IS>mgHJm_O>m!+BGNhYs%c1`We zl}hUbS}+zSaY%FubJVLsueQ(A^Ye`h5~hxN^zF;>>o8LkU zr#)c(RG*#54-f%+DXAwadI6$+YlMs_z}Jol*HS8jk#ecZP;Q=&DLZKf63#L6;TztN zN`)za_D@EQ`l>YTM>y7N(;&x3RC+EdxQvX$)jqi3k7asoaIp2@z~r-0vA&12w2azv zb}3#2=4s#ZY-!7vckfW;iYs`n6dCBbX{1=U&VQqW1PNm?*- zGxoCAGRx=H|CIdcTrSxuc01VivgXNOOyGiTU|zuKk)tnd-I=FHoblnU_hTit?}GPn z-Bft>AY#P#pW`0n*d#cgo=tJMR!@yq|BPEqN=*VeR!qQJD+4#yRD=fg>SexVuCT_j zqSsJKp*{evmvEH{(X(9yP?b-xpA{b^gjl(LcyQ zLnVsu$YQ{5suqiT8u>1^pn;Q#r#q|;8~H|boB06w{x*_3} zIr1c*iazxs6$07JQn0NyOW9q5sKwh1njBOh{w2<+Nl=IJmJ=oiKh0`2#qTz#T5mus zlkMFBf3@O)RNqeHNrsU$Y6A>L9&x$v3dD9b@DUtOLo>Lo4-3D?ajA%Xy{;;uZRylt z$mH=|Zpz?+wg^^9) zOf!F&UC*Jv(>sL32toYe^`JuH4CRv3ECli%z+M!Ds5j-X$@b?0#!Hx=1Lo?wzsrc; z#}CHduTn8jkG*QBIw=|JMr^6j82){t{iq0MAne4#zuNGXhD2Z?Y~A6I-s5 znw=OvsE`waR9d42SA}5m2uwL?CK&XP=}g#B=R@@Y^GvRSYRha?Byip~>QVh&+soVg z&6KX2=OLK>JYOf(z_E3}8ID}ovtRhE(_nM@TUWL9`E}#u-gm5kYc-l=&=^O=5jx)H z*Ya}n3;M7wuD>#{NjN=hKy^z@iQe!H5>D!feV0-o8HSn;GKJfl$g7QKaTXCbPoADd zn!QXl4nLat>f%;QO~|PDm^KEW7`xvslhJL~z8sAQn?E0FMFIuUK#F>yW_HS26${9v{J39uGG!o1>jdp{{COQ|b_ zvwnMgXu;Vz`*^SZqRHRv_|ZqbZ62Utn3^*4mYR|i_JOj9x4emv1!=(+yIW}|?uSC8l8fnJr{&ZcouQOQrU zS#6@HKihw&E3x21B`qt{-K>?V_`;8h9|lNK>g#M|ZUl$a0t|Wf%!Nz&2i~%>Z=GcA zWcoOh{cdsC)@ObAO7)}6C_6livUoIA?p`4!MKyBEarK)2%V$4AAYnj!`rpPGFOmHV zvM!i77v=?bw+BCgBIPb6?%i@)4ZmW6@)PLG9<{q=6c`;i5#{}BcYaE2_#XFP6h_9! zrv)62!B)#IUWD0-;?>te&$q!`xZT0=A}kq@XINBp>IZ}+=`?i_KX zJ_SFe!Rrb1SzUN&UBDlvVL2jD8d3s4^(i#6Q95(ao8n{)G@=NfqS`TtIvm60HdnMy zR7+oYuRrUnmKYL{C{`bI3evKpeQ$PLrd?Pj;dKHcM~H_VwQam%5XJKkiYF5@)zybQ zl~eGQKkV4C`fpzhP9mbs9(z(o+a_A) zJ4CRz?B2FbS1+$%J#%5k%*pkU9Y0< zhMUL{j!l=&I@rbF|GenYIp5eEyqYx5WU0jWHwokO6Juk#a77S$*U;3^5nOCQ%P^pJYtn z12rRh-?3?+Ht7?XKj)`Ik&yG%(&EC;{97I{Mztg@%hewk^DUkqZYtb(=_J!?4o7k7 zy8>Ajlxy)XHzwa#8R>jCUZj%~(a1h2jqA9=jqBhAM3|68kv|L5IGkZ3&e_FC_y%R< z)g8?*Xj^w_n$ep2<`hc-fU<)w}*XZ1$>xZRr!yX*U;tH8@d0<6)HvHUWG1hZ0Vr9d?^rC z4B%t|t0&JVhFmm<;H?-3)E#x~2R&W>Sl$Qwp|LMVZ{tRN5Tkv*niNmW^z~>)J%1?) zY&x7*EBrDJAOEe}Fj#7LB*m?Fw0_w+6eg12VLf$N`Gpd-0d~I*A$$saxwq~s9qIVt zel|^0YMl9_G}%NV(LiFprJ0z--QF6?p1b+yojZwpJcK1(AvnDC7FV{qts?JprWfFq zhq5-79EO-<4eaOnN5%$K%lI3ji^>6X%d!3isq)pee%Z`Z1U!Oa)eLz&EH)8qZ4!vL zc-Mkt#WMeG9759?{Y&zBMye->$kV&OLguqQ?o7`0njXB{AcqMrVb!yLcA54@_+_zw zw=56*Gx6&7zE9m@23D2u86O&iOLt?#8G zSkL={(Nz#{$wk=Eo9jw)h7| z?01zF>`uX!h`S$AFrmIwy##o_C$4CmPOKhwX@i2Ru6f3?c**kuq3oWH;O{&Ah@FDe zV+sXAFZJdqolnO!_J*$vVp+GC^eVmt;E9Z|Jix@jKBdZF8{Qz~Znuk?Zh38Mw3|_` z9~1Ulb~orJ#!`i0=+&yTvq$uW=eF_h;h*4+rAE6fdxV|yi+@U|EgzE7ZTil5Kje6c zMPpE*1t@F!AY81)qFXhF_)%!E^MTK?GoaxWq|zYnn4Ll_eF_$f2^ z(HWDb>Ns)gk&q%rbU!I8NWij`?p&Zew^8k|%cwrxKZQRZrJsj?2m!-h@*3)PsZ3vc zwy&SkLIw^MuSmdXDcUG2Zz%1UNfxf* zpc!RidCKn*mv-SR6^gN1AdyE3yEp1a`2rs7a4rokBObety$(P7w%5f* z(pluXo}O|<{owbN^YBMC_a}0b+2ECa;BM1B?F<*fBA?NN_63otMZgxr2Q|UUCt8D6 zo2`>h?-67~;+l|y=Y9+7sW#2uV$PKCl4wEX*VZ^QRy(!BiXX;(NPoR4?JqMb#jMb( zq(5CUL0wWPMf_yg!D>y)9Oz`D|H)%emL|-26o$B>(m8FscQiP^pEU6<&2^@u+ZsE@ zf)ohKBMRtT2wGN(KJCU;z6BaxYE1EI+J}7si|tYbM6KG5cl1xb*ZroE{xj@_p?j%5 zJR+S}F-QDavxAYdU3C6{u-Q#))j{!&8T? zPBLiLB3x672hq!WzM~y37ZXc5zt5_5HVHLb!m>Ci#glJYn9v0FgZ{9gHR6w@GVAKPTyKg!HF_d-zSyG<#`>Uh zh;ie(b)`oIw1GycTgGjJYisjZ6LerCC1CjRn(`Y%UJwCC#|3+?_Y3bYn?}!M0sU6ZYao zzp3jS9^vXSA#fbp&XAFZSp8)F>VT=E-~&!opS@c;VWSE3suv3+G#%%pP(l?-e%WQ(9M&@^Z6>3^P4Ia zF39fw#c7sBy~nJtWl`zoak+)=!;z%Fh!1?pXWvhQ6R;iM`;FP#rjh%4qkxl3JDQ*jGY0fj|~J4Lym|YEGsqX z=iW9RO1Cy1lk1?4I4&VF#QR?dVjv>q$oK!yuMv$@!76EGNM>&gWAVTe zcv}kU4r_oM*ch&+?NJ~r$h@TzN#1M6rpyfWhwNLYgn||?^J%E(2#aZ+u>tmS%kq@T z949Q=F0^tZhQH-smJ%E=qzrAb<0wQGx0Cl7d~dy73octx4~;)rC9_8;x05eVf`fp5 z59{G=ur0^k+B9M4X)7s%3K`esP2^3(<7qnr!f8v+*3G~nSVz4}@IYM|X$(H*Sa7UG z6aH5Wvvmt z?w6fe4g44m>VPfYK+tv)*uJonEV1E+@@C@{wbvw5z65r9yvx_&`!9PA$NCRRG|H?L zPZXSG7ft6ahUO?kq#Ik&Y)$mjuRvBP?5!lj^nJEetkMBS!bI+auXe_4W7WCskdyc^ z4*g>=)|B6n$b!>p7uea`OqZ59Ii0Afn4r%D+w3k3^9qf|KBI|~MPO2-&q*~Ut9paT zfEf)h#e+Jydea+4M3Jo7*P_?JhJbFxb_TI!VKjsU=zM$3C4%TQ?vej8_n%yaA>V(G zkCgOpVlg-FWh`q~75LtzrR3r}TIVeh%7OI?ot7+2}F5^SrFTviJK zId^BP@d!gd61HNB8W1e0boJ&p)7uj;p+XI6jX%hhY>|I{Zc(aQMZ8Gm5Cbe78y?vs zl4>(~n+=<}6&m6X)RKlrV*C2ZXVm=(1~L7BZ(-IJHoUzQz&RNl9A9NZT^!xjVmH`? zv=dPCB>a*U{`*@ANGF!|id#l9?Exr4vDfIqfS_`e=!%V&74KwTl z6w}sr!GOAADz_qQP95~%ZWqXPH>y(SwFscG)}r69Ib`a(jCeFge2YI(KbB4?Iis;d zhJ)hMKO-wfOYy9v5IK+^;CFs>=XNnrdS-UZaAtO2i{`S^EhfOtUF2UwVz4HlSSwc= zM=520P0ZXEE)-kyk(30@YUHvvA)`?8rqMQ(cu=R~k*~I;?|X02XM#!m;B=Q(nJ0eW zVYBDFQ#zN!2W2whime{z1#N{iCg6xx#jF~FR>izT7;4H_idbwjVl;l-vT^YsaY`^p zdMtFwt%7wTcSO|@rZx~fv`^I|6A%Ud5D@0w&=R1LnMzE_h&wTO8H`8Ur+PU4O5E4} ztco2=*9;p^3m2Ernw?OxoX_^wLMA*F#O!hCR!=0&CDBt^A8=+FRB)%s;zhZ=3Lo6d z9@)3EYVgCoz^KW=BPvZYD-Jtpc^X4;X0NA4nv3}L(i%;^N^2`;#%rR^j6$BBumd;> zbIeS1SX0ksQ4w+?p@CjlFb=q3rcz|_xY!?-aQkC@dv`By@K-F$f~HhC8moib|!N?J=;^GS_1V0J3TLij~#zg zim2$Bg1!`Len;S~L>yl5IZRZ49=}PfSb|Roo)Pe-CeH#nrg7FJp~zi?*Sh%z$`%}C z2sJpN#hrpb5Al(Sw`+VCBnt-d0L8pgdqGiTp4U0;-`(kIF`SXC!TmeZhSwLqhIRj)alL*eMU zRLI>PF3tT=bLkDr_Ij>qJL9V{4)FHt_B=^>N58j!@7g&7OIcavze=S;cLyHTKS6Iq z`x}(X4bEh%@2vZ}z8H}Oy;=zrPLgoplf^SkAU*_ze}Zb{)RxF(R{nm**GNDj8(c+& z`H11gNzTA+UZp`>q)Z_GK~W}rC%Ex%a1wc9gkq;RxJ&>`(Fjn^Hs#vEA&;g%02zioHYP1rFPz|Rk$}Mk#s6!z;Ov$o@O*e*;I&r0?q=O6C^&4*s;d^h^W0X zcmE>Gtehtjp0mnlHsFNzFP3ldG~0LnVo+-~TtMl3d=3|##9jcuF~P*cLzdqjhQ%>R zvYb(8*fRp$bk7#{0%SE)^dIy)Tdpc-bi}ZQm5J@ai(5s%7w5Ot{#EdaTwIgQTF&Mh za!)X(kpCu4TYC%k4pwq(L!mZ75Kj$h$RE|3wuVb{_CU8dR^D@6$%Mn2kftDV33qo9 zBWu`f#!!4{cfgTOSy7^yq9)UiBM$Bo+ z1Ozx+JBF(GnmQUS-5$FR2}H}7pA7LGW1^nwRB4#FFs+rzOJQbKap;CO;fRm^iCCFo z2d3kxmpF`<^$;>1IPt=ezK>2R6Kj=3kWDF`anqOCxI{a4n$<*)H;Cqd&xJ2=S@{mN zdAfWiYkwXD!m7sjNT3*lIYIcSS8I&lxVUCl%aYsD^_`Hv$PM|}%MJpWXr0dBw{9yU zq)*^Pjm&N{++5J9Oz)?^w3F$PrZJ|je?E%ax9+E%?QbPvfd{~LuhRC{dKHy;tT1YK%vk`X zrb+qRbG?4s*0fk2<{TLCXd!pE4Xy9{5eLe*U9Z8TAQO8F+Hm1u)~=xD+I?{o`^FPdR9bAl*gUS=>W;IUBV6msC3s@?XLx?=qI5mdj?$L0ZE6~pTB*FS~p6DPhlzN9T~ev z%3`a7CRr#%#Yq0O(AVut#b?>eo%?Z;Ft<-?OYP5`%DEz+!s>3a>~m9Sb0r+MGBe9} zTl0OF8P^ug!fLT7cWc{`D9CyHJVV(i*w0A3iA;B2%z;1fiC&jqQa#+|NDOQ1tm zB&3J3J*sR(2B;N)fIxdn!!!6C8X7wlQcgznR=jbRH*NfM9cEu!D%NY8%fDJ{b zxp{@8?ar{E7!(c{Erx&g9p9tz*asAyuGku~Wmar&d~8Y+mnfdz#+mz7?7vL2{j)yj z2ccPxZ?DqpBi(a{{*%4OP)=@mUEHr!k^e~&sFz5yJjKV9QFXR;0YK-kKBo;`dmG`juJF!?hC6373LB2#)P)|7V=kNiGoI{f~i;iJo`}lg8>% zwom7S0JTCsBt*;Rw?8t;a~&qeUbRGM>*%x%B+urzH=6C|boK&5dIzvF8IkC_T=Vpx zyN&RXQg=bYtB9KHp|CPh5B5won0orjOF5t@P7zc%A$NtnaYG-q4}#@?n)sP~c3)t|?o3Q8mQiXOHN^0+t%{xCbq_HI5|0GkkqPMl?Go1h`_DKqDfyH}ol(co$H-C)swO|d{?!3!} z*g=22)Y9*-2!X}|q#EEr;>q~HH?I7csrQEsIw?`dd68Jcz!D28WrEmGNZ7&)3B z8opj>+pi~mr`6F~&Xkc!kRKVRh$nsNbkt;a_;}?DXS2!*KYkQZ;F5zqS4$i-*c3Wd z;X<@xqUdH{{a!kJ1(JYdqgA%DCC?_^CfX@4=W#5y)ic@kLY3;$!me$co%-No+E`zV zHoxDlgd33o+-$uu=Ros|xlJ^Ah}_C4_Hn(K1aCg`4{fzFQ1qAOdu>PMdqD}* zHwJInf~aVW^l%lGWBM*lx`y^=H+pKt#|DB$R})izAcCk+1u1LL(h8fGA(w9bZ)M%* z9m7CbEW>x{kTTaPN^aDB7N5KbRPNez!RYMZ$M_KrgM8-Sx4$vsMK45hDei>AMfgbg zH(Z4?K{lb61S~)+;^FrudNW?y+;U-uvukxC4yG~w(A;x6I!=g0V>mtQ#Kn6mc9O~i zkIOzUlb)7RirylA8z0JuK#d@<7=Bi?s$15*1&YKPt_h+^C`;l4b{c5fA(>a{) z_y?2FtA$`03K3=L^nn8G8id!qTD!n80a>0?gi|THmh+IzEzjT1dpl|*gjeUcc9T=O zzHbUCTJcoki6R$`VJLoHd;BwxG3=0;5Dg8Uc;FSCSk5JVD%%4<4(m*=`RIv_*1M$z z%FDV>ac-C5GL1$M_>#WK)xW3<9k6zsxK|Z=uxrwD{<|q=|74f*F2cL2?p>+>y@ENx z@T9oJW#UpYR$gPnhr}P*w0FETY)DzJ#y}3SyzoBcC0AodvyJ&5Vg$$$m1sT{Id03? zt7=cXEZSy6!J0({Z$-2>dcU928Fb|fotuOY_`Ha*YqFp8G~FOfH-BP;nW}1i-yCXc znRfv&`kWmKo#(12+~P4j4^0{|)j3{@8;3|@cvQ5Gg_6TOj$YKXf#@F-qHN!m?gsAr zd&iJ^sO4{|K3gSnm7T)vI=!2Pj$O5kq0Qxzp_#&iCTJH^76T6E(11VK@HnIkC&>Tu zx>CHIJ(3+YaFR?J#K2a|CmWfs36?by+KMC0>uDJPM>S;^u!1>7lpU)q?OzL+aBBAW z>eJwzu#Oyh8U%*Czya1poe$}f_bmhBk*2%0-R5~YULJiDFFCtQkMiQaW5B!Yv)`Zy z1@2$s|AK2TT6P5sJGIg=7FZ$DyWQXSNayRG!Es?s??r8akDpvS_D~vifhJ^HY$Lnam@8&&?t|OJSzZ zjjc)zhQ95v|1Wcy=M?k#Pg~q7Vjh&KbBx8z0cd95j*P@T;_f719;J9_pq8z3-s^v? zH9eC8^$@4Et*faOoh;`zVx&abi)$IO!jh|fu7@<*zA;X?ZMfSmw?`^pix|*DY-~>w>_=GFee6 zUn8+2wp~`*XUiKxESg$iQTDG@dR^p?%5SOHH3*i^ODnHw&<0E1NEBbx`&k;4EA0BK zHb!HSES!IA6biJ_6vm!sxzGPxgb)nZoXx?w&)#3zxN0F6UW}_uuhWOs<tvS`2 za$|zHz1pg;MiXEDpzH}X8cHCgvKyd~|6XHUMG}49LKG1?B(C?IEitmztkFmKNM+W5 zLLYVG+! za+LSkcs|<2R#LozgR4F<`N28T((OZM?PJUpL-^&hv{!Sz?nfE<~9B#Ms7vsBO z>87X4)+W~z^IfaLS8h_T4hpX>K0y3rMwE+U=g=%TAQoB78_(hFZ)o><0oz2zFAk|! zkbV>FqF4yX&mwrVD`R^oUXh$*Z>iA_l=yI{o-c_s$Hi)u`pasbMP{!YZ^U*YPDwy` zUxO@QTd&?y|KavAmPo=|uIX8GVR`mlXS2gZqKC4cQR~dAYQ5HS$c34rS@R zRbWmT6xa@xd&4|^%XvR1JoLP|;A%z@rp((V=u>;Qu`2xh#C<-m1Ji$|YkP>j8b(>@ z;^WJ@35p}Ic3uE_MIZhSp!lQWuG+xG{m0v>B~>f-zkO`0{nFv*94GC;s5iepMH{}w~AYkf%@ z3=Ok9o@uIt9cpFEluMQRx9srRHLX{PN7Xqscy2ItVC~(jQMxMN@)5|6yG*eyP#SW4 zhmOKuvmZgI$M!CkQSPk&c&X8iWufW`!_8W$ucBCdv{~^UB4d>j4O4tWT)#kSyIy)4 z#J#p{BxNl1?Lw;O{!k0O&SWg+q?m*)S2;ojMc$$OqUKqmM+3ifveIr6c&FkzD{2-( zYju~-VRPl`Z*IgM_0UNgXu!=|99CUOh|&%+;x1cI85!VR88zFWUX(m)$moY^l`?_w zEG<%hr3XE>^edBPzHmwEf{}s?UWaLzSj5|M?uzK@$qvRpvUp!#?8BnG)$SeWg#O0$ z*~p7>Q5XW>M>$ti-)!8id`~JbGJGV%dL52n&bII=>yqp%oGNf&SbLq47r8k0h8=)} ze*g<3E_xhC+wva1r*6Ra_Ybg|&I^+riYH5DYu?(nD6e7Wm@jR=`H{#^FzWCdy8;6@ zgFF9v1RmQd;LF|##*p;|lEJHKJ~|~UR6Ztt5Jtk*Sr2I+uQe05dD{2nKex#+_EKX3 z*yR1US?__ze;D&NXEa}vMp^ZZm;r(Trn`l8@mymKf5#l|baC*>;=+{-3Wt=uep22% z=G=+KP;{J0WMPV`c6id@nE&bck=(i~FM1`x#TdCdbUy#||EPM)uqe0p4OB%!DG?>4 zBm`;cW>gvkq`SL&h#^FzOB$r5ySoG=hi(|UyJ3KVne*=b+y8T&!_Mx5!D)#{}Mu60;-6j2xT|-{zj3?_m-Ab&1cSpNCGp-Cd#G=O<=gnupZj|`StY$ zPn48jDWzAvh(gpCm(dl?R%_ysvDVdEwQPP-CftNX#1KiS70#R;K)o+~(G*HF}GttTpSmU#M5;<7=p6BxJFyzK;-pnl$3q1c3+`LuJ*akG{uHbZ0}xS{zsMsT1M$-_DUN3QHZ;k^q76dLIy@MFS8 zqv3oSXC)yIqm7p*GRsq0#rPhHIO!ka?y(2buprTt=j8cE%R#jdEfHfVwh6rVXR%`2 zBocF1gVr*8zVMuxmKx`%3HSE|vNu%w`fEQDzIwWt z$*d_D{rf5Za-uQfl7qbG2kUXN&b8g#qtp5UhqgSHu@AQL3>{zJgX(N{Uaz%YM6JEY zIB6^RD_Unw`uH{^LY2s|-X4AT;asBAn5=%;WTKE@tUP_~f13H6aa}8xjM%%W|3#D! zqjcuHhSrFs-iQuwDPOlsDf#wq@I$UyC@DE}{}Op3J0?p#U0S()TY>d1Uu}hh^6;jL z%F`vaQRu{@T2#-Y{Ol9&766!s)1t{GvUT>y(8i?28vo#=)D&Txi^*Oj!v5YZn|*-G zm+jV~00b^S$#1<7oIy2xG2YRuSBw2YX1^D$ZYQ)lbw+z*v-AdVzj&sVvd83{(Wmze z%~UDbhq4~EN{cwn1R=U%x6nOTk z+ejBgu=16Z%|_yH^BbeRAaQSGk2^p3u#n{&?B~0(5AU$sk$B#se(1nJ?0IlE+h=kj zX>uX&NATsD*JoAZ#gEX+15#$DR^Nj(!tlZlw$c4k(YKgX#p?FmzP1}n#Ixy8zGhPY z6etTcbZT!psf_>?`iryYI!lIf3{-7!4Diuha)B^CxA04!yOn4oMPbFW2f)xNQlLh( z7qBnsv}ZR~>iaXgLKO{yV;sNvAYN)+`7X9W-`D>~uim#%mk zB)RIJt+;xO2zvYW0~SCF=q;dXXYDGxxSKhJv_LgV!#bm*KA|8O(1$J74$<^GyluZv zd(Wb_HZ}t8fXP5N{qXeCnWL9|YO_#lPjVx_BGI`cdDCy*MSNpmA^hzTH(`xLZT|HL zeffgi|BP@&3ZWpfnc;N1k>Q1NfYdb4W&5>omAd}8*bhzynIyUBTwa24JOuDn-4vit zjOfOvO7NHss(mK&qCDWU4l3rcrcNu{y}cbE5>MG9r2z{P`(R+gkNz&}37zhoKx1P6 z{ARGHX^`u@y&zJ&@YM>(h)jjH$wh#IkB=5;c=ldJQaP;2=noZ77tiYc)wmymS+<^u z`1-B$S2=fgRi;_c81O#!@1%LYb}cOw`97@-y7yUG`H8aTq1@wGv?~#8BULgw?D1MB z?@ngF6hd3@5Xy{af1<`lfAiEN7@p%0J!7p9JC&anwoS=z8r5>L+}@b2Cm=2W{xj>7 zEIS;}F?_`h%h?vH`KpFJV$hTQqB&mYT{)rW5DI0?;#LYuX)|=A4PMyBf6A*P9*aB4C2|{$^G10Z5bDLVW605mm2R-I?xsd zp4itoqB*YI3Qeo4ppN+Q-QYTD-I^zunVxf4Z62D3-9+x?Z}u+l)||J(bi%$%u(SLb zNP%JdqlkB8`28}-6Muf3AmD?Ra19risxQV6T-Z+AiG>w zKs5#x+vT$Husg6d=>I3>{3Z9hvLfm~V%w`!l7CY-HCaLq=QYygh}b2Kupz&~gBvm@ z?ky_E8{3Qd%&~rW`FiD*`0?+G?`S_MHD-rq!a0PTbiToOZaY^+CnSY0=afh6gXV6IrTnSlP_%KA&4W{$^Av zS+4#4r&&oPmzI2$haJl{+s$i+D5@Oigex-rFbxhhACJJ5TG?13gK@Rvx1z0Y+?Kn5 zkjuE~?T;TF`HN?Yqp$TGa(zj|loUI@Gi3M#-tB1N_-;O1bXyVohYtG>%45xAO~RQFN7i|S^%(Uh@5Hh7k1_Ak7ks7fesU^lT~J-%JqFnOon;Tl-Grm9 zG>P^YqQWmlAS*$=!{riyYv$?>)qAIOEmBvM0zh8yTMti}JRA8z3_#b=WO$EjseTm+ zuzn?*soRZiY@ZkA%Im&USKgv+KwUJW16<^YaPKh@QzIx(*}^10WhjD@T%pgznez0{ zhegF5fBeWSliW3`pvSI@QpXTX5WSIipF}rRD6pi_2I#Z>3#0kZ!VtIpV1A3TOWPB1W zQF@NBbhNY89L0XHp&MEC&3nI&fr=1`#xJSz(*`1s&3(>eT{7vSoK_-kBIsgFn~VgU zB0rQ%Y0JJ;pajwAm{JIR=^IDe6#Zu6nkMM>l#%h-%Q!A>MBrp-$Vg$*U?h^sL7`(S zZO^wdZo?(E^(Y&gTwZ~t(@9yE7@)-j-eUW9I{0OD?Og`-JD)BR4yA1M?(j}hZ>T>Z z9ZXHreUe104xSS;vL_;*Slp=LLhymgfp}iB?|ym`XlhJ=z-? zy#7r&UtXji(Ccw{X5oY_5(mfe!f{^#J$?N6lP<|avr>~bZWEj~<4rJicW)Med&RQ7 z6Cjl;>hLUKM~5?^cwk0v(UZtoWfPPt+@(7;2kL{4Xe!8<3ArQ=Ez!YPn*++Im#qpOFNjZQj6*&n( z$ZN&mZrBx2^;zg|lbe1g&}W+9=0VN*81a3$TXEu>qC~j$SI>-IXX~ zbmpYk-qeXaf13()L3fPurtS0d^KIvY|I*rWn&|$I05)tE<97EnmamKti0ggVsAY4b zUP_}*m&k5l|HGOs>F3WEw}u86nE?{~B1}^slbqGoOw?wcvSA_%+hxQ_7nRCHzmtnH zojzY{vrMl^K0E{TxdDksg4v24ElOpQ@<4idK*L&SSXk_P&qP8T7j`zUdRm$sAb%}H z*$n!7+U;ok_61HmeEw{L7sd)M%;I+SJ8#l*&dCBk#1zV63rA%UC zf3><4@BOqf$MksoV4?6|#$-;cckc`{sdVeZq^tA;(5mWAkJf2#ypS~H{FRy2MrXJ> zS^X{3nWhrMvEJgEoj;?|Jj~Kl52xKDSWY2@ysmSH?UvK!T!5L)`yi3CCz27Q;n_gU z!UKL}7X=*WQ-OV(c&l=rHtr9p`0t=A(ry@KULJjTLh?V;#H|Sl%?AXhxKw81K?KwA zH-tZw=T7A>M(?}c(p0|Ulb$?Zt-^T1UM;Wi$1JWZdb=|h<~ZISukMxwu!ePNC4qU` zi&x|<>KeLi3;?q`&=08}Tw&o824`shF%Z{lGO|Nuw6#uE>2hEYBH*H2PsNlasOz65 zD82DKOyz0u@&1P%VS1uBsotnA8k(Lk>8A77N>L*KvMRY({d#i<>C7!D?+!#zzO&Z~ z)rsjEb}@@*(o?U$8}Kg~+6tQs7)<==1|m6WeuY&4Kqx(2-yiPL#tJ=|aXbtQ7sF-M ztlxh4DWMIfe6q^gnWj)69FRs8-k@2jlA|tic|4hUyo9A%7~6vTG@3wE^?FK5@|ML> zNjd5J8BtZTJ<+m^{vwXdFy%E_!p@6keB`Ij!j&6s*S0lv*Q06TC9frOa-Z=!3j^1^ zd8zv)$WqiXpYly))0&=rmd&e~^o^A{%-QoGAXy|R(lE)iJYQF)9zhReCs#a3s zs*H=yh$X-<*^(fF$KDG!(uE9QTm3*ofWxO5h|KG(VU*K0GXw|X_HW2q-0gdiZLpZF zA=UYv`j6)cqJy&q?<7pTY}k}y!X1{fLBPa~ zjO{KnX8RaLR2&7tobK(24x{a(xmh@Pfq?P>Z2^ATxW$&2M*-R96~lOCL~`a29_UuH zt(Y5n$o{nA)Bg(`eiOO9pN&GB{TCN;(V}~(3DQW!$=r4hZ7s@7i>43>yJ_TivSG_S z5ON!Ad0ToLJ^rDU`?zFYbA)BE=@k=Z&~LvwjOt3uQ3mZMFU{4Ro#1j2`q2{MWKmyhj>(`xn|vQ>8v`prMEulyrl@jqJe?xKxHWJZ1!GVnHePe zx0iS#M2p49=+hUXgp|NIhG>&MhoS07w52ONQy0mki3OMm^@3qQ4$6iF`Xqg7GMF8*QBc(t~r+4~*iB%h|#Y zE3yr+7mQ!IwG5M>n$dAB_apy+E0dGD{WsVCcg-OfVdlN1o3D#UGm+Z zck^+p`*wo-%6d8PjqY)u}u%lAhxRT(jNi|vp1C)aVt)X|7v@uV8-1SCa*qpV5Ly-m4skqH>+P+Z@%A5ct}cS$ImfGK+&i3!w7sw^%gJ|`iE>q)z0@A z0Y4O{7lD9N^%l}&VkAfRK{w9Z!Tc`gAuJ)O{jJVxOz~J|_fO6o)3+^&v=a4c*&nXT zl)t{GEQWpgQT&S;4TbM`!P-CqTm}BX{_@(*44pnU!^GK=={tQ85;#96oSW~cAs0H{ z{lTh7W`roSGefY{e=~93oMvEDAm-mNj`-QyxNcH)5jDd9!E4OZ4*c$~46<+8yA!L4 zf9_7c2!=@_`oA;~pk;TdtMqt|xcr~`Br>1mZ-wTMZuTf{-~jKWd>IzBQszJ1M{F^Y z*4Zr9g8F|<-N0`DZcrq)}ehyp3p3v8{p%zC|5E7XW(o}DEN_;C6nk8RQf z+*H?V-si{%la1Bh)=A6A_T+cW8lD`N85iZ4A7PM)Zlmi?7DsBD0l%s1(64Je&5^th&oN!2?w}F^z0Ez5fHmzgieiejPE!eA2OQeUifg7c5RlVent=aA(5qs z@+Z07)V%pBP!;bxav06wHsLYvy#4v+7GZLU?XY%?pv*#Um)WOz?9>qhJZr`YbG9CN zliRW)gKS8JXeHw2TSLgYSGo{HyY!L;ab#hu*%Eeq!Wd>_Z?}QIk|b>RwfgmO$)BH& z1X_SpLyQwVk|7YO2ul0WRFkjr0~_1$A5a35@_&|iG=Mxga4(L*2uW-W!RZawcmLI} z{|!in4>Rl%%NdjfQCg$9vp1-ay9U~9o0mwJO2>kk{F4?jo59CJGAyVg2;JWc;~dOS zodh0MU6{Lbc?FkS^OFo5*8|y_h(6A$UX@F!mqb(LE3fcHc`=r}u8E8$k!?Z%LJ@j% z)OSmhzuxumBw)M=G3;@lLafyO*$lu{jCZ0~HS1gn@Qzj@r#9(w$I0VTQW({lzkmNO zv8h(@iOcn99Gk~xI&Pan#Onp%;7TG?Z<|%E)~2ha1+;)~rW~Ac>*nc?_Q%U{mE#m9 zJa%}A<(GnHzqa+}sKM|!m+S42m?w(l;T@L3jw>9C8@k#+xWU=#*!ZrS4TvD3pQni` z=$pj-{#W0Gs4|w&XmlP|a7%TS*`yba->yAfU*8~4)B$dT8S*zzAuQ`zb)-cSRM6Rx z-M%9mci4Y#KM~uS+!2qZ*oZL-)|D7Ye*R^;Pzg<*Y+5WXNbPHb7l~}JAi-`bfPQXM zxIdp}mQ$PiJQ~FFLg6WGu7ZG*&* zla(%>iTUkmJdLyy%3cw{&jM6C;y8Ui$Ka+HfT8({25V1&3jNw)5uxQu5vI1jdz+^B zx_1?Q_CeaEXAN?`lj%2cQU8pTyTg(Vul}uS3)l|Onu%?j zJ1E!R2R534sD&8EvBqDK{aSe_R+Rz>jX@%z;_npgA(vNTt7`gRSfsyop9+3(=-ae`O14SP8ZPWy5WJxb%?ZXcocr10WQxLj z9kbfA0Ktg<6CfrvKy#XuDc_xx*~+f|nLlUTgkim2=tRu$;|JfHYa8#I5oUgueUA(Y zhm!^y+0~D}SIn5RLFoLgBzSW#NJt_$&1AE^Z#fH<%3c<$F^2bl@Oz4>y>^hrZO@lB zPn2u!@q#c3XwgQDQ2r+TE^K(fb}Qk`$?n?Jv;WkAue+XU?ouq{%HdO>fVU3^0=8AC z=o3@J8rKs>D1~SE=V9CYvg zu6>A%?#6_#kz8S8hXW97L~@PA`zW1I>11y;zGuJhY9!)XFodN&F=baOA6bm-Ounbg zgYQp%e{T?q&ab#01;J1j4(UJ0fv^1i&R#&qQ7AnaaB+=~r7R&wp{X0E!&mdvE!5j} zm}W~E>*3eze5``CEX@^ec*D1kV&7bRX36qUqiLd1PKu&TPsnNEG+&>jQAbC9n$2jF zxa=kZJY>e#Gl`^Eob;H~%cDL;NAw=KFEJE>PZonxCYSqyrkP{nNg(7&>HMH|GEI*wo+H=Dt1zhCrWY5434n_vjA6@3a}8 z6RZk9ywvu3<|yjnq8s&yfk8yA*!rru(V^e*a@P%e>xlMYbhH%aQ9sp2RFJ!+@6PWn z?$MRb>Ny@GZvx02a7mD-BGOUe>d($QyE+_v^}+$aWwH&mr4zugd-XcQt_R544n3ic zgMDENMxNuW4x~Uzv7SGdXsR~*+U&}2JzE+EII_|*EfQ0I0^i)t<=Urc+0zx6(Xw%1 zOGT&mAOrdw*Z-2H2|%K@Gw23`%OK;81ZPyRz2D9e=W3zLSF6oi>I&#Ox$M@{b|Dz9 z9dCGS{2%=?P_fj9)q4hL_6bz`MgMIWs~LqA2L=TJwJH&g}9!?uQQeO`D7-Bz@&_vi{Sxt9hDV-8MhbFOhm+Q6sOz6=OwPeEp85nQ_ z;g0Eo?&^texPOIby?=~{t#WTWU#QYSnm=s(SRo$Eg3{0RE!a*UbFw%Pdel{DVbGTq z92C%?qK)d4Z50IL08EIF$Vb8g_D{U7kFotge!w`5H{a(}a3o!n+Dd*1-TcB1b{oEi zqmyIEOvfv*XkV{x^vO{g>-TTj(7Nbvk3jr~wpCqdNz6L!MVayO5p#2zRlMD!A;W{% zi!7~9lVlQZM1^0}Y>%ICce^P)Ni!>4Ieqi|tl!NZ1(>;WtX`MzJahcQ-|_9IwD9dc zb7Q-WVwGeU>~EDC9?`j}xoMb3V3~TFh|9}hyu;2lGz8E`ke+1<`@RB*CyoN1kkYj0 z+kcMupg7N>{{X-taZDioQt-_j$x!+ONB$S4@<$Ah6oo;L;W*yX+h!whz;@SgVQL>uxCv&2%-Gt zEcF?GaM!LkuQd#%e^h^SS$RQFS&5!TO4X((jLom=aT})g!DH8Q(P{K;vCs=bA0nVj zCRp*ksv?m2{fx%x!`<*b)D8;|PwL~>5Zk6$nNbV}cwAciBMbB9F!sI3FRj^GS*y~m zH+PWTskWq$l)2(@fbo{MW8|sO6ag23QouhRdC8ytF)oD+6l;IRLEO%P4X`E;cUUisg8Cr{PFgvL zNUeJB-wh1i^OwI|t<>!KanLa|L@fk6cC@nbdj+0e{u&AggBs4S|lJHS1xs1`tH;u5#r9N%F>Br!<@l)q5uT5>d z_=eecP8T)GRn9y&{N8440urNd97@cyo1dFIA7hJ#2Ja|z%lqX@()>|!DH!mR{q|qN z&3{z>m1v^X|Mxh4BQF|O`)$Li%YNYV?el~WX4~FVg?a`o7Wbz|x-2*6gycfbSn8>` zk*U0WIf|{{@`rT>x_mzCvLqs}39pal{eeV+%R?WsV%4&!($X*9H_NG-{5vXio3_L% z{M*en+Pvy+oW#*0lqR1RE9c%CIg^m!C165!D;=NL^LEZK^s_qD_kM9jeimNc z*a=`KE*D=48h)QI+xa`5PzvApkKNJ>h9_yQR`HF0pR_D#)Q4J4mA)=kEs>XUi)YoK zTqB5~@!|+{v3&?AE2eu#A5yt`Sro^w;NyLMLjcHvaHQ}kUr@^hHAQNPhKtx{hp?_j zkX(GXP3qRs98P_Z$tH3f3iPQd(@h#@|MFK4E`qgO9NhE5q3ynu`j64$h-Nf!FqLcq zQ#de5%aTl&EY#?D222eDp1)?MeorS}ueeUGRoV?tgE?PcS^*}2m;gBc!ham;19?H_ zLNwnh|2j!g3p4ONHb2XsGkmO9k4G6)R`Pk%*#DfhOXYiHdj~R+aJzEft#C;{ebb6Q zEycauetTy!t$44&)49vJ4+?)xFqKF@T=AMftm!ar3gmMB9(;gLr;ZDAh@g~fzgB`ke@Vz(jIhysf4a<>5$p>41 z^Oa+YWYJssI`o8?a{ztOR6c6Ba8>Vlx(xHSR4(>xA*Cq@k6s1vQ;KVXzn*Y(3Ue6FV(avz_?u;6?#=3JHM<4LBmA9;ErUX3iN$T%w@QN5)(Zgw07Mv-kK66MI23J|Lj29^oH5vvG z^2*VdCbD>SOIZlo5TkgsA>PfxBG0f1 z44SMQy(E6BmsJXocHnm)4iuC$S>TA`3j~Gx#Rnn`ByI2lk}pc3dOM=3XK*T=K1Q{C z7VBA?5HLl{>UGO;UzQYQfv+!ySYbuWb?a-u$C%N<#B-^nSQj)2byLyN^K6g^Obz}! zI;kE~7{bvoU>u?D{5Uq9nHkMOfwJ?Lnp~CR$j(%L!x`WpzqU~nSLwV*L%z^K%qSE3 za%FbbK%7;+!Y*{#2eE++mR#>NQe5kllFE^)fPDp&xFg9fJAI57 z^bKCNR9~XCO5$H|;$ z?f74!3~097EW#GSDIxsKw2{3s%5gmt^04dKoE1Iz+P3J!c%>3yRe3@} zN+_XJ^y(~CM`vFg!#}wu-N#3%BZMo-M{6&@Rarx_M+sh=4nJdz4+(kY-}Q&O z+YyBp{o6B~x0=7*1z~<)>B#nbG!00%p&Cr6cuVA1%FFzFG`+VXzR$l+Xl-clrQFNb za+`9-9X8h;Hwe4nj^4LzkJg{V>UO%7+8$1@BBE|qSKc4|X!5iNyNrzig^c8$#a@nF>K6HAT zbtTqyZ1Y#0eY3<%4u`bAe*u!nT%=u4p|aWP>DlXpPqs?EeU6yHKeB=FmEDOAdf^Y3 zPGP7=KnU6wV4LPjYZz3?`rd?7B-JiQuCCd!^D*f{e85RXy8%-xMWKr6?~kCMZ1baL z<0ffsi~K7E2i0$iw&ahYFRre5%7j*rKZ$XiX0LHCL$XywT}3#M%U3rbFw!WE;1!RsQxA?b*{Of4|fHRapLc9=JK2`V-@^?b~k@zhtrr zu{wXdhZ=`HHVJs=zSvTx-{EO)aiU((GFhY@gc>ciHwT-8>(dCU@VVTF5+U2mEQ-QF zT-}3YjNbR+=6pd{5$#rzbvj#bE1>N+b=`}ZpLWeF}EZgwKNyY z*4r+>C!4KENPx;6y;KAOhAQQJQ=VUYW`1xoNCB_qIp3uiG}P42iMr|9V|j_oFQk|a zH6CIuHtPJYvxQ8KAje0?n)cijVwYN=re(MKR*&Q>M13|ZbI!Mt2^EqkwU#yS7w+~b zbo@dn5Y$qX%u-tv7K5!wzET5=$($>t)p; z9#G?aox)-u1g8-q9G~COe=k7DFu&8*TKa{^r}8T$WL323;JTwfE*dGP&Vu+$-g{+I z5#x@-IuS3L)GP;z8%CzLfIZw6zq+O+yxuZy?@~g~WX!Cu+96)FKul8IQA~^N6K-!^ z3EuFC*=>ZV736`Ls_kmeO6Gh5p@agIkN*98%>U2hMP$1JPilL0q_ z>3NHl2eX_0@rf2i12RXGK8yW@t&l^ilgl>jtkhu=eXG+(Cg*4QjkD6Qy!Uk(?^-N1ZnX)5{&scA*zCCMstX8%0D zUTcPrzUv27WErNkN%B@~!22lKCRfwiA20`IM?1uwua`z=ipt6o%-&_rAt0j^eEk%B z4@%oZyrV~v+ZWrQfexy>7VlG}5ZH%+)YlBCl`81*Yq`_*DV|C(^5!w1uH687)J zU<;-k5YqR+i27k^Hk&uH`g`Z_YAXS~B3sJFWBBlOHG=2c-;x3|#sS7^w+%t9ulKRQ zKDgw(Q#K1-)G3eaSn)}1z0u9KU2Ywixx9tTwp8!D@G$otK1n?vyiC4}=0l5QeLn6Y zBQKZmtO+q-Bt=2X$XImUygy;(zU&)!KOAvH1;1CLY;-73H``jlUtz!>;)37SlO4Gr zCoTf3A+v0gDzOoxOHvB_W?`4dOMM56@q1X`#cE8>UJl>Pa-QpQzZHkpmX*A;F2B{= zhFp$A9AMw5+jzCK=AHZ3q~^DNare{n&@N5a=Tt#EaLG8-+aH!nHbZjG?Y<^q)bA=g zRL=+7s3?FgY`JEX>W=~Q2-D6~iEZCSwu|kNSmI32&%EUZWoXDQD%(HXYt+w^a3I0s@jFjf&M$s6O{_3AXee_89>FPg^kK}j1>h_rD z=~Tupdu*$3YwU-gdp_iS_FP}4je-F7pa84aDfsQG>I5yRM-KX+#kZQ2G6%P*GbKgkKZ&1b{)Fr-+t$yYd#`PP z>0>;6-lqqeUN-6ufY!Kg&jnUu9rV2eb+6kp`{BO#%qh3wE6|2^mq2pA39Hza6C@a% za9QhGR9+rmmI@dtPAHmn0zZO^qA&}p6%O{aN19XvBP5E(1CcL^(5Tt`HiY5m5{%+E z;&)YEJ-&O}=jm3;ON&Z&+-(w&Q!Kgr1Su!Ds~s$vXjvOMBFJU`xqNCyRc@SlbfDw7 zX=#L|20U!-Abh;)r7HxBzP%i!_L$N%(OAB@U&W5IKRszln$5H_9||V-t-YlB&`)WB zs4p{TaqqwP1HH9TXPbWAOUFt(ou(6(n_{5>;&afoNqW|DG6KtW-Fqp79mR$Q{^K7k z3qEPjH#srjvqbrxhT7|&emxBfoJSb%^6n6vgCa?heVpUQR4< z%%51rwuz1hWgoVMda~F0!wv+?DqAzFD+J zJtWDydeg)cUPibV4JFkMrzv(EjTbZ-<;v1;WqnbzLCDiH*BX8O+uJ<9-){l?lX?t4K zuYWxirA3F;t1`@RtXoZtcw1J>fX4Bk{Zp5ZK0d~Igj%yuKGw;NyRIv;ylU?PRgGibz3rNs z8(SY(zS0C2WH71StK1tUHQTR-x}d=njR?!(@!xzP<@X4|-7YLIj|D1i{u^0( z-o{xlk{Ujg^3Jbi%d5#}CUdhs75Nsv%ps@mw?{hPymR+qj3gcB@TuO_^Q_r@ zT~zqK;Q>zd;cGSIs;=hVXbCv5=UGPY;RLrk zOASyRiHZUBxRolORF((Rswwq@LuqZOP<_V6jQqh?&2-6OwH#G@!$+j=sDV79Z|L2J zjr#kHVMP)BHn=YAtWlA@Vs;KX=XIUd=8V`IQA@g=$Qx~KllQd9nY9nuq;L--_c;um zXh400^&WHj>`CR{j*xrLDV-ldJJ>Zw?#(P)jJHu-nJC3}I4wKqp*VA3wjIeTGrF6- zL?(#AXV^`a({QxdJ}~n4a^`@&e>>8~_FD|h41HA5O3)+2XgHdnbOTP<(x%ZzZ09GZ zZF_=0u4ZF}li|2b)sb{2`cIiXdh{LZ&p$`_H_J=(64)hr6Y^P`D^F$&J0yVJh4$i8 zwofw*T*U4sztFab3*Wawe&%;VlH3#b#iS}uA{)PNojpAWMojv)K6IX+`ihuc^yPAK z)@*(Yz>9mpy0&w>mOaU_pJ)S^qDJm-!%ZsTp+ zqRt=hlu$b4Mpeac(Xh zjMVg!Za4+zBExC5#OY-^P^2=F$n1B+m2y|-kbEJiDH%y=ffm|o|7B&NjCZy>nK!35 zBFRKiSe~u<9uqkC4f?I}AHMmE*<1=`x7`r-1=%n=9*=|>hXpjBW6{K zaoz||L&`v8}oFSjfI&Iw#@Eo{c*dMU6LPgU9xb-C-ST; zDKW#mTrbhbJT`9FcTzGSvevExiME*~h7bIw{1Q<@d)xxoH!8#6uz^%XmHfT?4Q>a~ zXwdvfR9tMLJq#oB?CpuKM<$X;uJ)m`dX?jQ-}B?>R}NnWPe3yquGljgF}LDYH6HR0 z8@GL!|5i*$&?EAHK3JCZCK^ymak@0GJbHw>lo9`=8U{b-ZDg<3FXfH--iMb@i%{vT z?&s(e$}r&5PB+Xfw$cZ+)%Lp5-F9LgcbDu;JJ?$Oq<}R*2VXto8>OdguyZ$6U#?S;>X<30;8%*QIvk=50?}&-(FxDw*K!Nw?Ny8{<8U9ZE`vCo zIs!JohqEP|H6g;-D%7-;*oqhhQ^PWnZa;kPn`#}n>>sN1X9C3B)h9^IL7?&1q^I(3 z%(Y(qG2?>!1;0L2-sZzkXb*|=Q>3%EW?@pP*hyq#nz&3a?V3rbh5_R{~p>{aaV|Gn)`a_lxHM{omjOoO)wHmAT< z4;c(Lus!&D@0Cn$CT}Pt1mFqD_U&zzaoz)R1Egq=;GsO-Lt{aExFYNB9$z`(i2Cou2J*SV;YsNUI|b)Rm-$2GUI zoCqj0+gH~}ar#98p!%G)H&_iSXqNHwMg>P_mLi~daV}cP$eNv8Hz*V=XLf5(e7ad@ z@BD|~wI4jkTSf{xvh&hy+x}D^#ya6LvlaJd$f7O1(*oMd1GeIZh`e$2Yb(pSy}JW$ zK^hYCcn!iDVwNdv5c`D!@UcUFR_CSBNrQo@2YkhbICo1>zl>yYC-2wH)rDD$`(W@1 z`%jA<5F6mnQs@~(SqC+?YCav1vTYyB-9habHJ~_jL{XsVxpRw*y9OD^mc#2d8n-(A zw`#eTqwWxK5d4&b=HiH;EHm*g8tnIL5;1qL>y702+!yL1{O`*??MXN%>(2Z4N*9Fj zgGHzPONQ?qU~6CImX|>{o+7$`gqTg#zb{@zYP#iI0W&qky=x`Qdu>lsty6TDQc>?; zQCH3))l_~LJi`YTjgg6b^gOborM5sDo4C~CK2Iw8hHU?cQ?=R5)cn^&o9WokY)c=9{}`oQ`8JT1*u^Z|#MILa2sTDGa`VM9fwm@Dp<` z6n<{Ts}>c%Pl^V4D=stn&a?GRy-bg!Ke?IQ%nHD-@x)#9*qBZ-9mm8Tx}Bquk&%m& ztGJKRQh2;3nIoJZ5N&VkhLg%p{~MR+L%TUbW;j*%p61AMDmjQ1%YA8d@%N$?evR}AGSK}9{oTpYwD*_CRo;q8u=hkcv zLx%v8iUyt#jR8HCYY6TKMrIi6NxPbDx&N%bnQ1PxJq|xs29w+tcJPJQE8<9}VOJ0P za&M_`mHG~kgk`ebt>}=;s+wY@I!|tMzJM|T*dyom-@J7@w^A9t-C96sn;&06M@N%* zn3H%&ZAvfybaoHj?#PXZJD5}JneQ((gy(HeMvGl}T@NL4Y&akBkc(PJ;81aB2St)t z)hqFexZb=c<(S9~j!s;o?Mrr6;T?hjaRf8d56c$diuP)|1A176sN5TA*X6*Z)E&oU z0sU&95v1qIlCnk{EP_E;Vfv7K=z_!W)bV05!!%>M3jC}_o@{nNr=o+-Mx(-3*_-r0b*hN|app zs#R-vC~OjMAqTaS3USXi`cgX}%6g3dmh>a8)qkEJ4|swMuJ2hPyx+-WZp@mi>QmU@%9*ekL zxhdZ-$W@zd2)3lfS!Ibx1EUGkL5-1^li{19G)U(=UPo!PC|)~FS~()t_#;^Tp2<5O z#8py;me%s>Rr2-6g~%w-yw3Ijm62h`R@BzXwN=WI0;1AQ7<@x-prb+SK-5A1`n4Gt zgQ~5U*at4f>AQ}Mou`%C-`~&sWD#BUz%A|5h9R3bP)T628BvkO98BRE0fZaR{i#z- zWQjfJ#J#UH!Ulgq4sl*5(^IAE!`>t0)kk%pb@&|>Us>ZQxjhQKA5xPB6n)*&?+<5Z zp`%E+*KN^l>z&5-g&)dT6vYBU4C6Z2C88vu<#8o`KIvr_HK?{uU*yzb%R+4?c+LGN znH63%8j;b0F_s)nqN_Ja?}7KL)>DUwZPs-YI0@tgA!AWxWM(Z(yz`?J+b%ox!}Yoi z>9E%GbT&Kau)D+stij_73buonH+hPtQs!NK9)*y{?EHRdl@!u%^F}6`@I8>FBQqu1&JidQ>^x)I!?Wl65 zZ;B}~a{(*Sw2E`lf!4woil5K78b!9kuWio%iuomVEPIscB1)*B@_u)9i$1W(^Hm@B zg)KK=+ftKFWJ`=Bn;AUTYssz8?~P&?p;ZC)fcF8xcyU9NB5hF#q@OKyw^b&yhuI=G zDOOAdbqASw1TF{!eb|B4M4z>Ts-?T$F1~rex~QV0#wwiyIQJgsw-MK7qbwguflovy zax4F2Lwg^%{L7X0u?G0tU79@?rWDXs^% znh(>rL+H{M%qc>B>E{ocZgSvedko=rD|>q>&b{#!{jWjyDQUb{c5RDkk4J6M!YJv#4Ven&E^XC}_f`YmGoTQWbfo;d#V;cZYM zyYo_XqCR(@mlZiYuOjIL<$oZOe(!>ceiBWDfjhC%s(bO(nF^d?CZ)qrFMrr|jco^N#u zn40C8dsmY0ePt`Kd75K3bmIeHQse@sKWVq7xY}7B5cu3Xi~v&fQ~(wG$V3?Vl*}=^4a$U_vEr7?h&2)<9o#KPhzQj-t>VePgNk$gyo7pbEzac?RMIsA9dfc0!8WhmE7;{%*u8G z_c46m^Nw?ruX_&gjXpcEuJ`}L+k3_}v3+5qo}=QiAbKoFR}l~pP^z>gX}n3bRrZpYB8+%*XPFEQdCvXUjGy) z5QcJu+OMW$Icp6;SoPO+56HQWmoe|Cv5SzY87CLO*A<~v73X*OSyZ17tgvw-RqPJ> zA38N(nCa%Z14qF5`rYS1)o7VN;bu>rB@Jfp8PCw^p zY!hG9_AGoje)bJ_8>U8h1Pfdy);H68otd~OVL3ukj=-`P5y88MFoqTwlHdW?RCWu0c?Z?9D z!GZ!9Z1cn z2;TO?zn)ooSp_I!PiY&C74(^_4PE7(D+47$7wqQ2ww96CqL z`ax8{GxJ?#-bfBaO;2+iJ9kMeh0IESO2ti^ZTEP{O;tPS+1>i9-(G3BxvAXUlFyZ!*rAjqK^VX~&2M zy&n?eD0DhMEQwhZ9k&ye_pNMjnJ2YfUQe+gk}obE-aR1TGC< zL@>#mtKWrps`TNm%X%;vW?*1oI5L#&FUl)bR8o{=QyPBqCeXu40Y_2<~8uejgf|tDsHN62*#CARtWGy0Go^hQ&WVoJG4PxN*VkjmN~dH z+|9SWi4F8n4f05+3-zAKl<*seBBn*Q$Ph#_$#%`&n2K1O724UzM|YB_jo-*)>qXiF zKEv-*E=O=BKkLs+Qo667HZmba>881MpC2Ah)JKY66>1YNKqhBA++Wex*H4i{X2d^q zHr1<{COSus+zde=Qrprh1_tDHbs-Alp-mtS&#hATw22|)tp)Am7PnItGe9AXc;-`P z#QX!yEmu!$lqjs;>+kXXe`LXYPZlH(kZKt+{t+^P!qC69CkMG|qQkF^5x9T!Zrb-W zUToopIAA_4Z++)AtFk{3cPeE=L1tr>n8!|m(^Oo~lsGG~m;ZJ(>Nm>CDz$9K1?qTu zR#P-0T%UfES0Cwa*0Q0uh7%lLG>E+MAa|_+nbX_a0Kyf^n#@q0qMqJ6 zPJ9aKFjp#rN&$p~?6Ku2D9)a1Owzky^+RHKg^p=Tc`4f?saR>!2EAw;GTVutE&y;0 zCFqW7O2GI|8#0aa>0foxYMtZ)a=dGu#M18y<9!jAZtNwGm-3JyT_w%!? zr+1%1wMj+DH#ZBDx?!&(lvHw3t`P3)!Ll}tpEJ%l4t!a)#=E@o6z93?=3R_tV0+IC zQEf{CR*usZBIuYQXf^B9NL@(!{4n_OL!=5EM&#}A%WjenyqR{wdyz=n*go?rmVk(* zq*sX*vRyPQYft@yaJH^}mj@5ex7(mZ%b!zjn{|^xaRGuRGMOIBqzC3 z-9j?WVC0S}^G%4N$Br#RYNe&X>I2J%>|EuaGtqb}?o1ihoY2?Itt<)_T9g_<{6Zc1 zBQ@boCm#QipTjTcH%)(p{v=~vV#l6dTq_BA!aq`mt-fTr(-gS9eT(U?M;0SCgGm$R zELnj_ug;LaxVC+snlwmT>%Ip=nC!Gf_WZ{914f~z&NZvL0r?zV8+*O?hQ@eB{ffU% z+VVm0Va!CS%AcaEgrhr2X*<3pYV-+M#ROn%0OY71b8j8VVlRzO#WSf$2-y_pXQ+PV zk6T1*CXMnqZ?7_;?E*?Wx_Y239U!*QP+ARDI>E{4nUqW){60#d6m!ebo8=1%HkzT{ z&D6~LZd*fDIA$ozOFgxBA#knK7yuehW7ez2)?1+M-A=aBI~zEmk#b@PnbVh93~r<0 zZH2L{Ov&l)ouKN5<#qdtu$Hs^H5{>TrTvfcYsAfW5+}#;C-^+q}SNq*Q9sa z5z0c?WQ-Z1xq1+Simzafi`QK*5oNJe@?vH}!M;0~)uu4&usg5`??uh1xJ3O%=Kd|l zK~x(Mwql=+w4HqPD7o(&`TAnWT(uHDzl$;?*YhY(MK{S(w=xZ6NEoAPL_9sSC zXXkF;!A55Pm^nvhq|{Z@s#kjtQB!AU0&9boI%U0=N@mu8t<#vJC9>2mEJ0*=+h+sX z8Cb6tOtJ<<`Ak7sS*1O_6d7cInQf<2m&&m}J_MLFsPukUjU+kWeT2A5d9^5v#L8Hb z3Ulcio#Yfhp8_X4ey&|HDL=U@CfA-rv5~gRZucZ@7bHAKSqIDUprNAiRPA+?ct)-{9hALk{PGm1c4h znH-Q_o72TXbXnFb+%iy5umL9zxmQ(ET=I#9AYxgcZ8u!KJBoUyEda|-VXYz>#qdz3 zWbIEbEE2jsb!2N6Q`1H-N%Iuo{J7;|60OG0JT#q!?M@0JhTm=vqEyW;m@I=5MHS9# zI(x4;m-m9{LY1yxVq$A;JBHp*8eW^tiK(jIy6URx4y-=WTS{y0&n5$v3zeXrJ_U=w#ga^TwH-@ML1SegyEh=CrnMrbs>B0TS90Z zLYUZy$YV*~(7@dA*?Kw0i8m+nB&l)u0zRq^TIvVixdK?4mZNA+`ux$nQ&}`N zD553C;Lw@|JY@4TW5i#L(URBcx9f$RXk*qy{yuzs`9s4;&eK~m;ooFDCSTEh;kk=4 zCwwlFs|K8}^b&wwV9NLm#6ILQdSho_)yq_c0I|uQQ+iEpCtjfXE$%On$(}?ng4*>v{TiX6FFlB#^j<>YmM@_pmVq84mvv(}uXVQw z-j6%y81$*NK7*LwIhq-%mFZF|8sL=jfXLskS{h_ZT(yEcFU_WqM#Fhe{3~8@=WZo^ z$#}nAH~=!m-qChYlml_1SG497E3MpJJ{kDFR4R(gh#L10t8;C~k!NV<0dp-btTo#z zZj8MEW|GLip;g@_P=be$O4vOUliZTD!TPvx%Ggl{h6xz;Gh5+?Hgi?${my0YNC8Yx z>NVYZ+~~Z3axlzVgxMeP07O=J+q+A6ZBA-6XS27>vuP(G4y5vh+xFy8?t!G;kqF+y_|By^ zAU#(r2E#)5D7ht2!Lg?v`!wFmAP^0x@p#zg(`h&s4la)+Q@u;f?U$fZ1D<-zY@ZSATy_KgsG-OTqs zF?xpAVU%oUVsSw-Stp+bWW-{Y2)z6bAZ1+~t9sYgk;GaPazc-Kl>+j!(w|b`z7Bx-`cAxXM zu?j6GuR%|1H(otHW3?bwQL>7AIvqdX%9b!c>xsCc(%i~`gL>Vw>}V%XyCWPhS2-Uo zH@~lpyKiDfaC|L4m*s4V=Jy-ZU7fD%LKSCNAXD$lh_@*qk@ubZs*%aoGHt+od^L)!kcm zW5c?>BhmJjz_+{@@^lh+Mlu-@6vHCzFtgMcJ+KPD7R9g>g}3ul{auNf+YG~*x2LMK zYeL-IIyO6Lcz1je0Lu*SuubXUxvPB7>@)e~=newdf#ICb0h%VbKO^4*9( z?FX*X7QiY+AQ8ucvSSFTyaffa8_m{5i30%5sH5sH{kqY}r8xlLW1np&izz6ZggS0i zWHR0jrG{BUttL$lzi0qQuVRBJo@G{-u-&cjQ_7~rfsH_2f%1ivll6&)`$;63Q~Cz<}A#cp0uNWFg~=P$Ts5w-HO)S7j|Q4Y!6$ zEkpq16PcPUYTrEFS|hX57(QQo^pd2ieqWBMEYe*>J-3U6wDyi0FC(1?_)Oew(`MEp zFb2IQU2y*KMjd-}fVL z_IooG>WA=%pFDbmC=9l-xhE>A2TBr99KO9j!f5(MHn4Tc5%`rT{w$5_u8J-qke1B* z?$UmkbY-W_k3PQis#jC)P%xC^7_SGz?aj+oUyDk&To3D-p?CS}uhluzbLVpU8zr!; zaR|W1D3#w(!mlTIbcbv#*;D`^^)wMXE`eZSp*p?#YmT#Mh%Z1IZL{a-)dD2e#ypifgx2nb2#vSw`vD(<5Bj-}3fKP{y@8FKL@TrXvXkWk4B?XI? zrGun7W0YNlw`i*f38Qx>lc6x*Uxwwu>R60;Sv<`6kv>|J5;}7(^q!mD7tw_?>z>xbF3XhPIhOWCYemTFbc z%&s(ri({`@^Zq`5Fn8q)E?FiaKND{0=JvHxXYQ4kYW<73SAo>r;%>wU8N12Z$cpIz zs7WO5E#G0PByr|d2lGQxfjP}2tX+YUsqFyk)Fum8U}VfmhT2OTwr|2%UpUi$ICOko z=_@jXdh-+#VGbReD^Aeo#h2Lt>q{MOCV(YNI%Cm z5J#~A%G)AF#B{oEmd&;Z!Cdw~)QS_3N#Rkacqo3;dW}43-`v(`2$J1!PP;?P&Mt=? z6HvC5#{7!%ZBB94rGnVi<`R2yHOQS& zLAgJLahr$NT(V4Wtq2Z*h^_M9j_v0zp*~2-j19`rh^Hx(`Hjo#70!617@}^gQmTv{ zzdk!m57{+(%X{mMlXizD=4K8~==?1cso)8nYW~Ov`2_nwv8z6ueCW1hoJoxcT$O!{ z9YzU$@{%#39_L_-sdjRkk`(=$PkQaf}C~*XY|-v)G}u z{}5ND9D2^+vOekx5?}|{p9XEcm{$tD8`&p|ReMYSfm14@rfdFKO0Ou+xm6KLuXrM< zURmLBqIdbEu;X&iNyUGhzeQHh1d6mR$4@#EYNV4Y8{v(ZZO**=&Px`X#8F?8O^seJ zuKQVO+_*t#&-*MS;+N|T;dLcW)#QHSs0Cb*)iUl&9kX)y(H9r+NacM0&F=9kB?}uP zx0NWWzGZ0Ml);!`==!2K*|hA~feDv1tpWfR&;8T+A&ETuMPZUj2s5$%ANSU zGt&PZK?fuRdPjISGBGK>jDgDBxRAzmhWkGA6?d6-bw97<+eZWFm)16-=mMWj>l`d$ zHW4A)k*&Ys@C%wzx@ANd<+Ik?$xFF8DNJ+87@96JnP4m%=8$5~iPDT!x!0w(AsG2Utll$jaJ zA|AM%>^da5+Rg^CrI2RH9J+cyRTxPolo+APWnRYS+>S4o|Ke8`l<9JmuI!x`l#^BJn9vce@*iJ&R=*n-*Amk6!|AaPVTqV_C6xzX({l4)mebS4oN^!m$p)aEaI)qdSz z*l0f87|cAi6}tdJAg&6GC|W|B7#b@J-}Q>jTb30TiZy3asz@6*LeLx&?+X9AKDp>& zxobZ`dobb6>-%PT3JN?`_Qy89G3@1e^tzS1rfy3nAPGw%&CZ(WZ{50$jvhB$D?bRm zq22g8mhMZ)ckFDp!8iFrwCe>y*vwYnOsHTP*O@V)(~HnF6BE-`=b~i&kdWNh-EBz# zT?L6uy@+Ablg418ZNn?f){*{3arU8O6%?}kX5RX#+G!aq3Y7sHv)1U>UC+|um(&sw z`wTYaORLVGZcj+a3E#M5QR$Q+{B?H~+M4vY@=1~k5uMdKbB23GOeWM=p zt|@`o?R1lSXe%IlM`x*lEoxCyH$WX`%CDa*ZuA6x6-AWI?J6o3^|EF@WyI>RnkqRJrA`csaGWf8c(%oN-IBAa7$ zt173k&vOKmvXYW`6G=VCp#YV&&Qp*w zyQ;?Q#A^9FXF~2|l}Dx4!D-(TQB;C!bG0>Zg3;otMT%2Hfp~#zaO+(jRDz_1dSz~T zR|UGivby@flcuk5tzi zY%@1Cjn*r=EKTN{KQyTjeG)va#tpP0f)|4oD4r@r5h09>kW{#t1TJXQF8AT}CvHYI zCKsrfjaUq^Zpy^TiHpfP#s@OeiWQXPQ4bw%bT2HNrkUBkQT5uY6W<7|y`tYzV;QINHrJ+YV%25x1%6 zDROav>=3`#<^LvK+Uw@T%2brjWXIgz3ZTgiOTYChC|MLDGol_E%%-TUr zNJW!UTbq|t($pnY;Xn939SWC`0k3_InRL0>6ENjtA8jT!^cmxbG1#H!qlWrkR@hWH z4IU{_QnFv%TtN;Np==s;(iG+8bub}teXz}yjjnX5=Z0z%4EZ$7KdFkkYd>lHXQ@0i zS11sf8qbgFiKxvvZsfcwZo`P?H08Wyyvv4){L&3fupLc6-+_HAF8kNuAgpOE+5(^CJ^_hv zc^or?@o`};+Wt4pb4cE7_UP%~He&PdB7iK(Z5ylsUk8JeORQ?@j0}+jdWHAXfO0oq zk4U{*>%-6PEKK8L!cX$olDMVuRS+$8+bX(L(w6HqKH8(-2y}S}hz2aw@+t5^gf|ghsk2l^ z;RvbUbaeITnMgS|DF?lQh~&kY92JDf*`80(sZd48n9wQo1RYtDu4~G zQ@}eh23xE6T(iu^K;=(_1qp!S%RQaU2Nwfe1Q+Lzb}o+-N`+TOI5G``L=*#L=>y^?~Bv~ z@L6ba*rK~iprM11#HzLM!42)97`$Te*!$MH@`Zv{`^W`1Lb$wqUaI8VhkdsDk^@Uj zB9HM%AR3pteHX;@b+oi1$9H-2@8ACQ=iuU8F^7ePg^{VP^sBQlj|kaCeUD0!Xq%2^ z4~Ct3or}zCSUi)}0B?5B|F=^l?D?Ik!P$%|n0&N_PeUU{V5RxY>5`1(AKp{} z?V{kxtFG)v0Fv9*ekRw**i2^9PgF0|GBvzzO1O5`Tj@8@<~HiOA7;-8`3`xJ+Q5$doz7vq40$w@b^?>RU5;cQJ(VDk zHpHdI5%@aL@8F&O5U;OK2cORKuCc;5o1$bNeA)Ngzf5nMtp=c8D{n@`Z*cY&s$YQ-wq<}oR@s$f`&5%#FmDCxxl65dp_J_ zaPmtZ;`dElr{JL=%gyBCD>fecA&Xx+;mn_17l|vsVkE1&Pm@hvi3~@{EM4my5-uv6 z%6yc%K9?eLlo)IQc;WWVLbiFOTOmr^#ixqkk36F3XCPr4Vi)86?)Ju=JpQGZT_RxU zzM#!#7_mhh(68gU9lTX=o}Izo>PFac{K@s$*K=%dNfgELb1ZOFz_%N-p=V-J8;tuF zyms-D($Me?eybC2=3f1JHvBDw&17qZHSx0srL!jM8So+(*bi0PoK~omFd04ItWTMY z_TbYmwih3teO?)?aRF{|_ftczy_TS4MVXEiP2dVXh{1TSq?_1a0AYrOnh#KtuWbq!wEW5C?j7rbcm~RfA2%qLN`YgZd2(GBf zgY@U*=P!lZv-4rLJ5T)nS>6a)C)DPg9FevKOAxm6*vzjjz3irKVWw9F$pf;n07osC zrk=teppOii?3s2kV&*N}BQ=qxZp#o&qg2Ujl)vr!8Q-*DCxY4YhQ6!1V!B$9UC2LJ z`M!w@`~FPuUp>$iMUUajHDe63tx=mGz>Q5e^FlkU$ypS3nz}=K6%iP|E4^nKH;47L zL%8|-rchOvvE|QGwF1iyW>q{op?QD1>xIv-$5i8s#)#RT#dA;4@U{0&G?-Hqtk;vz zRjRDo4D2NN4g3->I-tfnS@;mXe@Mud;4FFYZ;*eG1GA^|NL3J4FKXccJoG7y0~b+s z=My*qZDCAs$v6Wc@Rq6#Wa)mcS{i(Rb=1wErM4_18U6gXM-Qm>_@>dq z{)x-gRlpM^j}DYucxO(7#*UAg?l+Y$tFN+|D|CI5c`TRh{)=L23+id6l-CeM8@Q+q z4SrQLO?|V2k_=Z($vQ>!fcI>W3v<~htME>6LuAm6Z|_o|r0pIpMKb4)9M7Q~_Sx-~ z{WhOPmw1c5$O))ucOJ+L80~VOkLgUZvaKx{&5>dD4{VSlH%6*RQRwJYI_Ul~A$Z!d zdxjrd5!4_`^Gt!K3Zd0l7$c%wcC={B&D7IjVr7TJN>~8KuY;`9@}5c4Dj^3HgBPRn zLf2c7e%-2urI+7IPd3L^<6{3LJM7!s^Rv#*l|lFvJ>Fo6@cIt+C@Cka(N>=Vf{7O$ zP5ylM>D3)2sge_t<4;?mLpNm-gb57npaRUIbbY!itatGiy+9-jH7rf(Mc%+YLP>l6 z>vRKN@__OpS?lw6@1He?Uk1P%Cze{#7reCRY{KrohHI)b;!mJ6woY!5D@FzWZ6!yM zI$m0KU$Q%JL|#0Ar%V!`0q45&<9)#i7x&DpZl8ccr zeFUA-oIL3IR(358%3D};6Bdk--`RE*l71-fTEv5eB?z>q*SIeR{p9RcSRdVl1q<2w zdXX}*XBS1htjg+&a=;A)V9C4Tx;pc{YQR)M3^gccm1pzli8Vc4-{I?~4>Gk-|Nicf zJll))9d>bXdBe%4)Lw#M7qQrl%$$nC_GIRT0~cnLuE-qw5+=Tg2xZ}G85P8{@{{bB zXT7m(SM;OwiKEL8>J(V;Z*q6#A(B+YW})GrYZVX+J6Yuzj+-p1}63-kQ&x^21p8~D(fk`CW#5ZJwFKJEn@ zVBp|IHb>T}0HnOw>&Hbs3c_{P-ozpjC?l1q@X3a?sa1WM>Lw*u*8@QA9`N^gW^V!< zP^1g z;x2Tc55F_468`QbWT9%^4Tcw&-{#9-5^`Ewa!O?ri&Td9%^Q zvG+g=*@UZRW#e{+RRcWD+9$!Iz!Ui9QTp;4w+DAg%u5e$wZN*XmmM|V!GR8G6L0?= z!6#R^T#TF6cTii2JxOpzyaY1IMf$tyZ%AX-?NYA7)tZ$4bisMi-Pp|gGwWs_X}r(; z$ezBl>Os0N8&8*+(`PoGdwp+gg|>XCru``7yAn4DswjD>kbDa#EMh5>iWbbyZRnPX z%b`8>{OZc=&ogPD1NLR&+|!o3y|Fyv#K!jzFca6(mYKb5QJ&-8t`ffCK<{PQ6Ee|O zML!t#Vt=l*vuB7)kJ4sn>b>+4`)BPP+h@DXZj-^Ep+9&dx>ZXvbw9yhnBl$u4OtBS zB_Kvro@=~CU<5pc-Ig?tXV>H?zz!WGUowLJ;IkUo?noYy)9=Dg+^k(x<;Dd&HSSI- zsq?!g%CZd_yMP|`MujcanzG!oMcqU18S*h}kuE;kvi<{jpOLQ}37f7tn43|;V1 z#>asJQP(gb?Npu+D?zU`oRb1ciK=*m~_Ec{Ak9h;&tV5;-W_IZ#HK z+Th)u``?T?u&19q-)mgwQ}U|9-5bB=T)H(~NTeL@C!wDLxPk4d(ks8xf#;A0J}h#f zIZb0kht<~k9^A_8JbuzA99)zMSx9~AGRdVFH)X~ZbNlxEw4?&+_o_*zkLK^*dmm5!w&XkiDevIVjD}1NNb1OOh=6)*$-+3^sf3rW zp}SQ8vXqAH7q~#E)kbfOu4$Zj+xL@8^6r>hmVNE5#IUg(1hx_2q3{&DgJ``Si@nBOJ2TIHw{lUfn=AGrQc@82 zKNN?3-*4~o^TWadn;_?n!u zGJkMZ2nra7=<32ir|oiV`-m6oh@$;7zOcUp;UM!eSGMRAG12**orx2~C%Y&xHRBvW)upk9uUF|Et9DV@RA1+kJNV@jQ_lIl=wwYp3~uN*`Xef?Jm2hd_m)8x7^>^4!Y~d1jyKa0a;67FpI{vfRH@3#rLVM^rlH^}(*1sCjO}U9GW&9Ma)1)e8emc);1m)h)t9+=l~whV zq{&osQw@s^Wg8T1X~$(vTeb*x&Uo&(vda`U&SSF5BNslyW}+bEd_=I7SNmdh<;K_g zSoByqer&3`F+)49_=+-Rz}R8&ZSQ~6`9F7q@?M6BYj4jfE$y26D&wzdaBs~>s=O>x zQzi+6nrccVmbuwVA+VWTYly71b{4OMxoS_lBSqgkEnvELv);p`|7*Z033}a&E|XO# zd^AtG#2S@+c9etRD(Oail*GDdrvAOmX{1r%r;Q=sfs>clHb$XO*pWZ&s8PwIvSl}m z-Ire33c9$fZh$cT$E$j5vQXQh{8BYZuV(-+ON9u>UD~gVEAv!nJ6GB$MXx_Hc>GJh#B%_KInAZW$E13((8h_qbS}XRZcl%}&WNDaiC&BWE%*%l)8OZ0qm6E?4 zmkb6q-W7@rQj=OP%{6S9In=Sqa-tJbz&{P+0w-y+uuw-^txEb;tppfB|FX~+Z~{M$ z`)un$n3Nc;XoV59CmK^bhprx$IwFXh#jhL)Qlyw|xIVfYXlig7@AD1SJ^J#0C;tDqK+`DuXWyR(K9Di8fQpS4 zN#>%nG#2>yE=eih4$aNgr&b-)y`$$_U01eR$2)S**t7X}-1y>rTbmP$r%zQ~vu&w4|{xnObyg}NGIzYC(_`duL0aV^Ga*EVs1+x_d8_4fi^@r*kk3Iu0H~-y@FJ zX|&rN82|o3?x(@xI5d`5{w5>OxvsA?S8i->m^;<)=2Z2 z_mx?9j`i23CC)LB+QnGz>wZ&w}Il|I} z&sxOsI-=y<`N=R^f=tZY2dIKw6S1%E=w7GIMcR%6mystX&Oov22FlJIjmY#NWqlQe zRB(5xjdbSX*n*zQP>-O6@6a4fL|Ej<9#3*#*x8-hT~QnF7)`?mST4u(O&1G7*#-CU z_*!Hvt&d@nel|Q?@qRKc!97_IW*;HBJ7W9jSN?mtmT592QArUouvE~km+OyLM7=6S7g}au{W2QVs8A!Dd-Hl}dUte_g}b+38ej@< zgmUpu=w*{p8RFb`uHQg*D(^{W*pdIFX}=1P!5|`}V`INKVlNR$Ne)A>b{yvUyz7yh zq3a7G+@#I05hdznvwv;2C+-1~_D~wHSeG*hPKHhS_EN?^TP!sI6v&xLLu=h|7zbA( z&a2i|%P?a~?}MuS_X8s}hO8R`yN!P@CsJ?t=kU`ZScARa*hCtmPNkL^1%_PT)S8zy zMAWag7}ZUvoBcZ;HL9c+wnKgwhxYa@m@8~=pQg`)4S>riV^z1eL+3XfHRpYQUnkYU zyC>QHivP(52WY%@F!w{)YBLsnPUln%$I{qFg1g5)gDds!?hddYUMP2r)|#{H(MiNI zVyDOMJVbtQ`b^-EkWHv$GA+rmq6kg+Z@@~mcYUILVdfz=B{pBhlS?v767bu!Pq=Dg zsg%|9^ZK17-`)~w(zH=YO>N;#2{PHbwAMrje&uLpNYk{X_qU2OtIfiOpRN6ia0C#1 zuP-or)9?Y;sJX?AQ7?wQiO6k44^0zhVxojlk&Iz|YfqPl$5uQ(zE-b~m4I)O`i6%a zZ{C@elq3MfZ;8>N{cW{fDO$})rXb*gg;LG(qn!81vL zhl}ZbJpSn7Xr*m>=ZU=^R~`D_k7+UGsK`FY>_XfxnU%zks{*Pvg|&5&p(r;@-F2M4 z$>M8R$Iwgg_Avg$?#s`4>}kkPQMsZm+cY(05da%qn)an6jF)BVE1;6!{W2;+r6x`p zbvn|>WFrb{9P8J-n-sCHiu-?0RyXRimZ;OP*Q&kGJSM10$W0~3r!E+k;N=wPoBeWf zx!rFxr162ey1KHD)^$+srP_LqEJOI}s1G7L|IZQ^_dew_M9I zXeevN5VUd~ z3CQgBx2X1LZs>$>Z%o$`#i&H-YNhj-<43JU)qAll!hPV1_yl^qa3e34{jnG%z02m> z=db?1c|o7=C*^)noeV?aawgZTrF~TVx#6DgHH@$o^|l{WQ-N5EB2vbEYx)|NhH zuK0i7+%wK}9XI)166C%`joWEMt*TZ-_169jch+beSmb$4N4x-^Qf*(Jy!q_MO00x& zX{t2lP;+LAsHB38ber;Bqsfk|2_Kz@q)~=}UOu&R3*?0<8bbYIcNa#xy@vWI7n19k zgYzM&ncb1xj9s4_#3gCvf;y-;>4RPr8MY5;@d2O|o{RXxXit$xHPJFkm>ug~eLG6IUYq|245SliWyxUsjk= zvox}@5f*V;%som>0$QLC^DJ4vHYwycv0Xv(3F)g0VtwHwDK#%Squ%eCT>7Q|22g9r zbTL`m41O_Y#?U!!xE^c3lQQWmknMn1Oxdw0zy*|kJ9IpO)s$`hr@Y<1eZzhPFjoH0 ze4D$fl7?H+)ULOl<>?dFzas$ZnpU~vMcwutehldJkY=Ziczcc*f92iT`JnsaZV=CHF%WlEf8`Q3<9MQRWK6>8 zr{25o&=a%gVct+e=N8_~u&TMKXp&TqMC%&fiO)V1_ePV!6(C|`@A<IMRUUkF$jhlS+P&fXussOkG3G_rW#bC>v|@1p zo-UHimR`!K`~i4_`pxtO$yy9UUrTRRMk(nZo0o1TBhnU5%{wW|aRS$#Mpqd1JKX9f z$`W5AZkEB3sqYr)yZ7EV{y%k`>+i(FX;)BCrZmr?3lM{BU3nDuIeXt7?K!U+z~ZDS zzR^LoEhHs(8SIAE_6?K&FNfUk`ko-~-kq{XblH2>zMkWID)_$>{~uiNX29k1uEd4q zE-bi({Cv*sKr1xq>*<-$i~lI79@^^DA|R$*TU(mrJ_j&klFS_D`*MxU%w~bFtAKK2 ztmSXhZ#02{-F>NH<2_5cI4J*Ok{i5J8(!fMEvaF3NlXm4Q$NG2{Og6VweD^P9GauxosL;Mp)=|zQwdbT0cXHc49lo}EonVdZ1yVtB!|23=H|7=oovlehk zdMLqFda%}i12!K%!R8d zDJe+AV)_5t{Crn6f3bCK8uiAZJx8re*Vf4-sIRZ@)Z_hJiHA>#>U0-hshM4yUYF~7 z1C;thk<~I`^ptQ$n;4)FLN}JACY$3>`)Q3SOnknf(C;gsoieP_xW3nfN+fSe5#R3* zpST$mZ@4hEky(lhC>|TLR;E5Z>VSo9BrV!vtP8XeF}AgK&()Y6a;vXL{6#Z{`o6s3 z^J=(fWMpI=-Fl`!9|v@uO{sfsUS9k7260qGLn3HAB%d`KEoNP6&&eZus}a^FQn8bx ztN2I)X-ndU25V#lvwQ$%V_+^MUDY$yI=J_?H0nC+EG=cx4RNhI9#r<4;H}M!@^Gfao$9`1 zK(BU??lQ#2CcR;G6$kt_l9NxgMKH``V1h4~i4FMq+;_6r;u?7o()?OLf0^^oV{a(M z|F6i`u;kn^2_e{K7A~M+1?Y6sKy<@0Yi)G^u_L(yTh&z^?W{j~RtMr)@>)>c5}AWXE0^z**?z`m@mWnqy53980P*LQH_`=jwtgpF9;X!-B8+QX=r8tn-00lptUjBIVa`bS1a`f8xyv{-Fa zDPx-p4v=8n+})>>t-RtRy_QMe-vts}ZT=0feE5xHYc4y^+N;~VF}!v>kr;O`TWiGM zYMn}g-T_Y@OS3Jvd)`p_;0Yussi8sbKdV%Ca?c!xCCz5QhH~k}5I&{4L>(Z@UjIiR zVLl)C*C9cdelF1R<8ZW741}u7`^>k!AivIfHk6*?yjUz3MrgjVYzp~%Ln_&?aXWy| zAXhMC^QSbp#<+8B*Rg)Qw6{+DVr$`?7D@khfR$;&nJm|N%?QGmP^6D|Y$N5Ff-rxVB?ysYwZolwRcoYHYMNCL{(H_kv;0F?!zb?8 z``XvO_P(uqUqO6&$^RW&Ouf0~ljQ{aihLw!QVKMS@NLgal-()}IaUNtaCQCs4iX0@ zMX1GUt+16QoU{`;v7a!UqrojS*G8|GZ@;>$>MmyoxEX5U=Umk*bSEd=UN1TkUZ+`; zo+Ek!Q`+aJ2YB6H#js8?*VQznRb|e~Nu0xOI~R7zr;D17mOr0TQvpc*@}IuzJ~fT4 zL1bf#UX}2kfA)G&+hr3?pTyb9rk!F5YBRI4!bC0)1y4F1N1Efqm_eawi|XFESVD!X)?=Mn|yM; zJU?0_8quGyvcjfuNje*ju=MHiPH=g&Rk^2F#=J37cM=lc|3vS;XJxKI-E_LhL@jEQ z8EC$QfulMtxSej`RRPiz?U4>4penR&0fX?%Y68F)K5sB!3vFR`qd)wiy$NF0C)ttg zi{9SnmSeS^Ro%>wFtU5ZQC6|FHq)Z6`(ZL*>dhd1Q%94744K!>*w3p1yg9D}m$v-# zvK2DB=l@5(G&LQ>UER0XAZXEadZ4m@y6)s&`Q_QgL9chmc0rALJ_k!EJPm3c|Cmtd z30Lg`aqQtLvDD0E1JOp^v#BpH{Lc1hFJHS?V(V$=u&)fL>QQ^7I5<&W)~@1<5>0y7 zoh_cOFIFM-m~3he5P7^N8=5CSf++;zuM@0A&zaQq`+R9U*|V->UoCp^hfM#EVyvto zPw<{jtMu=V73`$-xcB;^|Mw3;aG<}ym>*(2ev*(e0t<+f@PXjq{>s%r^3XYCn zJy4B!oAzW-8++QXwOF$&a3jo_^L(qR%Aw6oN>G!uFzvdxG5Y2sJR-ulE(dJ0QQqTA zBgoH_Cj4J`%;(j5B+_6D(I5yc_3nJ)**C12Ot5A)GYZPfH4|JVV|eSPHOl9aKZ?H87YJ;B5G_>x|SQTX*rhTy=%`74ksRu z7c-rLS+JG^Fj_e}$1DDT_W{_ioQw*S%(V4Md4**WPtrByAyyE*)E=>er zW3+svW-qp>XkPUB*aSz19)Rig#)pV||3RRAoU1DGQ~f;vug-S&=GSVQ^u`P=&Bo>r zs}*Oid>y;lAjp}OnHefLik)e*@j728^RoeM0N~u-i|hhVYPE|Cc<6A2Sb+*{_fHL= zY!0mFlFN56)7X0p&VGh3~f6$9(hOAb~SwvIXA-5a%3y=@}&s3MB*$J z=*A&3-!he4aM2R7s&tl0BniRR><#2>|t4v*SVWkkxOA`at)!_#ytu?v(QdQ8a;uH zuOs^QAZYyZqRIHOJsd=qKi|Ox^-Q`Gx%VDVa76QqDeX?aB9M=co|wK9cfFZ+@su#` zd%Dy+On9P*+L8cH<^AOco|W>>I{L?N^X4j483mVe#i?_?)F-~nc!+z{n3-7PiRO&m z+5h0Hsg5F8rzUnChT{+io23LwK07;Gmk`vgcfP*@sZ5czTZ&-iVJztmrLYf7%`ALk z^3GQ!@MhfCbWGPD^$8WKc&X5rujNdk7vC$E@Z+jidFoR8&n_kGKiV&~-7X^~HP;I0 zN~HPljWvO_g1X{NEr_gL1vxIVxj7H^#c0(ZqGCl|`V)=9tRyzYJwu<{t_xwn6}`u& zW&@!tm;d2YB_*V4rP{vnAT(Xr-S*M|5PMq=0=XVTXZnu*^+K|f%xn}*K>}$E zW`@gBb3E0gic3uwzSN97@VNbBDg6ZYzz(EnXsn0hCex8C~3{4W%sZ}?n z)>n(j&SZX-!2#nL5FZ2NQV!2AHXmeS<>ZWPd5@*x`-BlN8*k%oQ;52JVZS2$2}@|V z0Q1dO>N8w;dWWvUxYmo8*y#~HJxE>hX1HL^lR%SemP`XmNj>`~0}o6CNyr%5pX>a? zWhssP*x^__@-2JNch)xMQw=6qE+jOmT{dy_4L7b8bnc&o5WBnF&sPq=FtQZbdR8SG zt){}@q+y=iRePcBYWB+3tTeG2%u=%xvmV4o=uE}qp zJCj-P8H#le$9go!+$a8LHGoO_BFN$?M}w=7&!g9~R<9WtM==sb6F(Pi=a~$3eqSvM zUxx>Dh6RM{4QQ5>%=>8q3T0#XNxlY|qruH)6|3!#p0|T6Qef$|fL#OYz>ija&cK)q zVXmnjftu=0ABNC^n`}1!8?owJD^zfx7KFxX?DNl^%?{Cy-C8{Th@7cAVT~wd(S3 zX<+Psy8hvS4GT((_DPYC+=oWgz}4q#9dGM(1YO#ZLByALcdcf-&*0LmF@stSf;|yJ zJQ5^+yc+rOdTRrl5hAj?x+;O>(Df!IIoK*4a#9Dgpy6}cQt+?KKl%-W4GX@yw`z-o z;|jMVz4&p-R>eCstllxMW>a;0+;TS5lR-#mXc3rUF+KIn!hS4`_obids9bo{f|xv` z?GAFEB|Y8g3QBwY^0gh4-0`J32RtortN00-KhxD1F4M1en7OY^cfa)zqyp6Y5J~@= zp#L(Wt#w)iO{Nd-7HUWnMsiUNM;32-Ooyy~Mqz&VM_>bM@)*b2*s%1tv2PUvSE7Yd;}N_pu2$v};=^YeXgk0G@wzdfGgT&Fycad`{5 zuA8IjmEDw@VcPyh*}npWpVX!uaVNz30c+aPQ(Lmw_6uF+$=7eQdaY!sb2L0>D=r{- zH}iD5gm=D&ra1FpaNQwbpq^6OHT1WQC1Q+wGw&0bO!WzX{Xa?5j z3dX|0h=DU>0;f)C+Y5hcrWBb^2;QCtk3j|K<{@7O>g%+E;M9VgC}3>hFPh$uU66C@ zZ^*^6v$BTy`d&o`4QM92FZnT}n3x`+=+B20bAjxs)zyum&MTfDAXM4TQ zX%9yLxX0A;%2rOz{XFf_x}N&ENS{)nHYE)hk+wo~c1K%l7mi*H39sXzS0H^mb|zin zukjUau{jb+@Yni%B6Zujqd4Cc&b^kygE@J@2oE0H1ICz0L1tM|&hc8|1BJ0|Ey$*TJ&CI@>*!PNQ(70uuUrKR=X6_bs?@rEZ z#6I6JFyB5~7B=6f=?^U_VQ7DJtnRZ*?khKW*@eQ)!|Eh~>}OU6Eg zHxaHa+HvOOW+O52oI5`^FRIM+v9#WvmLZgQ;DsV0N494$k`}pI=2_1V?yQdzNtBo2 zZ_M21O-;l8h^YG6RGBq99R!jer_7M!P6AzQj_M)@r&2F_r>{6V{%Zo5Bf>VZicw%upf5vCWt})`$Q7FlA|1$jNzX(FtM|zrrl{Myu zb3ocC@hbB((^C)gxSRZOjJaPP!hLVtV+(V#HM`UPz2e3j23J=ePdgW~D5;<&i!P;` zuElbxEFBwywT-@pUlbD-6cU+6;`o&jT%Ni#G3KZC?vGyTr7$g9weYV~3R%vnXq_HE z-t9|uRcQTZ^YoVMplLgw{YC&3*)dPl9WlGAm^j1I&ox6sA>kwT{!#)9k|^=JLae0e zllPes;Py+ea8iD=Lv5BpL4hBEPsRQKR4;EBETdMdXNocdNzpc*>pD)kGsi80#_e#% zLxcTXoiasG6=e8H(BeCbR;g8VoZDK~E(j|s5HF;pr0l?2>KxKAu=cYlsm(4ZC`){( zp#?Lo3%KNF%gLd#hDg7j&{OBuDIMw`0ezFQBh_%oS8kIw82&~FXFn>-@ zmz;KUMs~Ts_9Ixhjx|v7V~tO;*)+z*jhJq4tHfJwc9hM5 zU_2&f=}5s8GLRGpV`pDnoZIB-oh%z5jm(#_>eNt|g{hU(T8FoZnceeF^ZdEX^oaIYeuJf|D=USjF-A)96!^96;j2rcFPphGSJC!5$@6#KYWyxEV>8!G zL}VlkX*a+ahl^LEc1g~u&7dT@^H!nkeNTSM#eRmwSntQAPE|ek&94HUi-7rPB9gE| zcJG3W&Nr;7>Yt5x$gI7vI+qn%+s1^;Z_EqLXq^F%*AVUD?hwO1-GFHfYT4XDC>Gy4bRKM@3lX~F! z_d5ykw&P|#&F-{YrEdgn>gqasQsIbtc@fF^*8Nabr4?rKc#-G%)y8knW{bjhWP;LUtQ-CdR3|!iFrr;NLF#1PF`Bw1V>IozjH8*Qd(t>x4CH9R?sG_VRLe z@aG!*Pk#jIz`83fG(;)~78SN*v5s<2IGm_zMxb(R3$^|uojEoe5rG}=)o03{+Hg-Y zPB?#;Gm$Q0aBo`qhc%0W$8JLzr0yP?c7#z#HPrtTRxMk>HRL43yYy7qC?KLM5q8>R zNg13{Vs*+vQZ;?h!xpwJ*IUK&xc8z{U91hks;EM zgAi5@zwafJQ(GiNT575HKBo}9H}$INz47QQ6+vUP-7ci6t~6hH+Ql?OL8jQ;GGt?X zvwPR!k-mW~d%J9V$0%>biae*3&2~v~{0dyzRc1ddE5of78o_1%)!-Fke>20%tq}s%f46)Ytl4Arhm||n+ zQ**-)mPVx?bsAY@?9#jLd6LV9Nica2776hZ<5%N!gs}>gXP6sM9?u=5Hn4iRR$E%1 zMh`mZO5tGDyDXEu8W~-QhkkD0b$9#aV5xpZ>^_RKz4)qHW4pwxl9YGs7s6yZ_E!h3 zFM7Q%iqG)}_#1WBx4kc`&a2OMJAtCVJKd;aqp0&y13x+?d%o{^R5cUnd5F^+@#7Q7 z3p=C@cYP*S>M5sjLXdv7Q;6hiiF(?SD3zw+6c|i3^%#rjY1s*k{U!Hh1aGZB0Yb>w zj{D@$_3`2tKQ~zmi`H{oafc6rSZR_EtRo{L=u%pi(YT{xpK-6)v-lu0*>7MoSK6Yp zRGW(9W_OWVq!Z#!yraq4s5}L)@F1cr}pv$ar5NbSUWvv@SB& z8;p(~H~RUI`;G$AHakCnrcI@C0I!5XqSQbBowUSII_HmQTe{T^R&r0H%-ik`v{n1h zWbm-2_O~K|!c5R%p#hw=SkUR1@czBQ)07L<=RFT#wNZjmL8AwdYK@7PeE2;aVgdYyf8WbXIVa%R-*c` za@&;i;54x-4}{4CN{3&es2xhoQgA?%Reo4T!o*7qZwC|V_^f7Kgh2a7zs!65Ba^B%s~lm# zJk5+d@*k?2miD7=n2%Z5oUn!{Q*2+&;H$UTzs`Njv;tJDGl|6Mxvd>gJE^DLXyP%x z^emc8_!t%!$ClFK*j@DE_p3j>{YxYAkZJ{Aa1GGg5oc!}XqdmS3zRDUG;ZJsM`||b zNn3x9ZTFdC$8n3<`ZvjGnHOiv5>UN(K|Ft~yCu>fd!{F6^-zg!xWK?h0_01qC5&F+ zux)ftpT9<0jj3A>h93pdFetBGwQ333K_u>;bUs@pehh=fAD_k6S-h&)7iIqJ`6`>uQnD;+pU<19 znJ|u0;K5_J!|RFj<@fa=iZC_5+^Jbk&f$Ip2Pcw$J$pl5n3;B@p!(y zC!i(kiof+lI~daF1iBb-*4lYVu5N`2E-tQa$l=MV zk~bU3VIx3}dhAYI=`9c4&aGG>%#6+Mh26x@S9+Yb@*~0BH`94r zt1n+fi|#I%xEeKZReA5X$&Yy_TE!BMSEmh^99*3_(|Yc4VfUOeNTaf7-K1g1dRm+Q zQ}+x^VJx+{e8)FQa%@nJIpw=#1M&3b1I2fNhNsM<`BqJ_HiqG z6fSYSBd6x*N8qD8Keek`Yn$T!A&4ph#x5)lk!jW4FD={ue&7EfthOe$w`Wk_$j;#e z2t50&<)e)*>ps4+PhTj11lEPejo-0$NfU@`94q#EL>4R8^NWjT<7`_f;9);FRR?eI zfHo5<&(~V0Y$7^3hU->n0a0pf>fV4^8K(yA=hZ+H8^tyOuudr`{Q> zvc~1I_H~=>&;zQR&D|%U!w^!5>K{i098NmT!9G18rBFBGhn)s>LXi8YudO-a^5*Ao z(VCa7&d_kpoVENTbP**E^uBskYYP&+E}hC>hm(>~vg!qQL4uBwY8`g4JEE8G2!alr zsWPyE*a~V3Rn_zJizJmO|8eX=0v)LKo_Ahh<9GAd;lv8Bc}Y(kSPNe~u6D1mf~9Td z(ATI`H(@~t_ziNC+IEVfGa{jNPY6|D~ZV_=X{-VGkak29Wc6Pi|WIZ83 z^)@_a{FH(e9a*AWNA#S>dR+h(Vdm%O7x0|4Z5`{?JcGoQcD=gd5E;C0ygDT^^y>UH zz2ieNh28PpngyL@{77JDK}fpK?~AB_1-AruS*golIGrs958Gsi?e6v%yjSQodN{); zWOk|Vbdq%!W6&DX9#pU$T3I>liCtwu7DbE6AHl0cbtjsl|1wf~)sFj)`9pLk<(!il|cqQ#TyU@9CYgF$&2l ziYLz_6I6`sJ_?@i764uY{i&qC$U_T>`Uuf_fuV{st=AXFtrDOY#5z);{|?OoFo_)) zXjMV~%C1&r9AZGAVKL|P4#w;8#>Djaki5k_$prT^i<6_7x+!Dm_bVt^XY=6u@y$jX z{I9$jE4vTRQO$%V6V+eUoi=t6iQ_K^F622HtT)}rtNT|l4II+Ge`gRf^tO2qj+w+7 zE6N*AzZr&@2I@@V?~B4C9RnJ=*$3biE^GB1ww_VB*l+ZETHR6P7~&@=8t0Tqt41>A_^{!GLH;>wrtro(Ut1OYE6QBb96G(@d-HE6>i|COf*{rpmoa_FXw!tAo z&G!cBtxNDB&`EcSa;ne?`L4Cp(eh=3s^5DBM1mH^-&IWT=RFz|F*EYEs@3j(T1ZD$!*Qhl0oWg95gmeK)_|cV(G&fM4$1 zWRm~FyOs$ggcFBpD2K6ZKsJrqCDG?{xQ?Y&Dz?jUCzwHNm(RxYjdU^-2B1R#RV4Jo~LqPUJ8#Q?XuGwa4tno@l&sT#dU zx%9Wao|eWrSk08jaw(-rhqPUfT*X%ixHTwsL}0)nTue;$=QEKo1_2@aZx-D;sdLUD z^~vdAv}Nt(`8MEX05PV^b{|cKo$M`l+IXXMD8xO=Idy<|vl_(lMX!H6q7Zx)hjw`3 zLpd6q-?LOVFP@@hO$`D;WSsEDPGo1LxrM<5WwCVff9l3--o04)zU(Z5+^4wrZG!SPvTl*KzjatOjcYW!#;)ZM)Hs{8PMxWt zunv@nB3D&(z^Tw}h!^x#CS&(J3g046jf{+f%62?o7(qSeQH?E#V?ei_$?|wN>)sjLR!YxP1g*2&{8h`^mFUHFSGBI#_2vEAHUnv zI3=JtH(*1Eq=_!PoQMQm!O4WgaP+ogO8n45F00=pO_={>ar^BVSn&8b*4Wln_agW7 zs5*(pneaGUF)PClHtUDlCqL)y+Iticz-o#h*4Ct13o^@iXRM}{ICc0OUcdLS?tsWD zK{x6OgpMB%;1H z@Hjj>gOy$!d=Tm(+&i*$3e@$OzPEFU@jb&}l1;?<-DSd{saa6fbTmc#K$S+eLQVt5 z;6kbqszSGOtK2#7`!Ih;GB!A%B&AXEA!qy8Hk9Y&3!X0F%B@oay*)r{ef#Nog}C(y z^Xcswa`gCb%=Dq@NV9a%dO;598Ay6N1uFiP`B)kTgE5kLq#RDzNT4;t3w@7?(1l0l zuN9zFeae+?WTa}9jj>X&u=pld0&gnp$cYuel`(Y zo+OhR>eGB*@&Nrx=BdJDQ(FwxXPv&wT~qrwkbEP8NSv#?Gsy-4fK*)Rnp1wO?siDT&y=gw!FTsg?@C7R>X?MzEM8_;+u?MSek z`&Q;)w5HeZ3|SJ&=y#`}hh-(!ojk4wt233l>orF|UiHto_!G(^Z#?GJHTMt}X$K`l zV0Uo4H}P&bss$ktP#DZ`?ehZ%fjC|J-kWJh zCAG=Q@1u-D_*&(kTuKVrol(@;2_?<{G|>xEPytQx8;nQ#vJXM6p8Tfbc82#IY6(~%;2ZsyW;kN!UEA`Lyt&B&OTF&H`tj{f{hc0n9O67yVC*DP{Cj+}qECkeg) z6YfWZB+8BD6M!323LTosD&TP|{6449XDjI6jDK;_J`7}=7#Y*r+H76XlaF{kBRmil zH?Q|6={ZIH%S}LhUcrufz7`p+;{xS30hQwi4(+-nYVf;*EfJMdg1Ff~ z5MgEOkAU2Py~-)qk=5bteE?T_H1tbl*VZld2sfKI{?rAy|0}ATlAF0OVqgt0&=7f~ zUeEwK)ER@6&RETRIc+y3aEH`%7)Uan{Hq|ZxpFCe6Fm%ldBz8nbm2rI25`6v$OqEV z7nj{eX!OAvqVX8x^t_W{Yar4r3_be$WPA~=}3GeUQLaZbIPq~O(RP;nc16nQO#>88n zP{N$xo)ogAKXDpuiCd6pp70Wuu>RAprgcoqdLvjAQ)RSKc2N1Miw_0O{5#{1$2Z(n*xnW6UF~)8+IQ->6o29&5#HsTYv`1GQd{mO zX)X3Csr2^9NWvZ_w7dlgoWHss`F7LVX(-c3u3S5V2DKMtKl^S>MI+MAAx z&tVZ5ergx8*ESpeQZZ7x-xblZVR_ybx@tE}f}DhsaC6yaEs=3L21IpLEH8I_kG99? zbt&xf6fIKPMujeT)6&(gr5kQ_Wi6ow4h<12%l-YW3i}>cAZFBmluN)Wt44GTNO76V zCyXjvMqe{^WI;rem%U`dOd9;UUBO-LmEPrO^KEZ8y)*ZOQAK6Wde2lr5H>B2)*|iD zo8rgo(QBkv64qQS32wGViG01YwEN^8=8r>SYtd;M-Z)*~*Oe)8yfEz*CNTzEjVJ7$ za*uM9x+}-e6ebkpqi=dGJ?clgDkMlvQ7)Hwegj$)s+bd*I_AL)_g<&zRNaC;^Igw- zyYgbFc%F$|rkR|Vdo>-_l#|0B_sm9YQ=a~M8_xgUhWDEOlGDBwt`KiNPOq=3sH$cF z?v!*@B1*J9Rvfy7N7>49jRv_U4c6Ae zp9mkkQpHK&hCrKTr$R|QG!h+ADAA{59zwbU60!` z?a;!xW=+~LpFAO^P^opMfQ%BC7(e<(ekN`B`FA6GGUB1*j@mY@3& zdT40a@;ObxZ`7CfM81w`E9f+iH$#@?n*a5 zWvp#iaD`3pViGB5Ztk*9%oy~T_r&bA!q4OGQm1d^NtS54_26mtSn!Lq-RBR+vmYbz z&L*#W&>HW4L)1-Fgg+Xo(t539xsf%071AgD-v*cI=q$c+eGf{xsUjRN9Nriq1f&|- zHBe8;W?yozXI2Cm*;6ksI0NGU$4MhD?Gb(DuJL%Z-ah#ex$HE<82wD3n4>PFo}BXUUA_o*{*t=H z)M{cKa;5R0=A!2cOcuK{RR{R`TCIL)C00sL=Pnt2_)6M+$0wz#Bic6PEi=CRq)t%* z@UH8vGxBxP<(~bE^7!5C^vyvxqcqYTvfeJ|n^&Q41sVTyU^$r0(N2YEUWuPCPqd@E zE2&1QFcDYbt9w(y!tN||bj~U+CRtDP&y2Y5N%aJ378UGg`9JFPSCGg#4^raPJ{5}h z<@o7&kC~M-0oFeEv&br(xztm(^7lPH{3)mg_gGg5%Q3}7XjB~DMPeP&q(PhPH8ytA z;(#{DY>U9Vlw{)|hGXogui37Ub|+F0n*Yk^OyP5JNkmVr`dPcvp>V_Y2ai*a@N@k3SV${4ZQ_B7P4=trjdZ;)K?FRs0=hkO}{rn6sCBI3Tm z=bSFz-5sermEIFk(R}JFrexAh#7+Ob!p>M)SvEX6ZK)@2ErgjbKa0mcpO%DAi)nYb zZo-nX?}fZXr>N^DFRaHSn#PSKsK!(yF(i6x44|bw=+#~o9sU!MX?L28nC+IXilwM{ zamJ4)UIJLXgQ$-^e9L1Cx{+ctbO972-?R5t>e0Ks{XcuxOF(eT?DR8_jY>ZB%2ek< z0M`vZ*hiAcE~M7dT|&{8CCQ%f)#4?ntWj8(Su;KL!L7W{Gg;EC0Rl|0mPkR*%C49K zqu9Z%hlCEH<$_*;aiphE9wigTN_FLF2IL2mz%Ev{u#@7(E5-=%vOQ>OYMUrk-gVpn zF%NDQE3a?GQ5kQTZF^GEwk79gZi*@Gc}7Weo^8u795pO-KQM{jv$opt&~c}scGOiu zUFrkrS7oYnQ`+xH3*vEwfsqmCQv08$_%q~pY&{HozU_Ek@#&>CssHm0uc0c<>*xP>z5u5rK>m*XAU`ofBS6av@GzsQE(&;%MDD-#*x(+ePg5P)HR7h< zYz6u?(G^C2ij#joKg7rBKk)kNS7z9M!NRYf|3CKyVW}*V9d((|+rd;_e&7&$Z1G7MEu5JoESV z@T#}p=TIuVkTkARf5jQ^EYeCod=?|~D!C3%7tev*!{8AWh~^;Lj9LA!&Hs$10pye} z$eVMt0+_Xhxh(s%(M6+Z@jB%tdE4k)F-MWi#d3kh(jPlNt9pvpa=%jvPUJ*wrWllgMpx3~n1%vPa4fbxlZuWOc$)}Dano`HX9XDkq&^Tr%Z zD9_^sd3C3BqW4*QTyFz1W*d5~mYZw_x$?VM=MR|y%phhHUZSG9<{jAv!34BYr=-|; z?n$`*X}Rb{-((-O^Kxc7zP?OdEr{0ON|-BF^zs5-8V?RGYal+MIYr=8Nz8%|3?H82 zX-aa2t5a-Y5GyC&c!T;U%=cM6QycA#$Oww(9hkBA)*c&^7)!TZ=1$qe!}*$I!}rrS zw^6Rkiwp8&LQ|-cq7gmzTME$Z4ThI3mERw&#_=@CLVDz5I69@t*1KUvZH6;ROB+AXKaL*6{b_bT82Jd$_${3zXJS|o`_KbJv_v0# z?tS{1h#AWoAA;39X{6`dUs6-^R5*+P+mG~6Chz=Y{pr1!koWON4OSI{eJ*ajrV=@I zi>E51LuD45(ERncdE(JkilgJI?}w0nJwlb5iHR(z=v6Da+g-Fd(DIGQpz?9`EV1U8 zVeuoePuix4&m;DFIS8jRmUEh7+W9n&7U<*EBM796vs07E`S%k+9?~02!$wb-Pa85h zxRB{BwD9ET+46_6sZXwYIw5XzehoudWtZKdg52}89+3E_bfneTh0mx!0~tUtt|jS9 zyt&O|83|)3?Njq=HLkw}pLV-p)#z0LlzRkHK8Q^O3G6dm-+IPdT^`eZ4H2!Qp zLps>x(r#1@fjs-2MnFGGU!d;`*;G}YCwZ)V+L_LJS24{rVN5ekhtr3jNIbtcZsVD);kDWgqb~d= zBZ?*VJ)M7i8Hu@h$fiv)F9njrkj#&Nt+W}*<<<6Hf|fL1c*N@Swx9lI2~1XRR(G8b zo^quc-cwIYG+_`}k+1bnn;7hJSJ~Y=kX+q~xcaR*(lJ#i%|tuR^WCNy-e`^)YcP2W z9t5KQAL&6b-xFaN;4GI!PgiK%Wcv8c>2XzR>uR=96OVRQkcl*-hC-_)I1le_@I(&X zW>M18hax6qjCt50?4=+46Z22a?CZRrb{bu-KG)9nt_sw@dBs)$8$p z`n$nc(kN_ol^+;+7G*k6-!wG&HEnP(ZEFb=id=B7!>_U$EDU#xHGAJAM;H&DJp5Q#>+{5gu#52b`XK#peeg>2&ZRPhu^Z75 zbE~ypi@NW%+95;oG?AT-Luig<5Jyf)BZPwg3@>#`pOgX_5EHJR3JVCAPo)@p0(RqB z4ct!bdb)|Kq~*(M^jNd}+w2GeiF%RzO5Vn#>d3-4U} zab-2H;S`QCV=3$PLuOW3GaTLAiru_ZHi~l`weKi@} zLtaxC%ZQ>qm@p{(3!P}51Lc5Fa|`B$v-%U4q6(PCF*7dFR0qy^XuHx zzXhW424BHov(-9LaV9D9hbuB?PUWq8R=ZK880 z5%-~Qf3pf3#Y3j(2;=^j`PMo-+9ioXPrv7VsqRcYEjB-PSA}1%V%nVd96s)Q$bU5Y zLDQ&toNUDb*3q{UhDctLx_Jw{qpua4XVBY5;o>X5trg3k;$dK7`Q93kktno%3<;4H zr70sHkx#wGcpLb~1!HR!GDjyl(|&kjTS@+yMv3cmkZs(JjS)tco={_KpZ;*Z`b=pZ0nfsrH zeD$J9u+ZaPUmw9>@_LaLyjf~stCnbZX3@^(@5k|f;ArOm_5uB01itnkE%fUm&;A#` z3ja6VzrOJOe=+_4wk7&M9>I^>vT)>2T+oFfp4h980fE#HH1cr*&;8ff>;+@Z0x)sK z<`%b)^Y2%LbcsbI{jM4R^Md~mJnjFJ1NKnWn1Lebsf@ppNA1}_fB)SuO%)yr)E7G* z*#N1IxWq0^4eaWUr@7^{Qt-ptaYiF*%#mHkZ`DVwJm=%f>t9Nxm|EX^nz6P&-ErmT z8me`U-|UQa>kUFq7T1eo|MMqMKRF2 zC>q09jO%QT;lx^_tUDIW*iCRvQHHy9=QIlU1zUoKGCb51i)Mu64(lvrG^{P2TwtLz;ld`7&$wJbnf9&4s(bTM7s-J~U=q#^$6a2_ z+iTiA6m>f3{jW+n~NjX_+_RUMRUQ8UfKrgAv;C*1qFy&~i=!n>eX}!+@{=Eri zh2Y?}*VR9HGe~FqU*6(=cZ-`V7|D9*=(V@dWOxzcSWQ0YJ`Ljzl6 zX){KLM%59`F6ICPLwqV=6zf0!JQl?4ZC56~$mJ7>TanF+a>mDxc_QQ#+PzX9J!WlB zFDZGRWq&?=(M(J*Zo|0~mRf`5($92`@xt9x{=E$Ep_^kgDAOTjVClc$DpuE$eu<~I z=q!(gzd3P;VlDB`V9@Jpz-C;k3EFg4a%3d1?~>!oO3J zCPo8gnX-~5oc*;vB^CK!8LSIFJKoc0`h`;eBlOJP7c%nD+xuhHglr*I;74)*21#Mu5 z{uI!Gy%92JaOb3=q1-_luF$R+t`CPkhR6ri<;d9G#q=v=JLjV>lr-HHw#jZKqf@Uh1%2@ge*E~y`<1Os9j`N%X?Uf3VC<1 zTz<^QkuLIR9Evgxsd1QO$liehH~%2rX6H97Mp~uW!sjphXF{ z9njddudHN(+vaCv$cX=ZL)3P8)_Xas)5kGCKVM|rPK=t`*a33IwodLktGb+S(42{x zyZWc^Ibq%wD7^VPqD}S253+RC+eVJ~$E18po2KrmFvgta^E--m3=&sXg{rPT>(V1L z0YOV7H*UD@cT?)*^stjhm=mdoPe|XTnY2(P4$#|}mvD!N8K*wJsu)kVJ}ph|&aU=0 z?adCn3Bb*y-%Wy_^%r;@uv6T=&9_cvT@vQ1_u?IC*E*?&?p-ig`C2yV-skHEMdybT zox?gdoak!5?xM}oi4IVp#%gdjM~*JILuMqnb%;|&xz+(u)8b>=)6i8UW#;f2=*wWx z`39SY#WKGlJ-1{)uBe65vdtnVj|mhf`EzKOw25a|7xxH5OGjVgX#uG#EZ%WAOif)& zitxcKqyh}kCjIV5i3=BAr>XfPdfJl@8&%u2yWKWks`-^`Y~UQxyCk>@C*oBbML{PQ z5S~5!i+jZ8OZvnGc`qa{t7M==#SDtVpLf@wlwFGi52?BZ*lYbffX0k{3}{|D20K6fiCN7>k--J=;SPm8!Mf5 zTbE@Z4r?M5k*`HfZ3~Fy_?nQNtQ%ai-Mo2ox2*2Gn*O^xB;jH1X4lfsCs`W zSH(ARj3}+GSs#@*SMwGY!j%xco?G@jJUn!l7e{pphOHg!1ss>)Ag%>ac$R`=@?a&& zufya{|D6z^TbtPZc2g|r1dK++ytXTrX~Jcp z7{`QS`_E1`OeNU8FHtj_yxQPosww_O)FjvkODM~vHbRjN!y;T#aCZ2mWf7)%s9YZ3 z)BlUPH;;$9f8T~_(bb}^HbqJ)WM}Mzl*nGz>?($_ugR{o+sZPGZ4^UgD`VeVkYxy= zu~v+IDZ>mV+~-Hv{r&#Fzx#P!_x=2Fzg~|&uInYmn9uutF2`}4$Eh)&lUAUji>RQh zv#S*5$}X1lISNv#J@ypAf~p%^t}c$hX1=*PFc3r^q>yBWi`xJ8TU+WS*-tpV#jnlS z^CphfAF-CKJu)y?!^vSCUPrb)a@3PHQRlQR=s&zXw;$S3O1n-$-4(>!7W1A`= z7ib~Q=lq#dK8(qVI30aX9}z;5eR?fP(jdz1RN~7;}YWPax(T6%tZX^A84o`5Z3%_2}^yr0TcqB{P@8OL#Ji9W- zIggG@M{q&CRsnf(C5bFv1D-9yyf)(-YqcAE(TcRhol#xsr-OI{mp^cc91DfXo3`cd zI=uP`Kh+y=6Un}VKE1eH0m|L8W*w9S>okUvKUeTN6`!nqp>K!e`L~?H{YE)IgjBi< zSuk(fh63hY`UvggFgMk-O;(XHL*%u&H1BI-l2AU(aneYealaqGzR0)pA)h^mWIAQH z_3~X)(JW@kHbp-eK-9T1YUY&3vrlQ+h8*zX-8p}kSsCQG>R>r6dt2@MWTY-@5qlk! zce8|TC$}y7K4Y0XJDXg;X#c{+q|cS9OMS2N0)-Y(mCgtUH|coR#%F^N@hvi{sxU44Tgc~hPH)J|xhnR~-*atjRP zZ*-9!-N!ZD#_WOgWt0DhvOJ8L%m)9qYa$SVEGFaZu%>Fd%4^=S^)Grn&o24H*>=N1 zDDANQ(b375q;ZkB_!5bkyu=;67~_MjdxXm~a7t$JEM0?vR1(^9>p{u0A1wFs|NU3u z$(_e9YDz>qJm8mMy?Z5z89Z2M;?q$XQS!~UiX9R11c&mI_P-tF&XBfckgv|wZUi4J z%TPH_fF~1=)$pu|MsMj{&_G7cNHxgN$XIcl?=U=esv6#&BjQC$fR!+ldRUI+?r0V% z%!)uzEd<--Adc3~!9kb4mny2OUZP{LjW0qjY3Xv%q?UDzfu3S_Zo-cmzGSzWa!!wr z`#s?ZCIxW_nQDjK4gML%mAJIN9(=Hl2o8ctbWKJKda5H`w7Ntjcx@Y7c#x{Igrf!!Cy(o~Bxx}`bg1E%T1_!W%vEASEegiX{+sNb0w*`)m~j;AAH7e^@Z9m}!Am@|3b0)`n@ zA~)3u8i6GJ7dZJET5&Fkt*CtQoWDy8d`Sy+6M_=mjTI8TiRCnBb zQj13qeGc6|i{}`4?(#YPslH^LYX8hOEr-x2x?iX7)hY;n>UXPkS$!{4yP_jEmUy#O zu|w#1{euS&wBMM??NeNQI=RoRM5jM%?Mm3`<_>(NLi)FTAcxAO*0Bd{N48XC;;CN2lKEYpSXN9kZR5V|NmBaOwEQGz6;jM{yUgm*@oVa(x;MM`1uEIU%Y+T_sH zhpG#7zeNYj__C!yVbUIFXdo}mxjN8oU&%5wK?Q0f9Q{#4gWIG*^^Dc)sK@3g?i!1! zW2`kASA(~*jwa*-(6?C5{XXXON^ozN(amhC=+j#PMz$8bj=E;gusr3;3CT}&Y%!(n z!-D*9{T-zb7x6aiMi9zfg;21b-ww$qqpiq38vZ{6Q+94W4<9}xHgbAJm|BOdEfHa* zb6Sx1W^5fJzFu4LpUx{Ci>h21OP%{N#2MDNzu%uZ zQuFgZ|F}!p_XlLiguO}?pW{ueaF%xQMp-EtE%%RDIdH}I_V+u{piVL+AJjYN(JWVC z0mTfh<9>emSklZc!CW!QZ5Jw(md-seXKc%5IS4m5er=RbS&rgg;at?AMuuUsHYL>j z46$9BQTr>>&9+^3B!Yi@QhzESp>V0kJb6S$x%{dvtC4xP53{`y?>B}UOB{wmp*-MPm5^!SN6w7(`Hgka(zQsLp*N*t zmfjtgwvSgNAj1h{sKL6GP;Pm}Jt)SK7Y$q$`NxB1ZgRCiF4-uG&Yyww*Ouzrr6WT& zZ(%GIgrq90L&_~JMH7))j!b(N9e9TEBV4r4T#)gRPw9GFhmutjRGJP^{dNhKGs4|= zDBR46fSG4bIRRvdt;CFs4B9ilYa<+1; zn33#MdoRxy>n%A<*SuBbEzKb$pB)-dYa7;4SY0JqaPv&|N8gt($+J1P+KsLs8+*Up zGcV2%x5~OvB^egHkEw3p!lpRdFcYUNDe(x+)6u$XYBC!y&3;+3|1moM=Sm=&(OCk; zf6~mksb}gZ#0&P4PCO^G6{&s(hmJGt=co})XI~JmVTDY&cW}CgR>84`<0swkECHJq zj}0$BkfS#$ufJ^)cuxOrfM1OZGE74^u0SQ|R(N@0JgW;6>vE}uc9v8_?H^w6$vwh= zQ545QuZb0~v(nOG8A?G?O-+rG9?x5UfB)8; z;0^thS^ohjEbMx?f|svTnsATXvwNSA&Z2P6{wOWl7X) z5m+1H+7Mf_Ai7Sp|Ayf+2~(9tV%2A_RDD?(*-tnV+hoyjQg}Rz4h8XE6ho^6zX9ds z^|>7MLk|@BH!`UA>8U{z%&}k!bV{BlMMdom$opxLotpGaqvb%nfS{x$e)%I`tJANq z!eHl$mkBaze7inV9Qcf8bbM={x>Ua=6irQR22a*Gi$em(B=F)l)rsoy%`7AF=qeA* zE0fpwv#|#Zlhztmhi9{Xck(7X-zdS9oS@h?@Q>LBcD7#VT7vcb#2IfO(lW@`y+e8V-2n9}-pDNJ3Wk?&+;0mL(U_O_ zc&Z0Zo8#{|cW$1Gk!_AlM^8=e?aw)o@a~!#D&xbg;e$K%1XCX<7(Dv)^``?XyCCYo zG4I01*Q#r?TPn;liZ3vB^Td9_xX4GM@L*ZFuSyOiiX?ao?r3M)g6h zK=Mc;zyDRYbzh>3V1C&RTKRYyv2+Y0y>C!iR@T7{H`;7u(R-=w)iZSW{M9 zTADnYbSX1&NMSIW9X*h;N45f-Q{-qp8gtHjk$Sh$EoGN+q*<4qvauj%)esqQwvBuu5$!m3%<(RV#yi(_0yVAj1Ej7qBNz;G^jHg|Y zV8OyU>jqs*A=yem;St)=vrTZFERQqpxpp&hCe?QcgL6V~_DpEdXuYB9Qlz%FA#dS;6w<2oo3|*?zTPCgwY0RPVJ{30 z4x%^UO|^$tV_Vm8Df(4B)oTTQ5!b%Yy}kDNBa6SFRcuu%d>YGa4;^GtsbMzVxZT4( z%>Tz@zE){VO}kakG;?c4U+;|YkQ}>viv0@_!m5in-_|w=)M=G`NgbCN`L4a%^7Tb} z3iw}0hdE@1i=CZV9*Hh39bJPcO0tXeWb?%eFd0nBzUz$tYaDONBeAoL$bW4&&JCMZ zE^c+sHo=`PH$8v%cSVBpAqvW&jOcv3J?Z-iuAxG&mu3?FFVQ9KT59_!t{273oo+lc z&HzM?`jdDQa37BIwL6$>Tu*I95V>=V_eW|@LXIis^lBBSVS9*^S;XZtSrmj9gzwHoWckOqrbP*xGXO$VSv5H4;W9Q;Z5H20iS7MOc`^>2+ z+GmrhGvkim`l_?Kz&)GyQ9IOUKYL;)rGJg~#`9CL{eR<56 z=1}N*sLNScQ(`o(IX?sE)+RqK#27q7(#&Mnh(q(d%Brrmyfx@!LJWqcImzVVdITIM zbd5*hTZggze8(=kxfS^Nbm0qv6ObclN9=Lnjf2K(C|Cv)Db*uZ;GY(2lxdu#qA76- zqlQDC;!skysclL?hN+rnN2?Ck+Jrj1+7x^#`cS8~Shwt&8u8I>3MZo=WUZx2zU>@U zJC^+tQR5X-kp3Phu625lKIz$z--*ZY6jUudX;LK=6<`lMR&C9RYC2*a*pXX_QA>FK z{1n4-R&sY-i3;&RWJE-wG(YK(vB-z`g(POa*rvpQoRs+&lBW}5BeM+IILF6};p`{( zPC|uqWJc;4(hynY=n^&L=&B4VKt^svOJXQyj8BG6Y-M-qc7F4YWo!w2xTOkQTSO|I zRd|oj;*nB)Z7&nr81>_zwYq9d53veq=H$JanC^CV8O7~BFEPArb%A{700uRjzVh2L zMoUCo8ao}bWY_hVM#z`)mp6JG|#zxo>vkVvkW0;c(x0TNaA< zL&gyGi4FfhH0B?+>v?W~7$OG4HMob3cF6=3ICCD#G_Z(dK=R@M=lZ8C+{GQ@P9B<>2woo^H+|Z0nxNDR7PQ zN^tf_h9)L{YT;iMm#`v93Y|z^IT9x~HlqGZ*v%&<-&f|)%zkbxyu(|xng#PCE zMY&%e50ciy_R4=6(#H)QQ?yDzj4)_DzwL*i`JiFn>+5%8J36j1a)0|BKYpBseYL(e zACjyuKj#z(&x@qA^u>U-KejnO-LqLVHDrAS{>Foc4@u(3T+5zU+r=16O#tBgwsf=_ z8m{to!Q$GlJP8&zqPkTd`_iPP{$aaaw}8ky zcj=^;#p;#)bH$muRwMo6OKF1i>XbpA@uD?EA;r<4b<=^t%;dFu(->Xsw64OeWNdZj z?Ue?Zn(JIwYY|AzDtN_?2y^=(162ZiH(P!+a=8^s91?|cA-O3I2>n(Mt7>RS#=29R z-mM6cLa$B{!M1!j86}*gXqyo!jcOE_cJrc|iG*qMw+KnBj8|b#dA5lfw=AW^7_`v^ z8u^Pe*l%!lVM2KP-7Y+D3gO6JQ^k-)NP#bS06@`80f7IO=Af7GNX9sTGpW40)rA+6 z%viKS(AF!>Cau!Kv&A;=wyZ#%jvg|3Vdr5;2$)(lrLW~)D#uqR$C6YfzLiNx$7c-p zeorxP+JJ_yxwK|Un3zv#8mKDLQ(XLfamVkGr+yPN?6K{#+jCEPXYQ{lp3Bd8v#@^lw}~fTNvN zj{E|A;gOZrlhv=)Bm^f{UdwKcQu-iT``eS4Z`z$Qqk@=({04kkVwy=T_Chs(lUaMN zs-)0&8!>vp;_;*)QBIx9^2ssJQMdzrPxKaE1gRXi(-SMW7DPBFJpaSHE?t$On3eNa z30aV`67cX$ypERqeqlLj$$kSd&UgoIVe*%!iw_*rjVuV>r?;hDCoN9E3^B&ivofk^+(7V&v++N$&A*>4n=JMSFw4?(N zT-K!M|GVkOx$)xLKqh zt*$@zr-XBLdo>5$vsmM_-`tE21@(>7=gU=ee{T&S>gNZKOZWOD*4{H@qQ?&J=EZLpg_If ziHWy(#=y9y2pD9$&v~T$%XUJ7_Jk zHA>-Tdkl}(Odfd#;S)+QJ?V~{Naam%vx~pGPDr^m9po`l;o9Y~h~N0#IJB!yr|~bQ z|I|U)BEssr6nC&(Olm#T+;sl?SIAN%r#yC7&e|1{+f4BVUF?0~lCSTp1jdPyH}55A zpRRAVqr6$aRoc5CO}34-$a-q)IaRydY>V;)k4*CX>wW;;y-a=bYgQepX3h}E$9z7p z%EW=KPhW0jcjvkz^s3q{ID}2(jg3T?xR+GQ(SO62V}{phrRZw5V%rO3FwyiRpF@ye zs@dZq0|NVvp`3w&jv9=Cr!pd1e1RY%nnHD|!f7;`IAOSJk+t`pvyUI4XatoY?rNFQTHa%&fe zO5L&5|7c!+{vo1U&DxbWssJ-m^aP8;=5@xrTM3|3!H5NDvX6R5NNp9oaS4ba3W8Dh zneQHi7ry|_(x%K4{wB;ndBmDtVlGCtLl7CYwVF!UJauW~}Ch6(D z!orJSj9QnA2V2Fl;%lc{Rvj>}koGXQ@rJm;T{K)uaTPIFuI0KNnWd$@xzoRNaU3$j z)KTqkM+AG(tnTi2Zw{oyNSi%)&Ee7u$x|3EmzjurqfXcj$#j)4Rb4sCp#Uc@S%8~A z7eNF`*mJuKcuxuf+)kTq(Pj`wpfUWrcGzvz)gz>vNp^N#v!%c&!!A+s{0zX3&jSIm zZ;d1%5Lh7~SGXlj$)Bw|_jcC2 z>-cmIcJ`+2^|H$0`o?gREHsLL1h1yf2R2qYt`tM}YMNj6V;6Pk`5l?Q8hA28=Pu@S zNMl0dv6Z_YQeO>Ke=d=G_bezVs1WWv3`s!@pfnJbDwn<@&Ffh8h`RFXGkCNovTBh= zZM(|#)xd81_|B8ZeBGm!lo98QWS=0|8r^G&{zs$bkR$}5_VbScCKwOa5*Vmn8IorSwtz?X$^QS}0smw2<{(O{BIf z4_YO5;t4dP?2kC?mz8>0`NNfpAfL%=k!MvXWk3ZHK?`toZs4%-wNnhh=)c5u_W_gc z)$fyxJ?5oF&@W$;UoVu{ZC(IG6@s508qk*6fdG3``&6I8)2C0< z*oPe0xsO}7NqIYCtbIb#qNq2rQ*R}aeV4yK?1$(dm);qWPS?hB&Cbqd4a?zkc&eU2 zQ8&;6ane3`-CwTq-;AiQI`3->ejIL_Yin|FQlFH&_~VPJ z5|X1l2D8`35$3p*tq#jP6K4LKi@yBsm2W4`!M0eK_YkMk5ragGG#-7TfiJFYWgGA^CU~!o(W?-k;aNKu3qE1G-X2 zF1c4`Ol=7IxJ7%QxARiiIVAHiUTVZ|asL7gJA*$+Z+_lhiHe)K8Lf!sGJ46*EUU>V zUrzxni%!Y^E(G+Z77hI8h|wvIkgm|Jhw-HdTc$(<+>ER~hWTdt>z6#%d*Jx(Z+FJ1 zhz}8CqAv)tKzsh%29E8$y-ZP%VaI9v?@zJTb=dIG?d8Iiq9uP$KM~A-6D^e4&c%AW z^HOasv8>>EqinxqSr$k2aGP(h_%&@t6w9S@<%>sHHRYg5(c$vVITV_~vSWu=ZyC@{ zvyj{ooWFn0YB9~>@AQOuPox0Z;x`b^B8xPgkcEPJlssXwv+Xz)8m+HG^4$RPJXM&3 zuv%QY<%+z>e|xsSCO3#DenL1ouN43fk5Ww^A`U<1=U=L!SGNb791~`y0`JiT9Gmbl zx2m_fwd7gJObRWU7F9qRtbQi ztd)3ye>K9t9yf5sbQ_uEeHB@PC6GAJbCfyL;k>wQ(ArL%*!bOx_aZ2n&6-jAOak?=mbb`HMqZ~p8_yGI0s{|XMBv?Ri zp7y8<%pffPuQJ=siGxtoldbOXM8Lto`r~l}De@21Q#_ONOW>5#7 z%Q&b6f9qOBV%GN1@_%+mGBMeteFsMtBsBc<;+PTxuy3vZ_4ASMto?sW-}>LAZuQAX zTkQF({z(74n7Jb05(^<4^bnc?@*zGb?gRwSpOrh+_{lA&@AU;=bCd9VD$Niskbc9pXw zv4D3C4Veu>1Qr4YEl185s!1$Tr41SM!7X%}Bgs$ao=#0orS-g$42S?_32cNh|M9D= z+UGU&K%Y5@puFlc7wh8XXikK=|Ml%qxl^m$af<63@pVCjPYHkPsqCC(KzFsB?|%uEK6(bDT@k z?8O!djB&JCvx?MRmi4o&yq!X4;w?Ozc*d4)axoJ9^3=ATMF610B}B+jWxT7dBlo419 z`0PA;lGGR!+yZ~eey(FmT}Gq~6ouiHsKAk9!*A%?@cq_p+d94-YTTjpli3ftEs{Sp zTPfb18ilkzr(`+_DgKZ>qxQ`gFt50l0AU=C>lUCu3xF-|G1G#oP%8G9ZMblWSbsq| ztRx1ywAKIZeb{8R2_0QkKhA@QC=kpP&46Pij0ihTMF~KXobaDGMTX?*Nr`}`u6Ho= z`5jH*^wH)#NkNyxLW)u;s9l(!53r4$C{2Wut@epoPXTgJM`1C*4Pr|nC^j`9Q$~O4 z!rLKa>d=qH?WDhAn{2fe=BlW=NSQGD^y1$A_;!2L+lgwAO8Av1V1gz?4v`*kzesi_ zl3IhhMp`=7v+dF)FGkQxksAEB_VMa!XwA~lVx75C{%I^vCx1w#zfR%;93yKciA5hn z<|`;_{Q@EpQN)aKyz@qqpXS#0B?F#XR7=f{nrwP`4=lA#uMJuG?-M5f$ll|MAx2My z?EG{Bt}hwn55u|p_U*HemK!@ttbv4VKO8Wx$e7T8^6v$?x1-}3$rgoHJhaR1;e!W- z$T9T`0r^Rvx=cH&Md+r|G_o|HBqygOcgGgyfO*3smfp|g(D6pb;`2V12_V#Ms1l_? z475$K4)*iXmQR)LPw`qjVdx1*XFLjkc`st^`ci?{JW?I>sT>zt= z58JxSfjun5?+))*k98{Lrob=(>y8$@8`p!e&HyC_f!OgQ_)yxaZ<)zshd1BM4n+9R zM`u~<9Y4a|*ZaYUaf{m`&?-`^c;3>Uv5+-H{b45(Ww&NUZS=Sm~YKhUN-Tg*CP z{TO^nG3WLz+!RlYG@ky*dd$Qtd}u3ZG2X`_4eVja0+zh8s%ujwwWtk`lN^yrbdIl{ zkSCItZXkGGwe$+tAteYD$x8`V{`{5DVBwa~UOT@12EB~rbVb~*}^HMzTKUHryUEDEGM0l(O!zISWm&jp&9f`(Oz@O>lRDn`D-IUvb~LNMwi0V zpUFygO;Uv119qi>UbkS+1R1!4Q+b^(qI1eG)k**h{d^k| zT+c!9Y8icWI%-qfQ0UOX9pGeV#%3SJDlJBdEE?$0hQ4$SV!tHMqawpD$hfDF48)&2 znnl1DZHx0Dq!M zOnkieg4P8cZS7C{f`4u`*xQ;{P@o68UCyAz4o@IolUxu*7bVAf?KM9$fs&qrGT&R> zfP=Ng$*vWzkUEXl)5-IaQ(?Y}H~?}{Phe+0y~<8=bR$(lq_KmIHSL3X53xoIj5YKc zpb>FWy%t@$(@VvYy=uo?Y&D(BgFrbYMX9b?n{`X}ys~#~rb|!R5>b0^;=6gVi?=rDqDEEwcEW)W zg@Q0`O+>F0phg4Q>?X*pTLFbDMaz0MhMzqv2)c5!D+}pOG5de{G|b9i|8uIz<8d^( z@&!g?Nq1dm^s-uDjDq6PxHn5Os`Sw&6iU`P)d`<__o_y=KjG&thfL5U#2onL^CZVa zH%V=yiQb;xt=MQ=sPKU2+3}dB_q9AQ>Hk5#soP7qXXX1XOzCiBv^itc)=<5t}T>Aq&1O_4kF5fEbV{2}(bE&)IU&RLtZN zB)-XR>KEo)CEANhZ#D`Y#W>OKufp!L($T+FQ3Fx8W%Vsq{* z<$mVU1U<2TDx@J``dGJQRtRB`GU~W&_oK$OsSE8q(C)fw2`pa=s^y>ks>7N1x*<&AX>HH@xcv7$c7%WQW*pUUc0ae?n2uiZyGY+=M<|e`+Zx0&Y2VK z8%|QB&JkN3xv7^Ktxi(4&{nnPpn3UgxRQ!hEkWqH0I4}~Nndh03jNN*!8mOkA2Jj? z9*H)*N*{*x$dHVsrZwkN(a{}yBy`bSOJ8qB<9hXi7h=bXze1apz%Z3-G)7Y7;VNS) zYz=5Z`YO~xIr=!HQ<(zCSRHBcf_k#s7hoD>sC`3e8>P9T)r&Drx*6UZa7V@M09`d{ z4JL(--bW92&?b>xR7o?EQ1z9ruumR!4{orkf_yvX134|;Tiyk=1=E1^N#(F9MQ7{; zAxKk#wS0S+N-XQ;a*5F@$Sz|i1V|IG(B14Z+VDYY2#G7A`3FC4pY!_DJp_FiH+yvN zL17HXR6PGq__Hgus$sNaEz7D6R$HqaV%P7ysa8US8w@>OX$Sj`otj0pfhFx#5g*xT z6bYNeR|U)$)UMA$N_)oHdPD7hx4s&xg#q=I zwO{)+`f}oV>^`pO3G^sV;A4JgbvG(9F_HdQl9=@%6AN+>DRmz6(O>WcW=$iwtzWmk zb`&rd)IN~UH{1C=eQr9laZyB35z>jC$NKo~7d z`#pT|rdB775qwAijh+Y+K+OP1p9@lnDgGTL~=m5}E{PFfG5@N-6q{sZAAY?$0 z>a6a$U#e7jaq;Vg$uGG!mK(>G5^qL{7j%P8iX@vMdDH=6%?o8y&Zpks_~Zcq>)QX{yDC*c#6aHK z`PT)B(?$!`^Few_kTH`Zl>MWn+%FO9CiI{5ocFz}xw^XA8eq9uQ;T|P(McvUq_UAR z&|Q!zhL-MJ zvK7&J!252ZRH<9Ac5$q5@!C22v6nhdMeU-y7j`O%CrkcfAC~QAn4IOha~iA>^o6(a zDZAe7G~hl^@aI(j8R<9cLF#c->mgA~ODp}$g`j0cS!HA>k&j&$BTpPJr`lxnT`(DX3_XBG?{c#@AO z(vGgQ+AH1cNflCQPF-vGzAXnJlP81TT{`98qM&tZs4^xZ)LO6pJ04wWypA+kRq5Ab zy+j`wUmC~5Seyf}V=*9mMRXM^m&|CGc15}*V_=cPe_veeN;WPfV0@dWQ3kW*6l4d9 zpo~Ops{hY-AajI~K_{zl%$0;yNOPOTm}xI#QtC1QW36X=(fhTk47MEK|Cr~PRCprH zol2OjUwpr{Q|mWt)(7yu&_s9h4oYOi?%myO0qG@j(C!gSxBXcN2 zU_nwsxr9?Gan+s zrt6t6nK^20z40XMUXPiRFjesjT#DprZFYZk7Mf8C#mX5;UgyYe;IwSHJ`{K6 zeg4kAw`GeyEFVp%XIvU=`Mj~VLfprXGf%dXg4K8wN2|+rT=`@JOpEz55RCKS z|H@m;cZ**rRbr^s@TgWskbKtZ;|JWQ{7vc76<^IUqC%FD0S!4ks3h&Ah_^fmleZWg zjD%j4VRy6MVTUD;eN5*iYyrj&m1`cS+AZk~A*?zLTLqGOqF%!3DB1TzW)6rFm4N^{ zAY)+=M1z`~fg4$y5vCvoOL==4lmn!axj9#AFiaSV&4(kCfMlQ+-*HkA@Bk2BK!(#S z(KtI#JpGkkQ1g(4k%@`PTp5B(l7W(v2B3?9u!=537dWb|$V3sXBNlLLQVk%GeM2$h zGhIAK_n`MF|90xF-O3#1qWQd+`5M>5?v0XK09%2`gK1~i^681yaV5H(S4avzTm*PcY>@X5Y$!_U z-vA7fY|e*}b>&nL_yu|CR3qW?6}hB|H`x}Mcx6m<0$7G0Sn}zp*}_!kJvo0s(pr9h z8;fOaEmaG~J2Gc8nqjtsr@fm8@Bu}x$QSfLn%7dcjb!q?;#@FW$xyuh+yIPv5j)me z6w~sC#R*Y*>eS&V8S2s-n(y_)v5S2txrSYME%B%1J5>hL7pK|>)Y zHN7g@3)5L@zv8o=24Y_J;< zYT6ng8x=eubT=t6U@j;=o4yRa#F5%zQ9u`n5z*0`b!#7i?gGn^5`c!g`u_WypoTMw z>Js0O8KLQ+yUwD%%~zsGqI$n z&W?}tJ&9L>+Lv+Pt3y@@g4VJ5w(PH4C*Gv)47Z0nM_HEK)o6uiU&i9#w>AK(Rnb8I zWt<~J>ayw)dT_RFjKTZn-HMHJR=pr7As6B&6WhkmW;=Hx_$<{dk|p#U2=I7qvdr9{ zSeb9tGB$US3eY;mdZoh&6WR)&*}0Jd0MORK2?}?O#^vevvG|HLA!Gh9rQq3PY9GJH z8!6i*rz!%4D$Eu+TPbR zBuU6LXz6p;v^AYi`k|EYSVO%|L|lrXj6Tz||7nwe^mPr}hi8Vn1!jq7PXF+lB6NRg zr^f8J&L1^f3Z7eyBJ>&LP9h!L8`T{Zc6Z21r%s>#aKM-KhmEB0E4c%AB=8}%w?i6C zjz*_RJrB`gn0`Zzj0E2rnHLAj?o%j0{-JVOVIl(CD-8QI-+GO&m8oy=wRWG#y;fxo7(ZD!Ulcc-} zXz-sRbN^%2SXbau6N6yhT1Vr(k&cAb>p8u{&!00lS-k?0rEa$A0h82;@NgmwGCt=btOE0z8WIIjol zv$yPRCGqQ7npghmWB%E0Axx3LuSA@KoaZ@LKHdz(JVsMv7UG*HLf?VFLeUSVY>@4K z#Aq-_4c%2DuJhQxY-`02)X|pP?YFOD6_OtWpoYUEK6-X28*j`_7UuUjARc7WLh;)C zi662$YBl4ZFPH^4|4Gu~DTwSA!FxXeQYQpwFwX*-N(2W4XeZ@H;SV@xt+!S> zmAX=GwVzBM=&T9FXnx`Q!sTOEa}6;Oc(BxRTVGPPD$P!2gnPX^WT!lA4Y#-RCA*MoMEDdEF+iNe29gU;WZZQVSK91z4 zVj*hq(`y%cnNrSMD=nWoicL#%HGOk_Sm)EnPjB{^_qtp2qgytHIxq;osOPxO}Iw-_|2U&^1q zMgX_XE+semz}chp;^OM=*4bfE*4quo=4$q1CqkDZWcpin-@9;WExUY8Yir~Hv-s~8|rzMqn z1ro3;he8e9Q+Dy4F_*4r31Et9{>WYUM%3!>bH>=6niB~_NvkE5v&B2!O4bBPZM%FZ zl0oJ)l<5tr{jw2Za%m*@b-HR7KYx{BEW-rFU32%Z6n&SM`78g5qi0qAQByFnA~8Wa z6}zduzOryhmKRfU&t3A=r1R_6kGa{j^%&%lf7{!@MuR2>{*j*Mp2KH+zGNT}k%e&K8XeEk2?{LH%NMggQN%|J_*b|CW?x^W`A_N&nw^+x@@4gwU){mr-obqW0pK16K$c85gq9q*TrNau| zowc`*emV31X#7_CyBi(8vcMqJ*ar#+UEI!-q^ohA?r?rX;AqQ<26txqxQT4(_Yp_e z@0-=ne>pU~fl0ZtS9p(N9rQ|tuG!@2MSS|?eols+JtB*Tg6XVowH0KR)sacq>fX$f zVfb`k=uS;BS>Bsjq9(Yi(gxMWIGgR$zuhZ~`sW)O^VaHP7kT=!@9Ya#n~~WLCUP9t zViV3*-MTXu%)aYz&Jixd5RF$i<^fs`6? zqw^Q)gGx@VX%Q#3Wwt9h^f5oD1n-lwvmgoopIReRU?+ll7)>gS>>!y^S<{yIqI^-Q zJ=i$JYgJp!c}X$Ak`Y@f;^1Y;$LX`Q^rkpF!dvo~cUwpO>TgwYySDwo>)8eU;p0kk zj^+f~Aty7&0R5a}s_7G}cAq@6zQGrZ0j(~Pw;KW`H;DpDNa-~#)>^%RUSYq!2#BCM zwSqtnnl?ag|L2@@oRSdu&{jLPPtDGwd`5Z`@E$50w!KmKS@-JS5hB>3=2r(o1^O~W zPC6GvH~n;IuqqHac&rHC0-nBMyB>j-%g)bpEaID-#m^YT_>C^}NXEr@OFGn+e*Eu- zacp?RFiuicBJG!s0kj(dI~Eutr(=pt1htwU#WH=W*s*31GhDQpvHkva5<;<*v`>3l z>hx1v>r?hmwdqtuF9|QmPNqG(%C~Ux>uF1?iW{C+^Q$6h!}l5sQR_qXG5Bz<*qTd2 zX4i;V2kY~F7QJRMB_?+sy!=0ae35qrahTJmTU0o4OQal);eX5$irJ|V;+mx(a@uOF zd@#tPuK%7tDuMT6tj%KY=a99|<9wL%W1CgPQnKiG%8|M#dT^5Z0* zgxnb&mmle5*Dy|P6%yrtrW*i1`RS<_ZlBKs?$>nx+n)ak`)Mq_@eY^@&qqnw@lFYP z+D&3~F+1@ATfo!V;3Cu@)JLc&9!o4Z)b0l z=RTm-qZFP9?$>roU|7nx%ECG}A9Er*$2i%$9jxb8<9Z|5{)_e8PaRRx7qFg-_6qOq zw7T|$gC2q3IkcKkxu-jEkBR?LLqX;4sS&UykXP^nO^@rkz1N9%{dB=`p2ll?79 zyvgW=AYJHB2^{-xcR`(R`&bbJSk)qj7~_UBu7x~txNACUnO$k4d-xty#WR?*>Mi|w zMNac@yASXfGM((JVpNU_d6Nl=OTEhp8_@(v`lJvEt^n=xQ_1@?yT+5@M!+~ zT~2BceQuSSNz#;h$-|SEqi0PXM z{vQ)Kc4#DMR=1Kd~H4^@JINIPKl;Vo#TdYAJclV zk^G;r?YmGVs-3jgzU;W8r6$SO)%tsREuTNVhgejDZJo~eR(u1riu{%vyNQny>;t{v zMHu+f2n|}W92M!&9*18PVJ2dq(X*rD8xJ%^@4^Nmr)zw6q-tcJGjnW$} z4bbvrI>axe*fsuy?Q)cCefDNgD4Q5^r>H;2SUvu662smMD|>LA^r`G^QUCaSeB88( zm=xo0bhc*uGP`8nx>3y@BbAj`nyJ;B?}5&LwRFBx>U8T?;0@0kk`kxNKPSCanw*&t zs+LueZw|7cb_v-;EztK~&R1_x|G1c`t<93UocuF%u_q;p|D?-`;nD4}D`{ucXPmEK zZIXS8)tv6o?yvGB2-&Hj2sT-9fer0Nn8kulyO)mq|J=2)fA1~|^%Fj`a{Er%o(9yA zgjF1+E$e$)E1moFTZ_eL-g{I3XI&feBqfBb`x>R1Uh-TlG;K0AA1Ky&|M)lUl%tQ$ z>V>tdCS&3E3&l+K3Ja`t&6sV+`G9BE_11pFK-7V!fiJS(?D-$GvZOm*dq2`HM^>E*U#SE~uoDRgfH6o&Q&x}~sBI`gWsUMP{YRbK{wclZ-w&rU^?{ruiLKAiGSKbEc zGmpGtCg;3Eez7(pzpdX)3h1(6Qy^1V$0J&0AjZB{MXcPv+`p3v_g3TT*QTwx#t{oL z(N&GWpJrrc&fa86;{li^XRJS9|nC+$R!QQ1n7xc3s&mgB2+EE=JoH2`G z0r$WQPEtpe9Xb7p6{9UKM3gW2@TRMcsm4|NVMGa#cYm;-TF2cy&`*Io*AQ3zN^kT` zn;M3;yl=b~h04bCceCmNa|B7q=+3)IYCyk_Gn0JtUQN3vW~ztec5$pfe&F9K?stF3 ze?vp|*-B^yzWdt)ysJNc9drQxp>Oz)KL6Kbzik(@kJ3$0{k+70@~~ZG>d(tV{0}63 z|L5J%zrSI&chH;`Cy3LZBRa9Ba5$WkUPYPPf=ygOlcQilK!lZEz=yRuI$GaN2F*F| zSE|wor!AN~*idEom1mxVTo9j=Q$Z@;>CAJ>U8$UPG#&2sF?snRm1+f);Dp~q7Y?7N z#fC2%W$06E=s_?tx0ySGzUeQ0_Q^4upd}0FpK3Ln^Zc>LUjx)`Edu-#ff#giZATe; z@KY-d&r=BF(-DcCm~0)Xfh%8_Z4&?o7c3`FYkcKmQ^|%JVH*@Le?y7igx{jnETivm z6zfGMwPy1?x7(YQay(m)GsOIAa4V7 zPVFHZmhLLpT{XnUT#)^Y|AG(Dh(7C$PzC+CnBOd=-uyVl(su5fO^vm(O{Oe(RUdl| z=Hw!RQM0V8xklU~+KTJX`?is`JAd1Hm5(O$@vDzZudh9OCOlQ4CNVQJYv!O1D%hU$ zz5Q^`245WED(asvJoZ#ic>FI~DPa2LGqdZt$^`zecfLW|LdBoDu1KGXt|O%R^|qM5 zDF5BoxY)%oOWrvCXwV_sXW~RQ;B3AHL^7#pAP)#`o)?76My%XSENy|%8%^`;SwW1B z5n?URT=)yvOoI&xHbV!_O9gzr*s7cCRWi~XNT1TDS!fBGfP9}W8LoBJ-O@K~uk_U+DGj8^;Q`oHN9?SQvo(KbaFc8={aS94`ny^LdbV{2s!Op)3d~m%cITd*c|MKaMtkbsKA0;i(NyK>H!)<-5Yu{Vb;fdz~eb_ zp$zSn`00eacVFw^h0L6>u(`HjSrz#wBw zAQtfA6pdZUJrx+k2GA<_PDBjs6n578)eUn)72=C~iW?ElnWtt=t`f8p&@HhS(5)#& z3h3^=YGvPo>ec(u(%ti*8}+#RRqc%usyUq!yum7Z^?)-1o5mkUlecR^QTX|VA%meW z7Kd{U^ZgzfUXSTXQ9!A1$G8ctSf`t83lrTc>`RfWZ8;wvse8BEMkn5P^U=w=da76A zmyxAzlu-98l%uF#N0U1sYAf8k-FP1Re0x$@PK>)Q?#y98&fc9y9{|A}{<4baJaI#{ zE3yGs2xWg|hw6@8_Ecv7)m2D(aXlXw!s81zDr>DoBS#*7X)wXu-N--J3xgQuTubgv zeS>@A(cuNvG84SFVgKgBRX*_$`vMYqDz6xWM8+H8-_1MBnVPg} z=m^N@>{jin`|JmpzAY~oQC{Czt7IK%Xc{IzLzhZWUDFj{rPLl3UZrP??mjEgr`!=6 zZDLM6Uy_sPIHI3M33KhJ{3Gnf#rj^T)I|G*lx_oOgXuBQ$iL7WnecfvjtJy>7M;{*BX-uv?B`n2&ji$d!xLV6Ci3p8XJgUfmQKdWK3q7j336cqV zxhhiSG3n49Cny&OV(p+B_zWD%PKWI?gX~C=yvVmZk-SYE38RTmWhHLUe#fi1Y;2t+ zvMM9RqeV`0EUKM7Ox<&GCTc2>dOWCM3w$oKuAJ{C@%Uh#itJ`!f9gWv8|iigMoFnw zu;0CUnY|0*&RT?H#s5xBo`MdaKr6pJX?ej4>3zh*PUAa3Py(JYTCEyFDK@e@-_Sez z%^|ev6~yIGyN<_z=Lq^Thar}cbx z3l$(B{}vWtu=tdMtV;l%)k#`pGq4&&&~*2Db#~D!GFcCI1TYa01D5b;Nw68MEWM3? z@$E;~cCce%YLCCqem`)G4QHeE=DaPe8zik;duO*3Mmv|b6~dOe@?$=K8aX6Ti* z(@HNY`60rkP2o7J2EE<*9mD_B zpXukkVE3bA_;disGe*7xjX_}PAyt% zWfjSZY(R6uW<0`u)84)5{m{CA`*1=?_d4tly`x1E{qhl{v*TXv)1kzcB-fmRQ^be_UKLoR=yK5O8v)%ahQ_}9WNBv=TES;tfoQrJ-gt4$q z)6aJ)gJkVoTmZMZisZsuI~t&lxc*(>I{@)0H)u|$tdr{QsYINbeiuOl0-cFpOW0%v z#>a^{j`&?W`=G4RPLabEWDj#?A6=+Exru#IrMD192;UK>99)(DS)7_EvsK%C`QBZQ z;uFAf>*|?1)8oFmszQ;v82Z8`m=i|CRRSa@y322p#M?b$!m;MvLOczMbqmu?(@U9!1A=k`f*RqvrbYvo!5d-Yqz5X{u2a(SI!1GOR_l z&*zuwD~bB@r&b!=6FvDMvNT)WMgXw%dF2XweB<-NP_l@J)se0o0#+_Qcavv<+Qz>z zk2&?Lq6QF`&uH?9u$9Noq#b83=h@D-TFkOrpzUMq?`yaKf_Mq%Lo*ucAdE;Y7+K5} zoJoVU(X!&U1}Gk+kxrcL8@T@r6(>`qa_t5hux*U8^cGZV7SIXlO?XtK%UAY`AKecM zN`7_K-ciEuVp77~yPm{-Y3h%y)Zfw++27LCzBHv{#TkP}*26pfSknsYDs<(|k)5Z> zA0;@awJYUMKWI^r$E+lJ_Z3Dvg!wfx5|p;rntRoAxIu2xd2;4`p*lOlmCq!)_0D|# zZ#7lIdFmYU69~l{4 zI8t6#JGX`|=_Dt+--@gl6~6qFti;(tO&-H04-`$s5yN&TETHkPm6cX~Cabi=s4aKg zO(zE;zPZ8{HBbIY7l#UANV1}EMCk^|f<74-TUT9#%4*a`G(cch%aC(l=jbj6HsgSGJY-VS+}Pl7kVARO#B7Yv{MZetY<~ zBcy-%`sIP%_(AldIVs9ia&$+HI}jhR+=6a-0u5sV&P8Z46u0bfHJ9oit9=%3Q#TG} z;0tu=lB6RRLmNagGJ=EWZ*ojPqKovLwugWJw!Ie4Ip5cUfs9k~>93~yx4iTpOL%b1 zi}y4ty(EQ?B!~H^_-dFdI5h~?dll{Q`}P|cTP_8Lms&jMe_t15cPjVZ02=^WjyuV^ z&wF21q<_BDx4B+*+*!*1Ol~ZS4BSysHBCd zy!X3-FK-!%WjU9z;A@alWCnV?7BV#Ham&(PQg-ZP9IZr7^ZR&ut^m>2T~MI*ff^m9 zwDDC8CO@7+KOL?lNc21f7E-y6yGSAexnmLYGxNnz0S1<~xGFwYvh*P~rrHxL7WG?yl!@(QQ1BCn@P^VNWtq?!X8B-hd-CbE_i zmYGEE0Cxfe-~JW_h3w*J#1xX#vX(uSvWD^>UG%Ab^F(lIowI9@XR!!O;A#Ztul6s) zDGm{B*Xel^=TLSIh!+=?N zPL{Dj3NTpzN|aQ#p+<`EG5e71#y#8ZFM?t1Co?4}D-K|$IMVcS>+%FS2g1FRl$78p z&#=Mrbu~j`P2(v~MW@`Jp3X_%mVW13V|(doZbnNDWvFSzt?QXtmIf(+T@qx$FR3AY z@rVX3kkC)Y_!qKFdN-w$s9=PLt|r`@nKokN({t?orQluoUZ&#((5v6=qo)8H9!BL+30N?Yi<^0hj zMhO7%t-YSa@f6>?(4QR7L3(3o35nzB_yLtn$=@zjp%U6$hVn|bppwk1>=ai{_6WH| z54qbHN`iI1_H{*=A~;Oml0+NLsE1GCiB||s3?3?jUV#WB=@*1I^uT;z*vgVaPw%)p zXrh6{W^Hrde^vBrM;bmiuEOZGa0lz&D#Y9QzL{@N*>8SM5X|+%Gki{0PD|n29uCY` zUz8P@^lQQP@$qJB@ugg@NqC@^ZUl%gY_On2xhEw%--Lj5^xjB=MD!e(n_H77M!dGO z`h_g1PAknx{ANE-RHA}1wl5d=K#j!nl%fr!mqbP?4VlCNI*M2uHTrY|X^k>_Yecjj zLEavIX1GFjGdD851gsTtp))0;&cZrc)5`N@d=Hpb2FeyYs-S2dRPIW?gYu-XCcVJ{ zi3io54@&FEMuf0mb;6R4vcYI7W84jcY7|#ej%Hd4a(nm?p&_S%noHO7#>kJ7|AHj8 zr|6{b6yRse-_B43G?Q0DOmwXXksyy(*IvE>VjBazL-#J%_P%93&#TCAPUs}hZ_uLS zfZM+PFfKdK74!NkdDgdJI{?l_1tSBR@H*Gt`Ld6Su7szb!^`g|X27v6ZJa(>;%3LB2G`d=+Pjsvja0^LT^HktmJ zK}}B4oOQv!Mg%yo4g?|qU}@pSGKXv~5|+9iaH!D?1G4nPYTrA!auihe9@ zQ20B;0?ln5=WlT_XxnQFV_Q$06N24WTPrLk+&}`-S&f~E?IiRmz{`YhpP>L|;6L~5 zTB=!Xwl^key;|y`k*-GV>jsGS4Gj1kp}96U2CD$@HwDjdtl<-6tW}O&X25jd`6)+ut9CeCJj%vRx7bLP`~$|C^Ep};8;%Gd0o0M7 z^jMjhQS#-qE7VE1^8Dczqu5XX^sa){g++GmgnxFuq~%Wdg-N88bVHwF`G28(kUDXa zG3);}7I+s*w?*Vp`TXzAk`r$jp6CQ~L>PdJ2=^~H{ LYVrk_t_A)Fhp-%; literal 0 HcmV?d00001 From 4649120079c46810655b395f055b8ca44888a4ef Mon Sep 17 00:00:00 2001 From: HKR1987 <37500242+HKR1987@users.noreply.github.com> Date: Wed, 22 Mar 2023 10:30:05 +0100 Subject: [PATCH 110/130] Create BLACKPILL_F411.md --- docs/boards/BLACKPILL_F411.md | 3 +++ 1 file changed, 3 insertions(+) create mode 100644 docs/boards/BLACKPILL_F411.md diff --git a/docs/boards/BLACKPILL_F411.md b/docs/boards/BLACKPILL_F411.md new file mode 100644 index 0000000000..3ec56c8210 --- /dev/null +++ b/docs/boards/BLACKPILL_F411.md @@ -0,0 +1,3 @@ +# Board - Blackpill F411 Developer Board +## Ports and pins +![BLACKPILL_F411](assets/images/Blackpill_F411.png) From d29cb12229886a8becdbf27f9f7cdd35695e057e Mon Sep 17 00:00:00 2001 From: HKR1987 <37500242+HKR1987@users.noreply.github.com> Date: Wed, 22 Mar 2023 10:52:54 +0100 Subject: [PATCH 111/130] Create BLACKPILL_F411.md --- docs/boards/BLACKPILL_F411.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/boards/BLACKPILL_F411.md b/docs/boards/BLACKPILL_F411.md index 3ec56c8210..2db145a3ea 100644 --- a/docs/boards/BLACKPILL_F411.md +++ b/docs/boards/BLACKPILL_F411.md @@ -1,3 +1,3 @@ # Board - Blackpill F411 Developer Board ## Ports and pins -![BLACKPILL_F411](assets/images/Blackpill_F411.png) +![BLACKPILL_F411](../assets/images/Blackpill_F411.png) From b5553356944fe5a4901de28bff58bd7bd3ba4dc0 Mon Sep 17 00:00:00 2001 From: HKR1987 <37500242+HKR1987@users.noreply.github.com> Date: Wed, 22 Mar 2023 11:16:43 +0100 Subject: [PATCH 112/130] Update BLACKPILL_F411.md --- docs/boards/BLACKPILL_F411.md | 31 +++++++++++++++++++++++++++++++ 1 file changed, 31 insertions(+) diff --git a/docs/boards/BLACKPILL_F411.md b/docs/boards/BLACKPILL_F411.md index 2db145a3ea..c1f0473f5a 100644 --- a/docs/boards/BLACKPILL_F411.md +++ b/docs/boards/BLACKPILL_F411.md @@ -1,3 +1,34 @@ # Board - Blackpill F411 Developer Board ## Ports and pins ![BLACKPILL_F411](../assets/images/Blackpill_F411.png) +## Connect option +SPI1: +* MPU6000 +* MPU6500 +* MPU9250 +----------------- +SPI2: + +depend on version +* BLACKBOX M25P16 + +OR +* OSD MAX7456 +----------------- +I2C1: + +Baro +* BMP080 +* BMP280 +* MS5611 +* DPS310 +* SPL06 + +Mag +* HMC5883 +* QMC5883 +* IST8310 +* IST8308 +* MAG3110 +* LIS3MDL +* AK8975 From a55fb19e924a7eb6929948d4b2c9a651bfa95eb6 Mon Sep 17 00:00:00 2001 From: HKR1987 <37500242+HKR1987@users.noreply.github.com> Date: Wed, 22 Mar 2023 11:52:38 +0100 Subject: [PATCH 113/130] Add files via upload --- docs/assets/images/Blackpill_F411.png | Bin 1052068 -> 1052187 bytes 1 file changed, 0 insertions(+), 0 deletions(-) diff --git a/docs/assets/images/Blackpill_F411.png b/docs/assets/images/Blackpill_F411.png index c20f762562ae6c571d6f81b8fe083faad7e140ce..4abe92c9c5c31be606d4792a0ec064d405d66861 100644 GIT binary patch delta 68797 zcmXt9XH-*Z*VS0JC5fmI zAQb5(kf0D+5&|S7gcQCw^L{MWy7yn!y3cve-e>Q9iu11Iy}OcPcJTY2J;LAjW-1Ab zKeK&dyZ43dA1`e8y|DfBh3)`r5)2WuDzZ2Laa zwM8PQflHrr+il){M!XB^kPVz(0XNq-Od5qa2ONkrwwliI==)4QF!R}|sL?-aWPmr! z{L!)!Vx5|=ujJmya`o9`g)o9Gd@3sK9>T!o3AXWtaq?Cm$}T|{AR96LHGi=&c8=~@nVg1RARfEcWNm;sJxACI7TL* z-16)(LM9jomwO6}N)oo~8pIK82Io23AJ{1*+%_zZ`P$y@Du@O=KSKW4SZx@$Hfc`O ziaCKsJdRMu?A!DE@5~;--;YN_OVyqurcFc1kS*PswVLvZjELk}c@rJ(Z62+gyUEjs zPMvvSBdU@j3eS-bn~6lW(`V8*r``lcETGzmj42?^39%bH6ZuVgp=k=p5ajW69FT$K zn%d)ec)&85@%Cp?XVkJd?P{I4cW_>~NPZEE(trxc6=9xO8&RS$d^US9(pe^lj8Y_V zO_PuhW}uB_uJ#p~IuS&*XDm^Lw5)zTQT@S>Te@>|G7Bl+k~3h8S@6qb2^A!p-ndsM zG`h6LC8?XYX-#O`(>j&#GgBbBvM~FBd3a(2kdJC%xQ=CQK?pSfR6Q!FE{{2|8R$YW7 z8pL>`F_=w;R1HUIp@^Fs8YfM(A_H zmjc(2T+eb%ot0yD_@kVk5!4;vS1-k{csXdpr#67m&}XqtZdXS*D}{Sax+^kuCTNrC zrM=B+ZFf}L7ubOdLl|?o5w{P1LP+~5wWSRH2|&&0G~dMMgO43J9Z0_A?3zq1`Px@A z0fzNNdo}0QM%3fUGqo;@=-a+Y)WMD8U^=XBsb=bX|FuUhl@EZ8??A;olSr+HXP)Ak z#!I0Ia-()(dG4Q-5Q$T1r<8t|-=1yG+5Zah*Sb_=D_HfD%(}82y(6S^0J1p>NT;E> zTY3tuD}$TOc{Pn#A)lxH>ANU!XaK=~S`*8lun#e&&LPxF1F(Vow(3)zR z{w}|`Ib^_X;OYEdVV=^Fc}#kr|H=sP%JN-silr`3lQpfQ`stbA3lJyAnUxO45;bDv z2$y%yDO_e4i|P6{xcfYf^QpuNLvVEtO#ygsz^ilPPXY1I5|QVr;XlPLrxj+pWb4Jo z7t~K=+n;QIDOLSbtKPnQZDP+cL_t%yR3 z)rsP(+A9t@HBFLrF1yB-S>5|@xrQJ3^84lKpY%(93o=uG+a6&(&>rJB*8AqPGal6%@O}`8 zEAmolHlP@A?rA_A`C4TLG1{Qn(`%jG*Vpj);y-pjbl9sKBOQX@IvU;#2udqfewVV=Xr0Me!=M0loPR{k_9gxFn}tRh1J~3eol*Qcyvy2jAf!QE zgIk<;knnD13`Z%46;Hr6qk>u_!hV&fp{cyk(9FIBz_Pr$I;)?Lhr^pT9y}7FH$542 zez$!|J0cWcROj=}QSvj%(9#B*G*OCVKNy_FNfxpn)s{4ggdwkuwM)^pCbI>C65yB3 zk_u+96 zu^(X;x66p4Q_**w(jgx!(>vkIeHKi!DWELA7=;>lW(Kd|5O8|mih_PqfYu4_fbr>m zW+1M~$`hO&ssdI_Hdq&-M)xzFk_%Pn!_$|hs6KCyMzt?Lkdd#W)Eb`Q$hwhB zzU-zBm_k}Q&M8Ux@>Nwf&t@S{6s(%Q<;Ym|NVcyHii@sWc8gf*Kc=wjo=OLnr)-5U zFFe*={-oA@)^mgzD{R=?E-fo45n0SSyyi8a(l2#8ZUI)%Zu2Z4Qq9QewkNt-Ph*15 zi7tfAh88J1a8i+AM>CS_uVjKg6oC>gJUM5r>saXLfiRmhbo>PI3;87}llm%j(JK8Y z_q);ge~Wa_-pjwADH*`4rO!vj*#Bs6e;J3Xd^?%bk8H8~dG{?Gs%@6eU>{tU4i#*E zCD?hpZ|xtp+v^${VY3p>J<>ehL)!dJ{ z0=j8^nSu>mIk77P+J=L%Lzw(?Q-+bbhNW4D8q_6mp^jP2gSMj~vLXnGoB=snNF78294ODZac83f?Vl^)92#K7i!~Xcl`G(4t6dWq(P)ZANJ$BHM3JgCLlBJhI)@P0fuo z6~ySJwCUTsELvn6(HJ*22W}u{kMNPlo%QvS{7nLHA4I$jOD};=E$RpHi9%1a8XG`4 zU!rAypls&s4z}-tSoq|24qXY51G9IU&udi1g+iB4%{&!?Cg7W3Bmw>7BY6lzHSq~V z-QF7k*(VG@B`b3gFB=VRd`cqNa2T$V;3{slPa_g!Y+v1YDg0{$z;W%0`j1W?IQRd2 zQm`suL~vn8iT+~@Xg39sg^c(UaYP$Mh$ z{J|{wV^z{?HtY?CAod%3E2Cd6eV}(Bb)T@FB}0GijF_JPKlJXN%!c6n#A37YY8Mr1 zAK+3D&3VY0m^s(NW{8(8%L#pEA!lrZiwriFLBxC=a4N9nXJ_u>l1Q1DPdxh^9zxym z^pYNK5Q_t(Vq94f$!pNMXNo>P<)H#%hGs#F4CgzRj?Gn4x`Dl;8pJo!Jj+rTMSQVc zIO}#1X6nj0g!o8vXl4J_#nS$dm*$CYk6ULRQe!`JHkua=tndLnm^ux$eQ8Vkc=|8Qtewc%TRK?DA3jFMg;#_6nRDe_f zZ)jQ&`Rh^yHNW}1p{>{Rzu@tqKknPB4GyrA4LATIioE$Gc_ys+E_w2o;)NiDm0?tL zkO3mZSj}$1OSVr<#6?T80X&uj+C1Ojdc*T&OQ7B`@c?Ad*tcA^#d83+4(l_?G^dXXV0Ep zx|#9SyRW720!)*M_z5}3^~sLlU_kNyNy9~B42{%Pahz;xvbZ&C;b&?3Mml;9-yZ48 zT`ZNGY6_`T1~=V3slvHw#9M~}3T*ce(M^Flb}kKJE|8M zU%X~*W!0=vqp78B264$Zd``h@HBOA4T#aw5(1xGW3hk+t6Q3;7puZgmM*Q5bP~LUJ zX{vO7=t+1UWpT9aJGLO9Cnr~MS`(67Kijq=eT_v|-?{nOh2LDRbK z)jh($kG`R>F|Kig!4^r16-nW?ZcKkaj@X?$IXccO>eMe7BoM~urwvPA3*7TgF^5<+ zYI?87lH_DGEErQ^X_o9>F?DVfC{5aR%daJRQH|)7&AEc2j|D9(yV<113hSG9E!m{; zVu6?8Sn_h+)#=)RQuy*EhZ<+*_ZjFmv9^m)Y&&-Q}iU*}ZcQWlC(&&lnO~lOASM=OQRXFJgTr7V`ARKO9(J z3+(ES&?&O?xxOT;<}9~(&%qG{wIT|7>~!Do-$Sw09;@TyZ=d8!`mFe5&;B7I4k#&w znuidrMb{S^lP*8_L(g5`KW{t%&d@fjaiyJc>O8rkOWHKET0{;F%+>pF727m(ky2Kz z=%MkUXg9Z5m$k}@M|n;Kl?n}(*@ik4TYaXE?GN{zPfVPedOMricxX6K5@C0EjdmwB zgd5#CK-v5mMI+`!B=^|b7(6lpt|w1=)M~nLzJJpO`w!E2v=rR#M-?~|9tUBK*zj=0 z$W0v!*Q}S3YAK42RfAzs-;J2-mkMc=qm}USo#YU}ahN^1=^V|wbPZ$n*x=v0yw1vG zh<_{jmnXjz_($2H)wm#XRiV5R5mr+0_fU?}X$oy(T#8dM#{8zHt*fi= z=eeqTci$4zk9lrsw0=Z)XL6qS(Jd*PPez6ZE^7qR!^JLpzjCQ7s|zg4m;5f`xt^p} z3NNUm@&vJ>z`>;K(T3o1zSxlrinhlq!+KOPqo?x|OXoh@65q#))JF)-gmW`RJvszw z{jAAzX4vi&i<<3JmpkVBu1G~Kg9F2clv&G29dh6K$Tha5(S7Tk;R$y%S44f@JQL!i zjqUZYSV&J6y-DRy)Vhmi0RhnRnu;_Net#!T!~mXyXEoa5BqH6Pxzs3qODL%;yoQgc zG&bVRNk);^wHU@rQCllYagvuz!q zEVUyOs`GSKTn^D!W-)VTcZ5$VFGZ7%O?eHw>!W1jMSC=CjLz{@kGe6fE33t}WjQo# zGr(;8Iz!4X$dl(Y@7JgN+UZ|9zV)$eQrlnS`>wV2jp{=)&8Nzw<5suGIZAF_M4aE{ z=+RSRMvoc}i(eY{FY=FEUcasWsMt(ITIHK*(j{W4|J!EZ`-SRCHj+8x3iH4&3N?Yb z%06d?T11^ajpDxbZQP+Ok>Si4S)oRKpg;WU{9ToSj%Xu+!%_i8&GNZ}tM}XfnR>b9 zx6nV~nlYx7Z8~bNH{V}Z67RtiNA!{qs51z(XOlfRBh9{`87E$vpOu|!HBwS)IfB3i zrpI(DL^-@>gO|-Y_IV=Xi6>ov#U&Zs zwo~zau1S4}CAh!PBD*9{C9q0&aj@Ff#_*n8f;5yzHVZ5H52X73hfxy}F_V?lj^LEt zA9e&c!)>9a#6>ENiK!ql#Sy#X#?seKq`!$$Pu2E5=XQ}0HKpb}HkIwcfbZG_u&~sH zBqu~Rd-0^%1~4zu(?$bl6D_j47p=sLTkEa`H%SPsEzg#r6Y?(J<_{Nk*1OXa#5O{n z0tmUo3>=Rjq;_04U44cem`%Cnpc5+ec0DWkpoZ-2WU&M{X>?YbX>r zMr3HXk^J^Wo<1#JOdk{V7}?PZ)s-K)5|zT2ReMGez&lw&-iEC%n-dS2OA(NO+;28N zsS*xu3YaRCR^rb}XnJ4Ih5!Q7AUGTl%qhpK+wczTW2=NI1I;#A|FG$}>iODlI;@?S zdJ#qRd*u}spES0YwNUGAptOzS%xtoh?(mNv7p(N65-4S6r^U5yDPDh>cuEG$>75Fk zOf>~8>^!rCoZ0R}f0S4K_#z_S^Z>IksO*;Pvst^+m{?12-)e7kX0Njkj;XKkDO2wR zI-;DjU_a427z4}aOEiddcrLRt#sk00R9oZ@Zq^f=)$Dy(&<3(&%j(3$v>u2}AW_&h z{isSyc980JjbuF$zok*MRI^ueQAHTApJ@22AXW~7&w7E?l7!XhVbcbr8X&aDDc@!x z1}ravfbu9(nSiiQBBI+YaDgKQb3BZ6FM`v7#)6@rZ`82Hl8Id) zuH#zkmO#WDUZ1?F2hBpA^N1Ji-3h7mSW1$-1Ge|VWanh6zyuFxbX<=!3r#L?#q=IN ztEoz>S^43a4cypFqF(Y)C1&Qni#U{z%FZmkfyg2x&pyOyTU>`#YieswHVnKSE+gz2 z!5^CbK{)*-71x$bU(Rv!`X}e&6HvWX+TPf>p7$SQ+?Ur=)AI8nI~J)G6^iAR)k25A z9DgF*>XXxqeN{oit2hl+LO|K&K8)EqssbZYm9uQ<;K=E@h70rbY>IxeYQM0_C)(Ee zp;;2a-J<8AaIOb=`?dO605rAx^jq=Vwk3CfYl8H^KJ zw=fbqtDIkT7N+~Vs9h4nGw#{f4~kdX59ad`+wZ#J8+bCwI<4kay6(uuIn%9 zozv6M;E8Fuo$#35A#US1V1R$}EsqdJf0BNbY}zT6zD7%OvsJ(!meIO*VzWcPWOF$- z3=65>Ju|^u6Ak225m`>q?N|;s3Ec}wBf+i!MYiqFp`8#v_az48j=fX0;3aN2`uSH= z#vS}&MeP;fbws4&Rh{|~j<(AAdtRVRVr}FUh+EhsN>Qn)mv4v^*M8_xb^@sGFzK>>duGYS`2ykd`&$EC29ZA&A^4x}x)nRp zp~=10AKyOI78?4F(OJj*&KY*m`)AaX>QC_)?+1jt6Na+#Y(egHuYkEPIfJ`wB!>{v+?^Z~llb?*_6yFO{I1e2HB6^_ zmrV%??!@RLO6GuQHqG>amU(mGvlfI_(@k*0_N$>m`oXh4O|GyVY%1oRvKRQG%K&mcu>M5vl&E!f zP+wcK%NjCoFmYVhX@oG|u%@wP=?E}MsN>e`iefL%7ds+J{i2o1-5|l;sCUY{uFc~E zRKWgEHgjYM*4PN3LFmL4tzh`{wCKM@v>pBbgS6R@V4bRD@!*60liZ8rKzLwL zLD`itTk^WV;yzoWIq7CC)^#kWI_Tjwi+ zjcCrgEDLZJUwk&dk$75dYRV7-*AMm2Y<2}q06s;7*SWFnsNv5#yyxOw!;%5vpHH^u znKsv_ROy{)sOLzSlg`~ivW~}CW@ad(pqZeU$%3NfsBf8Jc;(dni$S#z(#fdvlCc8d zdw0nxFAf=9oQI8#j}Qm&+98CPB4d0MTZk1rWLnxJ^~K+nsZELNTi!Y(gU@N%V@N<|IQmFB%P_r zz1~v1ZcY=+{kb~Oz;36QvwFq6EbP4PKCTa4n-As;CI|40c4PirK|OE+NxKxh0;{#| zE=LE$A-XT$)R34|=JAcUDo-zeP&~wCWm2-_5ndBC2QkBZl5G@K+(PUU-gfE>sW@Y|1{&t#YLP%SoFW<%O zh9p-x)%WVxmE#M=uiM-nw2eK>5p#%+B+KD0Ukn`x3V*imkm#pG)5DQ<0@9>@0fHgy;} zHT$R8gJbMYMqdP1R4O7jTF$P9Bfp$gqpCnpNPhp&F5nnoq@WE6s`(HmWO?q_9||h| zX%w7x4}lj6APsoyAW9nebo=n+|MyeTpU%J2u5SO}INc`z^#N*Zq69j+O8FAhvj__-i|m9xW$~2E)Epm> zOpb#?sAq|#(;Ct%ME_{Z|h0dnA6pc*o9Z*zZ0ISnmj+U!S|*zVlOiNaQ7M z=l$iAz~O0o`u3yOHKHet;NkOcLK5bl6w**xL{~hn0W^Yem9H+`B9}s4&sas?$ko&u zHTUS$E=M354ZSZ~J$_pX$g}Y?RamK{LNmnuME$R@u$AlLAzdB=WZ&Ss*(oGz}ngw z!$Ea{Q^&+F(|f*(5MP^8`Gk5PwS*WCfiv2j4kTj^RsXp979eOp?LO4I@wtij;$kdc z)bY`Fd*f)WF!?czexxWx2tq$6CJ8Ix%EsQdo z3E@@+940q#Bm|xAFu{W>?<_-nJ|YfnmAMU(ikNpm;-^0!Hv?(#j%b}XK_F3nf*n_N zYt*1}685D4#j3Ribwj(xNkOSsbQ(fTdr{ZUaf<+Wm4SorrZyMcM7kN(d1SKjJ^|q@ z4b+nYiSX`+bwM~!2b6m%q-e`tnQN>Kb#~KZh&*^(oCF3ztrmldIy6JCDKX;YuLQQXEZ>9T;HO-wblc6jJHJI&CpkoRjUQyaB>iN$&V z{lH5{-~G3A=7L`SS35VaRSDK9;`f1fuLjXi{+$oS?ps)n;Z|$a?uazen1DPEe7+hU zExsEai`m2mpK5Jf*l)0n`O9vj^|9Hv<|293m5)frIX(XTUa7HFdPYUHs4iXHL^UVC?lOUpM1$Qx`nR z{bF|}mJ`uK2?S6W99a;`iLAap8>v||Mp<+zYt2wC6YO*SY3Q1gYSq4sCel9hVhs3lY&T3C~C7>M; zXfdE(46U0i7i1Kp5`}0;^sCHMmGNM<*#-uH5yw z(gYIzv9bYz75whX z4(Drrf|wo&3}0uv^ecW1-8lazX@{eZo&m);VU8s;Dt^l0)vmJ>)+We5zD2n`b{p!y zS3gfn(?0TD9ARIRJQ1>(CLkVO)S%)Rf3m>Os*%8#tv2?qh@QHJa-18J1g zxd|S_YZJT6A0Wc|5eqvYj(H3#9n1IpXB3@upba6K?-%P&c<`eJQYnJFMyB|fd5`j$ z+S!6i`;I8v+|j3p^O2qK&KtlK!E@xPxMWb#+iEim+;hN8+{cgRIUG8E$}kKft%um= z_!VO&TOdWzJ3}~Nb97#$yNF+!HU^xqh(pL@0<& z>iBzgy9 z>$G%K_{#(-{eeoan3WI-P4|z{>|vz^eL}v%zPN;oEvYe0wv}}+@bfK;x$5~2W?tao_cB6vhHGCY5xb77XiC+09`}PI2i9gm)&@iD z=a@r4lMrL&P-*&yEv`{4Ced1ub~Pqq`}2;Jt`yf}WHIR9X0qo@x0V`#E7qSNhQ6(8@ofUCJ0 z^Fx6n2mytUi*mMWfB5<<*^(O>-b!k~;`O(y>G9l|61t|Ztnb*6?^UiEo)m33(256pUo`UweTnOV_1w}t@Pr#yA$X-xu6wCfl$SS!1Vu7a5&1BbC3MKyTjkoE(ZO6H9MsYtP50#!g`F)gfy3(eNMl8aGYqt04eN=hl414qOD9 zC5?tDdnVw&T+0iCH#%hlI#m4Bg=*@SGz>VlfjO=+#ef|3bM8qPBT$pI?4)arnUV-s z<))gjt1f^2dl*mS{%h>7WPYXkfB$Aj{RydxYl?|@e5h{kpU+Sn?rW(~Q|8Y@S#0hO z_q%=#8eRP>v17uKz>7GKv#HvtO*&d7TICmrN8D@V${OuP zsn>_IfKDV=qu7QJla`+YVJ>gmZngTs>OtW~D?Var=_3}A^ovWY(wKr*I?+PYwPJZ1 zOMW$0=)JMTA2Np)-biz=#n4BgHm=~buEi;(g5@6`SOo?*1>3SrN`^82G#;a@65 z!nX_uZ25{id50s|IV6%0%NpN#9Z<=4Xd;63BGCu4fX->@isKRJg0_}X6S5k4Arn#eUesPKB+hC-7v9@`| ziv2#h9ftH7+d)p&-x5*J^D~QU%Wt1PecJzwDLs`NBwWy>V+2&W;$5>pTFf^m&gHK9 z>kA2O0gKysWo7QpR`$HLfmISeV6`$-A6GoRF_HKCpQO7?Hn2*|%~IqeVcKyU_8W-^ z`rpmbnT(0^At8;WP@w%b#_Bm?04lCl9o&`Ex)UkRDYkgHC4KQ0DrT)y`=*?dlC5Zd zotw>Zss!EWZJSqDp4>OnME=j^D5i@T0F#Sb=T^56IuqB`3i&i3L)Td(2+Yh0PH_&O zI^438E8fpF#HnhOh~CD0ddPK*V6n;;S_v*HyUg8~3&{rI2!BFTr>m!sr{2ow2(b*! zOV?felQIM;Xw~Ca0C#J8YjwmXW(z=Paz*s|1b$8qCW=K>B!O4ShCd#tN&<+1ue44z zxWe&GW~ycosKHbctrMFD91bf=+-cP-ue`+Ua;|Kk^V35EO?xd`aWB`F8ymH_Cwocq zhFUI>L`EHTN4Hvs`MDM~P7fj&7^u8r4nPv@OCl)2uOfK7*j88Ftc*ph{HK$81Squk%AR2vw5 zb(2`Hnt@eC-`Sy4p!yJB{|1eZ?Yjd`+V9UtIO>G*JR2_i9fyT zIMM1>BUXUm`-CpbHAyXh_* z5c=8!e7dS6rpL>O49XFw^j+dtM!Lpe%PkaRi{}32eMc#RFQQas+*8WJ?r2r^M@)a4 z9Qon!#@b-3auZ9Ky+Ap*?1$~tu?+azlqspzsP96Y}3S#&W7=| z0{)ocJk=VJ-jbb|R*<9c+iT3>ai#MB)yAORc3UEsiBHSdZ;Bsyn(?SfCdtUIh6Atk z_+`Yl@Vt>*T(&xioD=7cmQ2m%{S~+ohR7Hxg<0*;Nzg8}JGX0XvvLN1F{+&`4TBCF z{xj9y>{(theU`6;q`tg?6fPe|>|P0?3QPq}#321h`JWeI)Ak4>q$~i3QGh3>#ZP-+ z7!d6Prm-31H1`^p6d<`h=34}~iY@7a86=$~)gN^MU6=$u!S6#j(N(Zo<77kEwry@p z({vn*G7(htL(Sa`rV2y24}sI<$D`^FGV&aHs-DI zB@lT_nj;|1y8$fmGe^|;n9F2lrZ>%G30B*Cw|%F=keJIDlxamRx@{eu#fw%^%Ziv$ zBHe~Db1w%Tse8_ZuZ)!;nh)Qj8mW77!s`*{{7B=u#Ki)V)tGEFzYkpivvyu=&Qb?c z_U;q3@O{%V&u2ElJ&#>$qtg7Ge^`=OkssNjh**1v8r_dZjp-(+ruF6BBb#e>8e( zB`41>_OXD7*uMn4+NrtQODWsDNNDH)Qm8Eq^za@5wg zYy^va(=OCTe7imbYsaFZcRfH?BY~5Vh9KVZb@2llk>v26fmI)`dNJ)s840H}tWN@) zsVyL<;0kHUM2g#T_eNk35tN};5c870HUf?>X|1?s4u-j|?Xn5(8->Z14p`y`zPOD2 zc*%|UNhZ0`BF@9zy;m+s7@MtfX=3!yg*xoRoKig_NmEa|Cc3nyW$C+ZK$g|(urw)F z;M><2xm0~Dg24{D%#H_@Rg?;L?k=Gl1zr2$>(Grj= z>k`z|SB5Rj=UdF`55NA&j`$A**N^^Z*4_RkIJdmGf9~cnk(XK!>4mOxaf?r|I?Auc zzp?~76_f3owPFB$m zc7^N=?>-)CPV1H{UgBHU>$_`{ic0p%nHdei;_pA~-2=21kACTh^_c7)s`J2}Wcha< zv(>%#^02flSeN7!x|sJYHf~DHDOfI}GyY^Zf!b>I1|B|17uUaV-6sbuWywB9bQ)(4 zeDGZgb+}_Er)wBB^(C`FS6BO$_x7t)_3-5b;{VhK%=!kk-ErUMpWr~VYN`e*rU1#a zD!uEq76I(eHZS1yp{e}fw6KeGTMqsG)$1O;f0gC>X$+`R@7}xTIAzRJo9L7CEDbpGa+p5|5?OhP);hA5FMX8pyX3ikt$W++oRdx5}iz{Po2+4^9LGLme4hKn-N?ImcUh?vfk~D zdD;B`$nu^eSNU8!GG*~%exbD z#dYvWR}qniG7fpJDUC{=b_FBp1Cls*;u{aSe8nQI1DO64^~b>a5%It4VC>MKBrSDH zAC1_4NG+3Zx4w*pp5*7;FVLjWHc=rRviOa{PVq_`rXXp1Wt({qY^)d>kX~2U8TvBo zwqCl;poAG;j65o1+LQ7@h9Aftv~1MWWq!pj_z|{CTX_4nu6uNWWvFOwX&>KpP>5iy zJYIi8bU|DNVqf0ucv3d`v|!6`qC0+YAieF4=kL72g^8fr|5d)sA#Cy*P%0oRb+pC_Ui$2&9Bb8o$*E) zRZ=aXe^riHgGN;KODLM#i(B^K6n$vh?UOOvNn!wc0)8<0`$abks}c4+c^F$b<1ZFF z*Du4*i0?w8djxwnOK)8%Sa|g-fGeD zE_vpxETa7kb5`GU)vwYD!&@>FIcoHX4%_ThV#-d#`@-%r`4oO-xv6&N;JAqSU3phW zpi}=P!of>Y9d5>kiDWGK?io-x{ZwOMp!C09HYf96rn2y#eUA&WT6em|9@C#i=MFq| zGX{Mg>jyqoa=1Jr5W*2FuheSAiE&I)+1{hK^Dww7Zp28%@Ag`&aF(Cm_|`g$Yn;vI zY#PHp&hg$q*qyE_ZRHnOEpS&+snR3b6}7O)$l}w?mDy&*0#(DTD~Vt_V6c=o4176* zLtTx9_JUILb~mFUHgYh1Cp7cFOZkr0{<<6ZoIT%I>k#EwW1wZC7#5IyuhQ;qp(cMB zrCo>Dpvk}fpAy8fi znt*Xx^9lLPoqDrmGkeO+!y2y~A!RXL$Job_xlc-a<{p0Y7@hp<&SQ?5I`MOQF|fOL z`k71UDzcf7fhI)6XQ1c_e4Q^hP$*`2jb1V(kiV?{ke^*FCQsJ7@SZR!f&4IecZCOh zI_HgZ{~qW=H7Jm5nvHhc{)xNe;vzp~ShtY56mL}ymXCJvtx#Hs4O_xK?YK_1G&Zb@ zeCw3zn>~J7=V6*e)UWbD`XvmG*nbydm6(CrY@c~T65_iEQTXk|`*8axWFMmUjbx~R zv`eJl#}-we6){h^s#c~)Y<6H2vyr<*UsXZ&XXT_q_%-e$>ojAqf|dp{0c7 zCLzPFCm*G@{h|$OU2x4I*jI5;#@x;};o9#cc~|cJ>EY(#J?|DX4p%=2bd{{mb6fjX zUe+r1_`k)3J$v^4&+Yjew5M#l{MRXsIZbn4^P(sT@htMU*}3apvrEt(zFoBBwgvpm zWH}W-;D-C0$YEmeb!hKt)toqPN8EO`VG47khc52FG?JE^>+8@GSWcdCkY$tG;Pllo zr#rSI=O@~!Z3Op~p`tPh8ilg9Q&!4$m{{%8Nj7!uybr@%@PoWl+z2b3Jsys}6xVG|-H*@tx1z${Wq4A(^^RLdupX`C;GFp0pIGyk9hrTgf>}~mZOHTVt3=NK)%UcwfC?f=E+7=W}D4XzACmDFmX04{CR?ht4TDTeX zQ$fRBsHIS1A}~BU0!(?JC zx~ld9x&|eP+dop>c#p5)!RL&?pA77{p0skG0PA|Hs}@4_zufCD5{-{KrP+9CewbmN_Lu^OeN{ye&sc(9Hr@YW++S_tkWBpZWxsSYzf9C=E zcvvd2q)fX0iNw)ATuh~P3XDU3CE}dMv2-XH*^p&-kDS6Erp$_3#N05++3#EdBze>~#N9GiT(*Z*$}hXPaANQ$H2|-X~oX>N@!FwNa4~MadQUmQ6nrc`Z+v? zF&?Cw3^uEV;cldm{?M#t`A<~eRo4b*>Z(7Pl5~w%fRc2p=_SZqMa#2Ef zU`cWc1*sI07`c+?tAWbb596CXPVVzBLpC>_Gl^5bJBh0j;+Gxaprt{{znZAsb$bKR4Rj*X4MI%uz*CNllztkS)oCN3hMc(Z3*|GVXT zo=)D$b>l(~{yy&Lq~DeqZ4jge+JQ@B7yI*E%H>T~WnFyxqtbOAzQ~ddUnbE2`X=cH z=s*&ldI-q&o0fBvQnO=^_i`FGNyg1SD$;*L!RoMWkD&(ZLbshlocsuX8;nb|0PEWv zMDNOo8TkLB;^*(5;$eYZCs1V)46}v39-F%N`VIb;A{X_0dlLKQYHZ^^K6e}!mknI1p1?YlsF?+&3k-f2 zgR}nF(HOm7edqu=5;W94Bn^}D=i3Y?gc zZj)72rQ9a+`)v1IxwP-!+_dqKgHT{#U~ysHos-JjlL8)-ag&}FN88>ePSHCe{cEL8 zu?v~32$;>NwXChF?1)!zM7wr15!N9%TgzYrt`7$B;sPZ*lOu=Uku8*+>xAtz<`3PE}vKT6+7` zbsNTdA}lm1bwJC8$Q?${A4grZEyRtb zaetMjdZSCw@-Mvbth@F~OKIxX2)kPJXy;PvZ0?-V~u*6`S`C3Au@Nuq7 zqLis0`<|c25J4XRR|Nv#%M`)SCYz+rV`L2I#wTS*KO#RWYU7c6H@9DDw#3O=Rb%eo z!+ARScJII2)W7bx1?0~J(^T$gmfZ{vd3S{7b~ks_%&}h8hM3j-*DL1ZF#G+|7v$6Y zk?&o6fa4bHrr7(ikWSt0=Mc9o(JDkanOva0@?OSc=AUSX&vVxu=pA`!rw{n9H+uO) ze2SjC`45egN04~3TK{kx;mi~v;Wvo#SE#AjLXjnl-24_y|I9Ef52`AcXQe#bha>AbwU_UI2nnzj3M*Z?I@Ki(K)p;`08$hOK}rQm@y>K}}zQ}R2M zI&s^!#B@+1XLrYo|3^Cc|GSf#2bRX2pxJEzwZ+ueSFzJcsw+?Q zY-7uSz^}>YPu->emhY4rAQ7lKs5J%e&)HdIk5-8;Zj+smAA$aC#$G_LRNB>%lQ$BZ(x@ zNzocn#U#b#d`1LUaNz70!qSl6QreB+He>F``)nCD^F?wIJCL!Zx~&SIx(-IbB!M+AdX){g(MQ^jWPB_ovJapcl@g%j>RuKQ60e;nnls zhUxnMHe&u-PPQbCS7+xzS(O~hfPQgHd54mYQ$>VTrepmW&a^>Ankrz?@WSW_WB5|R z{y1Y!%E@{8rduP+YmH~_o)mucs)rz^C7hRt7aa>*mvEGj`7sWa8ZAT(l0S*GLS(9m z|HsyQhBdKvVWYTJP!ZXpf^-!Dk)~AXDhkr2MoIvsNeLzN5=KQqL_lijh&1Wa2^~>d z=%EJ)2%#o)LJ8#z!hX+nzVpow5uN0jd1lpn-D^!LKw4;qS!^q=j=YZxz&#di*Qnq9 zla46Ux-lW|u2@bxmiy3qE7j$@`b7T~g76ErG}m|gu_YaGy_W0xJ!yH9ZSt&f?^PC! zX)a*K%0BUKEd@tc2>9*!UKGqKn7K2;HS{(bn~Rh8;Je&!`Rfn~(yV(U6u*cD-7P1Zyyu-aCd)FI((vFveq6Bb(=&tS-QV9c{D zoErF1;pXMvOUk0Y?|3;TuEW0kIJgIN0r34k0Aw*A;-jb+kWxHix+DE~Win3jI+PdZ?DdB4$M z?j>Bu@G!HoB>=C?u3kmeq3)7wKTNdPQ>_&KaX(Te(!VW zwS~sTbo`bE+3`Hbw>--|(q*YgDTl$K<)6$+wsYmHWbpC+`Hm2C=#2wtmfb&uu(e4+ zAT!Ioev}$Nt;j3eRq~naoPAN=<(}(w`ZBKyJo~E;Q6HNLuE|b^#q(5kZriT>khFi4cy;)n%XvWe7U`uegT(Id(k9iFt+e@B zU#sN;4t%e9<{QvI$e05BYsBt1nQzZdCi{KTwM4;_lS}(IIBn{HgbCO4wTcHQbCV7> znXQ%D2`dyQWNyo$NXDBK?vUV}Z{*g>38n%ZeiO`pm7tsMr2ROJYkevr@%-!n)?8gP z?BEGrX0o*Fbxi=O_26SV?YsR-AdL32VRY7ueM)w&91jE~$c%Pj_ci$42F5ADojETo zU_Az8bFzECs!RkasmNBKx>3koB%8VJ@Ls{=AI3k_bDc`?EU)@O{^LC?m!oW9$iH<6 z7owxg;r411y=_99oQ_W6HMW4I4NTnnT1pKUbGFS+qUVQ(De|kR-*hZM0YqlB3CDo2 z58Mr|_`@}9fSp)HOiE66nf!p}iruY*t_&6S-j&2L9S-%t-kB*|;_@SZ(;@gwgr<~S zK6lHK@Ae93A`_gKcHpg?46W~1r_R?N%be4R%)!3OJFFWxfIcTr(0I($vzpWc)2%MNZOFzy>{UouxNm?4@tW5Lf@lR(*B=Z+h2p6^s|d+Lm3;E6}RHeA5?Q{ZEWjQ%gQ&G6qFg}^zYsenOtq#pBZ0r zjE~-wDI^V>y>Dwj(CdW!UXZIW`OWOtC6%A7ROAbMgbX^+AqY?CSh;&7=4#DHc3s~g ze&5yZ*)Pukn+MJ=-qtqZWHM|&XpbHfR_v5I{0Frm#n9?ud2*L|CqraLT1-L~20&X^ zwOk9rU$(c{Mk-(YqdikYzQwi^ry7*pWMoFe`267D1!5ObI`wM3N)-)gTO7vP7zixm3m z&MB4#$-DN4<8SPGr$(xZUNm1^+oeHL;iwErhV&30lZ{Zm;$AbPaA%-vKf~zp%HNV1 z#j_K&`9Upm&I+uFyGdkYgJxpb^O?qy?(JLiZYK=Rh)%YBOWIMmaF9lC2K<2iu;FW% zNlB(i-L-T2_msfiHr#SwNzSO9qx3z(<|0reLb(nN-9mBVvN_L zgMV%|ivHXT228o_Gfl1{aY`R~&XLS;BF}FZ4JE5(>HFzan^!PHzR)GWTQfE97INr5 z-XB^s&77h1(Cx5&ZSv%-;JgiwRQ7k~mtD6!gvXXF#gm>By90E|=LTsHOWzM{lzr?f ztut}|5dX9%QJJ^G<@=rPmd%&$D3=%Jk1DvAMelrzC3XXSJyS#3;|N$!HmcP-bo{at zZZC1^Tw$k7Wlh)8V4@}Uz}A)g#I2cN&1Q3lOv_PUHSEp#AQQ`2)fEE;>b}yB{p^&} z?{T>go#H=);OXu!IXyY_Mbt@G2)`JtUQ`sWQq+)Gj%R4GKpOE)HHSuh{(Ld-nD6rC zU(iS$(bRqff!p2aAH3Gh5!yn6VbyB&wY0|6$q{UC9WN;=O`;mDs_)KF5g< zGtiL>vfKmNBe6R$AhLLD`=QuRJNKe3%|#yvy!$G|0*WT3p!yvD0zBxSP33s&7RGg>9oY;UvCWX2oM z08zw@q~Zpm-3$;D&*lN#l0l4#myzMOenJpiYqc$uHJP3f$THAC zUnI}8?XPd4UMXVZS1YtwA=xO0IEwu|v&l)(*RoSgOhS zTJ5qHi>UQd?-D`n!771qUt;5cIDVvVV6dwsgyRLyQf}^WH zh{6^7tE8AL>q%R?E#~nZYZPE?NY?DHnhpMa59%%RnmNyOoSB)KxQUsvA&X!Nk`jq% zSAvQ5ve*2MO+f}NvAw^imJeCpEM!5dn$8bnli$KR_jT;`F2@hXD>kQUVK!tvPsthx zwuCg4T-dv5HsYCldb!f0#36l4o~$O05L3ce$p+fW5AQ{bD6;`(#%C zWU)Q(*K(mFok^+2a@sb&i}y>67Kc)Yt6`=pgxQwJd62-8B59xOS!j*eqIE#4#n!ly zj6DW>qNPZ2@zn!^>vLfd9GOY*qR*_taVM_ui^wq$_my>{!Tagc4ovq{(p; zR*2L69-=ff6`O{$zL)oHmXTIrFb1)ZPqfR)5uI{~%&-h=@6!=J;G0j3%Z9^<%B|*C(E9`%`Jl=4%Yxo zaq;G@A$djSvwAzZ@Bpwyh7;@-^WP#^G~otA{*~qa>xyZ& zh=;e1ul5GhiK(P;F|*BfYjd`ZZXKv(f)v^IYH3ZcyluokD|W@N>7c=)Aj1GZ^3!hF z*-KB+s%jDM8aVJ@59E!GO)f<@;v}_wD4t&26lwRu0-3aMhr^2$j#0#`gsK}4C@C5h z`9@V2d*(s9A2n?)aGNmQZxGN1AK;Oxrf^|6K|Q-^YAV6=uni5owZ5^#@PQZvr+BJ! zw2O^cU6Ou{j_h#laFk1KiVS@Ea}QZr&mfNXWOLjE4^Y?t-q%>WA@iV%!Afv1K9|jK zC#z3PtRg&Q^Uuh&M0%gp0bNMjl^l8%Gv|oEA3a*%P4K^sRfvYzAqT~MXW)re&ahJH z8m}z0Yr34= zz2)ia?wge5VQCI&I#5ij1C)2#Khbr>u$#OqB3qXH3L4NNmR8z4-~|QbZ%y&LSrc z>55l@D%r7@3EBR8{Qcd-CpEaQ%-b$xOXMeFAoIb9%?&j^rV8g}jr_7x_f`qH1repX zQqX*2Tt~t0yw8Vk5BKGB-ij3V>FEvY11|G<9s_!imXKWoF(p*)FU;+*k)sT8!q4 z7-aVy#lJGtFI=4Zi&RojjGXiVQMeUv_FogYhBXY`hcGQJLhT2u54z2I`>q3lIj(u1 zZ-%+{uL4$sn(4IrhH>%O@|LI&xiHda_T#&L{hwA0b(9VCSLoPLoA5YgK_P_}IX-2M zVd&D5QnA(Rbk=#qZxCgu&0yXE*g0xa*MkSEdQATue@9~AiCnrBFZgex#j}EW<(#uf zN_`sNIMWQYG1mdWEomg%rs|BI_xwf4cs))gfNXj09s(l zhq4~Nj405rC9j>TQVNxShfmKgYnHP#>_re(?cD-+Ea%fNg&%)#%l}I zwpQX`SGqylGd1U|G8GL#$tf!uzPss~MM4vC691PyWV2=j_weieRHJMJWhg6Ai+}T( zhI>}oVl22^?C@}}Rm%+|)|H2cN62yG8PYaOaU?(V|G$U378X@Hc4T(ovkFm?<{e`p z?g@CV31CT!w5jrq4Q!U%d2a@8W3a4g_y*g9dc45`vh@Gub+`U*y%G8Z=Zv)5FD!W(wL4|d>93dvIGWRscjZmK;xVy>qDtS* zpz>l{2*CcZ*S*D5V*U@cQ9f~(mi;cbkxMQ5x0qykIVg4YgrxJx6sE%EClYJ681M`Q z^%2F8ZJR%&RQPVi)#GpN-u$0_3}tEnpne45s#LjHArtUcOsum&?P_TFFvkI%8bYYp zAn|vGD0w5WPC9b8sb4M%=!xJ)8Lh#0Nnt?_+wwmdT@*G5oS@r<{;i5oP|SJ#&o`(p zNIetM2CpK$uSAFWBYc8~yE1$Lzp=>sp}fmRbmgy4vKeIUbNHCX_2Q56>9-exER_y4 z1FFIYXjnwG@)NwP5E^M5O~;iNiV{WTVqmiO?@gGB-yQy;JU(7BfPaNypTc<&lz3`U z&&u*}6UrRcKRPw7e04L7C7@oks?x%0>RuT}3GQFhxMN;&>1z}i-%Yl|O~VU8K2wYB zq1TI~Sm$yb`>`2i4hwUOwnCh=p*sIw$i`ehI;trHZGv##GY@3n{c8t6{dbZ5&;4*M z#53WSRb;~xH(m2@*Jd;+@FXAR^ZA<9+8LHVvdPI#TmI4@^a>X!wDZf1vmB5E{YVxE zcgwHwKtGpo-QnkgThYKB*BNO8Z4*Oo3rhli9Tx^$6jwGw)NI_JVt1Z6D8dz|2WlXl)wJDgUF#s z%QO!^mYn(};AD~l#aMg8en3l)pOj#Qxv87R&cgRVFaVoTmK?Y*uh9B-pR&rRnK>3? zm=WBL?2Eh#Ik{|tG2f%Vao|Jo&DFBtHPFrX4vkJLk2o0Fo9z5)IUnAy)FA$7T|6&r zP&{|38(%_NlzOhtCZ^td?g;F73|`1X@y91xF*cMDch}RcLumN9_Pny2nx##g&&!o_ z5^0CeA-$qU`!d_HT@G5qa43d@e@vjG)FJsT^3h}3D*%RlRBpJewet>U;9>Meq|R_1 z?uNvxiF>U|T`uX+oI;d7z1`T2WjkYDsl`PjYq(2B(rGenm^{_RC_;$~P zY5zgh!)Vb4l6`ffq|9w$uI;}QUCLr6WxQL5j1io55TI3gaSxvno}!|e_kHN53edhS zCp=rouYONc-OK;;+^}I&{Hn%WzecaN_88moZh!SYX+eJ@6WPg^`iRdpIGAhfcC58^ zFE0n0a)NMvAwJH$Dx@x}hmvkyNFUU~*m=t1&w8_*2!V3cio$?D|qM?a9>fwZ^( z-vArXilagP{itauNaN=1k~^%k>2g@xS=VE3(HfzPGnpE+LSzsTZ^OdO@t-k(`Hqy{}doO9?}R#w*9VScSa z$b&!UAiX=5V~&2++kb!{fdHuMyaloqQb!U!ak=$N^>jK%U-w4Fpw+hEvJd8z$d~!I zc!Wwc!t=9!$$-h!()|(V-Wpsh4tFO-k zb|MKJyWKZqZ;yRlJ)13Y1SnnWQDjH4j4Zx6eaSJaQ&(G?L$GeI2%SGMot=xpQ`99kb&v~2m3A+5Ez-f?D;G|1xf}nP3h&!c`0Q^6V@HXS z!Im%%i)6%>E2?wzB3i>WhCr~31>o)X|94>@{<|>i14D<_XnsRb5jPfbCTnYJ)8OpQ z$n#gYo^>U#lv^#sM;PkvfSycX&{LL75Z>8{&^S7GY0R)Gm|c)+0U^9qpph(V-!+ck zzM}r)5g5Q69YZx*aj`jnQQ{v|yF>?H4q&-@Jp}EVySL{fv9-5uQHR)y8a1vl%2EVA z8`s*!O0REV)=Gw5xRT0x>%S~IR6OeK?KKK)!DBMfBc-;`eB1QQOf+W3V817 z_jQ>=$U!?S^RvfsIz<)3NzIb0GT&%tHw?r z_DJq^5nz?RoLhp)#Tg$3Q82jTVrX<P6Nx&w6|# z*;2oK`L%RafiKnbKV(yEzG>?lHcX+QURT&Kr#N+eq~2HZc(t$N3bCxcUKCoENe( z-IP{3DqR<+Q$uCps4=to-gGx@FFBBeW`U{t1{@w7X~t^|cr_8_vt8x$`C8APKRf|= z|K~nTL)QqxT@`&xr7wYfFC<-7L5_3Qwz>>aL}H@;G;H@Rc^TQImsd1DrsVfrT^4^8 zxoFfSy*8vLO7 z>vL;Hf8~Q{TzN63_dbF&Y$Z0P=OtISoh~@M5hrS!R+9EBqpI!S^!IAW#&@0M(xnJgdyQquR6o7u~k1FzE4kL*g4;w`(%8ra9)0s?aV*Jiqs1r5vW zoKR!4KN@L~pqUxkpcbsYA?3bQGG8XSm|Og~7$?2E(%9SAXO4kBwbJe#4thiC?)n!* z3;!P2r7;Q$Z-x`s<9!DDXBK6Z?25`qCM5}^Dg=iwBM!;%)^y}ZQE#u7XLS@s!n=3> zNQ~G43!wRpvQR;eY%C4rKm;ZJv~WQ4o#)rIt5j@kvM;hq>IhVJHyxYYdm?>Td>6{^xcQJbIM`s7gW)P;E^oN13-6Mg90mXJtLxn)W9k7ILoT+MRCm>s&29l-AO%-40ZUrSei z-ln`G)+&)xUteEre;K?}e}Sa1`5%p!BHo^+I>INAj5@TJfcKg1jeK{RzJ7ZoQaRtw zQ44y8onB<^ZS71ol?Slx-$_xJ%j$1D%h=s5|oG{@=hI8_8)tNw20el>U{l8AXyeVkPo%RB*Jj}qzE|^?>w|C z+dgl=JQB*qEN17(2~7okl+ex_;Iv((RVW+SO!kmb0-na=wmsQfY^7mX`)UWigEKia zCZQtGPIk9~C}mT#VKJ{d=tdIMDV5Iz-`5U#0+&{Kj^REbx|_@Sfic z*b)uoo!tXkU(>_Ku16e#E?}>bIM3!{otOVrMZ?tRtJbf&$y^THUC`;cq`PKYa-&v)r< z<*qtO1}m9Qv~_F*$V~RV3z|%4)RGza18h1?f6I89^5PF`*Oi+A6_G7nzN^$n8uNSf zlH|52L}l7vzxXj;P8=qQc4}r9l=0edM0FO!uwtHzdF4j=K*plIc{G;E>y~m@MAu|Pj~CMd`D5m^*@BT@>(Kn8Wd#1?3^5^ z($@Xg-8W*Ln^{37^YAnC>M56rPs=(mP?99j;3Rl3s%(ocK(@% zEu{_&Qm{bbxhqw;sE&B?sv2mjm3qjiuzNnMRJSIG>=E3Lf}ARVK?$jr#Xs@G`>wRyEesI`CHcY>_S<6QbXhpJl;8+?6$;zn?0~( z;A=BdVhsnUr75<&ua*Xy3{#C0X&u;~*x$mp9v%#4R2745 zp{X`rFuIi4T?SMP zyeiSZGvw6kwtrH?$*}U_^v`a;!S@(2OAvlE+U>5*V=RaxrD9`@Au>x3c3O2ID5Ke| z+}skhKN!lO!t+znwmT|boNMFW%dG@vhe*%~g9zi1Uy&duINKQjR%VrxyNj?&-e6WK zJxeg$K%Zg_;5`f2YrM-Rw?0yRaBh0G#b^*{&haE+72HqhJepKiLsihx> zKf!6Ndy}*l!$lSXgQZ?10?%oxOOfLz>Ta;(#WSe72#3HwjIGH6Aq@|^0+nDpL zvb}vi?sRdK6AQs(9Liqcm(B~nfs#FNOpVTbd^z$ z)N(aPvd>y88>3GunEmt#oUh&4z-YLGXZGsb>*X8qP|NN7io6O=haAFQjTK6NZpnZI;^P9Zs-)m7+XxR_Q$y1Cxt990 z+2*Q#3|(`hz$_DfK6dtfdw;k?YWC;w@4N(IaMQYFPD&YbZb_aqjL65{^QUto)Mbb9 zl7q!ZIpEwmXsO+Gimy_4B0i)GFluK-Mt6qAV%9k2ER^A=gq@zUs*r2$fE1SQSNgz& z7VG2FULtc`KwNu*aC1U3FYRilXJ@+79MNJ*8%-1hd8? zQ~St|5)`-|i$-I_rY=(68+<&fq-5z~5cE&xJ&UmzsP+^REa?c>$55x$69?)eV|R!& zKLfQSweuJ2m0$+CfYBZ8wanIpk6)RcL%_t!rTp4^jiI}V!fI<%oeP-4Pt^PR9v9L* zXg}``W12y+{E>MA5OnA9=@-2RCoDdPbbKq?E$#w4*P8I%#wYh4cRN!f@vgQ!_F}B2 z&MnRk3nAXCky>%nxuSV@&QX!tWA*Mp>HM@MWDPS^2yy+au-$xYKFdB8b8Du|B0ntP74IMwk@L!Y?g>V!=4ZbG5OY7MxFoM7!{Y zEfHByIko6Rq=g!*Gt8_Gj{;iBb0=B7{nOKqwN9krGm|9|l#NC^jqJ*xMc|z`0trx& z^B+C{P`BzDT?2zSBhuKia^1oH(MXL)+W60oXF{Zhmd>$YrgXswb|SK~`n$8A;irO# z*p#{Wd7%Px|6jp1=Ud|Mi^ECD0#HF}aMfq(%EIejf78Lr6fg-0zs9Rq!7_3S?6)V4 zxtq*mGDCUiCBg9J%i0>;+TI4v`3%qlBURNFbOfl7Rdiq1Uw`2M_|Lg;|JI5TQk!|* z+j-%N+`V)k($!XXO}?|mZE5BTKP-jz!GtQAyW^>Ldd0n`8N=@!^{FdebZX;kxQr9^ z&V*v%guFWfk&!DmER3DQ&M5v{Er6L7RoR>TjZ(P0-#qwgG{x<#P)_a>LO!teDi$#& zx;Bx}+ifRz_ACaUkW&!O=#)VohD}lZz^)vcQT*6CdCL#@!k>i6x3t}3x7puBJosoa z_>beQws&uDKO$bLSNe1PJf}TQ_Y@z0r_5c7*$wW-sgLRPC4zzXE5^ipDXM6Webz|^ z2kw?>=yQP}fT1GozUQm>TQBHh?m|8cc-)POW#|x7TrkB4aY}Er_L5R&(P{NUI@D;R zqEuD>@S-B2st#)Yb=@1qGoBU)(RV!X4MAFuABlkThI2jF&Bv?tg=%hyIP!oRkm1rK zX~KHX7hJ4__E;dmzfus+wEd@Qln@$>^Q+?0@I^)~I8R}74+E&jrl>#F_{FAV; zX3U-F@oA})^7y3H#pszymG_go=ZYGhig`tc1VK2Hi4ai{2O7w(F?uI+Qie2!5$&)K8# zLwyt<`FV~+guc70iBnQ8+0&~+I$k)(o{86j@IT?(7lF=1U2E-&*+he8(`OZu`H5}H zo>}hAnExUB={Ge;TXGaWfJm9PwqLc#GGNhM)@5|wt$(uFNPwf+=APo9$5gt0(Ngi2 z(WNRI-099Q2wF)D{>}7CJ=L83yGPeR1J!TU^29Ko9&HvXbH{n6qJ<_()lp5z)!b|AQub;r~+*0185ntRYFVL7X*>Fy$%Gzf)$%$FZH^7b)na z92d_FRtSDH^Cof#XR1Y5r@$-*sv^tA> zpdDmxe23C1#7MYmG#$$WgkP;lixh|~3rLPc|2Zpw%DiCgcQ&Yl5i~HS4ku``X=tf4 z)YDua-&N`QO6cpFl=0cgFBogz}q)!=f^8=s1!(39Xs+g zqE@xWM(+;rJk4e1Y46SZ4?M4M?g32H=1%cszK9Pgfp0RG5GB#+~C z12^{iTkXA=b|)pC7;`V|=_q~?t4rYXe^Ybq#8%2^fntzrK&k}MNUtqsPQ-2~m?V_G z!)HpWT3Uu&WOj`~pQ7k?%AoIvSW(s)Y$3R5NXBqyCSUnfAJ$8iY}ZJqiWefsJ>L$# zn&9m9bJ&c&1mTq^pvm?^KF3sR@854rl1Hj>`*^n4ibMux7$`8Q8^^zqLB~Zos6dJ8 zpbHE}%k`v74wCYCEwIse&^a)P`hH4Fx2OP9URLXDBT?Rxf1}!~XC5KPT|I^KFHvnq zc18w;8)366?wMFpMkiN#DWF&4s{<#`<|{Kah0@F-Yo5$-)g zV(Z_WS{tz~K+$z&sKrkorQ|)SifD$q?WbU~WjYoUzBK3shH`-RT9sUk6Q1P z>WcaYYUMdRYrd0Z8TKh#VV%|COZI|-wb)Kb^pP=X_H6(om$f1W=mpl78(@L)0>zsU zq_|oBdoxF6Dbt-a)90a-xzp&#pTk-#f|oL@Us!4=g;~G-7%{&Nd{Py>Kdlk|yi3wd zBS;pVUg7v@I)KA7{Q2GUuU@{2;lOBJFiX;Knk=cOGnjp*v!^D`CDVWfQg6n|( zS_?;Lg;5#@5Gt*81R;r!I{NL+DaygqZ(++FkRb9fveC>A@I`Q`70rJI_7_dWwlhE= zH0mSGh<=q@9y(Ap=H8=EpFT}bM`*Zl^6%pXfw1I#g4Gesv~HD*D3jhcB_BTJ`;y!C zDR_-w28q?#W4B)3o@KHo$$q=Z$Ox7oV(;z)WQ&%$F#T}3{LHjWZyfr`fJ1h~;Z+B? zM3_7+fir-$4~;i~KrwgLaX21odOc+`?P3;$2fM`H#4n-&yqj-QAi?%qT2WPx3PN?;F%bg-5gbzVfphqi6gTlN5c6F_s7D zt#k1I%#_4`rFrX1E@9wMO;ZgPu{V|Cn({S$)vOplZASKvz1=q`j;5l%J3SWarVN8d z5Tpt-6TFPphzQ%k!B!yoJm7mNA(B^-bpVTZgVvpz!f$6CF2WyT=ME!Q2H!n&*W&xY zBk(ZQG&(Y>{aM8?EpV{VmG8ocBoTn&_eHDoykM|kdgilo2J|1MXF@P_of}Gz-l`_E zB%QTvcqhTMekH|JFE;X5%zhKZ==#M0o-gm_XIuKMRKd{}>=9H}aR;MGUpxly{7LAj zu!QnksT%PGv3oyfOArx5 zx0_v9*i(BNYViR`+~-;~(HR&J!%}>nC@cP^DF(|z{#MDJMj^}FX26ruBL=X7l+^Opp;-GcJ}{ ztwh_+HF1!t^1ZS$dP~iUqW5b8Cprh8-kT>hI9k4D(GTQ5^-)0%K66#8V24Gt%e)o> z(hw`F>Zq-T(zRVFEKwAv8ywuRwwGhb(V3Z&Vs;RYP#s?tI7{)6JI+hjgFfMsQ0ez4 zZI)`ZUEAN3RV+FaBvSZqZD*KPw#OkKY%8eo$8lri6Qh;q6Jmv6BO>vbr8^Mi z{}xfZFIih#yX|BoB(PLPMhHym7!mSz>r5N|@!VT&hE?*rxUp_#%I&w-x}Sk2EyUU8 z7tZtMS3G9(n!8zL7wypU<)+x&%+72wZ3mD5PTCs8Zhh4+wj3Vz_FWA!d8Vry^_f*_ zAet;ZNdZkkp)~abg5^%@mh7*2x1p>qmSM$fg`TNPrPL832DNWLwR_lUwl3CIMl3`I zYwyz1p^=`CI8YMSB&eT98TaedQ}oNe6&T9#>do;>QW44ubi%|l!R#1$b&1+!Bfx|7 z9QEhVsR>3UgtIWB2;BU4x6bM2w z`($sGNU%UVR9pU`QzzBfWAZ}<`gv&-C2o#R7llFzd6VoQBU-+`wKTW1oM$^>_o+j` zm*=%|C%3R4tWbf&1Oj+DDX5^fV^+&5YMWw6Tc~=M3#0TsjD4fO`S1iY&Cgh`UW%%^ z+7x|bz`IJVx#*=ckVqJs?^tv3d1T_m+p09Ywk?dBQ|0G$fRz^~&V_591!vG%XL>ZN zL<=~Vn)rrn5F_kQ+iz5$P}XI8AN{KFK_!Qxi*!^eC6;#M=VwY0kGNWgP-b~{!!MTL zd6>l+TzQJ0FemVs)_cEex9x_KitrSS-jf)-oqU?6SHBb(s1j3TA800J(v6kVFfSgd z{ZKt0&4$GG8zYIW&o}KIu-0D(s@OeL4p_ZiOqAB;q*+aW#c+V{>)e~YM`5ZVuKOu2 zo_H~;qpEr@QaK~}VPYCGthfH(!6rM_^7ooa(`tz?cLl=e0M&yGi>Jcj7pu>=MP!Lp za2E;E_^bk6y%SgKq~2vFj3lxSo7yhx2m@UMbrp;|}d{f>i_|5Y+oI?;%jL(fi!70|Z{o za0uM~k~>&K{wZv+Z3ZTE&@BGq@3(<)@%(^9i>Lf1x*Q!&T;Z!$n)6ZdTvG~LUm8ve z!F*ebw$XC<;N_Qo7MEg2RcaAS&m{<7jl+}1o#fupvi=EvWc_bvzOs^1gyvLch0&}* z?e^34k=kLezV1h{Zh9Q0)+#kL(Sa7NpKPR5zJRZu^tCJd%$Nv6BMZJ4;tMYVjJXZ6 z#$N_L%wCK#3tiyV2c0`^V}0W%uOYFpDWokL;X06h>DQVz=o`Re?3jD_kSZrHFY2hW zo8gC+F8vKQsydTpfde1ZY?8N~7X*avTERk}-EPHHNbzzY*zpa%$#H@r-niBWg$U&q z?I(wQE4)uS?f4Z))rG*qXl!p;S=xj)oUVBz0&U7F6L7nsvI7_Fw%i+HbE9WMK$yio zSTzM^6lWT32dBW>8Fq)#10)UZ&1JY3xPa8I6b{;G0viG>zKMv6wpgK6p!xg$7uWvD z)UnVdq}R7ad!G8j5n!QWX_>8heevwXTq&8ap;y;Rof&v-^{n?z4$0#%^@6^GEC*Od zh5w24%`Y*VCb4myrd;hBJkn4Kipnd0vDY`3NJoZMeL1hVk;P}FA-@FH6wJ&mx6`U& zXF#U5S-kjwS1;F*Cv37Ypi1YJZ;dJT#U2HVW&IpwM%Uga0 zUV(W*_6SyT#VU^wyYrcFjG8#Aw~U&y=QeZo6xBp7m_5`sW0ELXSgDx}4a@g0Nosdi zuNYUAA_Xp&jGVQ;NJxHZl@~ZeWwX(u9yKXnqYv5LR73hAs`ag+`CwQ;$eE~Vg5z5h z8)%K_vM+ioCs`cQ+4o8SEzr8uqv(He%d%?0j#m_Qt|X{cSr7R#tX0`zhbLH* zarvK2k$RhrbAs2cvY<(ATv7>8uZ2>Wn_l|m#v=1W1bj3pBrGmYAhpT0qv+-F%|H9g z38knP=w`I<1HdZS4ebooFtlKukpQT;o*)2jG1r{}ClkxjTeVv=V?vJl&%L0sdp|8Gw`*ua{a3(Y^etEmyzPt;7^3%%HK8nu&9`@+85WZSCU}y^} zYWZ_@CPC88GWx|`Ua_`}%^;)veUUraJ|D!_yVDR}adH8FsMKkg6F6nO-*-8UUKgau ztjti-D_D=FUwj=z4{6I56?NlEj0gem;gr_uMOM#`;A9s!(7kmhs*Z00M_%Vm&C#1q z0WkTJ0t*F7psCVAEoA3Rmw}yVnMq#C(SjxdA3l7@S0L|gWXeSy0oGvc+77ff*M%)V zs|4C%%R18O3~Rhf5f1zm-25HhKRW1i<~qxkbCJ5XHpC2Ju-N$WgY@1n1y97mr7B>f z#cmi#Hj2MAQjs-YviT2gPhZCeIDqRg1wm@77cCoBVWURep`F+}ymHw78{tG7!!km8^QR?qjL26Le-_u*=!cPUBV5cBsZCY* zOdrsE{>vbKMNF%mHz6U0Ie;7D<(S{ir9OhP5*!1sxG~%N-`ukx( zx14D`MQg|AJ8Bn+oBUMLrh6 zG+w=Lz8BX@KNAu*I4Err(#~vEQx<9H(3!@h|MI6<1(xvP`2MnjkPY~}7&C=PpO5UN zxKW|+IW=Az1VO(5;_?ZLa8CUg{1{2$@Pqx?Sq%k_n!=F$hGj!H5;iuQtLYK zT*66NPDv%GMxmRo{BuuC*f9UX>-vzogq{%^S1tYF9rTZR&x>>MH>rp?w1AwbxoHN? z4bRC^82F~FvSrgF038I$(laDcvE|<^(lXyK8RBH;h3uYXun3`$K2yAY_zi8UXKs3g zy52h`3ukZB%q8DMc$Mw}>+pB+*A%UC^o#QcGNj%K&}68XfbSA-QEGPI>(#bV9e2tw zIk{6#{mY4#~Zg6kXx43iSK&1-Yj>ZX=5`|YxjwA_4`rjXsPbdH$LPkva1(g z5?OX$z~ovG`08^l)>2IB>X+y=+)?X-E)&2uNCe9~0PadM@SsNr1Mm z&ScNDEI5AA0(;3}Crgcs*!7EURIk9bfw{wY)u z82T;`R`vb{$Rp}V%JpUJ2P@jrx8lt{DWNpK0yE3l8OR_55gw#|u9ng?)QD38p_rV6al zjyJVg<34U|`w<^&dZkT}-HY`wv?~qG`!!^8uYTaGvGUFMYR1~gMErL@u9daWoKu>G zAvuP{QUjfzR))kJ)CD|jx_`9x3R`^z(X*rDYt=EHJ|w?g3``KRy_ahs8S05P7$np! z7F2I^no`7cT7-JI{3VGewd;w?EuXIO5)ME(#K`|5<15S~hzX*U#kEfpUVn8>RlvC~{B!Lde_|cV^i>YV)4-&)GTg zc9l6kGnNxT&#>d}ri!mve$SN<=d8}sZ+q9IyfqWS3fINt1|7+yG zi{}E^!+E*cFyfOLXzeUbj-tmFlJeR@O)fo%#@V3G++Y7U@{B3NT+stop4bDInYd-( zkSxG01ez?Qawq7sEP(N9&owOWK+m6+-5yQPZ*W_%cKciP;Q{%GG_o_kRm;r_$&a)K zIRN`TZiJzielU<7a6<(t5G86mFa%FjQzZ8y3TjAkiBGBK&TYEt7P<9H2@Hyg+2=

        gtY$D;Dv$l_b-;#XBta_4rH3^+=$&^ zkky|jO%#L;f{)F97BdW?Yht$T5)#h4`k9S;$5Sjbrgmp4h zV5MBbyb%9jLYzh8$_}0JLTGR>e^1lahhYAl;AJp6Sz`ukq!F(U-pp!vfKp(}@cN5V z7my?a6_5}W71aXCYBgS-v_!vw0uu+MuZ^v#+7|)M{=UAe#fPt%?rCdkzC?yGiP^=B zh4&224d^SqNzdxmjP_ak?6X0VgXY5yyasL75wD{gX&3kv*?X{2WlNjo2xnY^dp}{@?V@z{LEc|jj5p7rCbSY`Ef4n2 z0UB#fn?K&(tnDyd#5acWa*B)V771w+U)b2jrx#`Sbovx~29?|ObT{a)m1dp3EzE%e zOq^FV8PG#}SHNI6*JM4c`rxOD5qNQ%EneOSk}4e~+Tn-mj+*-E(pzhK@v;Ef*3V+@ z>o2t3{^CpL1lUa1)Tjt*ZuI4!!_$44#zTBq_xFbhn67Rv_nP8jt#mNnj@R>}vTO-# z-f%_@jQMuiWI4Q!mZzQL)DF2ob*hxhp-!-My0Oz;;;Y$QUFA%{*|*axh*ROsTW6oK z;TR}}$hWt|U5?by;I-`vIK|B(`On$rxo{2Q`C3ho>!x%T_kEv))i|OWOKfz@M_j7a zWHQ2xP`X6sCp~={CAe;>$tWwr`*I~1j9bI*+fzpLgR{jl#8{k)ot$gzhIAN4_9mFq zRoKsN>FOv@mg(w>x4qN2I~`o^-hxiYPX8V(Q<~o+t~E4Y18EunGO_nYh;Rmts^m5o zKfkuZXNfit%>A^MZz7iKV;zj>>QIWfdHM5okeB2I z_>teel}rr8XCB=Xm?y{`u|mMZMa58zKMazzn};qPt72cex*zC1_eGWQz6d&sE2B8V zXWQw6nk_)lc@I-2%Ji|&#x+lEHhB3aV)P=#5= zCKxdEMMTANNl0V~c|6bf%$x|bYO)RjO-Gb`Xl*-QQUliE=DFL$uB460Kby(7SE8J4 z%arbr>>@?2UNmm<{H4|Hg+Xy>Q>b;#SV&^9RvFM|=xfur!siX`|M@#g3(6W(dFNCj z4L5Fd-F#jKW@i(9bLIs{$Nh*N;CT|u)^8IOOSjWD!{EcU?OKY~De^zJLzk&32#Ejc z>nh7NPRQIlz%W?IZcZYpFy8a{hIUOV3Qdj-#d&vw{~F*kNyixBUVTKmT%o-y!QZym((uKeX;gQCAFp(Q(R>SR;&LW|J4@X*v}SQ zI6RX_1cL>Xrjh@LtoIIRG7Hv+K`g6?te_xBu~4K7L8^cigisWuR|P@`>75rrRC-V7 zpfr^xgx--FdXW;Ug7g4FAawlB>$-RE@4Nh=t80=s=ggUT=9y>aFg#VQR^15J8=EUN?(`rb04EKG%U%B!X)Lkqt zBJOPve?h4WYe7ifsoe?6ylI-?mU=LBp)I$FCjR_#&iS3A3!U82QE{=Kv#0lu0p-=7 zH6`=yVPM&T?XX`t`TU*7`PkP#d#S@$OQt%0cjl!?J=B|3fWzqaQ)R1z;FsXXz)*rE=XtEu{rmgRZR*A1db zCi8Z&8!6^(?KDKH%$~l7m^<*o^@y%{l@`jy{U5zXPQ7}hYP@@2%9cJ@Ile!-L9nh@;Z)+I^y(G$p0xJ+M0-4{(xNNBKyu=fvCDMK!tpn!#Pp!8 zP_nM2y-d%jON<1`DM$QgaUoIeLKCwYn|Ix#sD;7S{OOm6cTaP%{~B=)SKTXuL@5bG z^k$rt$hqs|>Hp$AsMRgU?aVmZb>Ff{cHY__9^LnSbgNFK;Yes!vEY(1U`yT#IL85afN9FVW#u$Z-1ir z)0_HP`>cK=MIt88a>A6 za|@*KVJV$=@5}tvITodJuCTm!kor_GdRgeT+BHnhKy4Hi?*Pf=_DhnBd&?L6@oaK3 zlI1_S8hC~~ZQ^<p4h_;BGB}F=q@g>*yYOO zh3IYVT4xlbIAqMSR*cX5Iy^>3$o%8-Ksun@w~h>k%gN?+N&WHk&V+sq@cB~LFN~;5 z5G&ct?r~!{S)IbaP}1{G33jDFvCHp{><=gmiEI%^@8TKJ)+=W*Q&xGV?`N zlWq2aspEU}x_tce(N2E!hE|u$)@?tR+45Ral7LIy24{14C}K)k-1rlcBk#_ctez-$ z(?5!hIeCMWGNt4vChf-%gF9D(A)#dMoMo>Z`&8no66qoxl)ub9v)N)FlEE4BBDiVkK40Y9Rn#~F0dZxCF&?EDG zeXU9)uRgvQdgQaC&Yv|2KCg?nmc>DhM zLErAmmse^Vy$)>4qH?XE`(xHz zPA@gz$wxc2#JPA4Nh&ntRtWmpCDm`ZGD3%R>#fQ!I8qliTh|)j{&j`z*eSBlnEw$R zkxAUI!q5c@0Ey1`Q|~en0kI#X?fkG$*bIVlcO;Q2P?98#{OGo{}=QkRWL&YP* z97iES-)EhIf}Bn>MW2&BbsWu3*evMSFh{3!m<9|}xdnlfsdI#ZGzpiVo z*mj(3B=|qK%A7}mrjxh+bRi&n?9p?EYXoQTpq=i#%0{w6yE$x0PRqU!Lzf+8l zy2iy-Ig9l1aicut;T+m8UTLlK7o9mz~aTwRbs5}NSMWK ziN*4~6ag3NL%TbUSm9G;Q8bs`Xa#<9Tg=YYiK_{JFbzv2x9It@VGhVVs((Zzz#D$f zsr0glO#5((h$ujQzD-4vRVzp^#dtp9GrJ2M(fubZ%vHxn4X%H-4pU5lM)tOaA=L$s z4!`Cn!&Ou+!}f(3E)1SN{?}YNb+l-@vbITDIR034rt@j4Is`S^E0r`Y)423LJTVCdvk zU(m$>FMC>0ES1yU!9(nr9Lj(`h2rCmAhiAwn4=Rae&NN5Xp=JD6l_&kux)nNOTA>S zOKc+Zf+%AOGB4Zz-q5oMs%D@u2;>&}i^8+6nn4rkM#HxKt;(xZZ>Duhu}(*8mc6t( z@Lj~qAE=cZhP>Y+-sqQs_pCt*rKWF8fBBhuBH0osVmhc#CS4ym6RgcmMfS7e!JkG~ z;I_U4tq$e!XL{GM+T=eRO+XASIjg-JO|4*Vnt&Ls+xZIlHG3|mZ`K!y&#~!JU%H`t zsWM;4eL7!2;P>Zrd_^3CR#l?80pgrBF1bw>-$y<=Hz$dHKkg7_QEdlVl^yf5f)HGCZrl5hyZ+hzY0k8Brd^Xs!Fob?E% zSqgpCi{ICdKtY>N#&E+qQABMnW+|28gpifNPS2a}SWbjO`3_bw2D;M(9w}2_WSPA3CF~L}ZP$KF8jwVx>5|nyK8$!&ae-br z(o1F}`+kgq5RZ^^(uewzgL_9kSmCH$;$ok2&L!@%-TrcA87!1d@=%Gmchl86Q@#nBFULsHW8yz zRZU;ty9-Hex^r)#%lp_(P?hW^XR2e6<1(Kv!e&$v>=P4qAiJqA&F`Cg z!udF2l0`RSS}#^=O6>00PfGKBFIzz)_?@ypS9idlb<1ftyzR~2iRjVKM}Jk8y;^Qm zj78iNt-XU{uhMwZz=nBi`sqS!46a&xK$qVRQJ~na5XAQV6~mKhYD1Ya!#Oe3LBq@i z^KbHgM01;pq#u}pKB6_c$Q|41%ISe;iWZ%TGwm*`7$n*(yE}cgms&BDhR08=ME2)8 z{^{5y+Zlf(FJFkfOJ>eIMSsQJ%h317Z*)(Mz<4N9-^2teg26=p&oAfiaCN;#QoySP zRJBat<@Rt_6@mYD)(PL5ekN2EOz=jCspNO8cP1Xr5buKPEV~s93{3q(7b5-67@U{?JCg3RpAJW! z(D*5~_xG+J+rE13#5-T52$^f#T!;@blp@c*zG=JB783DGyK0_|)8chB$D-2M)HV_7 z?!d(tIaY34m=;u_JzEf$Ko3$Gua;4sN(dn9Z;M(mgk-U+yU+-N0U+<3l;gj%k(qIH z&HDNkMK53c!MW*Ab2bbYx0s@S>`bm;-;=)|WaSbYSNd)1F0+=AR2G-i#zD;uKF;Xx#&G}vQz+5K1)ppxfNe(L0)YMrkpW7bHqa7E8gbu`Hzvs z$?f#`b;Wec`afSS9~dY?V5RP>fn@v zHy2?^w}iw#?EFO|wNszddWEZTspIZElYVZGO3Y!WlgRmVbK!&RdZhM;dNw&^?7)E<`w>Jv4es zhe4{%P~#qRt8?rtsa|_2Er|?6k3K?*4C+Quk;T=DEVBMJwrnhPJE3qmr=#iQO74}r zfh5=Xl6D~)-39JCV`@;9<-kHhgC5=VEw2bb*oYYjR=}%d#$;yk|{ONQgwAX#>mR zMn7M4aE5@WuHBYd_^jtaO)$HRnGA<_aCOON6klJhZ*fI_2^&Tsp87IWQ_&Ey$=R4_NZbJ{_obCG=|P^l&AFm5t?BD5{w$UQj4Q+r zKNru7d_n8)K}nVD>A!Pa$jF3)pqD@9PtNo+$hSLjo9x{8QK2oZciOG;V53*Pc`2t~ z1wnJ!iDRmh`RfjO-gZ3<7^sT4cR^o+R;bs3w%3 zr19x5B*hH-oAqO4ceMXYx%~scE-SxkzW6$tx@q0{(W^U5#m8K=<96OcG3U5m#Cm;X zpLyUB$o#7JJ*vpt*qi3(Zf@b4&N1@EkTJf$Ub81C%M0`!&kJ1_LV&gQ)eiYH#0c2J zG06OpD!!QQ{lk}HLLBzd=Q%lEeK%S>BkwBx{*J7|gA3)z+E=IA#QMw|%ZG^oN9iu_XzT87z9O>Sp8=|V6qMqq*Gxc?`m zGdj6*zeXsgKSV75MpB`)_S4F+(>D?D&OuH%uyxKoHk|bGscKv7qXM^@X^)R?#HY5P zAB`Gp@n5H%Az30i&G$z$crHXmXy?w?KUOGO^t#fjWq9Y>?Ng{zziq_#%zrk*kj`MQ z8r2pncs>yG$@p03r8=kC>t`~0E}lm-*#|8i&&YLx+y7P;MdluhQW^qp1FQWC!rb z|E|B00j0b&2QR;WVTg(Bn`U{f^C=nlJ6#iV^1Y843tM;ipmIL{6^wnPaw4zNol|W2@w~N@_o7{&3yk=?< zTqe0HbS>3Nc+TtO_R)2L}Kr*j~wSU4WVxV4MLg!L1C(>ke#OC z^N}W52f0QZLsye4b`sMzozDCC(|ucu(sKwbEYuST-#gZHuRk@1A>ENgzWBB&cm0{& z4Ya&MZsR;7>$UGq5zetFivUsu_M>8YF*W+!KWhNd{I_qf+uEASw}j|0-FNPINvAqF zIXz;dDa4$^@*jmw8%(r}cx}!sj-WPL)EY3p zmh-PtJkRW|=Nq!UhN}%PzAAn-Q@h`P`IC21ZHhgDc7>-$poU`iahTZo z6M6pYsx;uUefzz%gKPfG%`jr=6?$|)V|KUxatq}*=9v>e!+_Uvq-MbUjHMRG+&umF zDU1r`-_KQ;;khfpV4&9v|9z0n?qq> z%BC?Meofxfa3!iR%+G39;`!vhalFq8M)n8wRYr{lHyj^q`IgfiIt1rG&qnlBHo*|q zsV_nDfxLtmw~}c8XY#x(Q4v!<;aPE)XPTGPq;pj8YfS9>hPUG5oR05-`H_S4SPjGC zsn{PShGTx;U-6bQYL3_3N~>qo8K4hQkQkJltqip^G+6XB(0Tl&uUY7;ZWG??LR_ zoL?Gpk2m5URDP{k#2u2hoKJHS^v%!Iw8C&HN!oZT??rz2N$hN;xkdi+tMvR@+bzxg zw_N>w*1h6#^aEup-fD^~QxYAkp*c3OqiVSpD~?md56&nq52@i2OAFWF{x!jUL4)?^ z)xt48)MWMJMIl=+{tuV59^8Y0TAr*o>rt&BxIt-*|Jo**k;Xbw zGu-N)qu0GS{|8FkCHz^*S4a0(obW1 zwQ8;1u}8|R4j}J4#0mtv)^sw>!rMo@_%{6G?c*7bM#c#IkK3l$D-=)|zHsVG$6I#y zvM}=D)XdN~yy4LXy*QA5nK(Ip1@AUIFmRo9r~cFr=x81y@R_66*X^~7Oac#WNp3Tt zqCaLahNV-3b2ZzO(ewsx4L)x)wwH1WMy>Kf>+g~|zN`~v4}4*p^~8ji-#eLn{TBD% zoZ?ZbzMDz<m{w$lg5^Dkk;9uKs6LGS!*R6XAZeNjcsgsLn?mI;qyaF2xg zuaajgM>^Z32iL@Mf9bDx!@+RxG2L&@@56#--Cpe3bLSGaLPbW~s`Ed8IWxBv#FHNZ z7GXG7bfE5NO91b)zhVjoJfNw4e)^;EE@L*PK%EmK00jRIN4xVK;Id&;R;o^@dg|BF z_QpGE@3u`O)l(~H@Y;gedN9B0*07$MhK>chwsGh!lafJ=XerXjeV`XHVO5{h22)aW ztqTKqs|ZC!-4e@f+&Q_|PBFdk9S2K9I`0mYGt~@LtLyub;a(5mPF$d9tK))uLA-wu z{yr0s<&~=Mf^YWvl?omF;3Pd!(+Ar3IfKQ+{K1itIP3E7ujdX9x2L8im%8v~sWvIG zIR&+qxs^+wIIh?M>4{KJ*Yi~H!Y;FzWeP@LSh9!I)lIB1jXL5*PSD!qpp=OBTDvrB zH!c!A=e*ZE!CalAe7r?=@{bYY@K|dRE7thzLzOXNo*m@fF)1{-=CduS?K2F`vY z;mRwzThS|*m!o}q%tF0~Y5sa-Hg0+E?*h#Zimpr8Va%os zCjjjt#lOFzRs7Zn+H{_$l6UgDzPR)8&Pxr44IF33y!5s>0|P@O(Edzud^QGiw$Q&0 z=4Cd3bgl0=g2}1(t|=nIJffwn?hvwZpAO_y{5$Lj6MP{ zN-SJvsRJV6a9l^Tnl z3VPeF*6y!v%q7~5n!T+)+FPDOY?h4l_>d5^ip1$)frKeaTh}RXSDfd2o58f?mC~{N z>9x}}q%g_V8yEu*i`6O%vTm@3?9{h^`kuD#-~Tj)Q$l!JcnTZch*iMrQYPECFl+#| z8q&-xyMmSM=D@+btMZWPK-62h6Vq*RO-iy!abFot|+Z}QwUK#Ks7nKt;FUiJ+VR%?lrW8nh*c&UWS<$P2k zs`zc|495*KH@6X!x;QS0t2x2Sf6EX%5hy=RP7P-V%`x{K==+;7xqFKlk_jq^AoIWd zQ0u*57q=Ewpiz?tPZFACDa?-6ejW9Muu`RzFT4-#tOeu9hM05}{l#r7X6a}@6Mr2| z{fcg7@$5X_YS9}hO)CwCOJJz(fG!8K1Iuqc*TZjLE7a;FRIOGnD{90#+`W*u02&{A zyjg3gWq$2KJxUx`S11_Mw8GFUpVaNqX_ngl!dhl)HQOR9{qsb5&SaBgNh#hWZQ9T8 zx2tk;I>zm&BDk{-zpSW0d(p2NqY+e$y&C}nUJbeQ17wWzDYuVyz?XK&D;bJ9#p?B$ zAk}BYQd3Gw1UB2jfeg*JnnSE4GG=7rt%_4m_(KhT)@FNEk0@MYNL|nO5PhXQHlk#_ zQa-1*EUzeQ^ap+@=TVD?W)1KEtqf56?hnyt@)>dC4-fAh_UZX*d3`RIL76y>;5-YR zI+9BS%vUB23cV8wuSZ6_0%?}-^4*(5!(7aTi>RhAipJH#Cqaa|srhHaiZ=(EA$mhz zpaRs+cWM{v;Jprvv=aCHiIsSaM-8xW(GK8M&4t#@7iqgP-f4S$1@4nF8cz`|oO2rW z8a>{p$eO3%zi3;#i^Ar=Jk1#Mo&U{+zm6+Lyb8OT880W?7?XJN?u{;A(2BVq=iK^4 zj@h&*#auR7wOB6#;ZwpCg@XM02sgH;pt{rJeOJ;{!R{z@u!&E}A;>LuGeDQm8`PAY z5AiZlryX1tVpZUt-h-f$ebOyeKyQ=bupQ64#HRmA4&m1~C; z^p2;#nYS=?d1TaXW(wdwW~W#VA?>H4yF{n-eoL)@9fDUtXx^;5cV%`Os5?C%@D$(h z4jn+*o#`!)*fQ_M80cQaNI4y|vaLIG5eL%;J1hG`?t>1$Vr`j~;(?|$GY`f)RzKf( znBK@_u-AJcX6#+`!HGHg9`5b&y`;d2v9E=CzQ3N59KDf820j}7Xr z^7f*84uql72mPc^t_<;)$}|(7$&L+k=)a5LGGpxjFGWt>Dl5m#lcA;mcanVPVKBV_ z+NKoWV#4vFJ<4461XVrW$e&74K1$9WrZByqtro@Ar^sx$KRRsk;ze&vXkXx{ zs_^Bvo<*7+<>qPODE)G1F2TwndV1FU(4kNOway^V_> zyYQWdoCN1DQ^^;9tdvcOcz;ivI>=&j>=c|!F-M0zzkmNehgMz^aKdeyr})OQYzBNj zG@PGZ=$T-C{PT^>LBpoZ3UUvdA4|LN0(3PbrXs~*9lMeSmpT(6?NISnQ70O8vybMU zg8z-pqag)~;7!P2al7A_nu>IzdwROpc*}FbeLi`v<|Mr(>+t+*l-|cyWyuv214EC+ z%p&#@%P!xU<74KjeT8|&XVIupu7?PQL(oJlw4C7l2>B{D-Sqgdfv3&Be#-vjqN93i zEGo5c>QqVpH}1>^-)3W-)CL8A|8DVlCagiwq$cN2xjHCOlCm2>6*GlTT+Elxd9N;E z^(pK&-O0%E9wMeQ*dlq1uh9sow>I%HoHyj(3OzZMaii|#$ql3?poaGJ&OgINdetp2 zekvT;rGHda!!5*5dy6ygQAgBxYKKxAM^W+E{90@ba09mz&*;$31i+-$32l&VrTKwK z^u!Dr#kMlL>XDB2*F={a8yoR(?{scK-O(N%?sk%{{Ox9m+Ji@4HCscvj;#}3#4gfM z^~;wp$9=Z@hlbFHjjTsTtg&TXB4crf0@Xk7kto58r5K{f_=`pYK#5kY`U~wm1)cdt z?c8cWc=Cl(pg6pJd1d9+K0r=TE&;Rxip?_V=T|Oq?=RdN)^k*H3Am^c=TKeh4)CVP zaxiGN4bNW%C%D~bBRVz7K}ug_)I6QwJgjfV8t)2*$|W97?X-v%nI+k`#1NghwrY@g zkLA3sbA6i*bnJvx!{buC254UG=V4ENZ9~5>V@EBQ?M8Ho{FMvu{TwGcFm(sB1OUq{S>wxw zbgbeJ_ryI{E9PT}(xk$0(_gzi(5RfI3kZhu-BpWOiG;k_!@c3UZsuPg0*~op@i4rz z-fx5Cq@%#(QTmmtOY*+{1k3oDeB-Sp_hc>6s{`}T3c;Ty2?MF}w^jv3goK{kC2#(0q@E{vgHBrE!!PcJs}-k> zHr)L(dCvnk4M_g1l`b`{))UDyY;jbagq1i!N8@U?qVGY6T_uKJpdm@5M8cXUyQG1{ zWh%O4wfY*vq6TxkfkDEsV3gXlvT7<{MOauQjF4 zwS_D&n$Rr8y#+G4(5K3aMDs>coD;h<=|xlmHkfEr8jmv|hT3^GChgC#{u(if?cM+R zQN_Dmnp*`s;|0*6s5aZCg*#>kCK46zA1*fzh~IRBGIaA;hm|kuyFu{s@rXolYTDLX8t-3ZdpDjwfWew z1~h5i#4KjT`IMqP`}$21Rvu!52>>3V3=Iuav!k@6q@?E5>maUf7b#nSG=!F^Wez^? zGIk5cTG4>BmxiM=s!_gwvZ9^}r4z-s|yw&#Kk}UuDNCHzspEFtK(kejRd=A&^P}{~&jAYQR)KuTSTl zcYw`@1S(2Czx6L5wMh%XiNPA!Gzm`QHqcV2C-R;}UQ=O$3 zHT4Ad#~pj{x5JV!KXNPcE!rXm;NVK_cIHrD0Rbxl=qEqQg| zEW%d#B$GZIIy{%zTt(i%D0otWiz($m(*#aDYuML-fp;d)-=a_kI7ZwD0NCzYFv|n@ zYT%hW2?DltAXsCfl_hYK5{m%&s2H`+hUHj z_39g@=cOQjoWhp<5I=PBrxN)L9<_A22#iTEodSo&vnL}kFfeL9R+XP3j8qn@X@IvD zh-H3&xFtS+@t1Y7B9B#Wp)3guGbt`pc39p1l#_31_mKco3!Uo;xTYM)6s_Hoq&6OY zix_0H_@UJ`7?#Q z#e4D!yrC5<65U$TS+Q=!6O8I%Xg{gvYf-s?EAygj3t$#h>OeNI_2#WAp6kZyd_5#^v2Ae3a7%_&E0+JY2P) zN}Hk}yIB_T`?BB^FeKVA0t6hLF!8xdp2%gq(|}S}4vNR#oQ{4AZbur@He<%FW{t(7 zwr)Jcj+mp*mf4g|h+wq8zrJjHvp@mi7ZM)cf!4L7DRS+I0=^3U$}? z@m|j~pUVpO*-QtI+ufs!IAg&PXPM-auKl3eA?$Ft?#R@D894SVT*!NT##b1n`mByl z-MZiFByOy^*i#&(Y2e;$@?LdR6B+p6+8m_b`XgAN)_iC}IK88{H{vkgCESg32+sru&^N>V}_oGKNl zXX7)HJl`LJ!P`e=_eI`&i-mcf{h#$v}xpcW>t8TBz z;#G#slHS)!Yr{Jd*95J+MlJ`LM$s()tY~>d`gL`gyQ}}qildntL-hA2Ywiy}U-(lA z`$x)h+Y_8ByLO1#rm&d~908~IV7g>?e33csy{rR=^RTX+6!8;_Cqa<7*N+s4-w@V$ z-&7-(SrX*0TQtXdU7mj@GfquN4tYVG#e4G!@e?^~rZi8iLj0kQkOK1a1xL)0y(7nm z36PAPph|c$JE}!FFa2@a_xc+jGqZa~>#eM!1-7&8kx*Xk-qKvj4hu#t|7>j4K}@4X zSt-*0UC>$uKS)T5#Iv4~JqGCHrAl-0*};ZWtky%$&mkkDddGcc<+1idz1V^9@$IQR zFnA=dbkvfRQ0BQ5qv3GuT6J&z_1SYF_U3`b0I3OZ{5@~Xx*vznBBuu(eBNEAJxr@> zPx8j0NXG&Vt!F3HJn}ENvhojVI(I5&=SJP%Z-hB9wPQ#MTj5K#WfLxlyU+LVb$f#a zgzJ>xgm{v4OqE}RN_PZNWGjn(KTiCVx(>E{I9D<$)%oLXLsG3&hqB$kN#(+C-#y)>MYwuE<9i4i_7bJWc^Hfr)AIhp@~W4GGiu23(xSl zKIh8@fAklj$0K*G=GK(tuMrZ8!?(3(?o$ko8()7OdeKTZO--+{k&(5FTG}dr6aaw| zW3f@LUF2geGZCZe8*tU|AqVYuxE|BB)fevbRr$PLIg|HhAL;z;psJtc)}W?nYX!2j z94W7^<1%h9w;v)8&#>wuEf>^HPO2^dGFW7Pf;|XehH^hE4ILP6jF`bIFy*h_Mo z4n+OBdy3h_?xW&bC`&;Hd=<8*)e#n8RSi$%Gp>)89SaK|yfu!h!@|yac02{7Zk-Yr z^Y*P;uw|%Jk0q}CxAL$tz`p>=&RiT7Bs$(ZDTL#4b^`41i0;ND$i>Fz zV@C}MQAmElR!jLS0$^lk{PSB_V|Exfrg(#N3{5`+e*nW zAurQHn^(#|i@+E3P>W_CS6}ae zDwwiklF{*1Ghvcv(7-e&2m`aglYH)p`w_AW*gq^Bo@ky*7=ZC$6XRy)i`fd`kF)LS z;x=cFA0wfyMUs{0^9$Gyt9yxCJ75rc?_|{cW`mLlo~;VZ$HC@j&XUDs&m8ZHe5)+2 zk|WSyU2d`x@`Z*q1rx+B`52uacHG6jnd$$TpUeotYII}gv=!WpPmd(B*)`W*gY z3TEEm+bOhv?X=3+8pK8y&hE^Fi{crAFaSPunJ9qD@Ejyo01qN1E_MI-=7mPp-`LWI zsa2(Tx-OQYKH1Ch#<5#v74CePyIC=&==cLigO0z&=jn51J(O`=^PaIYF{6EF1;ZAL z>u733-}U~G2_5ixUu=y*N%uwRt>$ueOAYf%X0BGC*ZUj+f1?~7kWS~J#OI$WgDvoy zV{9$I^N!^GBLG#efpKFC#Ju zPj9n`#ygL9fNG5`>EpDbByzdb?-)a$3hm)sOJ!0TIAHgIfuzPelf}uun~X8ZGt;=nh<^PWQgrw6G%1IL+Kz)fBX=y@b)@_lGRdfco(8KYQ=fkuKv7(NAcMf zq&!@|ZEu4c#`wCePBL{VzHc=bIVsw8{M}fO#4@jEu;`%BH@Hx92wINIYS!?I1UrR1$yD>&u?Cb=#wT?a0_Y9e zn27-9j)43bP>N&LJQ(LjoUa;EBdmkJsxv8_fiEVSeE~qVQunoT0A)K#aI!i%9r_Qd zD=T}t4RY(anXTKdq$~%97hw|6(hcm2mEnFujp-*l?`7S&xM{-Oggn_Y%?@8j00d!V z3`z=)t*JhHi=?5ABp)nbc<{QPBo{NH9a7f;Y8lfdYWs4V*4uB_z=S3EN5VYejzEaW z-JJYTzOL?mU7f8YnEg!PE3p^)rsqBzOG4j+b{bh7QY8f;!Dn_|X7yY?(y`OGsW(S@ zyjLCBG5*xjV%y>>GKa<9DCx0Cet1}2&EREDiZE2M!-H#)<6HSPBppwyt2WuI0vPhv z~s$8{IE9RtMwkWm-Cf69-o%ohzeEfHr zANsG(FZ2!Uqmgp?ddp=c6wRzj+6$O)m@64ND;frmBqZrvHRzGdiTD#TE+R=ZDd9ki*KMOWlX!2RRye5Jsr6Dt84 zZ6DILvl*JOw193wAd}_r?*yUKH5w<2&=nh-Nb)=a{~u=u?dxIr)65S9A$xMt=yRC*!1U}=Z9JFZ_5?uM@s5tj}AC%(HY zYb1huN?JpjRXgA+Q`nPLUa`G{eZVwY52g2gs0P^;swM_57;XSmH@c=!1+3eF!Ih3* z?}m!>ZiaS201^9mHMJQqT;>K_yXvdrIl_|t@VzQSB`THs!vJqWxJwz`QrmjOPf0%S zv{RRGlc0tR|G52AoJQr%r$PpRSYm;P9-96-+!h@J9F~muJ^|ZRnO;|CI0-^s2kWmL zIdQ;fujB>5wJ3LxX%bumieKS|Ye~2EC)jGbfk~MUg-foA5kE;EE~<2Zn|O?eRHUI@ z6WR-^1VFAu!Thg}sD%VMcL!gY9{-5>ix-bspaXks{^q{<<3>1T^h7!{zTKEu^BK;C z&w~T8OEl5>4VrGR0bD>Zq$0KTl&F&%Y3f~E{1r|ehl~s3xb9-X*^Ik#sf^m|8%6)v znAOmhTef0oBHG=7<7Y4wYlS^2Ce|Qmt1N$+@4k9ysTGK&XmG~(=*wra?g}#Yrro`k zo#YTyQzD)OxM}lI;7X7uZ|i}IsRK;%I`ffd9pddl()f02P1L)ryv~v=iR79&JN&6n zNRjah3GkDTr2)Y|*U}FYW!eBTbb7Eey3HLwWnld09tqsn8SEU57XNMW>)Cms)^b6WI zBu=iUvmQPI+eTrQOr9FFa-N@*ET!Q#jMQT_-k!50#k z+pp3*t<0_7XvYs~=;j$E@`GYNW(ASu(2iO7our40O~184OZu}5|PliIW*atYJ~>OO~e!yGBpbtD^;<^b32@jy&) z!*%rxPi_Rv>07p2+JHiQ#Y&}8M`%T+>c?>(W=MxL4~Cz4*(NRgp4lolFAmr$Z5O;L z77#Knt2NkMY_|kHGV=WXS-ax1kzoS!j1r~A1(h-?t?q>b%933K$%CJbDqX4q zYzdX>xhlTjCa-MNpsuNJddzJ+xB2v87LBwjx1ZT1 zEBLE!9$h%)##?u=!Qs0AQr432q^Epj^MIxlCg)hST6}+(1r9^rUo#ZQ#g;&U{xGIC zdmGwDr0yz`3R_vQ;oM(=CO7j?4^jq<*S^E>3p5aEuzOCr&*SBkOF-~K%mwv~!9_M! z;Dfda*NMVEb9daBkrJ!tZvVVPbce4e^LARP1rfn)Sj#xnZ`q2h_4lZ_xA(SAel!0Z zwU14Dm@3D(Q~$)@-@n3Y9Mq`bU=P;?Y+MCARD}QP?Qj)`5y{Kjs}CuXKt}os zgd}MzR&g$n9)!Wui>&REmjDse#_S3l?5HmJ4Q6_7?#{YkUBoKUo{JE)Yvr8#t{=%m(=A>{3;a+NQX2!s?}F-wa}OHp8n)qxAD zi<>DMwdC3Vumn>GYG)K=tgu}o*fQlUzom$l;ei}UzorK&Pi&Z*`%|BjwQ>xoB zsQ3oW(@!H0N-@z~`)YxuDjj@$Sj9z!vcXZqK=hBk{#&aXw_zq* z?0ykA^DjEs=or(@>fhgniTz+?R$m2GsH}isC5_ z+qt7hkYzESM|g2=M5#MqHzP`hbUG$=<0q%!0l;&NpcGP)3kV8QO1}Yg=_ zJgQQn7*85h%}gC%S`7ZQv%i3Slqw&ZCPSU+-NYl6-MFg(_>FOP<3D zPc0`1gVxRV>fMdhGS<@fkpv6f4yjZqcGz=vOU$UYPu1(-|L8b>%bo5pH2?nH@dT~3 zuj~JoW~TK2621t7g@1p1Ie)8b$V`70MEuX+{kaC)6oye*n_od$$;u9>KmYl;9oLST zP2Kuu<^vfqsAvBA80)w5|0qe_fC$gG;?Ip#02`+Con{3u9!Ar^W08Gd-&hJ1)<}$h z-pokkIz$Gm7%v`z!gN$a!(D7GoJfZx#4Rw7%=aU{V!8ejPBNTH{&)XXMs4 zD%p7`vb$T^bNOk4RLeXOH);hH@U6RzPf84eti?PG7FVtC#aYnO(ry4j)5LLRP@`Xq z2Ihu@t9I}>Zc{I>acN5r04Ht_6bxw@QxOqE%XU>Or5kVsO8TA&TnzQT!WcTL+rAIn z7vE*;&o3=zfXhbN0ZH=jpH8;lddbIq_4SZ%5*SC!VPph{lQ9r~r2yUOF!JmT&b4k| z-yP66T`sNS^GVn1cA5n`?P1r5F9l~PF)fc)=f-f&H-bsIX7M?F& zlPyFQ@jJ7sfOS6Zc|Sl{jsmI?9WcH11gKzekbS&B)i1uc0Hx11(;LQsN~5-c`|L$e zm6Vfw0IXZg#laKOCPznM8iqF40f@6kbx~y?mu)<5_`7^&T2|Zx*s?i}-iP~N-$-v> zh1G}N#jcFLC16fY2Mnh7Vo`6-1l-&BP7RIdtpV?o=biBgu!P=sD87B_6OjT)7}|i7 z2sqdNzpGOK9a@Qlf#6E@zNmmF2}-j57Q(PhNlQc9^dffR9fM=H*vwhlxEYfwF!NMS zu{R8LzK@K)i%m!^i69At7a|3*=AXkP|Nas@edRP&8`nIjI$}U!r!Pi$X?Yo2Hn->v z!PQ{Jxrs@NHO|m4G;AjFcLBwq*i@%fVGWOFG)*f(@@nv@d!f={Ck2sZ~wF9ktjkrI9#*f zct^)-=-?o0T~xfO;uRbqs;+|xeRcS`th*v`MLc7`0&kg<*D2CPdN&&{oFm6Ko5pyT z0*X0FYe5&Kz+dr$hPYQ4?%i3fkxqUACT}|TV1Y@KfU=R5x-0(3t+zl9L(}Kw8s3F=4Y7 zpOHBVCm~~N9R3y>x;D4423(Y3s3(;`_13iqtM`b%XW{^xj&rZgJ;EZvf2E!6Vsr%X z_~LOUb0c5n16ZT5k-X+5SGyi+H{!_w-VYL*H-8Z{L&3V^dm91?5~>E|N6He5Y}%eH zC0+X{7^uyH~_Dy*n%MwRJl4PCFCJxQ0&WM-m3wqOBYsWvVnLe_hYfA2(FLX z+3)$GUg1oHvcQd&?%8lS2Y0@`dD}COh}YVjEY}C$37*-RNRYW~TmH_v6pxy#U0k0v z|1}`=IN>TJyFUg)W}mFE$w`n+sUR*{3^7WnP_#L%Gd@=DqK018BApHZuS`>mw{LEVQA77_cm70*Zi$2M-%)bsfkGR?-vA;!V+l zsarssDL6JbXgWmk(znL-Q!syJ8xyvjI|rl@`5i!uYdlHs2|QpC7+YE`&XKH~Xwxn3 zLCswOOvbSlaOxF!L!eox*oFi5N;>yG&@b4AK~umz68O|?K>j}$cXZ_Ai4@rf8;63a z*m>!mnjNoN0)V@;KvDs376b&trDY~qSX`T(w8jgU%)OtATn=t70&DyXHzP7;jkUfO z`8mAvGAnD(YVm+Fdyl=qo<5Vx?ezzE5k9^0oBMmq1!Ho`Q{<K&kThY2zu^IPEq8Gm}6%uU*U`~%@6s*{wzL{6Xd$G;GM zc1UHxs-Y|q8T#6Pwx^8xzT=`)>R~_L++OC4%Aw?V&I4hs7ksB>YqsSE3bMl}&#x?h z|Ku%so?p74B@-Im&c}MYtF5`O3(>b0`4sFLSN7~Id8fZP{r`3L-tkoa{~I`xQlyZg zL2_)_LLnvLSee=D*our~-cl(!WFN;KAv=3yRrWge-ZO;kIL7aF>;3uket$oo-}mwT z{ra!ujQhS{uh;dwuIqU{%~Q7qNj7q%grPlw*b_Us7h9w=oF;wzGfMBTfWVt46OEwK z^m+%^oK%++JvTE9u!q8D{iR#o$Zbl&InnBx3sZ3VQF|1p0Q*qix{Ktl2ps`sP>XAR z=`p(l;DCvQob=?5yR)*4PXY6cz)H+i^YL+A0KZC2F4LV%SOF)Bi5t=d>`u_KyE$y= z{ZY{~zir><_G{t|5GY}itfle@lkv$OUXOk<2EcdT1zkJIEpW#h^}z~Y4y-SYB|(;k zovQA@C)SH>D?r)14t)ntflSu_05Z)7c456|AjG#d792hUQMQ#LpFvdr50GXWI0D-Q zTolLb9EdC{*TQllR#Nt7%_Z>I0Wb;0JeoIoW#0UIr3{nt?hz*mV zW8*vy8XDeK6pB_Txdu@6Z-R3>A}(fh9Xwv#c%XqqE+yL(KpoPv!$|?6O{2lv0E$iz zCP`R>j+cZgiFVz2Dd9^6kfx@#9L|L~&xkuD|BIavFTFXZdBo`A0B%9GcE4Ub<^0Q# zfbj1_$wb8OK8S5uyLAvGsEmAGCWyBGa+myfQ;TcI9p6&kh)sOU2`7mu>7%h;Km5=hqV!_sB3eP7#aw=#QSOirR@^Sg)e<8UP zu_mp(Y{3i)$OEwVM^Z{@r_X~!HxNF8LKW=0I+e7Ez*>h#Cyn+^pv*)dFIiN43Br z78e2H%5*mvHds8X2h56jAj5HPIrUyM`_8^+{sCYPnjkO46ZduT?eJjPK0W6c%PFAA zupYUo#5NW{4I|j64cG%PPP!hQ1h(h;(OdK2p}+uOi1Wmx4gq?Q4ZpPp!R#=Lp6AZY zS~9msV<=gdI4GdGSY6stjcdz7p9_Xo>gu!hU!MrIF{mr+O+1HJc=43Bn51_aaVkeI{3RImaa$&UmH+i5i-?n<=PV?fe0M_IwNkw!#48(%5*xawTqvx1D3uQ z1;)fLlL^Zq#pd1g1d`qj%}E@(Tg2uGVBO{-mC<{j_1@+QQ026)Vhi$h_T;dHhG zI0yT6DsF-PftJ$9*C`QZ6CEDQ_6A2fq)^3$(1leD7C!74Z~ z3gFfUlTDkBjdLy>2ecl@iYYTn$H`BMv&Oy$TowlHc8@f1jUWdCiZa$<) zHaS(2ZL-55A!rQT5&SKHlA*A2Ip z$D0yU6`TH6bX`@Q%l7tydwfqJgW_pRexYUaoBP>7sWYWroPhbm=W77^7>I9|;uIPq zRa#TUH`$I%XjSXWhx=8BEbufNUw~zMnfRj5M2n znwJ7c!p;^(8h|2eR-HeDdW@n~I}!GA!p6-OS2nQ!Kgb^!7U00G<0NdW)}{H=KZ4EP z-~b%Xkxt3miuv^xKC~?P?_Gc7*0(HzP*@&;-$lN_|*%2$pI@9^gcQx>sd(XYFqO ziUr=W6qYrfMFR9Uw1;*i6P7UH1|z-o*2};NCnp*sMEgR(1e8r)y6&sB%nt86#gnl< z!`@%w8%aJ4)7pchM$myG%*+uK%3MtR?BCj|W+|jiS3_G)2thJFDrq3LPwMVHEm`u- zrqEa5-#!{7O5*(?Q+Gy_976p9*~2^i`t-07W1ofUQbGQAV#J_<_>j52wDD>D8ZD2! znO{Pl$I!xv#-Wnz;K-M$mz37p7YqiMx)u>NJC+tS^ga%L*46x;vuY~_2cs|c4t~95 zTIy*E=9}DOIlp*yLrK=NYhmgtf!FNsBrC2(xIF=i2GcK7YC_yPD8;)rVZOE8ijBD* z=ngJRz$rhISKdBOw+Wtm4UmQ3=4}eLIzc=vf$PRAvhC`1!x%=S^}z89sA_+ z0?yDb+jK3<^*ysN9 zD4~DmE7aOao2X-O8x+?e?QoK23uW2WH9*xjh$lW{iG7~v5)%=@GoaA@9@;ZmcWvRV zkLa@k1}C%Vhje5G@E{?r%Zl-eyyVj*;5)VMPS*O(!01A&YC0G>4e<9%t?h-tduMoa zTx~DI^@fYniScqk3*`4n0f*^fzqM)w09s&W6+MR%utDrc;l%I}sZd8>QBPNrsAcHL zcHcVwmL$T%!(+DM1`MR041sYCmigHlx=-)BJ?2}-!A@s3zk^HwIRhe(MZdcOyc~Hz zU%@(&pI!e-TJ19N`a+8}8;ti|z>glZW<;3{KOF`J>e)>+e;ZE@s)~?6KEBqUE6A)h zITbT)b`#N0^Qn&@2Xu-@%?C8U#kf4_`{4S#dgzraABOo}h~b7#+(MXvtAmy+XDq)% zcZ%TP9On2Aaa@E#sG)8cff)V1f1}B0Lt=T(F_6_c|HslZ}B23|Zb5Ywzjz8aG zAQhbY1vXkK#)`_VVD{N#@9T10iiS0?E(jkCtz}cd-4zUwSx=@lTOuHE^kAp`yMyu+7l+~yOz?%FBMZyBa2gM zH%0Mj97rVxIsQU9{HYXw`Tw?_E_AX3Q!cPeakfZ`ds@C9IcN~FgVSMrJzO^th9@@*9k zM5XB+1azBVzsFWSly6oP`!)X3%mbi!!JJxwkH~#+avhhXBjbE7%+`1q+ThyuOkiJcZrcM<6iM z+AtvGd@Xd^nKm6L5sKCC!`tke^hE^D)(k*ES;3H#u%%#~)Y9T(L4k}bKUg$4Y&yOr zT>0}gcW4Xa6fr4mgiUb_GyB?smZbaXxHE&9Yl2EeXkWJh+@p(4F^<%#Kix{{2s$I0 zVG#gW_wnw)K7`$z^kU>HOeW;5mAngCXBCF;T!pc0>n8msST%Ee#FkoF_F56c9<3s= zKW>52!;r;1FsOL{+`tbz;S*>z%5J(RQx z%nEh=!Of1JJ^c5Zt!dM(W>QZT?3SD$h^Ng1aHab4%=%8=F3Sq6a=Rh*fdzgb6`uKL zWXpBr7u|<56CfpGZVp zY}43x&41+?w`07E`=z}rU0ONt{b1%Qu6HFur9L%jXGJGlk6#=BQfNQmk9Q0Mm*4%? z$@ya+VZ)Ao^Jm}^X~_r~Nug}LlMfJDq|-je8XQ_#Xf!%v``EE#vxN~?4}q`0IulHv zmk0tadEJ?sNv09eoWkj9TbJI1JBZFjJD`B3!;}2JU?c2FSMVd)MbOBQw5ad&?Aa{L z6-r-gRmlegKX!WowDTle;s9IC2HK5+0bDfzvfq_bu#KbQJU~ZJQ+HS0szt*KVP*u^dC0AduR2p^fZ&XN0ZXnLE}a%460$kfdo z``cdC<^%r6-kt8XNe*mDacBbHn+?dGv21K=a)tYJOo@JORjR-`X*BaXcItA@BCKx> z;2h=W970uv=3x@nB}@9)9oQg8#iPn4d_O1a1tKG>D6%3skmMuuy-?te8Te~n@oWVk zu2WjV!Y%EaG}s=$ycL0h8}~uex5#2%&pH$lopK{rJ$f- zUM+!smZ#<A|gBK z`6(AqHlWT&ePYVH7rbH>wxtz(ZdGKn(`sSPrSUDdrhS&HgtJGz$`V`e23(>&N<21_ zS8Wp)7!+jW`jpDs)5OCM0^S*x#y(k#UV4UK6=x{-yIartS z{U^tpqNnRRpTt#Zs$`##bhn$waNNBvFiUGtYzdrRrXNo=DXA~~$P!;BB(UK7oljB_ z3LbuW4Sg3=Sl2;;?Vev!cxPO`?r_O zD|`)$bC-sj*+sS?F!u~7z8fSrDZ6kSeW3Q2DDr_cn~!pVD@%}SwBGHDDrAO1zU{SXLrlEc||_vS|?IVgK7c9 z0@cF%GCl)N5Pt=t%8uf%j;RJ}ng5Qzs{I{*#s37PUwPIarC)6&!0A^7CA)E}{tw*_ z*N`h-4s|G!DD9W4+8)El2-@X;>*L_fpgS)CzqaZm#e`*(n27Lok}-esM2J;PFI%=w zUS8Dw3Z<+WJBqwPCNqiOAmv_q7%|~()&_Up@F=?+?&l0l`=xZkq8I1`17uq0=(l`~ zu^)PhJ+fDgHkWIZ!_b#DE#R0e3WX#Tg_+t2?icM%|AX@jZO7Zu{t^h#&gr}oh3sm!P$=SE6gZk)FYoP z>yjKwMU?4VY*Whboht51!Ff3ANQdvE^sy5}%V#)^WKqouuRi15lBWbLB#%*^!dLc` zBBC!{>ivH4z4frt3%02w#y;oF&RFAC%eZ2@(bx@uZ!wK&uw~3B6WVbk%4%qeE!=PD$Dx& z>g!DF1twEQF&A=gTjh)`xl*A5UH>ktId95M4cj`=f>wPt+}JIqw9Fn`s*Yfjd;BKE z-yU`q=cgrDDts+gDE;Wn-%+`i`BWk>gNkW2=tG5%hUy`|{_%x{jKV1C!%jZ6Wg!wb zlxSE%_;Lvmf#Gb>QAZbi)6KzT5ijRrgHVbILWl>Kxp-gnRL=Q~9mWU@A0@}~8}MQ| z&l(>YNo+XPWGek+4GDdOS}6IsBbxa*2!!s@Ys>Mexa<2P3s>~a@oOog>ywCW&QG{% z8~zb<_szoX2+#<)qi@m8M(*>HV&#Y-&FIRtIb&S*`yF1&hI4Ii$D%rAf0O zv#e=OvM?>~5Jd!(^6Cdut~$v*TuIA16yf8YKe=&!a|u5FR901JGssV838`J8E{g9d zzM$j3KD2U0bl%`LnHA-K&E3*Du*$D>-`Q6g_Oz@^uNd551O&}gRk2a++De=Ou za~z8v`iWT`r=XEh(74P>MTRU$)uG}1)XO4`LJ7x4p~nhAwX zUp{1SI8jZExOh2)w+oXYKdNJrXd?H?+sU&;Z*a*OGrLA13Kb9~YPXdC+E>};ue2YF zU}s2}6dwvaNY-*B>NKYpSn_JOuX+>7mpx1Ke@!u6!~1|od;?TrwQ1e!IK34@eia8GnzA4KarGIqWkO;%uBM_4%qVXYFR+3tS6-}AZ=&V zNbj6~+$nLksIMONT)-qp6XOf!n>%__F0JrchnX@JwX0`0p^7dBvo+qf-=n0HlNF^a z7}J^jpFv%II5?<_E|C`ZD#1E{#jHBd*~imCM;5K{vSdcuQF|N2T$$UooFHDCF*^ zx!o8M45C#eYYde-R$TyE-fnhX!JOk>A6~8$9)EmS42uj&kmcF6{$Axd-)cIa`@F5? zVN|b0oB<6u*dz4lR?)U)FykZug=0cxQpLb)HJt6ZX~6*amFc^7B!AH>Z6918m5FWM z*ThEhQEi?t&D#)26;RCpDUDYi6S|$xN=v}~!j30ErTDe}Pion6b2lW^+5gG1z~9m0 zqO;jKWVtHQm2$v+ZAUKwf9)$i;c|b2o)}3YFcd2J6l$lE-G(DQErTto7p#l6@ z%8Rda`IUk(vkKapsV}Xyw&do#@9$QJBevad*7LEF_u&vDOAm{)+I&hua3|zXo;&&U z?W^@||YJdF|QTROlPw`ph#OcFXqMCY{9}-E%R#(~07XCk6e{H0=G% zg)Gn5IAi!nThuNhlRU6!rt4QI?G{`u<425blPf+s3Qp6;!8vlf*G5>ty1IHpVY75A6 zm{8t?1}K~4Gnub7^hmlXWIYW~I{r^Ww#i1?-R5pdE7 z{yHVDXJ57{QMcgUdrlb^1ePJ$YiWRVz>9SVAANbuGzab6ML zNNk|4MeCzD$7j#N^`jZC%!p_2Skmx3*l|0-)OUUAy0NPYGxJNuJ%#6YT&)%BsRN7L z+0ovO?n=Sep9!%dKed)=Cl%ho-`x*JhVxy=s_>}FiBFji3hZjm^Qjev{d6%8itXojfqZ_*qsO~!b-(W1bWnQ%5+)GoDsP5ov1DU7{ zuH`}I2`Nwf*+NkskA#Dd9P71rwIVp)(1aaWKFjiM5e0XZXZA6>I4!A+cn75Vh{Q^% zYDyM_zw+SQf4DJV}kCbk_+VXK=8yzQoc*<#x$fC~YLL(!~ zzW8Aw%?MKoBVcY8!lfvh8Yi|ko|WI ztBUxqJQ}yZ{Ik`!$Jcj$2!h|`Lr7e8VcvjDsqugkCy$t8x%w za^-m6+TX!wd*yJ)Iqc<2TM5Zb*K6l`O4RV9PDR|d3u4^*_BbLuS&LAYN1f)%rPs)s z-7MuyLIB(w=_UNQifImC3_*%X0kN|0kD*!wurDR=+XsP4TIW z4gWMEO7`V^@_B>E`z#C|TatpC65C<`*y}9Rq@e%$Hqe>8t3Q5Uc7oY+2l1O)4{n8zIy2xxk4vi^f@P%%w!CSveHpip07_=hF+_-pB#If0II*X>a4 z$Zn*4&6%362afnQ6d1qbe@)n2B%stJs5B3|M^kv^q0o>Alp0i zZH@KOQP2P99Q2LW(|Jop z%M=Yu1EX7mL|g3IU72omZhsRRo0YVRkTPzZZ(~eB zgfy1WxbZ71ttn42mE z@=&6*#8gzX&Y?Xffi7f1j^ZT{hJKe6sDJY~caH72sRo~<|IBPrKiSzwdv;8K*|L6D z6mj-s2~FHD_ukI0RFx5282)(*E+}vLv14v=r~acdx*hZdEykqA4@}KmT}xYnTiiLO z9|6K<|Bca@8UD4%3FtTlLW3O{IkVXY_n5MB?lEqX;HH_~Gs4agvD;zXeBaB=pN+Oc zm^aCA=e~TV-7Q~ao2f)ZCp@SB&*=Y~`O?t0STN>Zah|i7bK@u4_WuVO&Y`|NwGyT# z%4KQYXqJB*DH;=KAvyb6oK&jG{01Sr118qDS;jYe`i2qJRfc=Wq~l4XjVV4SE3vOr z_R(>WpT^qu@ysbNQe00}Pj| zHX+s2oBIcW8)uT4q8c!#gPy0Jefe_!)aC<+FUMBDOddo8bxaJ0es+BGqbE7uL(*Dl zThk`aj6s%($%tlAWZdWx@;Bb^oKws7-9jojEWapn*9go-fcWN$W{@ynF-XQg2u5_A zdd-9a?+`EPIPX5*^~k`Bp-dzmRBDkJ<3+G2&lBTnkUjgW4DI1@(^qs<@B%D6X`eRa z<2bY#L?)@@PRS{0`eRx5PJbBDKTnGpG^qhY1h7ACrR)5YN5r`V=UmUqw~D_SNPCL= zRVJSSg>m0gSN2R-F}M8>49(fC7g*`z>-@Ko0(Q^~c&5OwsH2$zq|6LE7jwTJf!Im+ za^fL)3c%?C?r!c<6dQjq+j0J6MC>X|pf)S_sCcITow{46~TgZLOLhdEKo-V;~n=k*y*Z!FckLX%M--CI2T z0ShIsCe-!Y1^FXB>*#b3mK3BDK5OSZ{%*f{WQ=3`8%pYk`xF#r`cLljsjfh($LO+P zX~GL(iW3|Uqxmr_J zPbM&C%M{ljc7+xVKvNm72ELlDzdfVEA4g=DvQcGsH}Bp|%0k77@sIMHjHmIFr7fc8 zvGK1w=d;orJ`d@;okdO!Y2NdadT97SI4CTyxT3ao6CB(UQ|jb6m+Pz`Hu)5H&-8)% zS+aDw!i2Kf_xJ(-BlwX({I8ZT0hy0CVHri6vg6aMmy(SaCL%rzP=4)r^&vlvk1GEf zZ4+GI$_d!SNNf^Ol085ec}N4r?tQ9b2Eee0;>e-a=R#%>4-MOR)? zkl$LGm;b|V{sYARjorNdf221j2{qICf@SNNjAQ0118{vtdK`?oALdRIs>>JS%$PJB z6=x8PviO$rg}#QuZ{jBJP)v|JYJo*91T7rbb1m2E8~YLWSz%viTKmj6z_46C76(Gt zswXfbt6-&vwtrkS+?{QHo|cn?Kuj)%mh5Mjf%sLn`OP6)f9>pZp>~eBWass(cPU{G zb71Tmr|*xz=kzp3?&vzvCkalvg_lfE`%vZeml@sXipjso{hHjmmz{us{7_a(QVoph zz{vd<#+$h-lPD$|vg`n)huBD-;fq3XUdHR+R)FcNDPLPDg&p58F5+jJtovQnQu<+P2Ud%^&LJuF$-CcAo zO|rIXwyArb3r9^|{duHj{%H^Nay6AU?Z@6DlQw;t=BqVxGsYz0D`H8-)yn8vvL(b3G8KQOHzIFWQTEhMViohGno`1XDTr|eLM$hG;l z2holwOZxSm*hyc%mnoKN&Snf2Vi#1w+~hkK`)B>HGEZ8CWaD6<4KdbVp! zMyFc;cx3Xj_^mG88QUiRAZ6#u%(nhdXbouZ?y|k87@uHl{Lgi{L|q&z9H%t5soPByaH2@rO5ban_C0eFkkZ7rm@g71j@^K zqQD2mmKd)s5_3dVc3leTks~mAW>gMe4A%F54KV^nXF#a_(=6l^EY!~&naL1>mi>@) zPt;v}b%tiK!l?q4BFN&w`&l3pM~6fSU_()*re%7)3ybg!rrkB##6-VljK#XPMk;tu zqOFKb1tZeoD6v(kb61o}<%vd5jF_R#Bbr@z%I`ly ze)UI8Q%+s%bz5|edEw<);7&^2LejOIU)v%Q)2a1D>te>JLH#b1@>x4GE)9bf^iUE5 z7^5bNs0f=qya(7NHI?j4ML`{=qLT3{Q zQZIUCMU@dEc~dgxwgMAVjN%aTZsLUDa-_+sqSnQA;epd?%23?nN<)Eb1Kr9qhD6`E z0ZI5!B`;GEI4{t==dZHHT_I+Lvw8{M{lV`4!C5L>dJA0)mlEY*i-B&Fzph!?9zx2v zzEKI5E0Ocr;0pdwai%*pKs>|yp{&lFSu+Io_SAbevlpO z9zPhGCrV3urR_D9444h|IB)CtE3OtUG{(#rOkFVhGy3#jGoWlpvuOw68Bjv@DGEek zvsa-J#66TQb9rknQEbns`K4rqvb)zvv9(s;;6YCo;==LV4ClBX!<1&)gNIr%Egz?+ zNXwFKZcD~<#f_kBd_k?W!p9es!SSXPy=n{(dzcmZ_kA|3vnYBMS`yqR<6a}kzhJrg6E$g-t-ldgsl#jo7ZQx2g-vHX*JPvZS51h z`7&vFqWaDA7hlI=Ddc`KUeEoaEBxYU3=|~~Z{~~r@yPkVyyK4Lb=yd~K zlwkBA=J{}87bQHnaMECBk@!iqQ-Yx|r`QN^(SRvDw4p|eqNNo_Oe2!(+gIJ2#r4Rf zT^kjMu~LzDeeMh33z_j&h!@HqKjO-A9wsZ916t9JsQqhjgGO9tUp47AaTWW`gC<#N zflrA)Js;ha|5}PS9m!oSL7%5rnVM@c1B0{tz^J7w(0f9_lKpG2Ef0=oqU*M7tNVCt z3>OFM#CKy__FIh+K`7KjcVjc-7o?pU4aGV4E_nx!a)A_FnK$8WQaOQ`;IGJ@v&zcU zC(i+~{-dkZi(jW0Pr-2RHzwR6D3O!5yI-~8GmATES}uH%`yCKfG1vAe*rD^@wxI^_ z_LfS8$Tq29Ah%}WZ(v&JSB1#burPoBIcclaZBv)m?Mv>421Voy22~A3f zSO`7zPy{gj>k?s{SN^*5$R+V|}{-oF2HvLETG zb*%ONSnEGxtq;Un{~2q2FxHwc*7{Ja^wr9<@YJu+$C4w6cwoU7wXT7i)*=sXe)I;6~`n zl7YU%{P>*rP*RaXxV$2_t-}rL3H-AbnTOEVML4gr2kYd@ui}0n1!n8bWZ3gnnC^GZ z9H~YeBStrvs|#C8uoFq%e_Lj227WR_ zWFDcy@~%9FWI}%y1v4@sjkR^-`e81Ce?{K3n9TI({k;Cy^k?S}_5M-A{hUGEKoc?S z4sxcY$Gwsc_St7qtq))LR6tpLD|jbE+>zkGnq&~goPif&%nQci^2Uo|Ufr!6%?gOu zMka=ZEIq58N{c@9Lnjuv@0#5J(}YfyU}iy25RpEZn=!S))Jz444(+0j;NZkE_>z{O z?8Gv6X@^fD@-ZmWD8 z9@`_RCBE<9&;Dz_A14ypg4DCyPzlii<>bd<;kLJ$dI1(9Gh|z05tO8V{^%@xicc=O z**&>+XFa-UyFp}OaXAl(vrFqPpv_8#_i|FEq2DAH8br9~8*!Wh-8~wnYjU)wsI6^m z$1}1Hz#fxO95b8!sEnMsE;;o*k|^30RI(d39R0caQ64z6(K5wSZ|jAE=Pa0;lfD`bgw{kQRU734eEew#j_cnzuEjE$@S0_N>~#(fwOB$#9=Tz? zRwox~A+ z4G-iKVC4?yL_!bClmFsuwpy}(b^|0_@kQK^k{`_z!z!S!Udw5)MW=S1Z+zBGn5JB8 zj_$2CINdgQuxK_zGD+(WV~6O)srp#EKN<(xE@U$oIk1og^ub$C-(SEU|FO8c2fp09 z9ywp1(H9PF5zf|J>)UYE@o3Nfv9!k#1=ZXl$VP2sCCn;FP1YZw3Ypbu0|*F5pILE} z2(nt(V{7C$G*3yzxWWQ@)4w?E{|&$|LIVFoVhpWpl>PXr*wgTu56V?NQ1Y7+F7p$M zRE_U>m(5iGTIkv>({K33b$7{!+-d!l#TEtY(@nR)QA8iuibQyKjHi4gUAPv9WPqDMOXQxrZo_h51rWvJ5-kVbOWoN@#n>ppGgQ+h7mr2~%OOZ>;%17FlX z_hET`cQNf?b-uA*MBn;p6jS}l_wo`Cxh^?W*u1vmT^5peBhCabSK@o7ovTtXv+(TJ zJ(qlcLTlI94xM(p1+{!4!ZW&$oK5N8dCN%BJdmJxWH7|k!Yu7@6SM1qv6!TsTq(7A zbqMeYCm>Q-eeom-8p~Gvb5K=|$KtHOtgJwy*1B!|-M5EVp}44>zu8k)S^l?g72S0yYG*JiXzIxYw1%VOL~!R% zfJ}B_K3D@;JXX^9}KfU*#glaStig5)RVZ94H_m!5LsJ>pP%rf7P*j4I7Ch zXZQB(TT6&(rR}ADq);C0hDH^n@_-s#WAckw6e)BVd7Y;1NuG?tjusW?My);uw!;T! zC}SekT{=NR6OP5=z+PT4EXPjOd3Xzk0}qEJ=^kpqr}{MMB{BtHLvUjWL%^G{!;~qy zlP{SpF!p-P*kO3SbbuqX`x~wM_UZmP_xo{Ol#x|Wl%J5Y9@zQekD}KG_8oz-i*CSv z{lxUBTIwt0AzJUATU`UtFBPZr7E(`jb(*K`?4&-r@{iqs0CRZ0Bt|(d#^-dVK%0%- z$(C$V5EwLl-a*`Sjh;PLURw1==t$n1sAYnG!vrPz=R8yzX#22HP_i-~*Vjq|vYKj^J!qGQITg7+0J}L7r zodrEciiQsft3bcDL5k|64RReESjf~lt4a(!XFdI!X{R*|vKHnhSjk!n{ov9@H z4(>w4h=UtoPuOG49Zd<`B)4SX^L#vepNk^ub|kKJihD5|Dm@j#J6Qneyq}%Y=;;nA zMaj{3&aVnHz3f4nK`wq7hg-<~Q-z_#zjcl#Djk4+dHVb|l-ySAMuup5a}k>_1Hqej zH($k0Fdt%<_DU9oCZcaTr&N}gCKu(c^qSGkx=H}E!iI)P7n%)msyc6{cU7*XAxQHy zyZ`2DA1xT0sOSkv=f8&PDXw%;O48pGAV>GnoRdB%?hH*{ogn)l(fWgN`RnMHFy*?Z zQ|nrh%f8HpcDN}rZN@pVSLdD*mt(n*o#ApJW!H(i>XBsM5S0;)T5yBWDlf{h-Cypk z029{7uPr>%TKQD4c%qiLZ17y%Lq7?5;JDt9ZVWRs#H_}6}&E@uzDOf<-+Iou0ML3frGb{k z$R_w$-afpi?eQ90ld$=#io3dM5%T9FEVDi>|CDA=+*2cuLP33`+jnlK zu?2L;M=To*+_VLIU*lNV!Z07T$^}L^TrNR)@G2a&;tH!>IbHhkQX`utapf*5YPY_Y z6+sGpS^mh7tLyX&0$9bD zHGaHjJd*kj9n2*5+h)**ig2xH3z$~{KJdkYSokYZ`1;GCM(*{gjtvz!(YTo2FB(05 zk3#Cf0Lu3LED!INhf7@5Jg#LMO;Q=eF3an}w{a9raVz;VBHDbK_rHl0G?J#P{(3fm}*)hJOv;-Ex%hrX)AwCPzIeaXJKRp|b4B|Cx@S)>)Q;QEGthmLT+HKm=cz zo|ScZsv0X|D2Nz?uRhO#n+$u3a$tL~#bv!_Ogmp$VWHHNu=|cwU*=SZsfy2xN~C*N zsdaz4Jg}#l$*2!{yRGeDlpyYP;ALx|`Rrt+2L9Vyje?H&3^z+%3#De(AzmK<>GUaP zKY42Czk5DpH_OE^pq%CZ27&{|!mzb^)D6fkW0j3z}bxC>5WhF9bvv6mt;V_xEn@!$_cGc@C(=2YMB*1OPD@o8+*ff)g zs(`9zDzwRwTC65^+ewr7!z@#SruCnF;A zIA_f2*zKsftIq)Jk&UENLFV0L(Ad?`qht2T^qW4l5fRLE2V8UF<&WF+dAG; zDwWgDewCX+zj6aR(%QAt+573~Wntk=6q$3Vn@0#7WF(?L7y8cqGZw;cF3|AO!tctP z9^l8>;6J%e|0EI=N?TG=tV!|m{JZ>CuGVfz_glg(Nb2>mjBl>C*_O!5Eej4Y{Og0l zk>*~__|0djHgI&M|8UL9wbnjrAQ3(&{h?06d4uh?roOoAYU`*(Mzgb~RhMO2T8D;y zNMukk`Omk?)l3+n6Dp{6Q1?9wvSSEUv^H;TFp#M(80HU%$kolMVG3BlAQj*Y_W z>+7k}7mWq!@y0!eaFU-P!!ZvC z`O5~*r>&OVE*+jbgtu^tj9afIOJy?BYTX$$gcPWi!E3{NA>EBi?5EMh^5KQI^LNr> zj_cg+SiXbg05Ne9J?kqdgUOn};=InQj#VzSn=?Usi-R4r@2%&~LNh9h+fNaiRu!(u z=2E1E^`OrRiwh@(qjNcA%wkR>IAyi_h)x9<&Ftn8t|Cj!Q>v)?xQAoc-!OLC@&XT7 z0Z#`0nTGc^i7B%Aj!^|pdSZ*6w`*>pmWlZAQM8}{zo(D)P)w!As-1o2<18_`Qn`%j zKLkX8o*t-~2R%?|bD=&k_{+7>PUyHsr7(yT5b1(mGH7_EI21Crm~yVy3!T&M)zhI4 z^-+t`I~NL|D+}lh29FBa-`-!_pNz-PDt03QNN9=@aMI$=`$_i6T>E zHq9RHo>^?P`@oxg6)5Y^%;>ob!M%@VJMUq0&mR(vF3frCxv;XO@@U{hi@PO^9;l=9 zLZWw03}Oz_^O$7|q!$3&cit?d+LV@E%18o5TM{lKCX}!vf9E8~koSfc-p2^k!uY2n z=0`K!2M-qpCbr*su z;ogy^@S6aR%BOe9N+=@C|m;vCk4V zgE?llGNH-Qto9b__)ov}m%X&rVf*7c7a=kdp)dHa$jMJBlG|+ktDfS)9`1!bZ7Bjs z(?g>EQ)}iLk?|zw#ueA2JH#36+y%z*vkJp)VWsP;J}9wSRFT=jM2UDB?_wNZJ$F8g z;$z)MUz`M(PM#aPJvdy3x_pMZuwTW_m-cVH^kuXDn?arzTs>E38ebPJ3?~`xMpApz zug(XP)J64u(g*gLoamilJM1`!skipKP9nmgRM1sr$7%=$41!%FKBfe zDqu}!s#@RdoJlAlHY0oa(OWGr3f|9wk!P&z(NjRYtnQuBby`El<6xlyge`|3+e>+*RT-E zRWRqKTC0dwwq$p%z3+_Z%cbPnoa@}Okvd$7b5tGrM0t-7; z0MKk*0!ICGCB~#7kyw5&l!&saRTuM1r$?>T4c|#QJde%BL|M7Y{R`}Us&l`e*VokJ zAk20BG9o5GlFnqY2Ui*Fj#Z3wGWKpVcJqg}Q61_&riM{oTK0y^VeZdl zFLP6zxfGp$1vH+fQn(4ce7=Z27}VLl*yFyIZeisJmeF=j0CMyuD<+Bqr;H zAgxhm$bG4K;O!`_Wfr+}E?;u@3wSxuB)>wWh0i>q$2c|<`2xR_4AVQb{ou&1i`rk3 zp?93_9e9aiX4dT1@7D|44YOiRnxQ=AwOih$_`KIM$!lY~ciRK~$>hGh(sxnq(i)FU z4kT&>I7phEQA{OGH4xpT;mqBPTt`R3-0oZI^~r=p(1i0+m&Aknn8n0JGSw%ObcgvV zOc%N*197&O3_636Iepp#$|r&D5Q5W;RS>^8$O%ca)z#G^1FxhSwwehX&3C(~>(fcM zh4|`s^3TO!@ql}w*Z7xu%X9@KMTMXB>A_K`Ij2{J`c_6F2RwC&X<>(R?x`2RRNqxh z5m$@&7|qVk=(0qF<*?TA_#PaG7D+Fqw=(RPwgK)#eXatC*~cGTpUySvsY)pa;5n7s zwOn*Nf-|z-GFg`g{TWVrt4J%w#pky04ZKY{>jJnA%S0T{s)IS7QNo8V@CtyLcGN&( zrHDt%jK%~`Y$;^9p|8QEF=wiklA{#R(-(egd#W*Fw+9+Pt7?MjXNwo@-oQnPCNF>Z z+b82ir{6i#Btf!6djn$TW=Ap2h5H|Fq+b13>t1xUh3|qHhah7ekzyhhf^^{PIQd(( zpm}*`wC><4oy3N>M?bRO0=pl&HMTuf?%9Sl|4FRdmlfI?Z<+VOJ zS9t|*e=%C9E}!eY&lpP9A1d%l&pGM&^*g&)!<6rsxJ*o3;+y<$#xE6r!(6*z$DB2zMM*@KXoSZmrVpm`7-WnTx(5{a3?9jVow zr$MaDcN)8*S}Sh~q`mUk9_xEARW5{sCb&<&Ns<2og zXsmu?T@r1rZ;m1~l0X z^{wT%A4HAslM3I@Vtz0%%+`#SiRHp<8UiO2c4hKr%9GyFM}s=KEX-^V*A*ydtt{hj zxAW+f0D^*{a1r4Jyf+3-tQwn6-QYV{){X@6= zugAP^-QI*5`iO4=#cJdv$l4yM)sie)R6_uR`2Q&@-_;jcT?>0YQ_a%?>XRaCF;zxu zBa`=KE1j*K-7>ChA1Ku&Jl)BHl}2PGIuC1*U$OKWrdeCeT0?w}=h|oqMijO#7rYTW zyx97>>WcHzcTt0(nV$M+(h>5ouBOwniv{33+>9Gh^#Nw8nRj&A<;bkuldGU>8jw2F zd9Emn{P+VaYQ{By$oui!EVeX?MSQ zhMqa6*T5GuzLlxM9p;}(Y!`XX*#ul04i1ga9klR<^IzLaa_{ftL^J#FMXk{pu5p*S z<0%WWc$PsGYfyQy#h&d_#Tm_80LBF^>vMvpKecQ0f;Oa@Sg$0y!;87ssi3+0re-}0<*&XEoW$zm|)m5i4 z3VZaJ(E-R#a}+D&ucU7h7~ottG#|ubdTOxi!VGtN5!QB&;6N`jY?<`XadT{qQbmvE z$#;(KxvzOG(}X1PtlC~#g@1+uc;~4w*{>m2DV&;E%Iwd+Md9cKb(fgwtJLrA^W1K3 z^Z~gWRYNv6^~vw}fq=2Ig!~@_bv(1gNBNEX$n(WTzGG*lWHZ-TInT&Fi}suWf7J!l zGl_1GC9N8wd^Kfgc6di%ap+ljud3R&(HtKdY|56BR@4rFm~M2@_VAxMt1tnY90~Jo&M$EiRYAa-c2wo z|H&m6L-M(|H&c!l)_pR7Zj4_9m}>w(<+~)e&J5wRc^eK#kBp3r$3?P3WzH#tz;_{Uk;k|3U&O?K;R5fdjANe+uYxYpCR!)zgvekR+Gn!5Z22Rd zS6h2Pxt>SOlc$YZgHIEO^_^ znhdNjOK@o=4SloZwr^|GJLSeBkH_C zk?4{uMW*LIIDi@&8YZbCbCVx<+1+kjBzVP5+<*Z)IxnGvR&UGfL`U7 zJvWBDxoVt_^%Zmkmh_H3NM=4`#t`qLZ~6pap3A^n0{@sf@Gl-5{)Y$oKWCd5%AqmJ zP)W!i#`B{BjW46GPEQK`7~FFkXuF6NvT#R#+N6I!XJ6;`XOdthO)m2eM z-&s-l6vvonT_v*Sb9EMWGx9Qc%xdCGzU3Lf8TItg@1r!lCeR*?VfHHUsi2R(T1!t<^TF=vlOlypPF7^I#hIMEEtA&!HdJV0tA z;DmF%AqDMf&>Pt&g4PMUG|uVQiIYGgDW^`hjO}e$+a&lG;N{ZvAkV_ON|g$vk_a9d z8pFcL8bMB8pvJ%nZ&2e~iek1#XB_`ppPr+9w)w;z9p)RDhCde!C~jd(ojHUO|I!}eYy!xHE6A> zhiIPQXAI2C=Zt=zB9SVDRH+?mrKPkENKgkkuLTFT)Ip%f@&om<23MimRn``^v8T{G zb<;aoNH@+Cti+}DNKDiaU~Bxr%nDG~E*>n2Vdcp$;<(}Ut(!Y;s3`22;YPm1w@RVF zQBi{=Vjp3C27f}t->qZzBYrj>GZ;Vn&NxO(0+WumpX{g~wa7?DF=ynOuT{#h*xJPj zOOc>pE}GIFMIQHigM4?<@Oe_ISsU{JopCUui>E)a&%}Y}A3aJR`nGm$9kx=hi7)9V zjj0YiD%Lhlb26>X*0-FTCL6>&Kmyk0IwJK2MVvdBxPl)`XQ_JhVjDocs?f zS7RZVIPj+LJ$dlz<$x*H!5X~&*im=xkH;6WTg)It{P;y?5b;`jvp%L*nU*v=S@Zn^ z+V}HI8g@WmlBuq!}p~ZX*E-jo8eXBd1RJXipyQ!Zlqki7dD`?BBW)MV`sP*}hkk|z79eY1- zd3Cukp{|~O#Ye}F$0-{Ga_s#%>O*epgc?VE_KFw)W4t`HSi^&+tOUKKmENri?Z|AN zbc*6%54#dZQm^F?F#Twb4Z;~@bpheNkEvg=KZ%!7= z1LP!pY2ZdgWLGGQfz5dhAO%{{)jRyX3MFgW>Rb+%f>T=qi| zV=!^~b&GNxjHf;h9G`in=G9TKSPbE}x|_gXJbiFv+^%@sk2Gip2IgL53_IGauB`6^-nGs^RB zk_q$7yiX7v)~O1&BT$?zVyg;Bvs2OMPW&y0x^uUdx?z3bVKmP?O1xw2uA!>W->_x0 zqEYMY=l#h%_?2dP5|I0R#$UGCr@LouY4<#@e9K81EqBUUV=jQ0vunSdQ_~Io6n_cr zsC%}yMU~m3ElJU&>7(upTTsT&0`=?0Op4Ka?xmnOF?4v=RnwN9DWaHG1l&cMIUIIh ze@*>K=b5PG#ocQ3XM~F_m%iyq-saAesDsfQTfzX?HZdn*hyms%(`3Z~-Q>Rm zX3q_Fq;)#5*&K(0-IEsXvo))?+}0w6M$-P0JLVzB*XWfEg~=oP)*_*IjGXXZL@x)5fFb#6|6+?T7r^GI&pnp%~~@$dhZ{m#&<&or%K9lRtO zInmG@Tb0N3uI^->EM&GO6CJ&Q&IB-5jX2zx=U(hJsi)0xM{hXIt_$Q^`rgiR_t-^> z>-9De!U91zvG!^si?>8fL zp|#Ff;z2c-m4%=yf1ykp|JxhVqj*johH zKG^dNSAe-C*o2F+%Wh1VW@#t0*am~$&z@m-4sIiu>5RkVkbqsuhi^6f5Z^Zr{=13M z_lTJNfBatF99%e9-ZnRiI~(Nc99grr4LN1pcIEhz^QtVWlG5{RF`3xOzU%;;2>=wd zJ31K%{XxI{hr1_F`2p_eEBuc(JKonO+1T1odc>=(a~5Ju=-zxr=uO->ysnPt3KL&dBiTmry$-BQCPEyu9|QXtFUCrxh{D3xd={ z!lGO+DkaP|9LC#tP4Qj>>R6iR10uc}!^^D@gVzt2m?h=vNlheT#^QNj2+qK3*@q|8 zy9;Yar@jki*e`UtQD!K%laQE^5u5Bb_Lh;T=6-|@CZM8jNZ8BQ*Dqi*MJaX^_;Q`j zfMtxI&y0@`bq(!K)VtLhGQhmQkt-bZ>X?K&I1v=~%3OaFxSx%G{Sl8Da}hwl(BK$Z zFFn%hh0k~m83Ye5sxD;t1*yO-!9${U(WMeM!9S|Drn`3$Ukm*BC1q(G0ez# z)cbZ9Z2+7TyBx2arzjXqOFk6>sxubDXvQFcW8nn}lUe6VOI2tcF6F5sy!=pa-F~y? zskn_5o>9j>)4e9Eu4NnPK||#+-i>8Nxj>xfZ4bX_1-+zT!bt(u&Qcg$Cqhumt^(S2 zlX16ZHS=Uks^x)>I`FpMf9L&Q4gl=C{&n5&k^G=g3u)9A`;z+5MLLq@K!Wp*IOA2c zmV~2nFrYg*B-%x&?53zVqFZl{RXIxYJWOO(x{O=LVrQc=w=J4jaa2lP$84z3P6g>F ztyk2~Lb?Pc%~a2x=OvYdx)$wSq~Q!|V~)lMeoENpOdGR-|B~suu>>#xipU+TvJCTx ztx$EFMLjOiYwM>3e`$Z-6Uz%dChE}5yH*Dchf>yh$Ni-G-o@~DnwlnG_-52K!b9TG zHhAW-v)4xW&fD7CcQxbeZWD)o6fb}8AVWd`|K$0jM+lN2SJ!(o^0)QV#5Bfl9f+}7 zd{K~;W_ARj@LV+C;F=Gh;Vo@}&9m`S3PI;+dG39D989fyz2FA{LHLfH^Jna6J7PBu&aPNzJd6pF>6D&D-@cQ_P$v#oV}vm#juU~7 z4|0FxOf_akE}f11s}?4aV0Ev?3`&}m3EPbnLl!}}PnQV%sO2hlBz{ciaUZj;8Vrv# z+t6oD&I2R((VnUt9sd)Fd~y@gT`n!>x#BQ(+;*EcO$U{jhgY1eJ?RL#G!A^q^A2D| z*TDyGChFO>jI)~>CZE%>)yqctI&}j}|3NBR4s+Gz-0$`M6@}A1>B=c3c?c(8->qRJS@Q&)6N_ zXS^nfLMuDWS{iTAz;B{hU-)x=xc7eE8Y;Jh1PPZB;O@P9Tb_{Eic4%>qDv2-U1qko zLjv7xqwKz3XqnBsaDbP(U62aF`mMRsQANQ$yZCPAQE)x{P?Ct*b`9|Xkd@S;rToMM zLMM;684eApxPSk6bx2ibitpz!aTW8p;}UXHjX^0mJLQZ>k-7`erL=rWqwFonrPN~ocSSwJoQKXETRrj+qgH{t%q8Gf0 zgOWW;^J>%a@PRi!QIEd?+7opTD*2U$YDecT4y zWdKA*hR-6@)%ehu`Hto8AH%?<=MwODg(W3ZUqsl1z?s&2yc{g7$!nv}YVSLy5aplI zgqgf->RVRk{O#1E^lcO2EAjJTOWUQ_d9D zBl&B5Gm1x^bnECEveZ|hd1c?(Ehwmg9~098E1`cq5AMkHG9~M?>m4r3cNgx}3oSgw za4pi6=$)zR5b?5B|C0D~s&>b9DA!s-9h{t+{jV;63jU!IVu5~gu|+i9r)+-saiN#{ zZLYyLDQ=;17hvC?>FE_wrh@-%I4+C|<)TP73us>=qEX5zrxO(cvyi2T-bx%6swCgf z%u5WApJ|zKONUfv?eX=W!&KORC2;e9q~qknLvt%j2j@)wP>xd% zfGl);6tVaO|3G?Je>nZnE%_wdMrni&8#qQyHgP%#i7?*SrZXRs1bnTqu1EM04zJ4OwE;DDoX=u-AG36=>%K-8ZM3kay>Z)@7Z zab>IZxP`8_yL95iDt5%$%pxkV|t6jB|lBry&#&yF3`$A2D(x)+p zdOjr=cc|eG^@!uhCeoPP!)wYQIS;CQ+d5wl>dpr&6AQIn*%2`{_^@3SHA?6?%GVA z_n2%{N~>){w4pit#Wr3Wj(Y@PDtOkl@%CU3?w_ip8S}`2_xVWRm(S8p9uXDYAIMeA+T{XI*a1uKL)YbKcoT zr99hHU>5j&gGxynC#3bpn};Y{xsR;Wc!~t&=KMX;5S9WBiV13CqJhj{#z<{Z60B{9 z;kVCW%TKvmFC;Mi*3mGk)HdxoRqV4}v%3@AH3r6s>-=qbUod=bT1|kHJ{!HAmntgE zWID(v?3yCeC#_YY+%w(yGYk{8@AYeOAM(n-P?p9wQvF2T;}~5!`MEn$_I2-thqHdC zTfO?od9r)aMq@7lh1b*M*9u3M*c!>s3;KC^i7djOx6*yaMT}G2ZyHL~C z&9RqwBN|<~0REHFtY*GFZ`9K$1r`Awr+2au0Kt-H5Q$d^EiBKY{RM{DCo{g9Aj`^* z(Ea;vmsV7yAJ$@;@UH81e@!++;1m7TtIHG39x3K}YuPI7DAl6bCk74G=Y*m|dLUJ4 z_IXiO0{0naWBXxx*t1FLOy;lA!$Z+~`o2+YVo^AG@G0(?= z_iu7^!m~mukfmOb^UILXOkO@sO*FbTBANeYCigpgvizvhR-%yHm;<~S z3;k)w<>VZFy}X5sROvgtNS+iad^I@rn6S1LFWb;-W0t(F)a=4jc!RRmKzAiBt8y+o z?)5wKWCrJ=l{Bxf?egj2Xg>aP7XcVH&-XwiFU2jZtfvXt$W=AVg|A*HEmab*rFASd zj&7tBRy8>3N01eH5s;LZ%yrpp&7f3z5@@9=d2BS(7g^X`=A!TNd7%HF0)v~vnVC?k zU{0F%KTRC7jOa_kdMMK0b|rbR23P3qDWAM(2@S` z1FhVMK^42iYs1v>m!@=i9wesgP}gDEJSDH(uqt!rSoi|#wQ|Zf2A=s&kMvLrzG}bl zB}O2H0B4%UG@aq)YfJ~rmAl!rzO>2J+ru?nUE+nW#__F|Z4QfV5llgP;;KFXToIel zaDucm47OIk-!6B+ZUXA76^2Whb+feVum--lcV+vp&9D1A{Z~%)|7RxNxVCRuxU@7t z`#@sb8_PlANAaCPjm>oBur$oiwymvQr&oEp84Ly##pAltc+nIjGV3CmNllxE%XE!z zF*_%Q+vM1Xj-g0vYJ0^yf=!Fcn2d~E__T|`u<1^|k*K_pwCrb)ok(_l$zpd(N?|nZ zj$^H7n%wQ=t8Un+c}vse{V{w!Zy#&%nmOZ6qIKKFn7F-mO?65aR-$W$r-0US;nzZs z0c@hQ>#R}T)sLNiQ_=4Rx50o0@hb7vOiS;sLd{cYNn^hgcPv%=PYLV#e~v$=V?eoc z&5@D>a%9jX-iwWUln{VrMLLsrg>CiVZo3(xhV1+Iprx2ug$@t#<;9C-XH5pC0bbvYedMkghQqPyK2JFlt0lY6N=&F0JirUoOxqA zCL6768OO%v5%M@wZRc!Fo4h{PCFWro9e!(y{2C9bSUX`+fp|EYRICn{=l|kketY=+)ZCtIMt<*$K23#jNDoAVOCdGCfmy2_81G(-tH5$sD4=2R*+h+cIPzg zPJYevtY*aSx6};sq)$h^%efS*b&6xAXKSfksY*oWT|hV^Mcz@bwx}k5P$`Gn^-I8m zFdLY*e1sctPIH`kLB=O>L8Y%gR5=>q=skVsBUFf|;{fDW%IVb}am8i)`20Dt1ZuB7JG@5M5<67oUPdUB-KJ%#fM16}nhq-5HwS($+ zvL$u^AKJAEk5dAiXUvUaBGx0+NdejfX$iElgkrS)<(}}VheZ#rJ@vJ6wY@+_(-P5y z<^@|%PXQ+Dn25fWQKGoKuwLYNn_pSk;;udTjZPrFRw#PdVVSWLmFV7`vXdp-L$6S-D9_O&rJ9;< z>w8Rd5qz7ccO`DRy^eQ;6r?9A^l8b0*C zxXenQbw7WHIAzHj>5?R73PVM;HP{uERp}q>b2FM6U3f(S?9EW0*F03G*R0L)e9g)O ze~nh_P7H8fS9jRkXyIuBP?2lJPc_m!qg%qsNFF)sTCxyXn7?&&vFWSqZ(MeLqs>ZB zX#kbm4CqticEtP^_QNxxH%(h@<2pLx;jWmOJNsr*!LQL#c>DHCM|_&!oJEZHlY}Mo zV{hg<`2V+h1$nN3J$34Lz1aJsoEMT50!J7ic0i!?O6SIAD@)|a?J}Ee9AD7aBZ{xL zhw#hX)kSctCM4!}lL*p(jp=jfN%!&?FSSA2$Z!K>IqC0E=nL1`ixZCfEQ+a5^ zY_)*uo$;EgBxMI#FngT2^BDp2zM^u!(}Yg-n9bl#PyQi%&HEGdeoPPnQERf%OyYyJ z?0NY356oqromYii2jb54*d7(PPz9e)F+u47$|WERf-SVE*ySl-?OwpMFjOQhBNN0; zFsD=SMfQ1ZP(bU`lwVgKGsyCk7v1>EiSUR2j(Oy$r5s1x+%L> zj*hZnOIADNJUP86Dv~m@i1KreEi95YHNx45T=VqH7SOpp9Lo{&hN=%H5;%5Gf$-jTQ|KG*Ml?pybM@K6=u+r-@aQ_&Ubu<53>6fm(9sZ1m zdd=R-@$h6Os}<4VSMqmh!QVtxl&)QNI;Cyy^@cYSo(!iy++E8so?3oQMb1=9kb#5I zVPQoTE^Rgq0kapFmfF{cR8>j6nwo4PcVTonw+^oM((!R?8(M6u_GX&& z9ud;cw@HOY>ZdKXxI6lkx_0;gJW_yshrCE`Wyk%V;Q()1JX*>=fzIR9AlXL+Q^c~z z1a$eJ@z9WicZOksU!RRWBc9u4MensgSGoUX-|wa~r+vAe=LtIpF=Bq3xHmKUhWL`P z&}Tk*V&yog`o#YJ)a2yLnZj~V*j4@${^q`Kdd20Cp53fDUe*s#!){k0bqZd5yNR%u z#10N2My(tdX#KN7mD96AcbNMFE$F)+4pZkPBpuF_7Ez1_i%NzpF8^3c+Za-m&ldhS z?X~ZEXz%}=u8P@D27zshcA2W-i7TtuE-c|co+?dFHFC}ERtyq6v9=iKd=PR8o8par z-%$5bW)CR$sB3HfB^uq{FvvJMhPUzbw9E`0NLJyE*YOf3`3m$oMbqPds_#vzHjLHX zYrm@D=SL-igQyus#F?Ns>p>kLUKOP;%*Ub@z8yq9^xAl=8a|#UCc82I%NwDnHt^vd zgI`qXkZ5q~4hav@ciKy@P;m7>V6pzC55fG|4_qW{{YsFp!<|~QeJwryTzTVa-7#@QM_zO8)*%5duA;*uCT8h|`9Z+BxpOptZJ3QaV|+4*i-7+Ph?UnTwFHq7{D9G?ne14PSUim9xrQCvUr zUtfLS+=YGr9`s)WkW3B#@k@=<414;NYdEjD&9M(`aNkySEbFuLgA8f_Xc2|MGmIPK zX2vif(V>Nmx=Wav*eoMx^}&49qZ5WUocOD3uF^Y(4km*Q1O+6NNCzQwLT{m~)X-Z9 z9qEM7dlGmD!QbLsl7ddDJ?9AkwtlxPsX0xvDsHN~RMUv+4712uej9H_CsmH(%c= zVOoBeen|JEu2^nGk?|amY4bLL7Dci9P1H4!?`$CEmkx4QGAvhCx)g0bRMR`nzi0E1 zA0tuH>on_OO z?Nox>P`llHP+NqdNqNptiZH3Ccbnk1jV~JWFA0d=l7F@`=s67-bj)0>De$P|-gJn9 zM{|_OlB={vMUw-#gC0a*_TkArxTOfd(BnU!6KD z#_PtM%a2R4vjU6Euocaa>vLe^O8M~a2AO?WQ+r9_DP+&3ZR01Q5mm*f>ufspaPqXx zH<9%aQtFIQk~VFA zz;?w0WrpdvEdF(m`TOsACJJGml0Vr8yN;N43D9CJyBwasseMVA1n6}o3cMV)97*|NEgyCNoyiYhxeWH{E#7+Sz=PF%zH3E>TR-Y#wWW)d7Yw% zo|Fn7)bQJP#PBK!xUq-txEy^@PpWtiIrg2~ja|}>T^))`@0+`f{WoVtAdM-!l!?t3 z9d$$o*TD~Zm*tfOS89GrF|An zLl$tDh@k1=djkQ;l+5{ZTmA8G!3VTH4&T2tuXOxWpkd5ug-**W*k#R!e4>D?9URvV zeq$L-J}-8;Ff5;w$F`L}r~$%=_(J5H$;$PqH8tVlI!POwQ()~Lc=*m7Z-Z0f-%Jx0 z)$f*$2)WF*c8#T1N>*;MC~&UHQmeY>Jw`L2CqaqW(js?x>ibIW5m2a$boBc8k;8rFtS9YqcExJwt zjRYNr($#Inc*9C~jM3{b`wR#0SI%)O>rD1cIYEK;OtS7pMS-oQzZBffW5&N-#N#3h ztZ#%&tC`EL245Jo0s_IZa;~2CihDv;8?T~n!)5Cv|2%|i+(+)Gn;Z8f}>PLfnZtq}<{MwxuN}k zaUnXwh$V*pAbYE*8w$Rh&z0*J$5_8Yyp4SHt`NW7H>sIed%*};!=n9~`};vzw&}ua zDO`wxJMvB&c{IAD;GIKwGpYDJnK1R)AWJ2}nfv)L*(h1g4ibW@l*ZU2klVW>HePvz z7xKeS+I9J-2p<~F6tX>G;vB&9N?6-zf+w+Z27*KchBw{0LD=zP#0wR5L=ZfZt=s`& zspU$i7S!L3bLv=AIV9e{%PQ$ugnc@4#|phWojFQ8(=%4`4oozdTtW-{jsq_=*86>t zp@dF1h`ZYE0-Rx-0|7(xO!ZS97hj!yM;TzCyKG~y*pb?sexJ`oWH^Zb@mY=X zsh(RAbD?}maC@&jZI_dknKM?_reSAIy8E=;pIwmr5wEyni5UrUlua5;^4B5#i(@#j zJCif-0ExE)YL?DQeomB$&~=`F@-#7&@N)?|pO<=iBEB-=J_Lxy(?i(gf^!x|aF#hN ztd$*2Y>=gxnjW_6gXPL4+jt75$G&b4{-bzZzVgn(w?$&_m!Vu6nVXaeq(1kh%E-`v z+#FnLZ0D#Z82FzI+a{TnKMMC5P62AFLFNi`ww?TDSL;tRM33j;r^IRJW_gfzB`Gd%Gl(hB-DM1_i z^g_l;&8Ys@rwBvYDkS3Ks@;KVUV zG?cV>n_M(8_K+lNE8`RFO;OL-RSrp-HfUsTn{ha4_$q-@JC#Jv_gg4~&GCJK*YTUt`k==P}}!mbb1 zp91Szg88|A4}~MDkW+Qhqq(*wfG|Py ziEj(@saKsA7p(pn%*AibXK4GlMdg{Wh_3a_kw-mpL zSIhp9Ln65kvh9{Wo3LBk$!yD4_0Sh}8UsnleebJ+r4e6dK*vjZ6pp=lQVN^vAm02R zx>|6n;%wiYGd{9m8!~jMI*(#j2Ivfz_;%ce(dU60ZU@7#LR=%^_P2iTq#nrx14%OM zwO65{S&e8CeAun`S=glYk1KwAMP&EXR)y4@Ik%*dkKO2Up08c|59%OG1A`i220*=V zU~iEyr0gHb$Xa@SPxkip+YcNV-LNmmDa&s2uZDFERxOH18 z3^u5Ci(?r405^gyGqE3>$&PNBgvrO^@0DF58GNuSLy;h=9XkQqnzf(mo)IQ2W{XEFqy zMi?JwG_BcCm$GWDM#S|?sY#1RD|DcZg%TEr7gVMDJK6Q2{c|ubPOkc6nkALbm4osl zaT{qJ0%CA(1}j0`)7k8%l#FLMTsb0mvwKe`?#i2FiD!}6FuO=qnAv;&qgA8Y68L+0 zCEZA3xTFLy1C6t?b3@4%x|d_!VikuZo0TmI_ICX4*eq7viX-HOD$gqa6yu*KF!G`O zvCCLNNXmC~f5b0cZ9tzF?8c)VSzUh5-G1Pvn|NQh9SE!CJE5;Sx114i?tQE$TCMFL z5=J4>L(8}DI);LPQ$Ndycw>Jt0ohW@w`kLckdzEq>e?@=jw1t%;#C1DiAx~8w*@aV>>>0$>m#m7mfGFpMv7{QV1u3N$FFF zgiS%ah{I+2OO+t2a%NJ~NaYQTnjswPSZ<=E89$}^UB>L!DSW9W`5xQR^bhh0p5L~3I1fEMPq3BcSiW5){>lfn{788p>buWcLruwlk1qvLFAZ;p z+1XR63sl(InZxQGk#sElxxk+FJIOu$J4Ivs+%@&`dPrZ*1)M*X5^ZM9h8S3KaHw?fj>Qis9rD(J=dSn>Z+pb0I2Gc{^`M) zAb$>|-`;?lk%RS1+Ex4XFLD*ZeDIyI?ty`7MYJn^&H?wO=c7WvmR@?dGFBj4L@5`G( z`AENRi{wn~Z{gMO^ffjaQ4w+8c#O0|E2|Cx zjsN#J6cG_)J`6?kZa->J5 zD@XEnq1CWOy3(S|(_r%8Gw_Viu&q$eYL*&GdbYgK5i^X+RqlVgV{5)=4E0@R67WG{ zQzqAqgkDR#v~z*&JG*^;nS9UC^j7*@I8bDsAfJ!)*BUFENfYs2yNOgY(jAkBHU|Np zWZt)bimyu1Gr(YvRkLx(U&Z!T1xBOd4GqMKBV!TvC!f;GZr;@EF35(%P~*Y+g4ESl zdx1}C#UuAAevbiYEEihreEN%afo8b{XYjPQ$x1Cc>q~hFtFFIxj*a!!V_UH!UM1Dy zeZ`pmCK<#23M1D&JMvJ70@ugV)=)N9$@1=0vFEetg*ANI=xCuTnudfZZhmoNp=PNk zT9d7}!_uw#g^-%=j<3t-76=Pdn}FPnj&`6*xuta383jREq+nl<$?9qF?*wnm^W${Cp|P zU+Y9(jRlD8rcB31W8Ce5B%g~sU%W@HQZZra% zgBr{sXXDN!hs*eW!PslB?m`c8E$f(M!;%#;@z?@y-Tb?VO8vTvk;;1T8$mOgRxtw= zHR{Y!lTfx~bDTuffqn+o4gHgbK8#$KZ1kra9u?Jq%b-Gy*q?1PcUw9JyZTTWs4$vk z?&eg}V3Tj3mez1w-iHqOg8JR7!E!s)j5^3w>d)y^FFI}DJSy)k++sC7Y5TX{wms)hJJmOJuj28l6yo{g4XHWa=L zCwpgrizq2nksEsl`p(={YX#EzPLMDa1hJEGmCB*)(T8jM1%+LH=X7)vok7QL=RL_1 zROW+t!_o&5IuR9!5*1C2&}5pBuMhVa+_;R*9O@mt>b?LzkO+R87|?3E+n`}2T34>4 zQSNQuKi1|WvHQU9{pMgnccrL)>Vgz*F6=&qy7|IMe-+T<<0l$y1_c#ZleoP+2;O*O z!%5Xk$)cNA2Y^pkrC+3*r>0=Ejz&!MInG)5R()!}rCneblg$ezx3l<@g_cqZ>p>4u ztzm0{zr1QsO-XfDSTf>Y<3L*-ypXkB06?) z>u7MQk^gCCl&d8(-K&g@T*-NA6_8RnBzx;HUyT{UeG&=HhAj3uERsh5G|NV6y_}Xh-b|fY~sD%YvuZfRL=9`&1-JPA| zs-fxZa^6j^8`*fI%FEFyc5@&fCPL4Az8j^br#B1!x(MteMqc?j{q-TZ7DpEu&_4D$ z7yHCMO)@DQl)ou358%IVc$0?*dr&dMBK7+dr;*BRjN4?;TDKY?Tz(a7B8wG9=E8|~ zLPz;uU%9tj>3@dvDgKT#<=II+X??Bd{r1>0G|mZMU~y{9^(zgBr*Blk(KWY@9egUE zVygtN22`gBNJMbYXx|<#?7&|;r ze|GDG9X;`Tf9>3sDrTx(O}KgvYMmR(sSI*SmI%-|f_`Me!tJQ2Cg+ifIz9$*N&s^eu+>tF%I=eo-A=>^GY~_a}$R@zHqTcK^ z^ML!#VxT3T900ZoiO zY1q9@f-%|-m73ZzvOPM)b)U~;#4C+F8^B|PHlt$}c~lK+<|;TyQIT-wLzs*)nR?!j z_awgtsg3R^NSusAw2^0*A|Qmk3%jxzwP*|6=?In2{d=Fs41hcw$N>FZ3HB8d!mUDi zG{QN9?|#<@V+j3MV!o;4E&S7^HKaImbMrE}fUd-tEHoxlWu-0Ny|+u*LuCbGY#dj) zwuS}2>qp1R-N^1^-#gBVBGtG}e1uMB>)#$;azu8`N)dVvG}1K661%urj!xhsz$4mn@gEWwei0$K0BO~Z&lzviwtEAYtfSmL8lPd!jL=)2lc}C z2JbDaVG|#LGlGh!`$Cdq-dP~Q9?PQ^`Pjk&brm|74*3 z;k#SJZ$i?o6)KaH0p$d0m!Tj^R&1GTan^_q^ zB1be&c55zKqAG2EP47JogL`>VBU?; zuk!k7C^)(6GkBTK(=JDjQ=-ptav~4sIk7v7sz$d@Z^dR<#q)v`8VO1QPdw;mUA}yI zU{880#;T*Fj$`DlkOI)hctzm(HIR_+QZ6@}_mcq$Dw%++y* zOm?e@6SN60dW;pVw7c=2eYZNTJ_Q{g4jqnEz8y?|AMa`7-?O{3@h;_PB-o7$=t~L{k*9 zU)9oZe3V#8P}R;Jw_NwF`qB9L3Vs@nLA0M=?;tIg4*d*~=L1Sd-DBvg(=#$cWe&C^ zcd>4``nXUY85zS=rpp5xR(AbO?-^uY^o-Q;rp5Ew*w}z-7HsEpW4UHK9_toF;nAcY zDOGNT#h5MimG`9LuVpH;!=J<5+QhYBHWh zq`~~bE08SD7-)fyR$H|Kd@PCI?~7sPTRE#+Th({Fk<~Y~Q#FEQ9Co;nCVZ5=?a~9c zNkPdm0kA8jV@JG)Et8D_3VliCy8rqcP?`Ij}bwJskX26*Y+1t~wdnS_m!|i6;!1B({Tz6}# z&XMimo}20aTJuvX0sz5(LCZF~a?nUMzV3faSQ;7qEL_<+T_QqCfU`U<)C_=R+eEHs3A}95vD7U#@tR-n~^!9mW$7KC%!OC#QjUR5cS)# zrpq_)$L_iVhJU``Mc%S`Efx8=sCr=>7h3xBR@|ZMfGdw5IjJUAudS=g4U{iQADYWH4)1}N zBCR87k+HCLsU*@Lo5je;C@~VDAwPW?d8CT(c|1IFjS~$4(ngP_MSUQn5DsQPRMIA7 zmLhiBtk(C0L=L_D)OqB^UA!>-`T=N$(}(WUa4gye4BxfWO()N$Lae0rKU_*t4q*rP zh5O>bb&x|)f_3AN4(tA|_}NIqeCN{zA;y?Eisizy7<6VPg6CkJBW6jJq#19I>^i=Y zZQ!^GRHC5|sAr8bNh;@By_2yQiF6p-U0!2}>_c6KL5{<+9*b1T&@HQ9`9&TQf1>Ws|=+1!|)ynQq+Pi-mNccJuB9Nv_k#&-wx?Y=1ApfEs zO9usqn3h{s_B`HeZ~lrTUD0aQ)SC=v9enOXuY(QYV@XmvYqAb<_fQpp3y z{%EJ*yq5Y%S3Bswj<qhzSG5mK8 zM%oAk<+WnIRS2}sVUQS!as!``ItGBA! zU}`EV`B+CC-Dgd~aWWPZjGNC0U>qGEFSOkn!vnfl=u>ld$xOKaYiZhRTkJJIzfQIAE3nahy_K3%Hn5I0Q9~7mGw77n*I>`k1-u&U2(%80zzATF_WsYW= zb4)E2%axp;nS>+V>~KpF2d`v=6%xi-sdj$ciooxxYyr8+PP>Q%(`$w2)F5r1XHm6I zVG1%zBcIG{YE}W6&2Z{Hpkfybe?2+5R&Ie4mXnA6nlFp&psih=_8Tjb3*Frmv4mb;L>a#kwG-n9hF!6^ZXs z&{0Houe1P8@zyW!%*Q5G(aSB~W)`#ligjZ*mRKytnYe(_W8TZ3<_FDTV2ru)5g}=8 z*_I%@{%}YjN?cBJZP<}cJt}Hw^jhq{^`g^z^s&9EiXTrS5@d8{B+g*&%-)4z)IAIV zlbsJazst3`Bxkba*|PF#6F#QhJG=cOJ)sJA2>$x;ANyA$Ed>_X=QK4Z-TDOh>=a1q znVFeJ^k79h*6#!rCRqhK6V5BbRn+#C*(ER~J^zvA$9GzRmtu=kPkT+&#+PfKOHq5} ztZJpU-&;OI8(TRqQj^j}K2W&j66`Y5bhVU`(MCU@HG%!pFWz|Ga<+1^&gU!5TF5~e zB5@Mj5d#&-b|VH301RG*{I?!!Y9h5U*7)00wWBwcEibnr=Y@Fc8Je|;LA6nDf{ZRL zIHQe*l6n>%Y4a5d$20$19mU0^=whxKjFk-I)SkJlqH=ewiFSQ3IF53--R7?SU1CPM z+TDio*^3`~G+1a|`WS#)pcX)^H# zI!`6JE02F;&y8n{KAq+{Qy<4VtmRqNN~<`gj@(rgy=l1!x!3;13u1LJ-@RD?Ue)*4 zO>vRjKR8Mv>z;iZi+-_f1U5-rtEbz13=D`tFQp8DF0|?4<`oo-Xz-)fdj~w?0`ZIw zu~(U8J@fcaNQY2Mt>vD6yOi?eEF!hV2r{Vu@)b>LczZk2h^ZbSne`~p@{}ESw`OAd z#%}jrtH8@wZZ;_%* z@w|h68n$m{C$aRTLN-cA>!v%PXOq-gy>H-U?fBZdB%u;qMq+f9h0>RK_}0MAiN!nQ zgF93^g^6bT24l*viJseEXUG~n}hM>*xgnDRjeAYeR&XqXDf349S?7HGs~Fq!e( z(nNOXYR3Brp@@}E9yNl0Jb&0f*e8NQubYEKEP}(s!v`GT)={~#QQ~9#>!qG`{0zpi zm(PChVs`qoU1mEF^Il1B)mDcy5M#`QH*U3ukZ`B`u|$CDlqY!$rpkU6f)+6b+81h{ z2gWkvzOl#sj)KCH)I9tuRS*P305&ur%((k`QPJf4=OA#h*#8Kvcg4;0QoWY_a!~t+ zo?D8b{561E#G-{ZO8ePOt|Tg+s!E)imC@){5C?b_V*TF`)x-f(E*ur@}6{@g|+xJJTOf9*ekuudY&iQcsY%zZyAayM0mP#KfeS=|W}{ zx0(V3xyuFalHNU(h>U_Bxi8~JV_9PZ!;6rKgOC%4F%9qs(ebS^c=#}`QuY9_zy)_0 zof%wMG0XiLY9{_I*{*VTO#r`wCkgqN3~u`tnvcD2cbB?$r*h>4Cg#PHde`+Phhw&JCEzFdSjeWL<6jiNBt|z)RR$3?3uOtfc&S@>RRM3;_ zj+Dq`bmxO-aV5{Rl)uToUjEG2d?q_dr?Tu93LJIC>lm_qky}!*!H9g|(}&XmN1v>A zyK3C>`2c!_N`7_?ShF8*BO{b}qkHu0B-_KKL=-N+7u7?@8837b!(~*~jI;uo)CfN{ zRW0UkAcqZ4=hl5k&3ySY{(~dG_eE~8PosfM*jed@#FrBXd=;X7{kkoKI!+Z=2kpkc z!fr}Q^-Y6%SI$^BJ->@u&#&bB4OUN4)Msv36cpIZevUV;VWk-x9ZM;jQ|3b zvsC!#ia+;1(Lz?m(9_wDR%^f7=~6&9_a2h-2vX0(8R+j7s3mcJX_Kl$Nh5_=`y&d8 zZ$^XWzmurJvZm&!>k|>_ffh5HZ29MP(CTM3-*Pg@^|kyP`=ikUt)@D9vuDU8-8>(V zI&3TT#^gA2G{7$|*4rG-=u~!fFw3LnX?NPee@KE+)^m8~&y+N)=Der=bavxeQ%_x@UZaxpW`L9*-7@PPVfbrf>ETTm!mmSq!|w zUiqJQ!>xiA@!C;Z#8()&9oG(@YzPvfSv2m?fh*f)dK^ABqa_s(4|R7m6_hE-aRu#S z`syy2-9E%nT~m0Wo7v#Hi>wd&8)1l0OQTEl3!sf*;wdZ9d3hh*N-Ln?*7jv)LQ?9| z&vQnM!oh5U&!kC%E9%m0*`70-7k$u)56b0TFM5d(TY=QsPPW6mpzqd^j zM2fcGeFzqQ61T+CNX4TN$&o2lSrDi}y!`2h-)9mwSyYYT=j9E3_wJv=FadZ| zLoPWvV|v+@d*#0a`BN$@hx@)bf!H{73vYE8zD|?ZJ3LVLaG*PXS|6VIG$s4{=$l4D z%J%{j7D#n63e+Y|`O08U#z21!aVQb-&arAIs5)1nmaSpVv>LBz1QIUOE_C@u7&Qxj z6a1L}+gbITg*zOfPWLDlP)|^3+_oq; zeygae79`|WZAD-8S(%7;8+$y0nKXbHIA1foSQqCQggGcc-C~L6R*Y z@C{Bqz5HoVjG)9xDZH z;Y}+;%mdUfyHXH0+ zUyF)vHa`Y5BljuY<{M44&1^VrE$ymh3t86E-X`E|X<2Mj63rIkC;h@SR4^+$6M6ca z2ljjYwANVXt;VaP%Jd3%;UoqoWOEu9V}X}lj>BZnDq(;@p{$g4aqNz0!khq~|MbUw zpA8LdQ&Ub&1?h*jc6>%E;M>#6RZ5nvS$=(sM%)B!=2g0DoT9(5#PeQi-2VEdHS!?l zd*%Z5ZsSkZ2lv$`8!cOS8#lK_&ZOr!gfm=;X!hYCMlM8C<2_z!N)dN{4UzhtvO^E# zS>bT{*lb6Dwfv zjZN$&@mQ|xynBdu7jE-~y1%x**4$fu;q6T?FA*5j^U62H&oj2InwPu^Ra0)YEJ{}Y zc=sYtBYp~!z>SL)e;O$SGh&an*>mxE@X9!ud)B@|oWLSw_ghPUZ|C7!XNni3@jP+w zKd&CEW-*t=05xRGBtu*H_`F8K*sU%hV2qtv!B@`jK!KVnLE)$(tmtP5*oqXy_e)L) zviyRQh^1;^O&^_a`9`;zaZW!dOO5tVG?cp&qnuy_L-*{lod!wsW(3!k=|;9;sRmd8 z^ddykw)d8PiG5V8_d>=R7*&))3>my2{;hu z%gSPPpi*)kGS(F~Ea_|MwqRT%^AAmPgxG(ji?KEOJfMoylbBZ?;`yGMdVkd01KH~1 z{GM*=U+V6nMM&Z%XGusd= zs_w*C3x59T>EA?=j$xp*n=t~dXphy?Rk6@1<8TOTlC!=IpkOPjj^)cqn`;dfGDLBw zti3%YuZdzJq&*FdHrwYSeT%(hbe76jLu`6sMc^)*c}wgKUNA_Io&3xv6j|;v>sP{E zC+XE=(N6{&2-t$!T12kbCjW9r9Itj77^%Ql0_UyZDk@lDwr47~t;|wGoYEQ|rScBKOxax(*!XqLqkkD?f z*t6%VbPkvV4Q^`6u6}@&`n98z_cziM@EyU4SZ!k;VzC5l8bm#QGAP(1+t$Fu&M)eb zN?_&3xuhr;$Fd1(60?|HzkrNShcJBg++pyWZ`L>n1-P#!@{39IV;83Ltr7!^OdU0) zmb2^JNez0`&GS54NEp;R@MZwmG5O8DB|cwtui&-n!TVp`j3%9r-E{*gz1QO7UJqLP z*86ZQmAsX7s;R-YrywG0)n)EaHg0?cv^D2=nBrufp)1WlkjD!`*W%XwRrW(+i`jB? zbU|xBvW5oPT0{Hn@@TIXgn(d01S+@e8CHqDP{cDm@y8RN z4K3O*wt6y{?rF$!4E1*Qu7Eph6;4f+Z>riKhs|?AzQHRJ*Gs#+=) z-1PZ5cb+$cSp>TH6wKn?vuX)tR;;T%A6ltWF4X5PB|7u?saZgHYl6jIyB*7yMG{_k-Q>l>5pcVski4ArBf3w_GmsB8E}!Hd<&!B3QIe2Tdy%@mj`!F zs9<&~P+-|;26?$Tw(R6U4;Y7mz07=$^1ZHkVH(mZd)wQQxAZZt85DcExD2JLo!_7D zAd_qb>8iW9G7Aa|Ew&c%=%R8ErD1)PGSe1=v%hlHn417b^`Q#n35M=uWd=P}Dtb)6 zU&j?yooRZcoxX0zGiKS_BaT1)%m>C<>3&2(*QhFLO3+V7J+0CJh;pHgUC`nnv2D%u zfr;sB{$`ctmI2Z7Idwrrr{$u;xH-gAFXfHUj5O~?wQwPqVpGS+4Puz>Nym*cJf63N z{ONt=^yi`jH`d=YNk!)N?Ey1Zq<88U^L=n&kHhlbX@gW;TaD90nl!bg5A0ie3F{H} z5r|g}L$}uUV)7G!lXTtsg`*V`jaT~{x6*!(ltNYr+3Y_#j-g+Mg~`${Z@Z zyXEz8I`6%=imh!U<*dBxCrN75{kskk;o&!u8)gq3k@5|$^+H(TW_r^5Zeq5QEw;pf zRp3%vflh>bss0Wzg3Eec!FJh@^A9^)M)kM0A=6=y=zfRphJO; zaZgm#pxMej;cF1&>r8Y2dy^KX`&<#TLWzIeM6RKba;*Ei-Dd6{5l=~sPRIVv`u zD4(Mq*;tAI8Do;JQ+41g7IU#~@qT{NyY?3O*y6FT_f5vb`Eoy1Uw+VQ8}WH!*_SVSG~OI88m%jXH|O$Jg5cGa>x&(ey#5)@$3&nv5^?#znw$y1RjBpw#|rn~-p=*^mE(S1jM1t9^=k9VrU3 z@ubz7MTE=1s*q>QBDZ8&HSB_#ZKQ7Ha%LM+f}iOT-OIPK)}3NQuULSuK7zL}6s(?f zYWOmD0mFk5y2}$CT;{abTDcovnyn9NQ=)PGniZgzMaV)9hw$D^y(zwYRMLtQEwC}(Y)BD>_@w8 zS+QWBB@Mz;V}owuTiRA7U8D;(cw47k-k_(<%m1W_)!J_SEBv2TIaspJEfZ_(y|BsV zu8X?xQ^foLRxlhN92y(Tm)zjiR`Bv@@{h0n;f~y61?Ffa7eJgloJ@Xm=>AWwffN>h zc5m?2jcj}#!>|3{Ec=WVx((Wn*S<|crSFqx71WI5B+vO%UoTPu(`m-4_V+Yz^yiv7 zDS*in2L-d2XZRM|Mk&rnd%Uh)PuTWn_M1-^{;_WeT8&It+r>VazxdF?B5sEqQ)BB` zzAg$>jNEa`ktP4)*00V~rKWp~T<>6ir7&dM`r%Tml-pvfKvy`@AySYPS!P7CdGc(Y z&uJz}g|s0CFx1n>vPj&0=)LuC!erSU6Dkc0o%h)z2QIhm zgjPN+o7X3E^DTFf8rB)7?nnXvFmUkgH~}0fHTQ2~HV7kkyajZ#PY(++X22J&QHrvS z%C*j(J!=%SwL7l~@PSF~NHA%QzZP5a9~eEU1uPEa|3v*ZtZ>hv*z;2HaMk;=rfkj zdYA%&W!f}P!Y6$BVdWvh9hb-0B6-(4|G{$3#OI_BCC%^*K2s3~8e z7!QA)MW@cvDGUjgF7mpjs^j*a&iCo$$eMQb>tvr#pIO5#_@(8klpBpUN=i3+@Az+q zR#(MzwD*{pL0xx2+GZ!osI5=lij_d1xe zV__v&Y_8#q(QaTga%Q9y+(vx4)%n`GXmr7SO_uX+?MRT`X|N9D+ZqL3yG&#tmIMt60Szh9BmpISMxlG zfWrQ2hy{6PwZLIWg7rgK^xz&d<6+oI^1>N=;5$4)=Y&UGTwDS+{JIg}@tjN*Thi)y z!ZqT{hWY%6OrIlVFSX@U62J`Ixn4D8I7=G=s$4K&-4K5lS#I&A;Y+K%uJTED^7NN} zr_9i`wRTfKNQc?IF)=CY0~7b%jO!9rjuVvUbOimxin%Wa;9_c$NP|NcelrC zM$FZEffFPPY<-X4An}J2ZLw(D+}b?~sh-|)sIpkseQ_-^VenP=zPdo21JRqQvTN?N zsVl0t_ombfz{wAMza%xjAg4d|QfTBT$hnm6otDP6bn6*qZh~_-s5W+8dcx}Ive*T) zzosG3Cr(!|D5!uE?Rr$SB++vvdm}13FdFs8pV2yLy@L>=o$IbK%|i2y%hs z*m`8Pt%?>xi1muXt&4vqPvt}ZM*?b1UhHkmLp$%&;HQ&Dy=K|;qRWJVT`cs+nb9vy zOh(Rc!CqGwkO9H4J?fJi>-jrC>*>>%R`^3Lvat0l67gHG?xbs~Age+IP%y#@lF!10 z7-%f5ueC?J^|gU~xhg8QX<@y-2(6Q*HB-8+B_iH$s&|(f=wHp>ieMZ9OVC5WT$%N? z@EUS>yXs|PwZri5wiVQ(fHIrdTO?pa_bJfbXoO`X-yQj}vBb^pRh{;GKS*S}{>lG| zGTre+fFB8`({h$7mgS>FEI_&we0LfV6~!CI4MBiDwLZPn)cM_Zk7~{=-JAkag6Hou z%p&HWAT-7y(@R_7<*{`!uqoGu)P`D#Qn#Iq^CNG&sPKy(^w=H<3_MAZ%<8z z%~yj|xRLhnCtW`bMxWKMnK4EZSYk^1o7&?>7bR$xaBB22x3=7yPE^^;QO*h*_PKRX zcuu4%_QkZL*x#K%#u|^fVy=_*~2|d&0-F87g}i|)zo!#B6|D#RdY>7)kuj!tdfJM z1OwLRmr~T8iHnInA}S!LTfsmZZ;=8L5G_j|_2Merbbr6F;d2eQNRZ{{s9M)V+Qrq3 zR`tK(V3}Td?~T2qyy1=#^qGu{TWkL@BJuopw-Y^*Ju3fTC<4S1c83)Dqn6#0bWW`gp)q- zc1@N8;!u_g836~dvXm5~cmV7r1W6zj*NM13AzPH}Z+?<$r(fTG?H*|KX7u*z!O7k< z(_uatkBKN1E5-g5&9^#hPsl@U_v>SY%}53{hk4e2VeD!l;A!5u<3a)A^;WPLhv{ zOQoTVS-l^f8=1M_{Htvyr?|jI4Pw3i-YHxNc6nG&cT_Ad2SjSGz_hrXsteUjct@`b zS5-d@WLgYokQXWhua8*_r+ytP?)KtGog^>syvVE8ryw0iH^QA#@Dhd1TC@UT3|i*@ z6n2z?Jg`rQLRrYR8TOr$<#ao!6WEUlwJljD{9k%c)N}YzVl9zmcGNxSUTKj7R>W&_ zehgzosM?-z>>Bg*r&mEI>MkS9MpHdSnT{XDlRnLbnF?kLh7`8g*y&V zYlb@QW<32Vy6C3!85yZ&Vew+&`(0OwSRZGTB-^_x<8r2^i+?RrqnQNd@ ziIXd)MkfO%N&nmoUOxBrZnZE-fcYN_$@`$K!a`@BA51GtFKw8%_|{zlZ!7!_8T_;V z@bJ^AIW-IQ_A^2>u2;cqIo1EyKtGSuc8(y_rrMA8#!h#d;H&(bee24Fa8WE4eFb{P zEX0WDXuQQ?ru^{u3yD#=$|U4?YA@Jkfr)hS{`N$~l*Ru;)>{Wexi{~_V4#4&5mBT> zN$Ktq1EdwCQ-KAfq(t&Yu#l2kSh`VCS-KSgfn8E!NhOwCkXmAi-)Gh5Ip6nr`2){U z*uD1?GuK>m&5UdxJR)5kQ$hvanNbFBuck#Qr1fX=VbE$A^dDgWvTVy1(Ew{=}3S^S}Ah36|eJgCxkscBi|d%zBvuD8;Fmyx!R07iQd3Rqgmqny@V3 z@3vRvboZ%Je*A?D3#)$x=bn6ZPm8>GJYR?a{L*b`QK`1H3^|%p<62k#YXANIqrIF^ zpE|PU;0d)fl)GtA`WdvavjJ%!Ov5X66JH(h7CCvgAUnDDAH{hC>9NWM;zINm+iWwk z#nQ-G#>D7?JR%!AvWgjQ*lYV)ljp;t`+`V<#^c9%K*hhXEjPQ+#i0PPkNvIjv~vBo zgkVBNe@>g2Ej`;*S!v>~p0vdxY@n;#Z>~1{q4>kQ)GiWcWfq31HXy!)P1nqC@0U|8o zFM%)ncwIzlx{YPZov95@rKTG&`lYa*|B<8oSB-MR&-1$njVB!2V;?AYbi|jEI+as8 z0zo?7IxkPdP&G9%$&QM9Q{X_=p8B)V;2nB-Im@a?IJ0@-)6+Gg9*;|Ax#qYp3186r z`l);>?1B$@{ew$2biE?A8#QM}v-ZSHJ*bAWBXQ<+*!<~4Y1RX`J;_9 zz0+ICyG;gy>z@R*jDI+N^BhEtPZ9KAeO~!3S#aRc?$hoyp8|cFN15`9!<_j#u?~Wm z29OUGyr|I~&gS6cRBqZAzDgH(;rqt_yqm09BWnougwh@Kz&eNi)jWg$lx?Mx;bRW%Eue4yq*>!@ zV1FrP8bOczN>iH|39UYtM7SGVzf8;{l6Ny2@aibc3Mg{=49ucdW!-?dXaWBBvVrJU zJ4TMD{EANdH^lkG)A>Nw&~x*_LZIw)jgUZ!01{-`l$6wpYGQ1zVSP^d2YW)JCF}93oa18`4dn|z@lWMTzFTj2*g>O;(_~auQ5`ZKCiX)gYlbVgP;s3r zj)&jgExHfUC5&s(2?@G=z+MvY3Qa`S%+GgzM|hmr*TrA8 z>&b8KpK1>&iDehNxr}eMtkelkm*_yk4qIQvr zV_XXCy{^9qR%yNj7K!Z@?@lMNm7Rk7>R&92V4t0xWuvI2UG&J)gh)u7|8`pj=gG4i z>c7eJZQBydIMB2714EbhE#(*833C486Q0khpRMMjcw(|-#B9`2J3sVhi+Z!0?!qf~ ze=KX@*&L266fP%TyAN+57gV*`Pn2pYf5RosK4|8XayDhvuG5(Ol=H>TnanW-ty<#) zt%O8HrO}C<~L zadP@MOV4>>!=Lg~(GJ8Fwg@qW*>$$^Lm`65GwB3_&SVK8yawLNsx2#5D`X^CY)`X^ zYc*^?MJ!+K`l;7vQ(UfJF2AU7x4;u$k!k0>FYzh3Sg~mX7JqlV)DZ$p);MO^e)zbG zZhVL$)pPt3AV`BG|5i?dH5x7WSNkIB?P7mKQx~VLcHgc674Z!7Z9{5-*ZgQaLEXXO z*)lC>*e$U=`zKnzcF~njztU$o5)GL2-2zPb!`zJr(xU~p5-1PG&-%04Y6goWG2kZ}hCBn{~X`WyUi}nQcN#LEC)g9lPBt_9r&j z?Vo#JC|GycYd3605$0R;JM?Ok92oYgw+dcnB+c}Uq|(3rKUn3DQeD3lGf9m`WO%_` zQNlE0x)e5tey`Ur-rMf<(>T3WWwHos{ifm~`f5;iT_?gV;sy6Pzj4#DQs8Wt+ov>} zRH_5|<}}Zt`Pf^-E+iV}d46~?U*b?ld@qvGzcbCjTa9#SA;gq^J=!xtplczf5vJ4d z6ETaM6XCLc*V)*-b)UgL+_pHd781VG{nn_gbnChq(8@xV$8|Rv9CSRz%YI(FwSH^k!T8-oT?9*# z!TZ$bT7Nd@{C_v+m&`jc>$DfvPu{j5fx;>D_6Y`cO3E)9WL^bU_r}Z+Cig}*R+tu! z+`Ho(?jNP0lAprbQTcyhn#~4>LCbrzVxwTTNm6RQdTVH>aAeZeZLGN>3pfci464M7xxE38F8u z^{qSX?ry0C6>Y~(nt6aEY#ABNr#Jr;r6F@Aa?-JHzw{#3}~hr%jC$J-Vh6dvcS0SMrnA+E6vv#8gGj z$h|;GvYr7#WViS{X4WiTVTvu3VfcH&=0fw#382>Q_}B9FP*GjB-_H_t)h*E=o#>hk z6+AC)8%Y?k?;og7RAFGy@&ilY6DlS+SJI&`3BTB#b+r( z75s&+I|Y74CgwlqcI(d0T~nT(x}c!58IY*db+D#6yYqP#Ee%6#Iyj69_>_OgKOEJ#he!O#HGW*@xJ|Ac2t@aP?-VKX~Mh%vmE8 zo9<&Z-4K_PcH+5_>ThjSBD=Em0u&pCUh2LR*T>eT2u07ABKk2vJuWtlNfX>;n!h_< zqK>{SC~0lKsPPl1dxSPoKiF73sICiJzOL*_26}6;r0uc$Gn8S0=MkuIlL)%5-f5qpND4rP7F6lyaoa^zB%S{c8E6-tk_IuH&i6 z)aEJ!{V-Nb(r6zt#QZEY$T}Kjet z`PXB)6M<5SF1Ymm!Td^{ll_+>MqDYvyQ(D&xPMP4WU%TnPNQV`MX@5HPJ3ij@6}*JNViO_ zQF{7y0%FmLjTyySs8PKVA67kT@Ij$9X-IKLA3$b^Y)Pl65ARzfI%T z;tmN3N}$V##{16+Ai2SAqhbq<>~ZgZe$OwMkk`fM9e7aDa2a(m$2M?KaQEtxF9PLa9cLm4j(&6i`QUoiRvl2he! zuuzSz39KuJ`nW!dfIlT{`I5T@GA6~_WI0S-9B6sgVO>u`a_AZ|6Hyq7rmOLOXcKJ&y}v7T|at_!0tfJ{YyTM z578!B0i+Hd=8kHk7I&7d>NOt`U;Y0;fpgXxHohJq*A{hh3T-ZtEIr)*G#>uUOr;+6 zx{eE)YB@Q{H5tnuyQlO(c+@qZz%XzTZOiiMtExPi!uLFh(fNeaI6SWj-OL@3tt5FL z`Cn&gPj`Hxqlc<3S1cxO@xixWuMg6=oSrXkcyHeo%&`(S$W4cFNG@nLzRn#RK>6uz zY;G$ruE(AD+8XbbBa;g=$qjgkvlpZsDYWMar*ESqA+h*3)~1^2j3%=m>qU|Zmhz%g?C1r3I(QO;tG{|weQsZ)rbfW{O;^?Y5UWwWy0&{c_0?uAG~|I8f~Fl zv~p)N@1Si6ZTlQQHjS;PDo&l~XQ(p$=bVOkYK%n|xe3#ZEle1!AoB8mJzVdpquzHp zWe#e$!%n!_XijsnYipiu`P_doX4U`p^YFMg*PkT#lheF&%jyg6dtsw@>(m7lMR-DP z#QF&mdoN&d|KhM41G}8x3!h6Ht8r&dmuT7^#VaXG8+G11>@y28^8Z+^1herR>F_%b zUwzk5OII#rk7L+*iyH`M34OtVdZcj1j3)R~qxRyPb-F}>%R&*KpOKQF^#5zno6r4v z?Q45Im%+{KzO;2f*?Uix3s$h-`@s-n-6Fb_Hl{5YqnN*>QEvJ8E%({-IWeV(grEr; zdZ_1lW}MBy-i^pljX}4cQKP8;Z1lx{H(E?ZY&wS{n$MbzR!G17RH8`WVy7zI-E=-S zewk^y0djR6!w3e61InBUi;D~ip-Hg@Ikus(nmG)Z+u&v$G{m?ooXvyjDLX!@Cob;w z|Fp&-AxV6g3Aq@a>fSwdA=Iegpy6c9a`gInk!z5 zRsYSIj`MDc7QxO#gN((eN9mUm%x?0RJw!A9dE~i&AGx{yQjEW*kr|maLq|AuSnNkO z`C?DTRn2Q`)-Bl*r;=Z>zQ?H?|9W^K!+V9) zH{8X&jbEI2L#98G8+Be53J0D|{a^lwk%M79w3MB#LvzpgGo)E`OV(puN_laS?SM?6 zd5W`Ume$(3#_7uT={GNPK(8E?`IVFX=R=KWS|;!D$Hp1G?vYTu{U!9;GB3KH0_S0; zhfr}~Mq?rYWMWw^lw zA>wTM9+fzoikg(C%iR55{IR|(XCLXX>!%lUwvG!o6EL*fdqZMp*%EgPutGk z^=Nn|_RfXN;8O-W@dkvw_#%rW{bPHs|1DGn_FMdg$UB5lfo-ZCZ&^ z(vXWG`emvc0}`a#wQX##+cde^#Lya#@T@d&~NGj;(MK{6QbbqxBaKy|PUW=EH5aG*WmW*=c%}Wp=f>*F zPq2o1vP@KOYuam1Wjpx!MSHR_QIlz`>bwXsCVzzt_59#55KF)kL=seE%dq_O?{ksZzd*e|CwF{X>2iGQ zoVv~KEzvl2t&YI#o40s6^2*B}eDF9NI%=h*8g&&|kIrczd)CKwc=DlNfaWVzF}$xA z0@M*)ggCDE9SI^0j8z^{n$LM_lAXhi;R!tDP(Fuw@8>g|*oIIElTqBjGUwMl2YZ8< z(7XUcO_~|bDB!qmNc`(ril!4vt_;7x?!FK{6Pom*)+2VrIw0(;=~+V+mDGhYt0>R- zR8Ma;!I;KzrvM|`-_U158D@RDzv{i3azafc4JX9z5rU(X*9t!2b8WE){ieNDkCts$fYGJDNvgfEUN-q-xr1aYy6fZ;$jV_%~pB20C~|eLGEWcC~8UJ*?q$@#=*4 z6zGKF*BuBdFN3ficIqF$%5nCdk2WfcMrN*(-;MrQg)z@~*QDVdk7|2mTdqrw4p%Qp ziX2AKBgh%54DXEEDo1Q?Ls~)-18lgiuVkF8IzK)=I1jrr^Aap`(3#)M+>8Vr5`^4= znx|u7;XQcYlKgyC#b3{9z8xR*9FLgx^3Tl7l-YF95++vGfi&t{mr#>aQz06(hv62g z{}p^lUAzjU{}sa~OwU6|uqPl_b=sffn%Uos%=TqZPCGt;u4=n;D3LD8)SbA8GQR`^ zpfp~HBG&A?9ZP0j^xn$TS7hmSW+L+S&*^d4cYsi|Qw8QG&aCeLSR8Q^8?HK?z3W75J8 zXPcJXstA5DsptCe8F3O1T*WZFvQpBoi{sE3UdugdfKI}`j7%=|pX0;sKq$iGj^cp! zp*eCuTdo6?_48qzh7?702D7`9Utv9X+c))oqVPI$6)-=EGU4$`diJ)H@5acLm^sJ!D% zmUvhMSvMGOf0)jo#3=99cZVJkFl^yhEK`|C<}vQxCBS7he|*?<%pIkGPb7~V$Y2lP z^51P?6=Vtm(*N$=!RB;T=!(znN1qZg-VT42S zj-?-Mag)F1wqq2}n4`4Z4K^0aBNgvf@Bzh8TK8s69E&+=6nCvKkYCnkd0%Io6!Fk% z!5PhmQFfzJ5_dI_!}dy)WFe<9-CN$#WUJS4$*o&CiK_HEYQI`nE4P;jVCCRr_qF`}(<))NUcS-V?1S7xE03gTV#VIf0sNgrZ42*}#PV zCK_gb@`CvF7ISKzf6gXeC1<&%E*53~ibskH3ci;_3K~M-MV2G8BV{{n6#BwtbM0%c z+8sQW;Xt3t#@t_RIu5*0ovnN$7i>;ET+O{P3U;D@LycJaf^H;g*0B|F-cw-fH&xQ@ z7{jwt{44}WR6`2IDWk|F9QJqvntV4;uPGv)y@5U2M8K>q*R4hCuqBgHvb@ zPJc~QRK%rJvL(E-RIB#pHN9@}oPQ%@#bsAFp&nBHfd3mC2fe){WWhh?gpBCW{1M05 z7f!(#g#1j#lo-QN{KIdGU?FI&nycoI*3E(tvW@tP(vBZLGI*G>FI42(Oa8NCQwn$M zyTOXCeS(%4p5O1$3p@mN_&tmpxYDQE>uCaQ}(f%^p&LQt?Zo32KBGsE-zam`8 zZ6yuv0g2cblVPT=4TDal+$SSp(xEEZ8-t~RgPJjpOcEYyJie~whbCX{I{2_rZS-b9 zr&8&>M`vEb?(}(VG0rVC^jW`cN{3DM2A#&GGmd9E_h!7)6>q*hwsK0tKIpCX$nuLO zIlgaWu1(JSU!G?AfE*m}1}V^XO#mUnnBguSyby-qIU z2Mx3vvIvbPY}uLfargcN1ssw}3GR)%psjyWk#2$Xh%y23*ajhhw#wps5l41^;jlQK z?9yUG|5`37E91)jl-AbF_NAR#APq-BUk( z8#AuQ+9uI(&KjkJU~^?UcY{gY-jceH@1Whw~=7TY+8WlZ!?QU798&RE*Do}BkT6C$+%)4;Js@OS96Pt z1wg;>gU^b*uF1}oA_U84KVPoUH~xCbGw)pe^A!g8MQB*Dwm06;0%2|&ub-Ea-Sv{* z!k#sLcx=oO51^AV=7NsATc=E|8GtwVzLzC6*rXK-z9QkdXU>}dZ#oTu+D98!^9gW) z;}2)Km1O38Yn{sbR4|~XrCU*SZ3WpQNoZP+aJA`?o(bofU({XlODNkOGEJV*QP_Uq z2Wey~0p|~E>X{c)VrmCP5NQO&MIj>O!DVj%-C19C*rm2%YKbbGoF7J*Hi0?47p z�c?xa=!)_R-q$kxfJJowYOA2G!Mc6KdQss_-2d=7uA&K}7gO85#=O9dn35}Za z5x#OOKJ4yOwCDiv(>`*{Ho<&FV9-_+v2w+4CEBsj4+G3BGCMmPAMKN$9$1SxE_Myz z+hO*A6Fm$5{#-FwI;;`POzW2aMAiOM;h5=0;8r%oiU=5OYS`atI(FW#Nz0$nU91)4 zPWLbKv0RDM(-t9YW6TPzgzdW(c7KGR{pM=`hFG>e2G5Fc&Mm52t;JRY$UiAtu2>f3?CSNJ`@wl~46g8LkN!g@?3dl4H4%b{Mc$)&@sL0olIHQ7zZIDeau7=5VsBua zeJF~h#r$+hhP&cpp|Fx)d;Ty&KU4{#f}|DsrD)YFBBj*mE18%}<+po569JAM`OWZ- z>sh%*aDHR9Gt5td>cQa#XHas?Neqm7W18B1C9~76bo8l%H*@EwUiyAqz=Jec`yN1t zu4Q)@=JN&|Vx8}F;jg0`H^-)qhKlG3Knnl3%wu5>wA$2o3y;3Px&l#CqZ6|+tmU}Z z%6v+qJC))zGHvl1N85;=4d z*vZQ65FZPJ(PIESL^n1zD(Y~4^7Zva6$T#brr>LyA58fFgliAwGVRHQq~fdUS5q)r#_;SB4s@Sz#fWufN)6v2oYD{mp|dp%Nh zr9m}u0!M6zS=&{C`Mezflc_}s8hz=<0AoH}Erh*x6U7`5ONPF^)9U~_dWTZ2%FLw5 zNNT_0UuOBKNzrOuwDG)r;^yhQU%63^>mvf7(Ik{E6`1d_GKN_#ka&lBvVoV+2 zsE$i|Z;zNOAb+e_x`?$ZQZ>GlY$hI7@1}ll(TFD>PWvF~ux)<|mv_+5mF)DW(xLLo zoJ|`K*2cddb#q`Fgbj&-c|HH+?kt^T-3>A>eW@taIdLI?%n`;?0b0o>4y%_l$Lk4p zK@;4AXOwn7k8j>j*EdPJ=fK51?{k6#X~4zBlIn)gWc(-Y2^;6Fi0;QEm#-~Sj}_7; zd^S=M&2D)*b%9)mFZGq2-kWbDzwD_P_(W-$Jj+6j8k+LEYE7~$ZW1WQ?ny9RGCB1- zpuWKn>qcz*a>Glz?VW4jW-=a*_$hG`iW~*t0qvHA`Lf=8k|xoaucZ1BzGglRS%r0w zq?u5XmbQ0A%y#F+Xma6-W82!>J&f(P8mlX+s*-U@cXARZID*tTloX;&lhvZSej*o?D>FV~EW8RrVZnKFz8uiP8hWA|>pBaAG< zUH@7&m6xC5IoeMt?FlH^;+oPE1U|j={3pfyc3F?zJ z+eWxw@`m%0=q*Zr?vFn^pKi=4MqZ8NF``7c!qaL*EaYtxpeH*r%WJ_0wFypibE5Xu zNT+8#Nk6Z!PL_GRHxcuF53B6aP@$P~xg~7s_$b;S8!&U5zmV2|8)CfCbcV#r<=ROi zGbc~@Lf?25IGhS*50nTVK7?G%OHMLG8%+1|3odn89+edVRsuGmRmF#1y8jmTsgIw* zWz40{84^T(p^_T6vWSPBVqj%W5U3j0RU}|~Mol+UG_NN$b2Hs_buIPr8b~h< zOdy^^TjY>ER~(4RCIh7$A|!@{OMTN~^>Yl8l-0$qIjA6rJ2{z@Z)}s|mu;+~-iOj+ zJzP))kDHQS1*7ZN6dsg5R6)LZHpfgTg$}#wWxM4!HDej>Ak{tqlnMxqG$tVah)aQ}dQ9OVtMsZ;wK7&=-9(W#8R1M?USK@my#GPG?wa8?caUi01y z(-`D=`_a(uM=8244$h&U9uYLS<6A@eNx2tC=ewaiQLdKk$<4P`JbzPQ&;JsR;95<^ z$&Ee=6989W@%E0)Jdj%U#oURQ)m$n8C;+Rk0InQ%J2$~Xbk3ptcBr45y5q$&RW@iP zl^C;M8Y1~Nk?`y8^7{+fSpAcV>H!A4@uGwZn>e@?4_5GS2CI3mZtOjzOu;Cg-C6PJ zQg?uEE2%2=VR!e7gPABL7mJC`cy`l(?LoBTx`JT783V8P9?$Cm7v}`BTNkH1%ndAj zY&|qTkYoUKaw7e$14BUwjp9hr^4Fv0=Ae1JTuNm;p@uh~wPvl!)a_S53h8vmLI5c5vK$;R!4$6e}hu;8y-NNBsz5~F&_7eM2ciq4cD zi~;bAXS7qFd?Cl`E6so{FE#d-R$A5t;|doQ25+$D&ehaIWCjihh558`fZn*QbO=WZ zJLA@!%8N#x(sMI$o6Lo6J}~%FY;6zA*F4*Wlz9OXR8hEQxTz4xRi8VBno`;4|8CXU zk=x=#xh11lF*L>2*V=C?Y?>TB^2PsG#CH4JZ{OI4CDesJm5F5p8NQq|=Xza7V z{KvuPib9(PdBJVAhmqzW?7#`+I*_v{xU5gN;^9R+$+=^l@mn(MUoW7KLa1fGP3j^h znG`G%h?V;Ip#!@q5S8HJUvzZ`;eCDg2}K7!EG#T|_=lszH7HqEcGc0JxMyg^?eBW{ z^Rb=r8Sb4zsnF3L_>otyU!z5sT&go0Y-9A6763W?scNaVV*r?+1xUYhfLXMCaiDBampD*_lN z+0<@xOO1V>%=zVYdW&b74V*oTA<0fXpHKBqGq4QCJn0x^ zc*&_KFLY7kX~q>_$gXKI&ifPmZADLg-1iO*)t1w?gS>*DpGYRXuTZTUTdl~^wwM{4 z-%jJ(X-JvioG(8lN@f__G_36jq$D1czZ*FVvun%Y#A6$Bp6#_sH9lm$-=qqNH;ceM z$QB7oilOm(UT*8I^>$X*GBG+KfFF`O;y_9m&&b#dDv1uY0qRG?6FSa*d55MN#Eo9KOof4zhy~EqiQ<2T^h-HemZ)wYT=dkEbO?pFeEc&+Ck7_Z=`0T0SpDCst#~>K&tZLjA zK$gsPjMtazC~WoK!s;VW5mN=Qh7^OP!d7Cr^kzX%HZgfqR0sL+C`(96!qhPzp2@q2 zE>|aj#LmQuUMu41iRVE++q$d8%($I>e}*epB-bReBVY%J62PPO*FWar+$)ei8L8MJ)O6sEEHNHTSy3kTF*pEZwAeCikV#J*60OL&3SXu4M150u1g4Ns&8mz`UC4+ zTtBRW;99tS*=Kb{YfkhBv)A|gu(9Dryo6uZgQ@+YDwIeoCPdsc!le{WIuC##5gCJ& z0ya_!bXda`&&eFZK*GXS+zR$-AO`kg^DtA0en68w;Z!Ik-EXx#^I z<-%eDA?S4=H1U+!3fc7Wj7@XRMkgOm;N{V;*GjXB-j5!AnM~>l(mU|yZS}db@F|@z zKCdna8v8z3^+*fccOanrE7{G7eVqIXrL@VI(e`t1ZnM=a6B|F_hi;B)Pgn|`jFhwP ziQ&{(DaNc26A+aSLm7{MQ<~PG3l|h0e3YB=bUDCnq1I)NroUM;kaTWV3kiQ>tuEgz(2=K9pS5B4VNlx zZelBTbAYJ1kN*dglf@}W5fg=Y^b5P(e20cGf7@(rx_c@g0D5D>TAwC+LnXs#wjAX2*87j z`Z>FYUjhgi`1g&JBFXs_k4T2FTsSey#GE~D{A6oy=O+y`Qly%F9~cvFlrIl4**FJ4 zUBy)VQ*gNFL|6IEs_&)wZ>S+HDCg}mp>d@!KymfeFKrf%dl)!8&Cw8Q_+I3g?zvM6 z0B5Yo-BjR9u=+BGH<5~iu?@sNyWs2BA7wkrq(|wv9uP|k?w~(g=MiDewGvQRfy6F` z$zG}uINf0B5{O+Jh=lg2Ddhxs`VA0hj;v8QkjIt=KsZNyotkedI8(hvtiWbq^#k?? z(%}JkOnXtf|3(Mb^_&qvu5l9i-$R#v&l3;8NRJw`k9~kKmOt8^ftfGv^kuvvB6U1` zN&KI=I?y`Zn0OzEEn_5?sRabKKzGOHqIA#{4qIWw-nDP<@PQaQ7PUVT(Sw3v;Bty6 z3%juHHlN9Wr^yKHholYpE7LE}G7Q?C0iZqOi! zG;U43t5iSRHc|Wrv;qjqOn<=eqat#NOj#M=w-DRv;=fSj)cuX`Ip2({sH)C^=t*?h zlNWbC+eLaskIy!QaX6^=E zoSL1QegsplWOF+=Y!AWe;5Yh*!S&!LycF`kM#!WIxb7{W&@=*4Tlp)5spCK-1aKM} zzqOTErUsZ{&C2ZT7N;pNMF6~lg9FcmMTusV#jTw>je9%-q2bmuBSi#3}d4`=AnR8AL-#D!TNWCeJp!FT!tR%wM@+F7A`jHL!S zZ|+=EO3z@cIb%BxBtB6tpIR?r6N${h_(=g=&W=Xc*uvBNxcC;H!A&BvnABYW7es;p zu7%%#VY#@jon1aAPeT+@9>s4N45<_GUQNJ0vOhf+ub=-F0sp?&3MQ7YrV>fgeD2Q z_wLWvW55%{W%T=H>}aO5;&8aUDVg*_&ic0i=#6)Qw5DC)k+04WVBuE)O&P~0HE&yF z-@!d^LcD{3Bg*QtcS#rA_wSXgT{{N!pZ-1dk_Y6x?cjVQ$gKf)RavF&u6|EuhvT2K znote*T&Jc2m;(koC)>W5)njxh1J3K)8fV}1^7@42NVkdn!+B!bx$4p=2y{>)=?Ami zH~|u7SxJ&-Kz30N)X0-S+H1A?vjZ>@LGT^GfY>D%!x%PMxyHk^_a6tnAu|R75*B>l z+~RDdHU+(<-6mS9C-67&hIYn1@X@g;&B0*&Q|GB))!ZRov=%2tJNqPAJ$se8jK0aV z%aqpD)m?pdOG}DGl}JNlDl034d-^)CfajK#B43jrY0o4T)6RH~Txh6U$O>Cwr;y+y zQFZtcJMfA-?b(+}*?6+tg+m_dUq+zQhZad62w5Mq%6u>(>5hc}PkBOfe7OHkh&<5^ z5#FoCpLp^eWatSz0Xl1Ic8Z&b73(Mk7_0t!22yEtLd{VMV7zwbN`CT##Ha=y^vyy> zr91|{3x>LwUPVl@DdGXWhEc^j{4ic$mxX(dvpoCp9J@*EnL=0?4FDdYr{q%`!!T?RxiTCCoMbV1ocl-+!T;Ic^~Gc4 zm0!TF+|cj?8#vdnGl`rE<>A?G+-c|uG-MJW-2|DE4v?A?U~;YhRMd2|k59X4!Z;6f z6v;e;1A~K{rH%Uqzyv`e?XDGr2Kf7f3J~BB^626MhhWLhFxS*2zjiuTm>&gPzxC5aK?aC47VOWpVm1YZfXKU^vAmtRy5HHbY$l`j?X#r zf@vH1=pOAgpR50TtkTYPCPw}?dvgg@RhqdwYeb&^@XlHxyq*^{#63u$9}MYJRSDRpDtdaZ%;k}n}Vg_@+VpQ|3J3fV~76~&4V8RUpjwO>773;ul=pw z0TOVbzkdnb4vXgE2as19n*1}{1^k9^yik|YG7-XqFYLwi9@R>vX7)Bp;uHLe1cDup zzZ04OHk8l4pa_1-s5UY0bWqLTad;#oR%t&$-w2|K`1^DuiGJ`;mVY1MFP_m%Af^1r z2>KtHTWc~g#C2b9r5{@pHdO#L!v=J`1L5U)L!lwhbro_r;o>RG{DDYTkX2 zuI3C034sL=L(EdXqL0Bo4WLb&I@yr?-fXNpFwtGhrA>l`rH!>1Y)ZDWJP7(>4H#VU7 z|2DWFNmTo-^vlS4{v0BenTylYY;GnxnM&Z4eE|nLOB{K%7PwQl0mz*sTqH;`s0OZw zStia9?IqF~+$3@AsE2w4kK`AaZ%AnCwRnzR8BIu)UT`f>DV$}{T*+4tO51U zrb!2I)|^DWQ$0XwAg`fCqRYdW$_T@Mpb1#G^;?r@za~!N2s#-j5E1qk zADa3i#mm_i)}xO#lf>RfguBszJKPT(@mh&Ow3?Gvt^MACaKxvNn^Z$9K*?i zug{9b`|1n&R%KeocY56*7bys`Jy|>s-$7Es6+J+Jh&f^eijVP)7?b_bMJfZLS_mhA zOeQmPu3gM?2LXhdWO6)6|26wdd6Nti^$&h%IVvLpI3JIL{lrPMN{e$F#78tj{KiQQ z!D;*GGZ^5j&B+*)y~T{qJNfshC;I%^ayImc8@OCu;LdaL6_>|Am`aprSK^HrVmER8 z6a*pBS|Lu_AWyEAKTtMkV2W@~!rkf;b1;Z9=~R{oCOf)L#nsQx5pU++!HM0rW+f#0 z6sw%PPGocvw~4xidIO5)zM>o2YNa5oDbKKZ2UG4_QC2_c1`Cs#eAZHb$?j%SapP95 z5Q1Mty9sh5iXm&98SfcT3JB#YIZ_qX0>MpAUESEEn3_ffF*2!~(jpru0;vdCgYG3} zbe1R3!XRarQRq6s1w3L}7{ zB|ubm8VluuB*+!tg=-k#_uS{g!N%)c$bmAStAh+a%#<@J;BE+1o;oK=;qdDfyuDvk zotS)W@QOJ~0VzN&xh+3eU}VaGWK#`zxu|ag>9)kA>E!g*Y4q9H4jWCm)%s0sqLZI} zcZ>RbdXJsxr-cT$I`En1K$|5g3?w=J0GEXs?(2(2+layx=qPMozj{?hJghztP@IgaO7)0#@mnh{6T6pJ z78Z6DojF13xAuVE+%sAR7O!t0vgTzDCWzOx)eGT)HMB{v4D|8PlueZ!OYzvc^1vM& zpZQ2Yx_cm-j-c&Qk2RuiA63=I1Bt@~a}zL?7}LB_KoFor4i69Ua3?(2L^P4B?G8xu zTi^4?5CJg|T@W|!7)XkpT{~bz-LAIGl<^SAsT1BiNnQ%Gl^TE264UNniGg7Nnazrj zQdCTvaL7+pPn)sWs*_Fw{qo8nXOrqD5Ak5aK~+>r<4J1iX0tWorE18Pbxue_0!bsr zv|f!Xwgx{%#M47J0qI+c0h8p~M@<1IpaMZwTsg>4dugU~myVoi&ygX2+JD(+>Q^jE z0ks2EXS&i|SzlrM{S*ng$iC@7y0m@oYQs?bk3URk!+qDH@*qnc7J9bP;TCiF3fYA0m2qsD zE#p>Naw7BCBeSgR?0q=)mJ!*Tgky!@>!$a+_viEd{63HGi7`2-uD7#;BpZxBv_6p9iAX- z2V!ai-XVppCO8WrTLA|$DU4-@I$B!Y{G_W_`hlFBZ3|!mEa!g3^?a%YKzH=kFF(Ii zE>_M@qgO7le4YhB0WWm(ddVcn>oOn$nuNb!uGc*7U1Px=dgs6r{=*9HRF!Q3FZA#VJlBKu$^Ma z;X+$QJ`im%Jn+glr9iR_4G8C0GI*W60hY0bu{T$I_OuLH=535FR;JoCW}cJ+Jmc?j z2HNC7i@6Q<0Y2oL9JLOx0bhoPr4LroL0_202S(>t?dBG z!7pOsK=3Be!yDHN1i=DeIUSwwZAB9x2IHOVxg~c?L0-O&%KgVd)f0_r85v4IynDfI zrOg4btYJ2=lxsZ2VEYs6frRmx2$ar=5_~8KQ4O~({0NtB#O`)v@`dY*#n}TuFzSFu znALquin4srR0LKW(_LtLt>v52>)?Aox3)3c09**<@6qi@on6i4>ybKdV(ugM3@M7-~nrM z7wD}RLS3f1K$ByYo(tdwIVB}u#GS?BWuKBq?Mt-~12?D=qqez}@&SUVN}S)rj};3+ zIXfBf6ziOZJ3B$e31Ni%a{Dl4z&oL4 z5hn~5hfTcN0gAJ0y{}d>u+_q(?Pd&Ws=JOuo_4pg5)`fLzl7=hbJXeaPq1W~g1&HO zugiY0Gy(AWG=em$V*p_n82q$-tFnfXs2fysdoNB(09yiJvHTLa^zdlaP2Q*K$H-!pTVF970*xwHiI zccDEU!eS%3B`5!JJ`gIvKjk|Lx^JF-*p1Ld4s@ea+0omnfCa>Cw87YFQAxu4fYm$M zLQlZc{R^tPU{JiWvJ%+zM$L!Fy2j79?1!1y0Ki?e2*_A*><4mGv|SyMyVfGpe_ z<%)P2zdE%R(mw;?U1raB@g+hD-^Rx**G)%CZ3!J1>wy;AO+CQTHK4ky;MMxa7$|Sb zTo)Xp!~OXa!j#-*RDZ(qGxy1FyIat%5**+PWB`swgJFDxcq&K>f)@L%0u+UY$y^ke zF1GAi@i(=PnkZbGNseo@;x7Z8RAUN;nYEN5ELTDgNH~9jEjVOVg>TjeQ(HX|8vys`Oc^^PHEcXG8e7)(D*b4p`__-edJO+6KSi&rcd*ruRq{>QBGF+MzTb94i zZi3h;CG6|jw?WY)kTCQCn#Uo%eq+@zODM!3=fL{y6Q7)gHwI9MK4MZ)LjOr z?HqwxYfScuh1S)iA+_vwSyA@T9`a)}W3sjdK#FaV1uOkmM}F$pQ+x)f{ABMVQoJaj z-5Ox#tNQ>+xhohMjQTZn+gPrhNca6N?#L>b0c5YU{#P>u?_n(dQ+L^|_DJ7yKXLB6 z+=NrtPbx8x>#5etr}(-6@x#99PYwrVa9fQ3$T$qqyGhI|-dK`Y7Ut!>pB0|Wu)AJ6 zu^M9R!<*3sbWKe{aeTDqFteQ{6d@LAL|11IcKYzu8t-#Z!(P$gPC(-7K#6@gd!g&{ z>kCHutAj#7?@YHmbE5nS=={wxynwWHH?t@4DX5>CQZUv_x6oJa{VZ8@QxXLmUpV&W zQ(t~N$?WnemABnukDkkJZf-WZ=CzHiOT~$L_NHscIO@s!eH96l)y%B(VHb-6A=>zvOW9B?gVN_l)r(= z!k=Kz2y?Clk}o7E#y)BFs7S#0jVnN*p&*!+vECx)m)Yo-IFQ=GjTzXZUB*Cz{cb}s z%oJac*q$n=$nz#IB|;wa^Je}v@ylIm^&WBKv3ynDvdjSv73Alng)RtG@D+aXe10M9 zo2iqNTIp)qgHV6tr`)S%gFw$ts@!~Y*LAB-W`WwU&x}tj@o}5HfFkC@Q)t>OSyo)$ z7LX~CPr70> zUDw#~MV*cj_T&T7?=&Zw>x#1>rqtQ&%xI2xiqVES5^h14Z^dHUDrS9s(PF8s85$}h06zdg5rQUmNnga-p> z+msytD%y33Tj~hvnx!q zHNA*Kc=COp26-1PLAwr)sH2gfB7zD~3N?J$KIg)aQ(#^q7^Vh*pnq)xh>Fm&H3uZM zE#(dxz4d(2t!>4*EYb;HjqurE5_6MD*XE_YJjY{mPun z@{pAy5fg_?rKB3=l>tB%&}?9u*|uPIYI9O_?V2ML5$(+dc*kHjr$LZ; z64Ad4K*nAj7MMvZSO&5@H^@<;1YS8m_T~|o!%g6E)~%^_fQ3a5tU9-ql9H4=O)paO z83>cNx-vZV_N8h;UncOTYViH@sDhJ4|RA`9*`d4oYJ3j<(i zBh@awYnNs1Z1kiamYv$i zIl&X0lTOXoChK4wyDWpnH2b$iWG1XF2oRU*DVdp@Ycy?c!`=!@zyRnCz1Rh2eB?T! z09dU;1M=5EC0h!(!0QfR6(@*pfia(;q_uU>M4T%d;s&rmHrCg-0WMbi64q=$-U<$I zWOplvKfB?XAdx%h@9@x4VxT$)4ca@Hq{BhGP$|1jEw1+&EEjW34L;bBrT!EG6gp?X zs#Jy>AoF_fOv0e>#J$CDdrAa)z!Wp1+W;VmgeO-D5(ksO7N!Wx{{y;`v}M>I;llx7 zce5uS;G(lXU%!GCU5s=z8tD*OLrAqk-V4oMj)N~vh2Fj!&*pr8fyCJ!7v3NOG}(vb5AnySFNl+CQ^G%zXwP^db6UT>5%5ht4Y@FFbKP> z{qB&*4IrCiHcZsEd#kT=P)=RPhTlc*GNp2xm4!zm_|Eh}lMBGD6++oLJH`UjRQe7* z;vvA({9xL^p5p2brb9JFC~j%EwBEdv;4NXsM$EU+o7k|!`3XPJLi8fiYB*p5PqoePPolp-(k+8t&dcOB^mVeby^_`O1|l>PM6# zhJ2hKuTeikM?+a|ZhrCYS+xXlgu>Brd_VA3Ki;*MpKF>KL87tx`MTgctT+T@QmVZ%)Z17? z9?g@kaRU{CAnvY0@RKg)16aeFiq$uxHnkYGzShR4rP=fW^Zu400PBg64<&GVyF>2qnH|IDdUh6^0 zY9ru;qq)GuU!ayoSlSe5@ZZDJ{Szg@wxoaq4RHe#)e16|_Y~0jpB9wP#>O5X7<_Ol zI9VQE*^YKgH-9$vCi2xSSaNTC@z^e@1@OZCm~7spJDP*c@IFAm2OkIEddXh^C|7Ln$-W`qmKBI{30;nzNv!`;bUV8V*_XC+4` z?3lS8l#hcpik|+2LLFb-nSW?z!WX@hD69Ot!|~pCYU3P7M{i(nfF00bp+Vp?F-x;J&xw_DtJBpa*23lP($9> zYKOL)>bncmS?S&8unCm_N02;gNL6CnjWXGw*q_?&_4^yRXy{*7vNbnpE%@0gX!zgA9Nqg`1-6&11*<0Pf(RrwVc@^x_19=|8f7vB3ljflf zBoZHPefv^9njRSp-dxtTvY$O95n=|S>z8SRqoQoJK8p=0)K%AgKCaVaXMl{Tt3Qbj zQrKTRM6a8(!`4RmCd%&)ogf>a*R1rf3l2Z>Xl+fl)}r@pmNC7q4q30QbTU(Fbb-S83OBb4$7!=ZCl{ALGw2l%5Kn@>s0P<6cZKgJGaD{=R@T$WGw~!#4AZ=5r5c@|C*rlS!X>x7B+=O|S)gd^ zNRFm{ijnAGWi3_<*wR2TmOeicp<f0PyVHMa&1cajjAJOByWFBUfZxDAN*m%!-e8c4=4%zS~JK zO&+j0PONicv*7$@Pfk+K(0FBUmITIYxyNHRv|V_|2w< z9Cj6rE`cBYgqIfDBq2I~TmMZUD9gdqK{^Pm<^E_Nzz4^P9X;7E?vYq0jiT}MIT5|? zx{(kUcbhRY-ULOwAEnjf?Q}+;U42=Shuf4%eSiv_y1~4EW~KYo>>I7Z$9$vl%a?A_T#uj0`0(l-J3ywwxvesLeoHPI z4+>A$Ks46r@+ih**GEy9GHw>|7%JDftG-hV*6!grsVLpOOwL2^Xk5&M9GMOLFsQ1t z>u6%serk$+rXSwN;ztrt>R`0dCRqTwYAv4ffIE+FGJoj0Q+wHC+D@kbXwQ}Zs|(}3 z@pCJo)XbIB?KU|wOi||knz`668*RfyyxoDdNe!X=;ZaN5;k_O0A6JptH7r#~nVB}& zTq&PJ(=bg5TUTdyLlA+$CL+ggTeO!nny?=bQV_%)w5vZ9r}m!8gF==^h}k%iTO+hM zA1_fGXh=T$%dRM=e-U4swp|mjg6vCrM&&IvCrA#gzUVY@m)=n^UzNxWd9t*Xuwdpo zUdnq<>{g9i-sNq%>?yMN7E$xQ1F_@oRQ#s8O`JIC5UQ)tIIy+8<4NTA>^0|$C@O6Z z`B1PT+TyMbId01HSg(q>=xqh$bD2Bpv0QLoUHzP!gmvOO@6_B@v-wM+w?*FU^!=oa ze(y=q1xuX-;u$OLt%0>0mXTU-^;?|NwEMn&SaE5zdG{FaGQEe}jzjsHa+GCC13jEi z`mo?tgA~fx0U4u(2TLt@Ug0mg%V@T$=CTPYDO3A`Ie|U&aWHGh#3-v(@$N}1SMXr{ zM`{nYzIf=8b%rnDhdEw9gX{G99PkN|eM6?*Yz@-Zu_?Mi1Z!Rqx#peaP+#0>&pQFJpSN|q}q^|JrwyOV7&gPfHBr#9^ zzLg%q<56|T8_HE88*3s?%`__%`mS>R6q=6myUX(P($_0``h`XgchigC5riqU3yqAykCVuR8L8#EMZH6SzpSY!a1dnKJVZIM=zlROMLpc91-O502KHcS z{^9=hLxH=g6PSPbI(qlC>ubKHTf;_E3~u6zj(3F|*LX^+#(uMFW)wKUG4GrBz(=F2 z+Z!A^&o6$R23Okbv2Ga}-&Ac9tGCEPtH)6yUmrJ&BM<>G)Gk(3GbrnFf7-GREo$b4 zWe)J?$d}LW@A+C*931;e-Tjl;K9uV5#}f8)tFmmn*XJ*Z=F0&&r6;`9Lhm&lzVX7; zW9mGgchP{HtAy<9?`rJVRHdGJeS59bDWCTsRf$wInxCjAcj;23eGz%ZXRzy#&SU(b zr_oE-CL$E4Ir2GD)h{-;zu7qpOgW9B9T1r)Uc$W(>}wqR^+v!S^EQR=RFtsSqC}3l zzdD}DHVYXTs;M9q-w`!-oaI$<(AI&(8oj5?Tvw2cb^}Q3%7Z567CDA|mwP);RtRRd z=71Yk=d$}#PNS3=(j%bMLfeLQ?I>G-oKE)76%503$LdGMH^~a0I{T=LIw04up3Fvt zQE^3qhizM8D24zVul^AGZM-TZIL`G=F7sv{uw9+r0k*5hnf}dom2;klQr;k~Wu39x zQPd_foHIZE23aBQ^*R-|x*z+jv}nJy@&|7Mj|bxWqQC2i_lI^gL9%^PEz^tG6a0>~ zHMr#{Do>)F_~{WMlr~=@{JvCw53^qE`xmgcEAaVJm^>Jb2Q@dV-tMvNH#jp_N8Hg3 zfSLpM5#k-DsFbaMK*<90*B7cY?gaw#>AHg--7@)qTm#>7QH-3Y-<^;omxmNs?_@NARWX+$%kPPkiH} zY-GtE2CVQ;>r>@?E9l`vS0e`_KJ?{+*04;`>A5+M5+QNndNK# zRIkL#%O8qd5C7q@(jDQ$ddX%(jg~xMBZ}$HoV9YWVYqXyl+`oh%S|MX!&C~DV3-)_ zif_rWSjlKNO}1qH{Q^w1W7Ek7X{c{@vspsq8Jt5E6ni+I`6*>LmL_Fat$@0VFT8Yei}wmasu z$wQrid(i#Hel=GV^?TP3NuSRh?~HP<4S)?|iLv5KU&(U5__wSl#NZ+}sRYPFOeBt7 z#m#S0orgl>tA$$V0EUS4ApmYazpBpgI9+!1-DcZKx9kK6Gl!Fa4({}4` zB2Go4RX-x^>Rdb2epe4?pbo1&##!!Am-%VzXh`jdW+wDIEZB#?5 zs^4BgtIRoC^^Mr)sYy3fN=M4{mh^h1S88MTeGyR9@=YKN_?kZ*l?8Upm2&(APyy6J zo6x7Mw_LkDhaWN~;aO9D{+FbZj;S-;-&&Z{%UrXvB4*6nP9AEvrWiKA)!y5=^85id zZ@}5phIsV*J(mRC^V;dmJw;4#MVsU^wMg%;Ccrr@ku&zSwUM^MPVIwN4lr*1XFa=- z@aP})EN{!Yn4Vki!;UEf?N{~R@P@wfN&emK^ctWyx`Fz>clSt0md_mD9if8-yN_%4 zCHv(Aw-4d&Q=W{y>HNc#lPJ9ZA3dIwPcHXbfp0Xm|6Rq~Msi^%`_gyHec>)>g9X&Y!nZLy{8K0V-`r*}rGY}RQW}=ppWj1CIkW^tzA7$sJr)GDdFZc7)w7-dE zns>{U!wVlxAOB}D8|zjOcLjA#VD7e@jMUqf6#I|Fl38nm!A=+b;;|@lA|k{laSNL< zD0me2W>qIv^Wdfi%KxT2U5n>0&6OV%F3I;tkCJ$FPvBndf~84l&qVf~NYCA$bmk#I z=D?SnqB=snUYoP2NZ3IHOFWcj(`Pfzy&v0k$d~>)tzw-~ioN?*$!(VHv{-((isX3J z64mtnWa4;G>0|;q@`4`6?UL~f0i8zN5Vy0)sMXAQwySMUvPX;VfD@_EB=WpE_T^?- zWdS9FhT}2F)b{|mzJED2^R(~`cbJ6TE2qBKc$hpGT=!gE&=dFAI7ya+UXZv9vZ@SRO0W7nM2iR_;q z#8FI82}8O^62s4x8O*rhHKxz2k~66dn4NDgXoPicxKsle+>7{^x&kUT{ z1rw34e{}*^ewkHZWX?hI}>;xcwDPswxbpx2MeoH0NC#;cJ(=gIQyxc$HQ< zxzc8sm&Y|xs3QkR*1B|=>K z&fJq!t>}fq|ENWPAIR1tFs`%15Am>hHv|PPy*9ZT#O8-MV4f#1%>ZUijZrtCu*{wm z;9fee6}>xuLLMqrCpRMj@F9P<~|F?w0z%uU2Ladm1b3cevu>^iOJy_qu`X z53Xn@*5j5ZsbsI;=b}$zW!f$XUHF2196I?>;nVBG#R|zRjut3B3aPTykNO)4g1Cg* zk!$EXHrjD+?pm$38AcC7&$g`NupLy4xcDh5YKT6%p7wwo}j4vR=MZ zW30ZtBcfeCt-ZAJVGjA+y_`g?HSF4NVh`r^aM5f*6e;^Gs^njfBncn(diERSAnP-q zH`V?fk&^Oq%mMbCL`;nS4%f7Op=GYjT4VCqCne}fleu5$dwZ9A@p?3!LR3R5?ed)M zrSjH18qKwifR2%T=Z+V|i^PSK@})P$ETuDm*58cMJ-Lmz(D==*zbre5jfLun@)vV?a=eNFi6 z)chE&dY|JR(G=y6b&@XsIBWW?f6C}VLdj<*{+|f$EZq1sl>jtD8AVW7S7)auQ~S=f zM$O>Yep#qXwmHyG-{|msPI9RAkY+R)pIvjwznbemz`T1UGTL-4vR%toYibxV^#4#Q z>a#w^LqqHzowVD#{hKhyf}Mmfw>@t>=0^P{utk?tZGubWG|rD&kDyn{d_(M2u+%ZB z)BXySr(Ds;6t)mIJ&V`4%bdoo+JiW52O;R2$$Nf)3BDMSppmzJ*N=yoh$z0`_wq|Z#CPkc5VK7k%Qg_Z3)YjVw0=E)H!3*}u9 z#sC&y)dpqGNHg)hH{tD{Vi{fj7tq_(>a$AtFb$Elym(bj?}-+zAQMd_3?VnF&q*ej z`FqE=d^9>ej|-a^IB2txddXOh$tL3|4p_jug0xM+@7az-dEq{7jY^5faNZpBV zpAHq($Psg>W)(df7?n5ryLFWcA@KP%Yr5?eH3VD6coO!XWIeoE z@>Kmya7(;S2szV(jCVWG5tyu$d~>GWHB*^}*o$7MNM2FOJ}xhgiOdw$qFoj^8;vCc zr{461SJ`EgUP(LF?Pc%lLp8>yTStIij8;%;e!GFY^v0|>6)+>vywjhXeUa?)nizlT*(s->=@54hviGY01%QjtBURtGrG80(S7ri(&g8*LM%dg5b{!Dx8C& z(Mn)0stLfpueS_-c$0aGTReCGWQuY(7WynGz~1Vx%f1VI-wU+rV#umQ+B-_bXr}tT zC=iH?!RsMgbO6i>O}0+l7ee-m>+J3PNKZ>XyG!2}%Fk}$ipn$=UK8HzA+J_;(!Y^c z=nwR&Ir_z1ajW>7luj-M@6ivQQ z>Ju=cchB~vM#3{DhbwGSpehKkXFg`!y6^Yk} zavwWJcGCwg-r=*LN`UYwbWzJv${(f!&**<5Y^PkJRSUAb?cBt$mVF*)dgLS|!&Wux?g;-NUKP{?|s6{TU*YN>>Brb)f6{J>fkdcJctI+~N9ZWKg$lMKA z{Ba0`259$8Bc^ca9wnC}gWLSXGr3qqRGH1%t}YuDcYZU|3s`!(;NhI!tFI__E4DA4 zmltKUx?1V+S|FjSi-d&ojf{l2+Q$mYu(M2;+=$}*>Wc2>_?HWmsHNeRqDT$&+;!%hnXIM=WaTV#=Tr5AD9@?Q`g-&6L{kIRq=-D zu~7+%M=uU-QfERfju0ox#1>B_r5a?Z)>#0Q%32BFSn!w*E8v zH7(F}s+`WQ-wS$LsZLY;!PTgw`|337^9QXrD5ta0HQceWFJ8<)VjM;JWop>$3_km{ zv;Kx@zN_9JHA2R!xfTP}7em7#5yu~2JtrTN6Uhp}7_y6;tFn=#O$|r&Md9?ui=?Lo*uf7-O&R!?@5#$+z4V8L2Dtr zB#fN;veLrHY2|qj{CyDV#1rrbhQ-k8Fse=ni_~GE6O*XJFAgWFhLMFNS`d3f$Kkjp zOGGRjAVldaoBRH`iD=~O6((^tl}V_wl@nwABO+BtFy#A|v5bE|W@2$* zmvv7^b4B`@bP*bFArMVTWqx@cB}e(>zPUY2ET|s}Jbxv2!Bs0V^FAUCT7Nk(?)22e z@`m{EWYAHeGO?2WvuihF$1Q~K#Zj#A)f0Xya#wD2{NYykyOrAK87!b^2OiDEMOx6 zuh z==fD<>G*-vPuE?_zkcRe* z*|(vz_;VJg*Kb3=E#AZ8gMh`mHANS*I*X_6bKxgp($d0_dAJu6RTTsLwIh*PJQMa= z=aOS~MEhMU%x`6VjIFOAdu34g)FCe3L@N@=KM=-jHV*!)XRWJ4^M)zle<5{@{=@*ZSU^_k2cJE9W;B59hc;S4H)zd!0< z8C1R0y67A@gUWhLKAeoLNdzjCdsX*E{&Bc5`Hhs476I9Cr=QQlpz;N+<`S35BS zF-HA97&uk&{g5RbdY4dp+DWeW@pCa9(IUcEYMK6&K~ob(4UH3yh|!u#_^^(D4vTHG zreL*4X85hYvBGqgiS^BQ&HT!`^yo(j$49rs(?4P$+2}~tox$g+N=xG0<8Jl1F4n6_ zs;rTBDncR@V{`yO%E0Ftdi!(E-uvLOf&IG=1^HCAJ#%yG64PF77N%4rVO6TpHUf{j zS$sn!WpP~}6CxDha4M0b<7_(%`v2LY&)zwt2kTn&7ZH}_8xE~La7j>xzV=4lg2 z9)0wQ$>CM?y4DgITV;&#Q!#Ze4({MRdK1kM_+3)U$g{wX6b`1+IEaC7vPbAYA=xqM z4H>)`ms@$r$~{@F?@?!h9%_}#Bg2waq9bK?1`iNwl4}kl)tw&>{jMsn-N1D~nP*)m zKulHYPOKEbHA@F*DI3JNJ)KGoi@yTyn}MV?PcD#-8VQ zr`P!GZna0JjK}ekLkFhcRHwRN9$XEUkxi|dEHq;ru0Cn(bOHq7rK{uND`oJX2>;ts zM)V6%1vi+n1CyK}vXE=(i&YX54m_*|gg?cA$Ly^NJI$wsMW%4h5bA1Gx3hzbCp>wB z(|+}`z}6P*SgXD9kc4Zb(L{?UKr`iuU9zOH${=mdAWk;A8GxSO$zon2{nA9WGM=4Y zpm4uu`zt5_Yi=kxy#3iW?h%!iw6NN_t#Z3jJjW$ z^u#}Gqg>>=j=FMXTMbI>p+D~xLS5y@0G#A=XgHbUBI9~u=)~q@3;Aeg@`I151I>kz zFL9qP$HZJc$p{m}t8Yk`&PtpK1a;zmvAKM}E-2*tTlZ Date: Thu, 23 Mar 2023 13:46:59 +0100 Subject: [PATCH 114/130] Enable Auto RC Smoothing by default --- docs/Settings.md | 2 +- src/main/fc/settings.yaml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index c4666f6fcd..dd9055eecb 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -5018,7 +5018,7 @@ When enabled, INAV will set RC filtering based on refresh rate and smoothing fac | Default | Min | Max | | --- | --- | --- | -| OFF | OFF | ON | +| ON | OFF | ON | --- diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index ca75876bcf..b456feb478 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -658,7 +658,7 @@ groups: - name: rc_filter_auto description: "When enabled, INAV will set RC filtering based on refresh rate and smoothing factor." type: bool - default_value: OFF + default_value: ON field: autoSmooth - name: rc_filter_smoothing_factor description: "The RC filter smoothing factor. The higher the value, the more smoothing but also the more delay in response. Value 1 sets the filter at half the refresh rate. Value 100 sets the filter to aprox. 10% of the RC refresh rate" From ad3adc603ff1962a9dd202c4db04a0caf84bdce2 Mon Sep 17 00:00:00 2001 From: HKR1987 <37500242+HKR1987@users.noreply.github.com> Date: Thu, 23 Mar 2023 14:41:24 +0100 Subject: [PATCH 115/130] Update BLACKPILL_F411.md --- docs/boards/BLACKPILL_F411.md | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/docs/boards/BLACKPILL_F411.md b/docs/boards/BLACKPILL_F411.md index c1f0473f5a..73bae7db9b 100644 --- a/docs/boards/BLACKPILL_F411.md +++ b/docs/boards/BLACKPILL_F411.md @@ -32,3 +32,19 @@ Mag * MAG3110 * LIS3MDL * AK8975 +## PINIO or SWDIO +Default PINIO is enabled. If you want use SWDIO just delete this lines from: + +config.c: +``` +#include "io/piniobox.h" +pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; +``` + +target.h: +``` +// *************** PINIO *************************** +#define USE_PINIO +#define USE_PINIOBOX +#define PINIO1_PIN PA13 // Camera switcher +``` From acca688f8b68dfb51b25abe8419edcfe3d0267f1 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Thu, 23 Mar 2023 20:09:25 +0100 Subject: [PATCH 116/130] Set ALLOW_BYPASS as default nav_extra_arming_safety --- docs/Settings.md | 2 +- src/main/fc/settings.yaml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index dd9055eecb..335110ebe5 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -2728,7 +2728,7 @@ If set to ON drone won't arm if no GPS fix and any navigation mode like RTH or P | Default | Min | Max | | --- | --- | --- | -| ON | | | +| ALLOW_BYPASS | | | --- diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index c9aa1a2ff3..05897e5113 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -2312,7 +2312,7 @@ groups: type: bool - name: nav_extra_arming_safety description: "If set to ON drone won't arm if no GPS fix and any navigation mode like RTH or POSHOLD is configured. ALLOW_BYPASS allows the user to momentarily disable this check by holding yaw high (left stick held at the bottom right in mode 2) when switch arming is used" - default_value: "ON" + default_value: "ALLOW_BYPASS" field: general.flags.extra_arming_safety table: nav_extra_arming_safety - name: nav_user_control_mode From 183818886eaacf14b133621bdc4ba1ca8bd7377f Mon Sep 17 00:00:00 2001 From: Andi Kanzler Date: Thu, 23 Mar 2023 18:53:33 -0300 Subject: [PATCH 117/130] Update timer_def.h --- src/main/drivers/timer_def.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/drivers/timer_def.h b/src/main/drivers/timer_def.h index 050c674a96..c5cdc82030 100644 --- a/src/main/drivers/timer_def.h +++ b/src/main/drivers/timer_def.h @@ -107,7 +107,7 @@ #include "timer_def_stm32h7xx.h" #elif defined(AT32F43x) #include "timer_def_at32f43x.h" -#if defined(SITL_BUILD) +#elif defined(SITL_BUILD) #else #error "Unknown CPU defined" #endif From de0494d3b09e051201d6e7427a15a0fb5206b384 Mon Sep 17 00:00:00 2001 From: Andi Kanzler Date: Thu, 23 Mar 2023 18:56:01 -0300 Subject: [PATCH 118/130] Update exti.c --- src/main/drivers/exti.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/main/drivers/exti.c b/src/main/drivers/exti.c index 1b7835fb81..60105de90f 100644 --- a/src/main/drivers/exti.c +++ b/src/main/drivers/exti.c @@ -256,3 +256,5 @@ _EXTI_IRQ_HANDLER(EXTI4_IRQHandler); _EXTI_IRQ_HANDLER(EXTI9_5_IRQHandler); _EXTI_IRQ_HANDLER(EXTI15_10_IRQHandler); #endif + +#endif From 11612a242377130a9a31adbfed39c70cf9cae951 Mon Sep 17 00:00:00 2001 From: Andi Kanzler Date: Thu, 23 Mar 2023 19:00:06 -0300 Subject: [PATCH 119/130] Update osd.c --- src/main/io/osd.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 99f6d2aa31..171ff8b364 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -445,7 +445,7 @@ static void osdFormatWindSpeedStr(char *buff, int32_t ws, bool isValid) void osdSimpleAltitudeSymbol(char *buff, int32_t alt) { int32_t convertedAltutude; - char suffix; + char suffix = ''; switch ((osd_unit_e)osdConfig()->units) { case OSD_UNIT_UK: @@ -4689,4 +4689,4 @@ textAttributes_t osdGetSystemMessage(char *buff, size_t buff_size, bool isCenter return elemAttr; } -#endif // OSD \ No newline at end of file +#endif // OSD From 5e739e9e1ae842eeb1d7c5fd3fc7bcd6175aee00 Mon Sep 17 00:00:00 2001 From: Andi Kanzler Date: Thu, 23 Mar 2023 19:03:35 -0300 Subject: [PATCH 120/130] Update osd.c --- src/main/io/osd.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 171ff8b364..91f3a9ed75 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -445,7 +445,7 @@ static void osdFormatWindSpeedStr(char *buff, int32_t ws, bool isValid) void osdSimpleAltitudeSymbol(char *buff, int32_t alt) { int32_t convertedAltutude; - char suffix = ''; + char suffix = '\0'; switch ((osd_unit_e)osdConfig()->units) { case OSD_UNIT_UK: From ea69f9c61d2d5aad9a4f7864dab20685dd9d7f91 Mon Sep 17 00:00:00 2001 From: Andi Kanzler Date: Thu, 23 Mar 2023 19:31:04 -0300 Subject: [PATCH 121/130] Update sitl.cmake --- cmake/sitl.cmake | 1 + 1 file changed, 1 insertion(+) diff --git a/cmake/sitl.cmake b/cmake/sitl.cmake index e66c7a9e5d..10d8bb88cd 100644 --- a/cmake/sitl.cmake +++ b/cmake/sitl.cmake @@ -41,6 +41,7 @@ set(SITL_LINK_LIBRARIS set(SITL_COMPILE_OPTIONS -Wno-format #Fixme: Compile for 32bit, but settings.rb has to be adjusted -Wno-return-local-addr + -Wno-error=maybe-uninitialized -fsingle-precision-constant -funsigned-char ) From 819a75e91c69ff40564cfb0dc242be4bce4cd5c6 Mon Sep 17 00:00:00 2001 From: Andi Kanzler Date: Thu, 23 Mar 2023 19:36:37 -0300 Subject: [PATCH 122/130] Update bus.c --- src/main/drivers/bus.c | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/main/drivers/bus.c b/src/main/drivers/bus.c index 9dac892376..0da3f76d30 100644 --- a/src/main/drivers/bus.c +++ b/src/main/drivers/bus.c @@ -429,7 +429,12 @@ bool busIsBusy(const busDevice_t * dev) return false; #endif case BUSTYPE_I2C: +#ifdef USE_I2C return i2cBusBusy(dev,NULL); +#else + UNUSED(dev); + return false; +#endif default: return false; } From 227311f1fd8f20eedf15781006495a288e30a28e Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sat, 25 Mar 2023 12:59:04 +0100 Subject: [PATCH 123/130] Pull all servos to min when disarmed if thr is mixed in --- src/main/flight/servos.c | 14 ++++++++++++++ 1 file changed, 14 insertions(+) diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c index c4831870e7..67235a1133 100755 --- a/src/main/flight/servos.c +++ b/src/main/flight/servos.c @@ -360,6 +360,20 @@ void servoMixer(float dT) servo[target] += ((int32_t)inputLimited * currentServoMixer[i].rate) / 100; } + /* + * When not armed, apply servo low position to all outputs that include a throttle or stabilizet throttle in the mix + */ + if (!ARMING_FLAG(ARMED)) { + for (int i = 0; i < servoRuleCount; i++) { + const uint8_t target = currentServoMixer[i].targetChannel; + const uint8_t from = currentServoMixer[i].inputSource; + + if (from == INPUT_STABILIZED_THROTTLE || from == INPUT_RC_THROTTLE) { + servo[target] = motorConfig()->mincommand; + } + } + } + for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) { /* From ca1965199baef9846758f623219f983ec1d485db Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sat, 25 Mar 2023 18:19:36 +0100 Subject: [PATCH 124/130] Update GCC to 10.3.1 --- cmake/arm-none-eabi-checks.cmake | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/cmake/arm-none-eabi-checks.cmake b/cmake/arm-none-eabi-checks.cmake index 0d7633bd44..497828088a 100644 --- a/cmake/arm-none-eabi-checks.cmake +++ b/cmake/arm-none-eabi-checks.cmake @@ -2,13 +2,13 @@ include(gcc) set(arm_none_eabi_triplet "arm-none-eabi") # Keep version in sync with the distribution files below -set(arm_none_eabi_gcc_version "10.2.1") -set(arm_none_eabi_base_url "https://developer.arm.com/-/media/Files/downloads/gnu-rm/10-2020q4/gcc-arm-none-eabi-10-2020-q4-major") +set(arm_none_eabi_gcc_version "10.3.1") +set(arm_none_eabi_base_url "https://developer.arm.com/-/media/Files/downloads/gnu-rm/10.3-2021.10/gcc-arm-none-eabi-10.3-2021.10") # suffix and checksum -set(arm_none_eabi_win32 "win32.zip" 5ee6542a2af847934177bc8fa1294c0d) -set(arm_none_eabi_linux_amd64 "x86_64-linux.tar.bz2" 8312c4c91799885f222f663fc81f9a31) -set(arm_none_eabi_linux_aarch64 "aarch64-linux.tar.bz2" 1c3b8944c026d50362eef1f01f329a8e) -set(arm_none_eabi_gcc_macos "mac.tar.bz2" e588d21be5a0cc9caa60938d2422b058) +set(arm_none_eabi_win32 "win32.zip" 2bc8f0c4c4659f8259c8176223eeafc1) +set(arm_none_eabi_linux_amd64 "x86_64-linux.tar.bz2" 2383e4eb4ea23f248d33adc70dc3227e) +set(arm_none_eabi_linux_aarch64 "aarch64-linux.tar.bz2" 3fe3d8bb693bd0a6e4615b6569443d0d) +set(arm_none_eabi_gcc_macos "mac.tar.bz2" 7f2a7b7b23797302a9d6182c6e482449) function(arm_none_eabi_gcc_distname var) string(REPLACE "/" ";" url_parts ${arm_none_eabi_base_url}) From 064a809ad2dafd0077f5e544d03312efff26171c Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Sun, 26 Mar 2023 13:39:44 +0100 Subject: [PATCH 125/130] 6.1.0 sitl interop (#8913) * fix getopts 'has_arg' usage (iaw getopt_long(3)) * Rexec the SITL on reboot * Allow hostnames, facilitate compilation on non-GNU OS (e.g. *BSD), add IPV6 [xplane.c] * add required interop header files [simple_soap_client.c] * add required interop header files [simple_soap_client.h] * update serial_tcp (headers, IPv6, lookup etc) * conditional for pthread_attr_getschedpolicy availability * fix error in xplane socket familiy * remove unnecessary added headers [xplane.c] * fix gcc 12 warning is osd.c * update docs * fix for older gcc without closefrom(3) * add AI_V4MAPPED|AI_ADDRCONFIG to ai_flags (to support V4 only hosts) --- docs/SITL/SITL.md | 48 +++-- docs/SITL/X-Plane.md | 20 +- src/main/drivers/serial_tcp.c | 136 ++++++++++--- src/main/drivers/serial_tcp.h | 9 +- src/main/io/osd.c | 6 +- src/main/target/SITL/sim/simple_soap_client.c | 15 +- src/main/target/SITL/sim/simple_soap_client.h | 2 + src/main/target/SITL/sim/xplane.c | 183 +++++++++++++----- src/main/target/SITL/target.c | 57 ++++-- 9 files changed, 343 insertions(+), 133 deletions(-) diff --git a/docs/SITL/SITL.md b/docs/SITL/SITL.md index 8b0fb4abad..0040bc41f0 100644 --- a/docs/SITL/SITL.md +++ b/docs/SITL/SITL.md @@ -27,12 +27,13 @@ The following sensors are emulated: ![SITL-Fake-Sensors](assets/SITL-Fake-Sensors.png) -Select "FAKE" as type for all mentioned, so that they receive the data from the simulator. +Select "FAKE" as type for all mentioned, so that they receive the data from the simulator. ## Serial ports+ UARTs are replaced by TCP starting with port 5760 ascending. UART 1 port 5760, UART2 6761, ... -By default, UART1 and UART2 are available as MSP connections. +By default, UART1 and UART2 are available as MSP connections. To connect the Configurator to SITL: Select TCP and connect to ```127.0.0.1:5760``` (if SITL is running on the same machine). +IPv4 and IPv6 are supported, either raw addresses of hostname lookup. The assignment and status of user UART/TCP connections is displayed on the console. @@ -41,11 +42,11 @@ The assignment and status of user UART/TCP connections is displayed on the conso All other interfaces (I2C, SPI, etc.) are not emulated. ## Remote control -Joystick (via simulator) or serial receiver via USB/Serial interface are supported. +Joystick (via simulator) or serial receiver via USB/Serial interface are supported. ### Joystick interface -Only 8 channels are supported. -Select "SIM (SITL)" as the receiver and set up a joystick in the simulator, details of which can be found in the documentation for the individual simulators. +Only 8 channels are supported. +Select "SIM (SITL)" as the receiver and set up a joystick in the simulator, details of which can be found in the documentation for the individual simulators. ### Serial Receiver via USB Connect a serial receiver (e.g. SBUS) to the PC via a UART/USB adapter. Configure the receiver in the Configurator as usual. @@ -61,8 +62,8 @@ For this you need a FT232 module. With FT-Prog (https://ftdichip.com/utilities/) ![SITL-SBUS-FT232](assets/SITL-SBUS-FT232.png) -For SBUS, the command line arguments of the python script are: -```python tcp_serial_redirect.py --parity E --stopbits 2 -c 127.0.0.1:[INAV-UART-PORT] COMXX 100000``` +For SBUS, the command line arguments of the python script are: +```python tcp_serial_redirect.py --parity E --stopbits 2 -c 127.0.0.1:[INAV-UART-PORT] COMXX 100000``` Note: Telemetry via return channel through the receiver is not supported by SITL (yet). @@ -70,15 +71,15 @@ Note: Telemetry via return channel through the receiver is not supported by SITL For the OSD the program INAV-Sim-OSD is available: https://github.com/Scavanger/INAV-SIM-OSD. For this, activate MSP-Displayport on a UART/TCP port and connect to the corresponding port. -Note: INAV-Sim-OSD only works if the simulator is in window mode. +Note: INAV-Sim-OSD only works if the simulator is in window mode. ## Command line The command line options are only necessary if the SITL executable is started by hand, e.g. when debugging. -For normal use, please use the SITL tab in the configurator. +For normal use, please use the SITL tab in the configurator. The following SITL specific command line options are available: -If SITL is started without command line options, only the Configurator can be used. +If SITL is started without command line options, only a serial MSP / CLI connection can be used (e.g. Configurator or other application) can be used. ```--path``` Full path and file name to config file, if not present, eeprom.bin in the current directory is used. Example: ```C:\INAV_SITL\flying-wing.bin``` @@ -108,9 +109,9 @@ It is recommended to start the tools in the following order: ## Compile -### Linux: +### Linux and FreeBSD: Almost like normal, ruby, cmake and make are also required. -With cmake, the option "-DSITL=ON" must be specified. +With cmake, the option "-DSITL=ON" must be specified. ``` mkdir build_SITL @@ -120,5 +121,26 @@ make ``` ### Windows: -Compile under cygwin, then as in Linux. +Compile under cygwin, then as in Linux. Copy cygwin1.dll into the directory, or include cygwin's /bin/ directory in the environment variable PATH. + +#### Build manager + +`ninja` may also be used (parallel builds without `-j $(nproc)`): + +``` +cmake -GNinja -DSITL=ON .. +ninja +``` + +### Compiler requirements + +* Modern GCC. Must be a *real* GCC, macOS faking it with clang will not work. +* Unix sockets networking. Cygwin is required on Windows (vice `winsock`). +* Pthreads + +## Supported environments + +* Linux on x86_64, Aarch64 (e.g. Rpi4), RISC-V (e.g. VisionFive2) +* Windows on x86_64 +* FreeBSD (x86_64 at least). diff --git a/docs/SITL/X-Plane.md b/docs/SITL/X-Plane.md index 28f4679553..6a838c19f5 100644 --- a/docs/SITL/X-Plane.md +++ b/docs/SITL/X-Plane.md @@ -1,4 +1,4 @@ -# X-Plane +# X-Plane Tested on X-Plane 11, 12 should(!) work but not tested. @@ -20,21 +20,25 @@ In the settings, calibrate the joystick, set it up and assign the axes as follow | Roll | Roll | | Pitch | Pitch | | Throttle | Cowl Flap 1 | -| Yaw | Yaw | -| Channel 5 | Cowl Flap 2 | -| Channel 6 | Cowl Flap 3 | -| Channel 7 | Cowl Flap 4 | -| Channel 8 | Cowl Flap 5 | +| Yaw | Yaw | +| Channel 5 | Cowl Flap 2 | +| Channel 6 | Cowl Flap 3 | +| Channel 7 | Cowl Flap 4 | +| Channel 8 | Cowl Flap 5 | Reverse axis in X-Plane if necessary. ## Channelmap: -The assignment of the "virtual receiver" is fixed: +The assignment of the "virtual receiver" is fixed: 1 - Throttle 2 - Roll 3 - Pitch 4 - Yaw -The internal mixer (e.g. for flying wings) cannot be deactivated without further ado, therefore always select "Aircraft with tail" in INAV. +The internal mixer (e.g. for flying wings) cannot be deactivated without further ado, therefore always select "Aircraft with tail" in INAV. For the standard Aircraft preset the channelmap is: ```--chanmap=M01-01,S01-03,S03-02,S04-04``` + +## Other applications + +[fl2sitl](https://github.com/stronnag/bbl2kml/wiki/fl2sitl) is an open source application to replay an INAV Blackbox log through the INAV SITL via `blackbox_decode`. The output may be visualised in any MSP capable application, such as the INAV Configurator or [mwp](https://github.com/stronnag/mwptools). fl2sitl uses the X-plane protocol. diff --git a/src/main/drivers/serial_tcp.c b/src/main/drivers/serial_tcp.c index 88480748d4..9856aacdff 100644 --- a/src/main/drivers/serial_tcp.c +++ b/src/main/drivers/serial_tcp.c @@ -33,6 +33,10 @@ #include #include +#include +#include +#include +#include #include "common/utils.h" @@ -43,6 +47,68 @@ static const struct serialPortVTable tcpVTable[]; static tcpPort_t tcpPorts[SERIAL_PORT_COUNT]; static bool tcpThreadRunning = false; +static int lookup_address (char *name, int port, int type, struct sockaddr *addr, socklen_t* len ) +{ + struct addrinfo *servinfo, *p; + struct addrinfo hints = {.ai_family = AF_UNSPEC, .ai_socktype = type, .ai_flags = AI_V4MAPPED|AI_ADDRCONFIG}; + if (name == NULL) { + hints.ai_flags |= AI_PASSIVE; + } + /* + This nonsense is to uniformly deliver the same sa_family regardless of whether + name is NULL or non-NULL + Otherwise, at least on Linux, we get + - V6,V4 for the non-null case and + - V4,V6 for the null case, regardless of gai.conf + Which may confuse consumers. + FreeBSD and Windows behave consistently, giving V6 for Ipv6 enabled stacks in all cases + unless a quad dotted address is specificied + */ + struct addrinfo *p4 = NULL; + struct addrinfo *p6 = NULL; + int result; + char aport[16]; + snprintf(aport, sizeof(aport), "%d", port); + if ((result = getaddrinfo(name, aport, &hints, &servinfo)) != 0) { + fprintf(stderr, "getaddrinfo: %s\n", gai_strerror(result)); + return result; + } else { + int j = 0; + for(p = servinfo; p != NULL; p = p->ai_next) { + if(p->ai_family == AF_INET6) + p6 = p; + else if(p->ai_family == AF_INET) + p4 = p; + j++; + } + if (p6 != NULL) + p = p6; + else if (p4 != NULL) + p = p4; + else + return -1; + memcpy(addr, p->ai_addr, p->ai_addrlen); + *len = p->ai_addrlen; + freeaddrinfo(servinfo); + } + return 0; +} + +static char *tcpGetAddressString(struct sockaddr *addr) +{ + static char straddr[INET6_ADDRSTRLEN]; + void *ipaddr; + if (addr->sa_family == AF_INET6) { + struct sockaddr_in6 * ip = (struct sockaddr_in6*)addr; + ipaddr = &ip->sin6_addr; + } else { + struct sockaddr_in * ip = (struct sockaddr_in*)addr; + ipaddr = &ip->sin_addr; + } + const char *res = inet_ntop(addr->sa_family, ipaddr, straddr, sizeof straddr); + return (char *)res; +} + static void *tcpReceiveThread(void* arg) { tcpPort_t *port = (tcpPort_t*)arg; @@ -50,7 +116,7 @@ static void *tcpReceiveThread(void* arg) while(tcpThreadRunning) { if (tcpReceive(port) < 0) { break; - } + } } return NULL; @@ -58,6 +124,7 @@ static void *tcpReceiveThread(void* arg) static tcpPort_t *tcpReConfigure(tcpPort_t *port, uint32_t id) { + socklen_t sockaddrlen; if (port->isInitalized){ return port; } @@ -66,14 +133,29 @@ static tcpPort_t *tcpReConfigure(tcpPort_t *port, uint32_t id) return NULL; } - port->socketFd = socket(AF_INET, SOCK_STREAM, IPPROTO_TCP); + uint16_t tcpPort = BASE_IP_ADDRESS + id - 1; + if (lookup_address(NULL, tcpPort, SOCK_STREAM, (struct sockaddr*)&port->sockAddress, &sockaddrlen) != 0) { + return NULL; + } + port->socketFd = socket(((struct sockaddr*)&port->sockAddress)->sa_family, SOCK_STREAM, IPPROTO_TCP); + if (port->socketFd < 0) { fprintf(stderr, "[SOCKET] Unable to create tcp socket\n"); return NULL; } - - int one = 1; int err = 0; +#ifdef __CYGWIN__ + // Sadly necesary to enforce dual-stack behaviour on Windows networking ,,, + if (((struct sockaddr*)&port->sockAddress)->sa_family == AF_INET6) { + int v6only=0; + err = setsockopt(port->socketFd, IPPROTO_IPV6, IPV6_V6ONLY, &v6only, sizeof(v6only)); + if (err != 0) { + fprintf(stderr,"[SOCKET] setting V6ONLY=false: %s\n", strerror(errno)); + } + } +#endif + + int one = 1; err = setsockopt(port->socketFd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one)); err = fcntl(port->socketFd, F_SETFL, fcntl(port->socketFd, F_GETFL, 0) | O_NONBLOCK); @@ -82,14 +164,10 @@ static tcpPort_t *tcpReConfigure(tcpPort_t *port, uint32_t id) return NULL; } - uint16_t tcpPort = BASE_IP_ADDRESS + id - 1; - port->sockAddress.sin_family = AF_INET; - port->sockAddress.sin_port = htons(tcpPort); - port->sockAddress.sin_addr.s_addr = INADDR_ANY; port->isClientConnected = false; port->id = id; - - if (bind(port->socketFd, (struct sockaddr*)&port->sockAddress, sizeof(port->sockAddress)) < 0) { + + if (bind(port->socketFd, (struct sockaddr*)&port->sockAddress, sockaddrlen) < 0) { fprintf(stderr, "[SOCKET] Unable to bind socket\n"); return NULL; } @@ -99,57 +177,53 @@ static tcpPort_t *tcpReConfigure(tcpPort_t *port, uint32_t id) return NULL; } - fprintf(stderr, "[SOCKET] Bind TCP port %d to UART%d\n", tcpPort, id); + fprintf(stderr, "[SOCKET] Bind TCP %s port %d to UART%d\n", + tcpGetAddressString((struct sockaddr*)&port->sockAddress), tcpPort, id); - return port; -} - -static char *tcpGetAddressString(struct sockaddr *addr) -{ - return inet_ntoa(((struct sockaddr_in *)addr)->sin_addr); + return port; } int tcpReceive(tcpPort_t *port) -{ +{ if (!port->isClientConnected) { - + fd_set fds; FD_ZERO(&fds); FD_SET(port->socketFd, &fds); - + if (select(port->socketFd + 1, &fds, NULL, NULL, NULL) < 0) { fprintf(stderr, "[SOCKET] Unable to wait for connection.\n"); return -1; - } + } - socklen_t addrLen = sizeof(port->sockAddress); - port->clientSocketFd = accept(port->socketFd, &port->clientAddress, &addrLen); + socklen_t addrLen = sizeof(struct sockaddr_storage); + port->clientSocketFd = accept(port->socketFd,(struct sockaddr*)&port->clientAddress, &addrLen); if (port->clientSocketFd < 1) { fprintf(stderr, "[SOCKET] Can't accept connection.\n"); return -1; } - fprintf(stderr, "[SOCKET] %s connected to UART%d\n", tcpGetAddressString(&port->clientAddress), port->id); + fprintf(stderr, "[SOCKET] %s connected to UART%d\n", tcpGetAddressString((struct sockaddr *)&port->clientAddress), port->id); port->isClientConnected = true; } - + uint8_t buffer[TCP_BUFFER_SIZE]; ssize_t recvSize = recv(port->clientSocketFd, buffer, TCP_BUFFER_SIZE, 0); // Disconnect if (port->isClientConnected && recvSize == 0) { - fprintf(stderr, "[SOCKET] %s disconnected from UART%d\n", tcpGetAddressString(&port->clientAddress), port->id); + fprintf(stderr, "[SOCKET] %s disconnected from UART%d\n", tcpGetAddressString((struct sockaddr *)&port->clientAddress), port->id); close(port->clientSocketFd); memset(&port->clientAddress, 0, sizeof(port->clientAddress)); port->isClientConnected = false; - + return 0; } for (ssize_t i = 0; i < recvSize; i++) { - + if (port->serialPort.rxCallback) { port->serialPort.rxCallback((uint16_t)buffer[i], port->serialPort.rxCallbackData); } else { @@ -159,7 +233,7 @@ int tcpReceive(tcpPort_t *port) pthread_mutex_unlock(&port->receiveMutex); } } - + if (recvSize < 0) { recvSize = 0; } @@ -199,7 +273,7 @@ serialPort_t *tcpOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, return NULL; } tcpThreadRunning = true; - + return (serialPort_t*)port; } @@ -254,7 +328,7 @@ uint32_t tcpTotalRxBytesWaiting(const serialPort_t *instance) uint32_t tcpTotalTxBytesFree(const serialPort_t *instance) { tcpPort_t *port = (tcpPort_t*)instance; - + if (port->isClientConnected) { return TCP_MAX_PACKET_SIZE; } else { diff --git a/src/main/drivers/serial_tcp.h b/src/main/drivers/serial_tcp.h index a73e797379..d27610eb80 100644 --- a/src/main/drivers/serial_tcp.h +++ b/src/main/drivers/serial_tcp.h @@ -22,12 +22,15 @@ #include #include +#include +#include +#include #define BASE_IP_ADDRESS 5760 #define TCP_BUFFER_SIZE 2048 #define TCP_MAX_PACKET_SIZE 65535 -typedef struct +typedef struct { serialPort_t serialPort; @@ -39,8 +42,8 @@ typedef struct pthread_t receiveThread; int socketFd; int clientSocketFd; - struct sockaddr_in sockAddress; - struct sockaddr clientAddress; + struct sockaddr_storage sockAddress; + struct sockaddr_storage clientAddress; bool isClientConnected; } tcpPort_t; diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 91f3a9ed75..627ebc85bd 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -429,7 +429,7 @@ static void osdFormatWindSpeedStr(char *buff, int32_t ws, bool isValid) } osdFormatCentiNumber(buff, centivalue, 0, 2, 0, 3); - + if (!isValid && ((millis() / 1000) % 4 < 2)) suffix = '*'; @@ -444,7 +444,7 @@ static void osdFormatWindSpeedStr(char *buff, int32_t ws, bool isValid) */ void osdSimpleAltitudeSymbol(char *buff, int32_t alt) { - int32_t convertedAltutude; + int32_t convertedAltutude = 0; char suffix = '\0'; switch ((osd_unit_e)osdConfig()->units) { @@ -2471,7 +2471,7 @@ static bool osdDrawSingleElement(uint8_t item) displayWriteCharWithAttr(osdDisplayPort, elemPosX, elemPosY, SYM_SERVO_PAN_IS_OFFSET_L, elemAttr); } else { panServoTimeOffCentre = 0; - + if (osdConfig()->pan_servo_indicator_show_degrees) { tfp_sprintf(buff, "%3d%c", panOffset, SYM_DEGREES); displayWriteWithAttr(osdDisplayPort, elemPosX+1, elemPosY, buff, elemAttr); diff --git a/src/main/target/SITL/sim/simple_soap_client.c b/src/main/target/SITL/sim/simple_soap_client.c index 1dd173bcf2..f715e10ace 100644 --- a/src/main/target/SITL/sim/simple_soap_client.c +++ b/src/main/target/SITL/sim/simple_soap_client.c @@ -31,6 +31,8 @@ #include #include #include +# include +# include #include #include @@ -50,7 +52,7 @@ bool soapClientConnect(soap_client_t *client, const char *address, int port) if (setsockopt(client->sockedFd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one)) < 0) { return false; } - + client->socketAddr.sin_family = AF_INET; client->socketAddr.sin_port = htons(port); client->socketAddr.sin_addr.s_addr = inet_addr(address); @@ -79,7 +81,7 @@ void soapClientSendRequestVa(soap_client_t *client, const char* action, const ch return; } - char* requestBody; + char* requestBody; if (vasprintf(&requestBody, fmt, va) < 0) { return; } @@ -89,16 +91,16 @@ void soapClientSendRequestVa(soap_client_t *client, const char* action, const ch action, (unsigned)strlen(requestBody), requestBody) < 0) { return; } - + send(client->sockedFd, request, strlen(request), 0); } void soapClientSendRequest(soap_client_t *client, const char* action, const char *fmt, ...) { va_list va; - + va_start(va, fmt); - soapClientSendRequestVa(client, action, fmt, va); + soapClientSendRequestVa(client, action, fmt, va); va_end(va); } @@ -159,10 +161,9 @@ char* soapClientReceive(soap_client_t *client) if (size2 <= 0) { return NULL; } - size += size2; + size += size2; } recBuffer[size] = '\0'; return strdup(body); } - diff --git a/src/main/target/SITL/sim/simple_soap_client.h b/src/main/target/SITL/sim/simple_soap_client.h index 35f2299e1d..8522b28859 100644 --- a/src/main/target/SITL/sim/simple_soap_client.h +++ b/src/main/target/SITL/sim/simple_soap_client.h @@ -23,6 +23,8 @@ */ #include +#include +#include #define SOAP_REC_BUF_SIZE 256 * 1024 diff --git a/src/main/target/SITL/sim/xplane.c b/src/main/target/SITL/sim/xplane.c index 33b849790e..07be72a09d 100644 --- a/src/main/target/SITL/sim/xplane.c +++ b/src/main/target/SITL/sim/xplane.c @@ -29,6 +29,9 @@ #include #include #include +#include +#include +#include #include #include #include @@ -63,13 +66,14 @@ static uint8_t pwmMapping[XP_MAX_PWM_OUTS]; static uint8_t mappingCount; -static struct sockaddr_in serverAddr; +static struct sockaddr_storage serverAddr; +static socklen_t serverAddrLen; static int sockFd; static pthread_t listenThread; static bool initalized = false; static bool useImu = false; -static float lattitude = 0; +static float lattitude = 0; static float longitude = 0; static float elevation = 0; static float agl = 0; @@ -92,7 +96,7 @@ static float barometer = 0; static bool hasJoystick = false; static float joystickRaw[XPLANE_JOYSTICK_AXIS_COUNT]; -typedef enum +typedef enum { DREF_LATITUDE, DREF_LONGITUDE, @@ -126,12 +130,12 @@ typedef enum DREF_JOYSTICK_VALUES_CH8, } dref_t; -uint32_t xint2uint32 (uint8_t * buf) +uint32_t xint2uint32 (uint8_t * buf) { return buf[3] << 24 | buf [2] << 16 | buf [1] << 8 | buf [0]; } -float xflt2float (uint8_t * buf) +float xflt2float (uint8_t * buf) { union { float f; @@ -152,18 +156,18 @@ static void registerDref(dref_t id, char* dref, uint32_t freq) memcpy(buf + 9, &id, 4); memcpy(buf + 13, dref, strlen(dref) + 1); - sendto(sockFd, (void*)buf, sizeof(buf), 0, (struct sockaddr*)&serverAddr, sizeof(serverAddr)); + sendto(sockFd, (void*)buf, sizeof(buf), 0, (struct sockaddr*)&serverAddr, serverAddrLen); } static void sendDref(char* dref, float value) { char buf[509]; strcpy(buf, "DREF"); - memcpy(buf + 5, &value, 4); - memset(buf + 9, ' ', sizeof(buf) - 9); - strcpy(buf + 9, dref); + memcpy(buf + 5, &value, 4); + memset(buf + 9, ' ', sizeof(buf) - 9); + strcpy(buf + 9, dref); - sendto(sockFd, (void*)buf, sizeof(buf), 0, (struct sockaddr*)&serverAddr, sizeof(serverAddr)); + sendto(sockFd, (void*)buf, sizeof(buf), 0, (struct sockaddr*)&serverAddr, serverAddrLen); } static void* listenWorker(void* arg) @@ -171,13 +175,13 @@ static void* listenWorker(void* arg) UNUSED(arg); uint8_t buf[1024]; - struct sockaddr remoteAddr; + struct sockaddr_storage remoteAddr; socklen_t slen = sizeof(remoteAddr); int recvLen; while (true) { - + float motorValue = 0; float yokeValues[3] = { 0 }; int y = 0; @@ -189,10 +193,10 @@ static void* listenWorker(void* arg) motorValue = PWM_TO_FLOAT_0_1(motor[pwmMapping[i] & 0x7f]); } else { yokeValues[y] = PWM_TO_FLOAT_MINUS_1_1(servo[pwmMapping[i]]); - y++; + y++; } } - + sendDref("sim/operation/override/override_joystick", 1); sendDref("sim/cockpit2/engine/actuators/throttle_ratio_all", motorValue); sendDref("sim/joystick/yoke_roll_ratio", yokeValues[0]); @@ -203,11 +207,11 @@ static void* listenWorker(void* arg) sendDref("sim/cockpit2/engine/actuators/cowl_flap_ratio[2]", 0); sendDref("sim/cockpit2/engine/actuators/cowl_flap_ratio[3]", 0); sendDref("sim/cockpit2/engine/actuators/cowl_flap_ratio[4]", 0); - + recvLen = recvfrom(sockFd, buf, sizeof(buf), 0, (struct sockaddr*)&remoteAddr, &slen); if (recvLen < 0 && errno != EWOULDBLOCK) { continue; - } + } if (strncmp((char*)buf, "RREF", 4) != 0) { continue; @@ -216,7 +220,7 @@ static void* listenWorker(void* arg) for (int i = 5; i < recvLen; i += 8) { dref_t dref = (dref_t)xint2uint32(&buf[i]); float value = xflt2float(&(buf[i + 4])); - + switch (dref) { case DREF_LATITUDE: @@ -230,7 +234,7 @@ static void* listenWorker(void* arg) case DREF_ELEVATION: elevation = value; break; - + case DREF_AGL: agl = value; break; @@ -274,7 +278,7 @@ static void* listenWorker(void* arg) case DREF_FORCE_G_AXI1: accel_x = value; break; - + case DREF_FORCE_G_SIDE: accel_y = value; break; @@ -290,7 +294,7 @@ static void* listenWorker(void* arg) case DREF_POS_Q: gyro_y = value; break; - + case DREF_POS_R: gyro_z = value; break; @@ -302,36 +306,36 @@ static void* listenWorker(void* arg) case DREF_HAS_JOYSTICK: hasJoystick = value >= 1 ? true : false; break; - - case DREF_JOYSTICK_VALUES_ROll: + + case DREF_JOYSTICK_VALUES_ROll: joystickRaw[0] = value; break; - case DREF_JOYSTICK_VALUES_PITCH: + case DREF_JOYSTICK_VALUES_PITCH: joystickRaw[1] = value; break; - case DREF_JOYSTICK_VALUES_THROTTLE: + case DREF_JOYSTICK_VALUES_THROTTLE: joystickRaw[2] = value; break; - case DREF_JOYSTICK_VALUES_YAW: + case DREF_JOYSTICK_VALUES_YAW: joystickRaw[3] = value; break; - case DREF_JOYSTICK_VALUES_CH5: + case DREF_JOYSTICK_VALUES_CH5: joystickRaw[4] = value; break; - case DREF_JOYSTICK_VALUES_CH6: + case DREF_JOYSTICK_VALUES_CH6: joystickRaw[5] = value; break; - case DREF_JOYSTICK_VALUES_CH7: + case DREF_JOYSTICK_VALUES_CH7: joystickRaw[6] = value; break; - case DREF_JOYSTICK_VALUES_CH8: + case DREF_JOYSTICK_VALUES_CH8: joystickRaw[7] = value; break; @@ -375,8 +379,8 @@ static void* listenWorker(void* arg) 0, //(int16_t)round(-local_vy * 100), 0 ); - - const int32_t altitideOverGround = (int32_t)round(agl * 100); + + const int32_t altitideOverGround = (int32_t)round(agl * 100); if (altitideOverGround > 0 && altitideOverGround <= RANGEFINDER_VIRTUAL_MAX_RANGE_CM) { fakeRangefindersSetData(altitideOverGround); } else { @@ -391,7 +395,7 @@ static void* listenWorker(void* arg) imuSetAttitudeRPY(roll_inav, pitch_inav, yaw_inav); imuUpdateAttitude(micros()); } - + fakeAccSet( constrainToInt16(-accel_x * GRAVITY_MSS * 1000), constrainToInt16(accel_y * GRAVITY_MSS * 1000), @@ -425,7 +429,7 @@ static void* listenWorker(void* arg) if (!initalized) { ENABLE_ARMING_FLAG(SIMULATOR_MODE_SITL); // Aircraft can wobble on the runway and prevents calibration of the accelerometer - ENABLE_STATE(ACCELEROMETER_CALIBRATED); + ENABLE_STATE(ACCELEROMETER_CALIBRATED); initalized = true; } @@ -435,22 +439,113 @@ static void* listenWorker(void* arg) return NULL; } +static int lookup_address (char *name, int port, int type, struct sockaddr *addr, socklen_t* len ) +{ + struct addrinfo *servinfo, *p; + struct addrinfo hints = {.ai_family = AF_UNSPEC, .ai_socktype = type, .ai_flags = AI_V4MAPPED|AI_ADDRCONFIG}; + if (name == NULL) { + hints.ai_flags |= AI_PASSIVE; + } + /* + This nonsense is to uniformly deliver the same sa_family regardless of whether + name is NULL or non-NULL ** ON LINUX ** + Otherwise, at least on Linux, we get + - V6,V4 for the non-null case and + - V4,V6 for the null case, regardless of gai.conf + Which may confuse consumers + FreeBSD and Windows behave consistently, giving V6 for Ipv6 enabled stacks + unless a quad dotted address is specified (or a name resolveds to V4, + or system policy enforces IPv4 over V6 + */ + struct addrinfo *p4 = NULL; + struct addrinfo *p6 = NULL; + + int result; + char aport[16]; + snprintf(aport, sizeof(aport), "%d", port); + + if ((result = getaddrinfo(name, aport, &hints, &servinfo)) != 0) { + fprintf(stderr, "getaddrinfo: %s\n", gai_strerror(result)); + return result; + } else { + int j = 0; + for(p = servinfo; p != NULL; p = p->ai_next) { + if(p->ai_family == AF_INET6) + p6 = p; + else if(p->ai_family == AF_INET) + p4 = p; + j++; + } + + if (p6 != NULL) + p = p6; + else if (p4 != NULL) + p = p4; + else + return -1; + memcpy(addr, p->ai_addr, p->ai_addrlen); + *len = p->ai_addrlen; + freeaddrinfo(servinfo); + } + return 0; +} + +static char * pretty_print_address(struct sockaddr* p) +{ + char straddr[INET6_ADDRSTRLEN]; + void *addr; + uint16_t port; + if (p->sa_family == AF_INET6) { + struct sockaddr_in6 * ip = (struct sockaddr_in6*)p; + addr = &ip->sin6_addr; + port = ntohs(ip->sin6_port); + } else { + struct sockaddr_in * ip = (struct sockaddr_in*)p; + port = ntohs(ip->sin_port); + addr = &ip->sin_addr; + } + const char *res = inet_ntop(p->sa_family, addr, straddr, sizeof straddr); + if (res != NULL) { + int nb = strlen(res)+16; + char *buf = calloc(nb,1); + char *ptr = buf; + if (p->sa_family == AF_INET6) { + *ptr++='['; + } + ptr = stpcpy(ptr, res); + if (p->sa_family == AF_INET6) { + *ptr++=']'; + } + sprintf(ptr, ":%d", port); + return buf; + } + return NULL; +} + bool simXPlaneInit(char* ip, int port, uint8_t* mapping, uint8_t mapCount, bool imu) { memcpy(pwmMapping, mapping, mapCount); mappingCount = mapCount; useImu = imu; - - sockFd = socket(AF_INET, SOCK_DGRAM, IPPROTO_UDP); - if (sockFd < 0) { + if (port == 0) { + port = XP_PORT; // use default port + } + + if(lookup_address(ip, port, SOCK_DGRAM, (struct sockaddr*)&serverAddr, &serverAddrLen) != 0) { return false; } - struct sockaddr_in addr; - addr.sin_family = AF_INET; - addr.sin_addr.s_addr = htonl(INADDR_ANY); - addr.sin_port = htons(0); + sockFd = socket(((struct sockaddr*)&serverAddr)->sa_family, SOCK_DGRAM, IPPROTO_UDP); + if (sockFd < 0) { + return false; + } else { + char *nptr = pretty_print_address((struct sockaddr *)&serverAddr); + if (nptr != NULL) { + fprintf(stderr, "[SOCKET] xplane address = %s, fd=%d\n", nptr, sockFd); + free(nptr); + } + } struct timeval tv; tv.tv_sec = 1; @@ -462,13 +557,7 @@ bool simXPlaneInit(char* ip, int port, uint8_t* mapping, uint8_t mapCount, bool if (setsockopt(sockFd, SOL_SOCKET, SO_SNDTIMEO, (struct timeval *) &tv,sizeof(struct timeval))) { return false; } - - bind(sockFd, (struct sockaddr *) &addr, sizeof(addr)); - serverAddr.sin_family = AF_INET; - serverAddr.sin_addr.s_addr = inet_addr(ip); - serverAddr.sin_port = htons(port); - if (pthread_create(&listenThread, NULL, listenWorker, NULL) < 0) { return false; } @@ -508,4 +597,4 @@ bool simXPlaneInit(char* ip, int port, uint8_t* mapping, uint8_t mapCount, bool } return true; -} \ No newline at end of file +} diff --git a/src/main/target/SITL/target.c b/src/main/target/SITL/target.c index aabe2f6d2c..5948b6148e 100644 --- a/src/main/target/SITL/target.c +++ b/src/main/target/SITL/target.c @@ -66,20 +66,23 @@ static bool useImu = false; static char *simIp = NULL; static int simPort = 0; +static char **c_argv; + void systemInit(void) { fprintf(stderr, "INAV %d.%d.%d SITL\n", FC_VERSION_MAJOR, FC_VERSION_MINOR, FC_VERSION_PATCH_LEVEL); clock_gettime(CLOCK_MONOTONIC, &start_time); fprintf(stderr, "[SYSTEM] Init...\n"); +#if !defined(__FreeBSD__) // maybe also || !defined(__APPLE__) pthread_attr_t thAttr; int policy = 0; pthread_attr_init(&thAttr); pthread_attr_getschedpolicy(&thAttr, &policy); - pthread_setschedprio(pthread_self(), sched_get_priority_min(policy)); pthread_attr_destroy(&thAttr); +#endif if (pthread_mutex_init(&mainLoopLock, NULL) != 0) { fprintf(stderr, "[SYSTEM] Unable to create mainLoop lock.\n"); @@ -89,7 +92,7 @@ void systemInit(void) { if (sitlSim != SITL_SIM_NONE) { fprintf(stderr, "[SIM] Waiting for connection...\n"); } - + switch (sitlSim) { case SITL_SIM_REALFLIGHT: if (mappingCount > RF_MAX_PWM_OUTS) { @@ -108,7 +111,7 @@ void systemInit(void) { fprintf(stderr, "[SIM] Mapping error. RealFligt supports a maximum of %i PWM outputs.", XP_MAX_PWM_OUTS); sitlSim = SITL_SIM_NONE; break; - } + } if (simXPlaneInit(simIp, simPort, pwmMapping, mappingCount, useImu)) { fprintf(stderr, "[SIM] Connection with X-Plane successfully established.\n"); } else { @@ -119,13 +122,13 @@ void systemInit(void) { fprintf(stderr, "[SIM] No interface specified. Configurator only.\n"); break; } - + rescheduleTask(TASK_SERIAL, 1); } bool parseMapping(char* mapStr) { - char *split = strtok(mapStr, ","); + char *split = strtok(mapStr, ","); char numBuf[2]; while(split) { @@ -158,7 +161,7 @@ bool parseMapping(char* mapStr) return true; } -void printCmdLineOptions(void) +void printCmdLineOptions(void) { fprintf(stderr, "Avaiable options:\n"); fprintf(stderr, "--path=[path] Path and filename of eeprom.bin. If not specified 'eeprom.bin' in program directory is used.\n"); @@ -169,21 +172,26 @@ void printCmdLineOptions(void) fprintf(stderr, "--chanmap=[mapstring] Channel mapping. Maps INAVs motor and servo PWM outputs to the virtual receiver output in the simulator.\n"); fprintf(stderr, " The mapstring has the following format: M(otor)|S(servo)-,... All numbers must have two digits\n"); fprintf(stderr, " For example: Map motor 1 to virtal receiver output 1, servo 1 to output 2 and servo 2 to output 3:\n"); - fprintf(stderr, " --chanmap=M01-01,S01-02,S02-03\n"); + fprintf(stderr, " --chanmap=M01-01,S01-02,S02-03\n"); } void parseArguments(int argc, char *argv[]) { + // Stash these so we can rexec on reboot, just like a FC does + c_argv = calloc(argc+1, sizeof(char *)); + for (int i = 0; i < argc; i++) { + c_argv[i] = strdup(argv[i]); + } int c; while(true) { static struct option longOpt[] = { - {"sim", optional_argument, 0, 's'}, - {"useimu", optional_argument, 0, 'u'}, - {"chanmap", optional_argument, 0, 'c'}, - {"simip", optional_argument, 0, 'i'}, - {"simport", optional_argument, 0, 'p'}, - {"help", optional_argument, 0, 'h'}, - {"path", optional_argument, 0, 'e'}, + {"sim", required_argument, 0, 's'}, + {"useimu", no_argument, 0, 'u'}, + {"chanmap", required_argument, 0, 'c'}, + {"simip", required_argument, 0, 'i'}, + {"simport", required_argument, 0, 'p'}, + {"help", no_argument, 0, 'h'}, + {"path", required_argument, 0, 'e'}, {NULL, 0, NULL, 0} }; @@ -192,7 +200,7 @@ void parseArguments(int argc, char *argv[]) break; switch (c) { - case 's': + case 's': if (strcmp(optarg, "rf") == 0) { sitlSim = SITL_SIM_REALFLIGHT; } else if (strcmp(optarg, "xp") == 0){ @@ -210,7 +218,7 @@ void parseArguments(int argc, char *argv[]) } break; case 'p': - simPort = atoi(optarg); + simPort = atoi(optarg); break; case 'u': useImu = true; @@ -227,12 +235,12 @@ void parseArguments(int argc, char *argv[]) printCmdLineOptions(); exit(0); break; - } + } } if (simIp == NULL) { simIp = malloc(10); - strcpy(simIp, "127.0.0.1"); + strcpy(simIp, "127.0.0.1"); } } @@ -261,7 +269,7 @@ uint64_t microsISR(void) uint32_t millis(void) { return (uint32_t)(micros() / 1000); -} +} void delayMicroseconds(timeUs_t us) { @@ -273,10 +281,17 @@ void delay(timeMs_t ms) delayMicroseconds(ms * 1000UL); } -void systemReset(void) +void systemReset(void) { fprintf(stderr, "[SYSTEM] Reset\n"); - exit(0); +#if defined(__CYGWIN__) || defined(__APPLE__) || GCC_MAJOR < 12 + for(int j = 3; j < 1024; j++) { + close(j); + } +#else + closefrom(3); +#endif + execvp(c_argv[0], c_argv); // restart } void systemResetToBootloader(void) From b71148eb5bc8ace6374756f9244ea971e2b8cd97 Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Tue, 28 Mar 2023 14:12:41 +0100 Subject: [PATCH 126/130] parameterise and reduce TASK_SERIAL rate (#8921) --- src/main/target/SITL/target.c | 2 +- src/main/target/SITL/target.h | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/src/main/target/SITL/target.c b/src/main/target/SITL/target.c index 5948b6148e..0fc86f2fc5 100644 --- a/src/main/target/SITL/target.c +++ b/src/main/target/SITL/target.c @@ -123,7 +123,7 @@ void systemInit(void) { break; } - rescheduleTask(TASK_SERIAL, 1); + rescheduleTask(TASK_SERIAL, SITL_SERIAL_TASK_US); } bool parseMapping(char* mapStr) diff --git a/src/main/target/SITL/target.h b/src/main/target/SITL/target.h index 1e3012f76b..284171c8dd 100644 --- a/src/main/target/SITL/target.h +++ b/src/main/target/SITL/target.h @@ -53,6 +53,7 @@ #define USE_UART8 #define SERIAL_PORT_COUNT 8 +#define SITL_SERIAL_TASK_US (500) #define DEFAULT_RX_FEATURE FEATURE_RX_MSP #define DEFAULT_FEATURES (FEATURE_GPS | FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT) @@ -181,7 +182,7 @@ typedef struct #define UART7 ((USART_TypeDef *)0x0007) #define UART8 ((USART_TypeDef *)0x0008) -typedef enum +typedef enum { SITL_SIM_NONE, SITL_SIM_REALFLIGHT, From 3851b96b45a40735d6ebcf6c02a5966b9dc09d3b Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Wed, 29 Mar 2023 10:42:58 +0200 Subject: [PATCH 127/130] Update Betaflight 4.3 compatible OSD.md Add mentions to BFHDCOMPAT --- docs/Betaflight 4.3 compatible OSD.md | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/docs/Betaflight 4.3 compatible OSD.md b/docs/Betaflight 4.3 compatible OSD.md index 20992a4498..0e9644dae2 100644 --- a/docs/Betaflight 4.3 compatible OSD.md +++ b/docs/Betaflight 4.3 compatible OSD.md @@ -1,18 +1,22 @@ # Betaflight 4.3 compatible MSP DisplayPort OSD (DJI O3 "Canvas Mode") -INAV 6.0 includes a special mode for MSP DisplayPort that supports incomplete implementations of MSP DisplayPort that only support BetaFlight, like the DJI O3 Air Unit. +INAV 6.0 includes a special mode for MSP DisplayPort that supports incomplete implementations of MSP DisplayPort that only support BetaFlight, like the DJI O3 Air Unit. INAV 6.1 expands this to include HD canvas sizes from BetaFlight 4.4. Different flight controllers have different OSD symbols and elements and require different fonts. BetaFlight's font is a single page and supports a maximum of 256 glyphs, INAV's font is currently 2 pages and supports up to 512 different glyphs. While there is some overlap between the glyphs in BetaFlight and INAV, it is not possible to perform a 1 to 1 mapping for all the them. In cases where there is no suitable glyph in the BetaFlight font, a question mark `?` will be displayed. -This mode can be enabled by selecting BF43COMPAT as video format in the OSD tab of the configurator or by typing the following command on the CLI: +This mode can be enabled by selecting BF43COMPAT or BFHDCOMPAT as video format in the OSD tab of the configurator or by typing the following command on the CLI: `set osd_video_system = BF43COMPAT` +or + +`set osd_video_system = BFHDCOMPAT` + ## Limitations -* Canvas size is limited to PAL's canvas size. +* Canvas size needs to be manually changed to HD on the Display menu in DJI's goggles (you may need a firmware update) and set as BFHDCOMPAT in the OSD tab of the configurator. * Unsupported Glyphs show up as `?` ## FAQ @@ -43,4 +47,4 @@ While it might technically be possible to replace some glyphs with text in multi ### Does DJI support Canvas Mode? -Actually, no. What DJI calls Canvas Mode is actually MSP DisplayPort and is a character based OSD. \ No newline at end of file +Actually, no. What DJI calls Canvas Mode is actually MSP DisplayPort and is a character based OSD. From c22b23a8e2f12ebfbee77949ba3b3e4116e22720 Mon Sep 17 00:00:00 2001 From: rmaia <9812730+rmaia3d@users.noreply.github.com> Date: Wed, 29 Mar 2023 23:36:39 -0300 Subject: [PATCH 128/130] - Improve BF compatible character and icon mappings --- src/main/io/bf_osd_symbols.h | 6 +- src/main/io/displayport_msp_bf_compat.c | 137 ++++++++++++------------ 2 files changed, 72 insertions(+), 71 deletions(-) diff --git a/src/main/io/bf_osd_symbols.h b/src/main/io/bf_osd_symbols.h index a63b9470fb..4176f966d0 100644 --- a/src/main/io/bf_osd_symbols.h +++ b/src/main/io/bf_osd_symbols.h @@ -32,12 +32,14 @@ #define BF_SYM_ROLL 0x14 #define BF_SYM_PITCH 0x15 #define BF_SYM_TEMPERATURE 0x7A +#define BF_SYM_MAX 0x24 +#define BF_SYM_PROFILE 0x7C // GPS and navigation #define BF_SYM_LAT 0x89 #define BF_SYM_LON 0x98 #define BF_SYM_ALTITUDE 0x7F -#define BF_SYM_TOTAL_DISTANCE 0x71 +#define BF_SYM_TOTAL_DISTANCE 0x2A #define BF_SYM_OVER_HOME 0x05 // RSSI @@ -138,6 +140,8 @@ // Time #define BF_SYM_ON_M 0x9B #define BF_SYM_FLY_M 0x9C +#define BF_SYM_ON_H 0x70 +#define BF_SYM_FLY_H 0x71 // Speed #define BF_SYM_SPEED 0x70 diff --git a/src/main/io/displayport_msp_bf_compat.c b/src/main/io/displayport_msp_bf_compat.c index 0ea4855920..2ca34a6e9c 100644 --- a/src/main/io/displayport_msp_bf_compat.c +++ b/src/main/io/displayport_msp_bf_compat.c @@ -38,7 +38,7 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) return BF_SYM_RSSI; case SYM_LQ: - return BF_SYM_LINK_QUALITY; + return BF_SYM_AH_LEFT; case SYM_LAT: return BF_SYM_LAT; @@ -58,44 +58,42 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) case SYM_DEGREES: return BF_SYM_GPS_DEGREE; -/* case SYM_HEADING: - return BF_SYM_HEADING; - - case SYM_SCALE: - return BF_SYM_SCALE; + return BF_SYM_OVER_HOME; +/* case SYM_SCALE: + return BF_SYM_SCALE; +*/ case SYM_HDP_L: - return BF_SYM_HDP_L; + return 'H'; case SYM_HDP_R: - return BF_SYM_HDP_R; -*/ + return 'P'; // The idea is to form HP, resembling "HDOP" + case SYM_HOME: return BF_SYM_HOMEFLAG; case SYM_2RSS: return BF_SYM_RSSI; -/* case SYM_DB: - return BF_SYM_DB + return 'D'; // Just D to resemble "dB" case SYM_DBM: - return BF_SYM_DBM; + return BF_SYM_BLANK; // No dbm resembling option - case SYM_SNR: +/* case SYM_SNR: return BF_SYM_SNR; case SYM_AH_DECORATION_UP: - return BF_SYM_AH_DECORATION_UP; + return BF_SYM_AH_DECORATION; case SYM_AH_DECORATION_DOWN: - return BF_SYM_AH_DECORATION_DOWN; - - case SYM_DIRECTION: - return BF_SYM_DIRECTION; + return BF_SYM_AH_DECORATION; */ + case SYM_DIRECTION: + return BF_SYM_OVER_HOME; // Small up pointing arrow + case SYM_VOLT: return BF_SYM_VOLT; @@ -119,14 +117,14 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) case SYM_MAH_NM_1: return BF_SYM_MAH_NM_1; - +*/ case SYM_MAH_KM_0: - return BF_SYM_MAH_KM_0; + return BF_SYM_MAH; case SYM_MAH_KM_1: - return BF_SYM_MAH_KM_1; + return 'K'; // K indicating Km - case SYM_MILLIOHM: +/* case SYM_MILLIOHM: return BF_SYM_MILLIOHM; */ case SYM_BATT_FULL: @@ -167,11 +165,11 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) */ case SYM_WATT: return BF_SYM_WATT; -/* - case SYM_MW: - return BF_SYM_MW; - case SYM_KILOWATT: + case SYM_MW: + return '^'; // Power symbol for math + +/* case SYM_KILOWATT: return BF_SYM_KILOWATT; */ case SYM_FT: @@ -183,34 +181,33 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) case SYM_ALT_M: return BF_SYM_M; -/* case SYM_TRIP_DIST: - return BF_SYM_TRIP_DIST; - - case SYM_TOTAL: - return BF_SYM_TOTAL; + return BF_SYM_TOTAL_DISTANCE; +/* case SYM_TOTAL: + return 'T'; +*/ case SYM_ALT_KM: - return BF_SYM_ALT_KM; + return 'K'; case SYM_ALT_KFT: - return BF_SYM_ALT_KFT; + return 'K'; case SYM_DIST_M: - return BF_SYM_DIST_M; + return BF_SYM_M; case SYM_DIST_KM: - return BF_SYM_DIST_KM; + return BF_SYM_KM; case SYM_DIST_FT: - return BF_SYM_DIST_FT; + return BF_SYM_FT; case SYM_DIST_MI: - return BF_SYM_DIST_MI; + return BF_SYM_MILES; case SYM_DIST_NM: - return BF_SYM_DIST_NM; -*/ + return BF_SYM_MILES; + case SYM_M: return BF_SYM_M; @@ -273,22 +270,21 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) case SYM_THR: return BF_SYM_THR; -/* case SYM_TEMP_F: - return BF_SYM_TEMP_F; + return BF_SYM_F; case SYM_TEMP_C: - return BF_SYM_TEMP_C; -*/ + return BF_SYM_C; + case SYM_BLANK: return BF_SYM_BLANK; -/* + case SYM_ON_H: return BF_SYM_ON_H; case SYM_FLY_H: return BF_SYM_FLY_H; -*/ + case SYM_ON_M: return BF_SYM_ON_M; @@ -315,23 +311,24 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) case SYM_AUTO_THR1: return BF_SYM_AUTO_THR1; +*/ case SYM_ROLL_LEFT: - return BF_SYM_ROLL_LEFT; + return BF_SYM_ROLL; case SYM_ROLL_LEVEL: - return BF_SYM_ROLL_LEVEL; + return BF_SYM_ROLL; case SYM_ROLL_RIGHT: - return BF_SYM_ROLL_RIGHT; + return BF_SYM_ROLL; case SYM_PITCH_UP: - return BF_SYM_PITCH_UP; + return BF_SYM_PITCH; case SYM_PITCH_DOWN: - return BF_SYM_PITCH_DOWN; + return BF_SYM_PITCH; - case SYM_GFORCE: +/* case SYM_GFORCE: return BF_SYM_GFORCE; case SYM_GFORCE_X: @@ -342,23 +339,24 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) case SYM_GFORCE_Z: return BF_SYM_GFORCE_Z; - +*/ case SYM_BARO_TEMP: - return BF_SYM_BARO_TEMP; + return BF_SYM_TEMPERATURE; case SYM_IMU_TEMP: - return BF_SYM_IMU_TEMP; + return BF_SYM_TEMPERATURE; case SYM_TEMP: - return BF_SYM_TEMP; + return BF_SYM_TEMPERATURE; - case SYM_TEMP_SENSOR_FIRST: +/* case SYM_TEMP_SENSOR_FIRST: return BF_SYM_TEMP_SENSOR_FIRST; +*/ case SYM_ESC_TEMP: - return BF_SYM_ESC_TEMP; + return BF_SYM_TEMPERATURE; - case SYM_TEMP_SENSOR_LAST: +/* case SYM_TEMP_SENSOR_LAST: return BF_SYM_TEMP_SENSOR_LAST; case TEMP_SENSOR_SYM_COUNT: @@ -381,7 +379,7 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) case SYM_HEADING_LINE: return BF_SYM_HEADING_LINE; -/* + case SYM_MAX: return BF_SYM_MAX; @@ -389,15 +387,15 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) return BF_SYM_PROFILE; case SYM_SWITCH_INDICATOR_LOW: - return BF_SYM_SWITCH_INDICATOR_LOW; + return BF_SYM_ARROW_SOUTH; case SYM_SWITCH_INDICATOR_MID: - return BF_SYM_SWITCH_INDICATOR_MID; + return BF_SYM_STICK_OVERLAY_HORIZONTAL; case SYM_SWITCH_INDICATOR_HIGH: - return BF_SYM_SWITCH_INDICATOR_HIGH; + return BF_SYM_ARROW_NORTH; - case SYM_AH: +/* case SYM_AH: return BF_SYM_AH; case SYM_GLIDE_DIST: @@ -423,14 +421,14 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) case SYM_FLIGHT_HOURS_REMAINING: return BF_SYM_FLIGHT_HOURS_REMAINING; - +*/ case SYM_GROUND_COURSE: - return BF_SYM_GROUND_COURSE; + return 'C'; // C for Course case SYM_CROSS_TRACK_ERROR: - return BF_SYM_CROSS_TRACK_ERROR; + return 'E'; // E for Error - case SYM_LOGO_START: +/* case SYM_LOGO_START: return BF_SYM_LOGO_START; case SYM_LOGO_WIDTH: @@ -594,10 +592,9 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) case SYM_HUD_SIGNAL_4: return BF_SYM_HUD_SIGNAL_4; - - case SYM_HOME_DIST: - return BF_SYM_HOME_DIST; */ + case SYM_HOME_DIST: + return BF_SYM_HOMEFLAG; case SYM_AH_CH_CENTER: case (SYM_AH_CH_TYPE3+1): From c87d641347f84a38dd4fd69a904e2ce3cc6d4871 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Thu, 30 Mar 2023 10:48:33 +0200 Subject: [PATCH 129/130] Revert "Improvements to BFCOMPAT character and icon mappings" --- src/main/io/bf_osd_symbols.h | 6 +- src/main/io/displayport_msp_bf_compat.c | 135 ++++++++++++------------ 2 files changed, 70 insertions(+), 71 deletions(-) diff --git a/src/main/io/bf_osd_symbols.h b/src/main/io/bf_osd_symbols.h index 4176f966d0..a63b9470fb 100644 --- a/src/main/io/bf_osd_symbols.h +++ b/src/main/io/bf_osd_symbols.h @@ -32,14 +32,12 @@ #define BF_SYM_ROLL 0x14 #define BF_SYM_PITCH 0x15 #define BF_SYM_TEMPERATURE 0x7A -#define BF_SYM_MAX 0x24 -#define BF_SYM_PROFILE 0x7C // GPS and navigation #define BF_SYM_LAT 0x89 #define BF_SYM_LON 0x98 #define BF_SYM_ALTITUDE 0x7F -#define BF_SYM_TOTAL_DISTANCE 0x2A +#define BF_SYM_TOTAL_DISTANCE 0x71 #define BF_SYM_OVER_HOME 0x05 // RSSI @@ -140,8 +138,6 @@ // Time #define BF_SYM_ON_M 0x9B #define BF_SYM_FLY_M 0x9C -#define BF_SYM_ON_H 0x70 -#define BF_SYM_FLY_H 0x71 // Speed #define BF_SYM_SPEED 0x70 diff --git a/src/main/io/displayport_msp_bf_compat.c b/src/main/io/displayport_msp_bf_compat.c index 2ca34a6e9c..0ea4855920 100644 --- a/src/main/io/displayport_msp_bf_compat.c +++ b/src/main/io/displayport_msp_bf_compat.c @@ -38,7 +38,7 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) return BF_SYM_RSSI; case SYM_LQ: - return BF_SYM_AH_LEFT; + return BF_SYM_LINK_QUALITY; case SYM_LAT: return BF_SYM_LAT; @@ -58,42 +58,44 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) case SYM_DEGREES: return BF_SYM_GPS_DEGREE; +/* case SYM_HEADING: - return BF_SYM_OVER_HOME; + return BF_SYM_HEADING; + + case SYM_SCALE: + return BF_SYM_SCALE; -/* case SYM_SCALE: - return BF_SYM_SCALE; -*/ case SYM_HDP_L: - return 'H'; + return BF_SYM_HDP_L; case SYM_HDP_R: - return 'P'; // The idea is to form HP, resembling "HDOP" - + return BF_SYM_HDP_R; +*/ case SYM_HOME: return BF_SYM_HOMEFLAG; case SYM_2RSS: return BF_SYM_RSSI; +/* case SYM_DB: - return 'D'; // Just D to resemble "dB" + return BF_SYM_DB case SYM_DBM: - return BF_SYM_BLANK; // No dbm resembling option + return BF_SYM_DBM; -/* case SYM_SNR: + case SYM_SNR: return BF_SYM_SNR; case SYM_AH_DECORATION_UP: - return BF_SYM_AH_DECORATION; + return BF_SYM_AH_DECORATION_UP; case SYM_AH_DECORATION_DOWN: - return BF_SYM_AH_DECORATION; -*/ - case SYM_DIRECTION: - return BF_SYM_OVER_HOME; // Small up pointing arrow + return BF_SYM_AH_DECORATION_DOWN; + case SYM_DIRECTION: + return BF_SYM_DIRECTION; +*/ case SYM_VOLT: return BF_SYM_VOLT; @@ -117,14 +119,14 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) case SYM_MAH_NM_1: return BF_SYM_MAH_NM_1; -*/ + case SYM_MAH_KM_0: - return BF_SYM_MAH; + return BF_SYM_MAH_KM_0; case SYM_MAH_KM_1: - return 'K'; // K indicating Km + return BF_SYM_MAH_KM_1; -/* case SYM_MILLIOHM: + case SYM_MILLIOHM: return BF_SYM_MILLIOHM; */ case SYM_BATT_FULL: @@ -165,11 +167,11 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) */ case SYM_WATT: return BF_SYM_WATT; - +/* case SYM_MW: - return '^'; // Power symbol for math + return BF_SYM_MW; -/* case SYM_KILOWATT: + case SYM_KILOWATT: return BF_SYM_KILOWATT; */ case SYM_FT: @@ -181,33 +183,34 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) case SYM_ALT_M: return BF_SYM_M; +/* case SYM_TRIP_DIST: - return BF_SYM_TOTAL_DISTANCE; + return BF_SYM_TRIP_DIST; + + case SYM_TOTAL: + return BF_SYM_TOTAL; -/* case SYM_TOTAL: - return 'T'; -*/ case SYM_ALT_KM: - return 'K'; + return BF_SYM_ALT_KM; case SYM_ALT_KFT: - return 'K'; + return BF_SYM_ALT_KFT; case SYM_DIST_M: - return BF_SYM_M; + return BF_SYM_DIST_M; case SYM_DIST_KM: - return BF_SYM_KM; + return BF_SYM_DIST_KM; case SYM_DIST_FT: - return BF_SYM_FT; + return BF_SYM_DIST_FT; case SYM_DIST_MI: - return BF_SYM_MILES; + return BF_SYM_DIST_MI; case SYM_DIST_NM: - return BF_SYM_MILES; - + return BF_SYM_DIST_NM; +*/ case SYM_M: return BF_SYM_M; @@ -270,21 +273,22 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) case SYM_THR: return BF_SYM_THR; +/* case SYM_TEMP_F: - return BF_SYM_F; + return BF_SYM_TEMP_F; case SYM_TEMP_C: - return BF_SYM_C; - + return BF_SYM_TEMP_C; +*/ case SYM_BLANK: return BF_SYM_BLANK; - +/* case SYM_ON_H: return BF_SYM_ON_H; case SYM_FLY_H: return BF_SYM_FLY_H; - +*/ case SYM_ON_M: return BF_SYM_ON_M; @@ -311,24 +315,23 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) case SYM_AUTO_THR1: return BF_SYM_AUTO_THR1; -*/ case SYM_ROLL_LEFT: - return BF_SYM_ROLL; + return BF_SYM_ROLL_LEFT; case SYM_ROLL_LEVEL: - return BF_SYM_ROLL; + return BF_SYM_ROLL_LEVEL; case SYM_ROLL_RIGHT: - return BF_SYM_ROLL; + return BF_SYM_ROLL_RIGHT; case SYM_PITCH_UP: - return BF_SYM_PITCH; + return BF_SYM_PITCH_UP; case SYM_PITCH_DOWN: - return BF_SYM_PITCH; + return BF_SYM_PITCH_DOWN; -/* case SYM_GFORCE: + case SYM_GFORCE: return BF_SYM_GFORCE; case SYM_GFORCE_X: @@ -339,24 +342,23 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) case SYM_GFORCE_Z: return BF_SYM_GFORCE_Z; -*/ + case SYM_BARO_TEMP: - return BF_SYM_TEMPERATURE; + return BF_SYM_BARO_TEMP; case SYM_IMU_TEMP: - return BF_SYM_TEMPERATURE; + return BF_SYM_IMU_TEMP; case SYM_TEMP: - return BF_SYM_TEMPERATURE; + return BF_SYM_TEMP; -/* case SYM_TEMP_SENSOR_FIRST: + case SYM_TEMP_SENSOR_FIRST: return BF_SYM_TEMP_SENSOR_FIRST; -*/ case SYM_ESC_TEMP: - return BF_SYM_TEMPERATURE; + return BF_SYM_ESC_TEMP; -/* case SYM_TEMP_SENSOR_LAST: + case SYM_TEMP_SENSOR_LAST: return BF_SYM_TEMP_SENSOR_LAST; case TEMP_SENSOR_SYM_COUNT: @@ -379,7 +381,7 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) case SYM_HEADING_LINE: return BF_SYM_HEADING_LINE; - +/* case SYM_MAX: return BF_SYM_MAX; @@ -387,15 +389,15 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) return BF_SYM_PROFILE; case SYM_SWITCH_INDICATOR_LOW: - return BF_SYM_ARROW_SOUTH; + return BF_SYM_SWITCH_INDICATOR_LOW; case SYM_SWITCH_INDICATOR_MID: - return BF_SYM_STICK_OVERLAY_HORIZONTAL; + return BF_SYM_SWITCH_INDICATOR_MID; case SYM_SWITCH_INDICATOR_HIGH: - return BF_SYM_ARROW_NORTH; + return BF_SYM_SWITCH_INDICATOR_HIGH; -/* case SYM_AH: + case SYM_AH: return BF_SYM_AH; case SYM_GLIDE_DIST: @@ -421,14 +423,14 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) case SYM_FLIGHT_HOURS_REMAINING: return BF_SYM_FLIGHT_HOURS_REMAINING; -*/ + case SYM_GROUND_COURSE: - return 'C'; // C for Course + return BF_SYM_GROUND_COURSE; case SYM_CROSS_TRACK_ERROR: - return 'E'; // E for Error + return BF_SYM_CROSS_TRACK_ERROR; -/* case SYM_LOGO_START: + case SYM_LOGO_START: return BF_SYM_LOGO_START; case SYM_LOGO_WIDTH: @@ -592,9 +594,10 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) case SYM_HUD_SIGNAL_4: return BF_SYM_HUD_SIGNAL_4; -*/ + case SYM_HOME_DIST: - return BF_SYM_HOMEFLAG; + return BF_SYM_HOME_DIST; +*/ case SYM_AH_CH_CENTER: case (SYM_AH_CH_TYPE3+1): From 4c015370c6d87fb40bb60ddcc6db6c7f3bb65add Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Sun, 2 Apr 2023 14:58:37 +0100 Subject: [PATCH 130/130] [SITL] Enable telemetry: LTM and MAVLink (#8940) --- src/main/drivers/serial_tcp.c | 3 ++- src/main/target/SITL/target.h | 3 --- src/main/telemetry/telemetry.c | 4 ++++ 3 files changed, 6 insertions(+), 4 deletions(-) diff --git a/src/main/drivers/serial_tcp.c b/src/main/drivers/serial_tcp.c index 9856aacdff..9f9f6666af 100644 --- a/src/main/drivers/serial_tcp.c +++ b/src/main/drivers/serial_tcp.c @@ -165,6 +165,7 @@ static tcpPort_t *tcpReConfigure(tcpPort_t *port, uint32_t id) } port->isClientConnected = false; + port->isInitalized = true; port->id = id; if (bind(port->socketFd, (struct sockaddr*)&port->sockAddress, sockaddrlen) < 0) { @@ -248,7 +249,7 @@ serialPort_t *tcpOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, #if defined(USE_UART1) || defined(USE_UART2) || defined(USE_UART3) || defined(USE_UART4) || defined(USE_UART5) || defined(USE_UART6) || defined(USE_UART7) || defined(USE_UART8) uint32_t id = (uintptr_t)USARTx; if (id < SERIAL_PORT_COUNT) { - port = tcpReConfigure(&tcpPorts[id], id); + port = tcpReConfigure(&tcpPorts[id-1], id); } #endif diff --git a/src/main/target/SITL/target.h b/src/main/target/SITL/target.h index 284171c8dd..f2c76497ad 100644 --- a/src/main/target/SITL/target.h +++ b/src/main/target/SITL/target.h @@ -70,19 +70,16 @@ #define USE_RX_SIM #undef USE_DASHBOARD -#undef USE_TELEMETRY_LTM #undef USE_GYRO_KALMAN // Strange behaviour under x86/x64 ?!? #undef USE_VCP #undef USE_PPM #undef USE_PWM #undef USE_LED_STRIP -#undef USE_TELEMETRY #undef USE_MSP_OVER_TELEMETRY #undef USE_TELEMETRY_FRSKY_HUB #undef USE_TELEMETRY_HOTT #undef USE_TELEMETRY_SMARTPORT -#undef USE_TELEMETRY_MAVLINK #undef USE_RESOURCE_MGMT #undef USE_TELEMETRY_CRSF #undef USE_TELEMETRY_IBUS diff --git a/src/main/telemetry/telemetry.c b/src/main/telemetry/telemetry.c index 00a5f182ae..d83bba35fe 100644 --- a/src/main/telemetry/telemetry.c +++ b/src/main/telemetry/telemetry.c @@ -68,7 +68,11 @@ PG_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig, .report_cell_voltage = SETTING_REPORT_CELL_VOLTAGE_DEFAULT, .hottAlarmSoundInterval = SETTING_HOTT_ALARM_SOUND_INTERVAL_DEFAULT, .halfDuplex = SETTING_TELEMETRY_HALFDUPLEX_DEFAULT, +#if !defined(SETTING_SMARTPORT_FUEL_UNIT_DEFAULT) // SITL + .smartportFuelUnit = 1, +#else .smartportFuelUnit = SETTING_SMARTPORT_FUEL_UNIT_DEFAULT, +#endif .ibusTelemetryType = SETTING_IBUS_TELEMETRY_TYPE_DEFAULT, .ltmUpdateRate = SETTING_LTM_UPDATE_RATE_DEFAULT,

      =8+Yh9q#d5z8ACcHs22b2x`h&3Hxs$m({up5-W5hCFAlyQ&`jm z!^eN=ll;Ul{WNAH!%OUAKb_9-AyD~>@?61h{P+JQfA~B9mOuaZU*?&ge3r`}yTY40 zxA@rK`ZR}=Isfi|{oTmDbPA^f?u_R7&%A&YN2xX#T|UG3>?UCV6L*BGB3@~%u&@;l zXxtoIIDYDvKf~6gExz!-{~q_hbBod!*qKKYUk;BGsFbHRj!Re1ke3t2BOx~ylV{)> z#{E9S(SS3TF0*m&Y5K#<42Rp~S%wOh#dN{#Td(u>o8MyZ!F}e_Ifd@iR5d|6-n(_3 z$?OiF{`^n#_N@mjuTM$!)A9bYE~=!cfTKaZkGXs-4XFkiAL4Epp+CF=@eSibldB%q zd#cQ{KeJST(m9KT=l;$i&ptIKGdb4Q@p#EQwYFxt*k^zDZO%UNELs;h7fTeCL>2xI z9`7F_{GdZTg_0wCJZtrhFl6}JwX#+ zD(VKA%wSNMV4x9bh_oAM8Eyzr*LA#>0Kubzj+7sXMs}qzy{;h?Jz8PSLrz|!)+@y? zmH4euwMli%1|NK<;MD$%?wp}zLBz|JK0#JEYX^{~KZ|_Q)qU0`+(LUFBvp5(ExsRk z;WN+kbN}!c@VQV|6|>!a-n@MuEt;pVJ;M^qQsB&$Gd%N&7x?Nozd`>@pJH6#wP)5W zdEu3h^2W!$$L&9Vn}Hc{SkEZV4WNi@wxzXLC8#XJ|MZtx$=ecn8 zDwm)880F@(47Q%dWCOsH>%ekWapvliTzU2>ZocsyzWa?=xqs(AI@bho?C#y=JFkC( zpZr_@gy%nbje}dS5*BGQR6eRniQs8c3hZx~A$2~=#N~P9O8R;Zp`o8CE{sN$Rz(40 zpP`!thmFNHHH+zz;D(GxTWoA?F`YPq%ULXHeB)ToD<%iK?A*Pg~) zq{8~QE4o!HSR9j_YwzfAUFi&J%N{sQV7mLuv`($TT@{=}V;j}<HxBucBjLJSA|Cvv6@uN@k!lzzgcRJyv&wPTPdi!18e&c%_ z?j16^yv?GrY@OfY*Z-^koPTlaH#xj{B-lP4EozA%pRlUcXOOH4J(KmeY!V z_dCDOop0S_KB>q@eJ)?S%CG(xe;->pDz)H~pZ)}QUVVq_U-};PWR5Z+ih^x`vyN1VU%G*_N|h2i$Il;fw!2AgWw~8#!5S zm``Usd2~RvoKn@Xv#0{zz4;EG(w>jL{374}_ur$cV%|iM*vmePnxvxN(m0a71Onc zlBI9ZBB_Q0!~g&w07*naRA>y&HU#Gw_A~0{i2Z{*ESot+o-ynxw$EcAX!cw1g``MTa=sd^hX>|KYf{<-Mid)^9F@vWXdo(++(>oU*nmjY)TA_l+H8tXdP(`ukLTkhe2m5ml4wu}z z^MGD|5KAZ<8!<8`V8Jdd%fmh1yZ$PdF1>*6Wz=?nn6}{bhtC54a3`yx*XWaEn5%Ki zLk5Load?+^-hP9ESm@Q@Wh3yvOjlruk|Dzo;>E06sr{`8xNq8iyYQ!cGoMYf`qP=6p7c%i_jkou_$)$ z?NR7H)xr}R$aKl(2Ad4bkYE?|DudOY<=pX=Fa8NHe(qz8`WwueB~?;x@*zTF z%EzrM$8dggi_PSzr!iW{3pjJ>GTT?4r74C~K10! z=N47HzWqQP&<$}b7DWiHx3m@}#~CLh6947H zs&eW0tBq$@Ic!PkX`hlUN=fQ*9}RVIu>#F`hZB$2U~|O`%fdSZ%}{z=$TqkrL#~wD zJW+15X@-=#z)MV$+4O3>qYjQLSZ2Oq;%fHof}MKGo$8RCW=3s5m4-k-2gpdtptgS% zE2Gxc!6&>|N$M0pd+B9mIM?~O-7#9BljxQzQK?7P@fRGgit4CblKkZLo>s|lOWL}E z2#dPnaC$^z8;sTz!;IbLfNHF$FZ8I+7Brg~y$hQZXGaugMpUKZ$!pKk>knAW7u1U- zxPWyHwQBhMum3XVp1FV&8l!c@rV(;&DDs@DiDEdlbsQZ|!6|f5U<09Xy!hfrID7sa z)_az=A!tM6K*T_5Q{o$s5yRGK#JFFuF(}AYpqE82vKWrozW5Zy@B)jFVGRV`U`%Rj z5(FbciBK2=I!E`;pa)Oz{L4Rs>5mYTA;A!=P}g&mhF-70q#}ag<8=>&4)=b)@pyWq zq)cdt+1%(&wb{Uc1!@ls3g^LzLaUtMYL1R->RL0IS}t6;!kwFMAX+EGDA-1r9?qE^ z?s4dc&CM~vRRk|wdE#0A@QZ)JVhQtE#jqSxqA7xowa!YfH7#4qey5Cc zXBv`6)p|~kI*s<%U42yRNd;Ei&tw!Nh09)G5iFC&GPO&zS8SO+=dvLql}A9_L6PMg zD#Jt?4y6Xy9P^N)&{s$vl%jE#WnD2h8=`buh}1VP$5o*pQWNVC zgf)-zm~$D9|GULG+ha)T9dsJTo;IL1@3amH9RIxd!}k9{34`&7jqNSww!!-)GdJbQ zk3Y#T{Nm^7ZH^gjk8ng1{MKlL+5U`w^;^HqOj&FQ7?a^@$Ah~MxbXBP0)eNlUFB1M z`_oM4M>yvxvK)h;eV|$_D9aKX0$E|`4M!|#sGTEZAX=DCr%Y#4!cc?Jn4*ZXbwNcj z^#C}qwjnG7XYwJgsVPl{UCb#4J+g9xqJJLr81HhF(I`CPL3tgSA0eQpki_q*e@N|p1I1--FIo~B@h!z&Uu=-W%u4LdH-Er`}SA(sh{2^ zD>PM=k>^EM)ncvvvG=%-wayI&kE{0By?dRfFO|G|>jpPozs~e%#&9@B>k^YyXam#b zlC9ANhJ*9`(U-o6=RDP7!gis^okClcdaSR+vE%u#`?B^BHEdAkQ<_U;YN4$#OQ%ZBXe2pZ(d-GOcDDOb*!|Z&Bt2dRf!xGr-Yo)y!GJK$&|XkRlNDtw{k9RZ@@aDl&Lci1 zT3zaS_NejL8d8FyS~f`vFR9AJu3d-&?G!?tNZE=)45ef&tz++g#h{n-V7Fp0KEwXK zyPz#%92$ddG8Qw(;m$6`yvBEn0U!PNFOZF&=_oHo8|+CLxF5%v28+Vtnitx+`w^^(mMvSKDmt=V!uTKyPa=!k@U*-Jx zJXfB63ZHv6FK&|cbG&$#iy8eg=h73GCx12e*#p38L1;V0QaCEo>c1|fJSuo&L5?S}j632)N*Fb2n%Uv>6ad7`F>gf@- zTH>^#H!R4@9+Uf1=0`KUhuV93DkBQQ`4o)2|EBqv8d6eK69^hSk)-VcVgt&8@`8j0 zLsXUbB9uB~x}5Xgjr;WaXXur}+3hW+`Vg%p?-+*6m>s}8w2*`-t&uUvhOgE#L|P(*RwsEddXky<4o zRyIW)h6sm@vK~+9z}>}!rMFCcO*KEjD9z*Lvk|7gj?bsV)5o<7B$ z_eq|P5Lp6oz4Xb0vC`jN8E5AlRa2As0s-l65_v|IaD7+SYZm4`9*HM_o1VgXLSvX5x zCiNKMcU0h0b(cEy<1;xS^9rfp4;AyIW*WnfBz z6tOKzC1fF%dRk?v77IiIXD^ueC{YG4B^2a!AxF(I!b?M|DRc(cS`Y6*(oU$*>4IR}kC>wh?-4JyHlL4PF|8#8N_! zk8NL7Ky)Cu7CViZ5{+QIA(tMz_ht;Yb97m-)f;07c)MUwYO1D=yvC+sGFedQL$(6k zy8b78x!UE^pZg_>jjLp8K+qYDwOAj}DkCOR){_dd0unn~OY~4Yv1PQVEcRAvY?S#5 z4T5DcJz($N>nx6LqDy#hvgDmN-{SUr5135@)@Kx>0uf8q%o&dReC(xj&x+)Hm;xq0ITOFzf%&v8EEo$GI5gU4jC{kE5=XBo|R6rJ!*fFxEDtb-sZ zXBaBY`C?26o$4Tk#F~ys0Ew70iqO@sI^p^$o-5G!I+h5@4{_!s|==BgFQ#s;c&>JGo z<0_BNG*w+Q+8VQO?z1T8cpBW$^W0Bfqr#$eL1B7aIe!J3kXn4iwNN28D=bvbyoOBo zxqt7Ft!D>JCwrhW>iL|V_ugPKImDYScJ95$)u&!$^UN6n7V8$wclWsc?rWUiDmc1- zll$-8;Lff0n9e2?y#Y_0JI_k-s8=0zs+J+BQgRnh>H!LI|+-wnaQSyN6TAm zv*=nIL}KMhynxXwG%BOihQ)HpgWC%>w+0ksY>dv~ssl3P7>x%U98GB|N4;?D+9Qn4 z>6^ga8{g!MvjaZ&vwxrAxod=GfYK40Lu&$V&9I!zIHdG9@u3SEjLET0YzI+j4SoTt zW^(s+-hS)b^i0i@=eIfB+vWQ8o7}&1#IjNZ(dazG1&7Ww3P-Oj8TT*oKmFG4BiSYH zy?e+|kGPQc*}$Nji%K_ZfL#nd+wameNydc4^CZ@zx3s1c3%@$eHc4~J?k=h9baky( zVX6dBETS$2@steIkXtzCaFf0e`-rAv_)#O__<<=&D?;rgG zUV7yfzWT*KW3qS1-~Hvk!^M}bFubtAa#@ih9NxLlu;^j390y!^<{3s?Th#me6j{mb z*WTgo>+kXtPrMQ$FYxjwex8d@zC@mtSZ{H`kx9nN zvs?E_yZ^;hPl(D@S_#SrXqN2VeT&z=`zP%0yvB3SoM)6}?B71*=FK}?f9)o>@9eW! zI&Hu~!{3uWP(gU_IgjnP@U?=$8XFOu=SZFw{AIUJ;Z*TSqB|-28v!y;-nr*L9xv z&2Fu=yVKqlw?PlEhe?wH)q!d#S&BMR5^bxEtWxBZ9amXZN~Q9Yhg9V$d5g=bxNIk} zBr7U4R$@_2BvGOyQtU~HASn_ccmZ7Cw&$L+&u&&T=Nx&MbM3wF#l2)wc}W4Q3OK+y z`|PvVTx*Rv#y|e?{{!3*P{NI7j@OZ|9bKgkE$7WPy0EA=Sy))5lW?}ml6Y(gd*^*< zg#&NmpTY(gcYSPTqCI8`8#)H8+g+RA6M=xwZl6iCg#fx!9KC#t5C8s$_CNpMKiC7uE2Kz5slLY)JZ(% znZNifyZhUmfBU18-hcil@UAB4NJpTyKv0Ys^1AnPbK&BB+_yWR zdgufPM+=Ux{Vk1eQ=$|c?R?6uc1Byz84Mj=Q{%no-QV&a-u}e9_{%@~E1v)IO{NDO z#45p@CXjt%#AB4jDTnrs>n|N6roiYC zaRTF^!#8tcNI}E<4(k-N#T=t5tTwpP6XPwOedfbF|J>hj@!=~|qp_y}V;}s6BzQ89w^2c0x@ozb~TT=R)aOMmzeeDWg{Nh)+ zert{oFqjN`4IQeo;=zj#a_ZCtKKO^9;LDeeIj;Ay+A?s8{c=nh9NAJdW$1D9LEZ?A z8`ZsJx3tyV{B6>B-1a;DYT zlb9IOX3Dgk(V2iahnA#IY49lNi1Q^QWjR|+xH#CMDAM{nWiV|(2iPr2e7T(@6GO|q zt9jw@8gUpnJ=|h|hDDd{gR@gY41Iut1nz)e)W(^Yj9X%7r6A0;dhZcew0( zG$Ry6)Ff%#uxjFzTC+76aNI1p{z}cTDk!u?A`FTFAueg#CaXRLl(y7uXUYK+afsJ+8TW%eIQD7iMoGVs1@)QM?d!hoX6s%! zxi5M9fZPX{JCEFC5mEFmcD+oULj#)qVhi5|8q=|8mMm3+F%~>1t?<4}HoVRf>W;z~ z3T=r9or**)9QzKs4)GlqcTQm&jkF#nG$y$Yu>HE_O+{4RbCZ^7%zsDeq&^l^ z%pr~lxudF=dy>^*#%xM=ZROIv$_4|w14m1jT8$Nuyq+9j*eByWilKUTfn8ToGzIs5YYrgb{pFm9t z8VR(E8r=wks^o>sFJsD*svPr~k9?ZLOV==SLHX2f^u$&3&T2~pf={Jwo?r zx1MWgyFXBXWH4}`Bb^AdMp(9*h{MOgXf$DKYlrc8!q(O{!3XMQ z0SF; z%Xg2_Hy zltCMl4GaZWDjMBlw<_Ycg+ikO#JWR#Aap)q#+{;+65|!E>!_tknYJfU;-X2S#|o5H zXaff`OB zX=>{^sBh8gj>%rhiE}l(J0(WdDCWetz^F7$*pCIreBVkY$y~hn0B?N5TNw{ea_PAv zUc9vAmCFq`u6HQC#n4w66VXM|-*9C?amMkJ|NQTB=7G~_4Mkycg7E4x|23JB!n&O7 zPrCQ^(I%znDd`I9J6aSvm)RzFmo=JkF`%nG#|KkhB+zyPPM;Yw8CC4;YG(86__&}b zDr%V{7@7u}rei*{42LDUFcc`X6~LqLwDYSR9be^@#gd{Z8I4BF=QE1Ja{j_O>TKPx zH?b_IH)&D$uH(upH`v+U=4f`z&4UBxiw5h)Xq%{AqiVo-Ys_@ITXdc;UpbVnlPzs1^dJvLdr!DtBf9Wh?Lr}ZMQgX7tF6Vgb3YIv%R~;crsyFb+{t1 zT+T32upv^G1(ueF9(sgF9(kO$RlI!p7GM6-WiDS@a_vfBdI(jyn{ef*z~o9yE0i+0 zqNFIRyz_ni`~Ni>NCoR0gTVl!lPOoPG!A{oGk^+!phSbDF0X_{#h{0%v}I>dqG~uk zn$w0FbOom?#zVzm5b<5PQ_JA0lF zedzQ2?X$NC_AD=7tx=ufR5|3V9Wn?Oyvh?yT^g5*j^t^sHkb1M#gTDPdg+Y*yRUlH ztA2BxwdK*#RS?OWnk0oQ=LKUOg)?l~3QaO7b47&_L(yusR6%H#2x%z7YBK}&E&u=^ z07*naR4^V+7ejO@IODj{%$TkS#CU~qmag#xpF}IR^#EHMS{=FBCeah$ z9@9(%=O_CNl|}okxUW?jOa2DuyJkY%@!gF{rxmVzTM*^824A*$B<3vD0*Z)Nf=38s z(V5QBE&|Ru3Zucu$^=mxjg1bK?V|;S?vkQbh+!oqr&RiDI$r>)Kvln{pcFbN6v;_6 z_<(Umx_^3G<1Ro{w5>q)O$y>Ev?ch!s+lG|;=5VuWGvZxBnacGq8bc1TpV-j#v#qJ zVKIl%wqZCa*xD(ms$F)rCJd^I;h-Y4HEpYS`swQ&9km?Y47~i}F$Xt1U2So8jQE%Z zXJmEnfkI{O^RiwN;|ObCm(3B9L1U=S)!)bac$&GwMStJq$<(|6TymNtSo1$F(Sg%2Jnni4G=-Ydg!b zIRkrvJi#X`5)CSG zmKSx+d@)Cxllb5hCVr3OH5y0(rD)nV2OdY=2zBd;l_o?(A}*K7iP1m}3qjJ>@R%x3fC#@6ghMOHw4W4Y zk>vH$8o>Ytg^wYLPZ&ifkq}{047o5qK`}jGig3_1)N+fNh6lG#Q??4*g%pH3kF|zV zvW=@Mf)}ngM|c&v(H-J+^i8!GWu4LY z4Zr?(a<-&ZZx$#Z>AkE@?xdm>0Z?MlAvL9xRv;ZZ-SYT;v&!oKQPx;11Y+mYzyhFR zBz8VM3px?hgLqQj3#Lf2gIbdPM=#~5B#l*S<5Dp8o!owE=Avh1OKsV9EC468jUEe9Kfz z)D~wfpmCBg_&~bfG#ahawBy($aT8vj87ZWVIc8(E6ckd~(N9n)5Y2jIGtbnny2?4# z7ll&}qmswH*aEE#3*T{cv*r14%=Vr_mpdr8jVniNZCRqPnI7F>I4m(%v#6IT;AqW! zF=x40qP1qRn6s?w>{9BHC@hyXWnrlbi?xQuvc@@sF{#`LKJo2N?C-O)b%HaeAL8J+ z;Wz%nUvT+)O<GhC2v>8_Po))p2EUh(>W{xPy)4^^Q+f03Xuo z=D=pseGrpq&F1w>YtQ=c=gF(|t^RY#<}HvKajVzJN^a5Uq@=dqJS2}$uP2=H2V6tv zDrqs8P7_pQs~8cLaAkHA<0@hVA2hWntSGdt(h4a}$`Ep&Q+3FDl_=(R!F$|Feb*$2t5SwG-WB=7PXrz|6-utspP;HVW2uFaS& zg=h-4wkygq;X&ikgfo+Ex@L-Rmn`QCoVEBa5KX#~%27$zdG>dAn9XNc>nMwY*=&xr zin2(}v5_8NjKlkwiYsk7d*3PmONN!Jp6xBvgf8?CO@ z=1*dNUr~A$-<5#s@oyiftY%bA&}h2DYqS!mC35NT1|o`!J0}=wi(Uqt(JVrX=@ci2 zBeY7+t%sqeCGzs(2(01EXqTe4gw7|C?HpJ{sf0618g;nyJno!;+7$O*2jJ`lwc0%7 zuGe7mJvSAm?scr2T=~DX+DIh&Fn{;a-+R5^t3S;8-dLSaU-gJ&HLE;!n_s_bsYSJ> z=H^01ivleat{|8Z({{mJ5`!Z2RBTbWUgmWpIByE;Y)+ruehy>^us}#+F;=}!Gg7TI z*4oTXT!Z-Qi+Qgb5Z13qdwv(dNZOPNl|&+(F0oa~R4Qimj2FH($JmzL{SlLiXE=e|NYb_%EEJS{g?tTq7ML*U;Alw$5Q>L1^uW7^zk<@5O z;>^AMMh-$Tb@G)6S{wH5faPeP`RqDVTH?TRxjv#h=y+`J3}t1IMT@bZT2E1HPP-9q z%kkCeb*{I^%$4WT>^e)|@^Ez)t2C+!>2qsHrEpx~z#5f>rt=wy>OcBz=bpam)taVn zq;*?EBI~;1&SO0xb?@sPGd5^U&t8$uFSmV`|3}BYc(NPGOj2e`bfvYXfUM491yu?? zNW7w1E2Xdk7@O3*L>Lc-EEY#dcG6W@Fs83E)88~Xv)7v+>Yf{okb>!aK4&{@f5VOB zH5*8y#1%%mDVn>^Nbj{%=RI@d^@7einX)Qtl~N3GC^Nx{W8Ti`I^p1zn#I&HniL#X zk-;Fcw_P$S9i@v5CPVfo70czEwyi-4F>0#8m})div<+iGgkd$n+5tfxHYPA#gk<|>*@!@^lJT~6i$br|o`Rvi z?b+zd(ao%7bM5Z7p0E1O#zVczV()RMYOPaM!RCXuo)RJl`-o0eVE=Z#eqR2aWXZ0w zrHM%+q#}%3*d2@*)yEun9SwnKg{$o`?iM^a*=KKDVVVZ#3^oWRM0Ty?!f+o^aHBn< zR*_ehM_6w;Gu~rZXmm`aYD|@4DsAt2qIY)jQ`FEZ4=D7?`KuClU0vKWBV8@&`seFz z|HkWbX|3};x3Y|p)gQZ8Y`p7n_p{@+XAr>q)SOEYNFI>sHxF28$*%MVHcrAQg%1IR zMJduml~!4>J@g4_f-8ETEBgC+y|J$c!|(XKlGffBjqkb@_OH#o%lp@CAWe9WCdNLS zNd$33@WBIS{r%jXjvEiSQYzyn3Z*StWvOHFMDd^ms}w^K3gy@;w>a|9`i}abV|Hss zG@fc~xG^?tO&nFJFs1{2jJ1ZcEGPO2sXOM=BMy&VCPYIBmPIXe zon_f*mP?`aCK0AZu~%-hXU0rSMG*|T6O7VnQbR}dt0*R{&r@RZr_w41t@WW;KLoea zaW=B09F(=vx7|?+g|!xmvUc1gWxXMbUYl&=Vy($pN~RIzpZ9-HBuT85!vS@@1i%_g z=R1rxtJn565iz7V+MBAy++DFbGeJUnkc`1uoht-M6F~&#G4j&!LAsH4PctqJ+A357 zHfrqBb9OwU+%njiaAkQ&N8oZeq>G-5lYK@5M_jh3nBascz308koW0>^Zy{DN2iV3LIFcuvSp2 zMkIhb!djg%L!oN}5=$2IlITH#B6bRbLPf(sN=DjJS<9BGsC2fz{2@_>#3~j9UTNoq!>c^JeS+=Lh!{I; z6B!j2Uw7(~PSa4;bIaO^j9+apyP#Q~)MR`NMyL-ZIQ%(6H?>DSS zk`zqAYz?7ouHVKbxo4TZT4Qyuj4VGZMz0tJ>-S&#Lfz}Q^Bz$-D8_Ul=!ZOdyuJTk zdfs{;s=Vns10ke5Gi!$|RR`9v#54Cxnvk;FUMm-6k*HCUJ(tAfG9Ee~Fj;Tcrfh2k zN%dzKV%=xQOf3U445eQBH-1ro8=pp@W!pc<4kHMFfD!6gMFOtM2U z1qFuEI0|hklx3i*G^G+%a%+@?5hwm-_8wP}G=OmXAsOKBC%(d6tcO<~MIvkQjoUV$ zuOCEjdmnnNRaQYD1@z5QbsZ$qHHxbe--l$m8ztTBTAP)v^SYr(G9FYhb!T(aK_EL9 zsPrCMb6qXDzML`-b)p3M9lh_hRUIy}c+l8~5nF*828q4Xfa` z`uVGe17iMpFC3k!gH5~@)(nHY9IK#||GhGROdG(u!Li=G_vU!Z!^@S&VV18y}&nTrw{dg>epN4514c<4{>rybt(2$2@tut*f@4 z?eL9`*Hs{mS&vk0+z@?w->3RL4x;GwHeymo*Fc^WQIf|@B{w;8nWhzx0dPa|fZB2+ zycRkMv@y^TXyX9ib@!4HPzHrY?z7;?P|lkiI0_2!NZoW{*{Vy{5$7g2tLfpmM;_DN|gP zv1EvA-H?cR%@u1-rL6zRs;q5em&O_kgDMQsY65{SB#{}3fzAhRsfJl>SkeJW8^9Wq z_`sqFD3&5znjg^#JUrQFG^o;pTc|YAgJxF`aHXY=OJ+38eaF@Im=@u5xt&}BqTF`x z^>}kH;4FFg;WkWPB=KhRq>;#7*6=RNe)kr@I%uwf)!kmVQtRKqNAsGmKl7`z;M@Q9 zTJXDvC6G05H9;7#8QAZ%<`I(C113?}qJmBWFCQIIOHD(K8481;;q++2pfZ%h0#jO) zP9*;rHSIDoo3lfpldt4_X#@s20-!aCXn_W;2v|? zC{#CJh3U!BS@Btj80&Lv(nwH9?1O@^wwDk*OSITz#ud_TrNYV$qCv9Y$%V--uQW53&74^XbnOg0xN4V?v6;9ocb@QV*W|X%UDoHN`|`do z$)&%8@3!c#4sy3!gKu8v+h41dUJ20jfqR9GZ~UIz1D@zJy!ACvDFf7?VlTLouH$Mm z)xCD@dTAv8J~nxW)m_8Fchm~JGYltVw)QNeQD9Iu6t>0|N8kdYBLh>SRY_@fAnr3g z5U#)6a(EE&4M;Reuu|m))y6qPp88U0%E`wh%zm%qH5*8^)=4EjXEJTu5}iSt^k4{S z3c|-okUVp)A)}$I8#=~_@(!cYEKPqilN(h^CBkv)eilR&UI}7)`(A*El8B88Bbv%6 zLQvWERbz|-Ngg(W0?DqYA&(Jw1zI7=00;$2T$zl~~0% zv6!HU(G!)&YmX-)m{js8K`ReIC693F@zJc>zp`yfC8~)@b}%(=be_{sYht1zsEwu( z(1Wt6gv)^A>(EHy`A$@O~1 zJhth<(26E_>gW-zm;^&ycwF{F($*pY94UkEblxo5hNBR9uI^}$B9HH#Wp7a8mVpLg zsXT&aXFjH^#>D0tm)iqs<9Q`^L?1cpCP`BvXe8*>1nrt(rW1ib=6p`lSfoY~x-MmH zN+Ti3LR#liQwort=a}IDrPFXgSroKwOX&)HOcIh^SfVXBV~L$$Fc@u6q#689T7m?u zHW=m5DqVvR`=N1bt$h~x}3y*_pMWEB_?!N$}j7m+m5#wM1OFjf^4 zr&9?;$tG~gvNPvu2~igm(IgyJ%Vrjk-Yp_@d5WhGmp$Vry=H?Nqf#e4*--~1=wt+^ zHOakE5YZS+veNC#O|@>!^g%f)azO3ZE>8^sQOk-Ssp;V-$v@q^IC-)Aj93Ir?{S`K zFea^?gq(aojkZgBF^1G&NIjDqv2CIk~f>j)~H8<-S$6bS{6xa*p7#0H>0=4gu z5LTsQ5P=vmJ^r|Hhgjn1+{&eooYy&*I2CxO-CWg{b0YE&{^R|JtZO> zcMDtqRZSS%3e)B0UWh3JmZUAJ^SK~tjr;6bNacOX?$U;jq^}9jH0#C9uSt5l8mApd zy5`y%j4O#Mxiw%@b0$QPkk-C*Wy%(FV@?^Bs}-SiE>CYoyzelsz>80_fo-7Bh8P9s z66aT2OKclTW0T`Sj7h(Dm3sEiRFY<}Dw!&V7zipL*0EH98_OxRZKx)OGiNkP-J&dO zMkCFzQXnmD*Pwu|O)`^2hjE6ktvTpwj42pRU@)ApzrV#RmjgGh-6X1tDByiZ>5>g& zjDo~~wPvM#@b!+@Y#@yybZwiXN-AA-k(v}fb4zocg(CZ@=jO&rhbVXSvcDKn#dI@@ z!dL|{u0&t~j3k8{Q8{y6VTipTgQR#WS#&~lehB)EF)LAJTLWc0{oG#~1I(BcLQq1N zHvo%HUP3v;OOBoE>7;~d=7&P(am)M<^mFTijv*luJ@-zpgVnkLkk+Yha;zJ_a@#0m zRDkZ+_4Y&7@qHDLjkaqF8tHS!%$881Q2AUsEvx4*f1uTybrR9efHlli$3a~)%jNgb z7HruHhsIb#E0LMh9H}L(gmt!MRB9yV57vMF7$P`BFq)b7Ty5v5>2)62JBO-~ z_cnYwzrbpP=!ow^;zTL~Dj=ajo1}auibSE(HVK}KN#`5$)@L=*k~h?}(fTf+MX)N( z*((dQ5re~M3qDfXD#0)Ybg8g9dD<6cYW_%A!xz#Eh9XHSQ73joR0>r(Y6I7gryRCZ z#wQ9+-#1{lxyfx@}eFx8-<5WUB!lm|5R0;MARCkx*3u19(PtH=EH zN1o&GhM=NF1&xTIZ6Z}Ehy;qlqD_K2zTRxpYcr5adf2SB7`rB+kH=%GvSO(_l+%R9 zuO3p}V^bLi>UoEP!sKb>WSy&0FeQm7Km-+6B{$?uMx{a>@)XOe>z{63rIKxJ3J);{ zub3lC$|xM`Kofs={o8CG-?IDD@Xwog_7jLzUs)60^+NH`a3%wN?|3*j7a{R=uA~&-CPm` zG3nfO)>2g=J>)?tn&=bUVl~s)vWOk7aO?~xY}=BdSGWK=D#R#utCAubj+zC>Avq>s zOwv5aXSXUSRGJNMkYu8$J0xFcnzFmbN>l zi;=1*DY6WnL2$Y^rcU>c(&^z>8;%40u{q3Obb{K#8I!K@>3Tze@@!q2bk*GQ_ zg6Px?5+8_?V1v>aR2QhNu!tQEZStvd5JE>~9omEO3a2#fvVquQ3x^erv}r>`MRZ{( z2bSYz&Rlo6QAtob`IXhlk)Rh{Npt=&QI}%AfvqA|nmTl}O4!;NGTsghs$))`)UfQq7Mf;RV^oPzin^Y2<=S)D%JS}S|2~fEDWCf5YqZBp3=Ba)x614433CsT9#bXM`wS@@2{mC@q2mbdvVLcuC?LM= zuh!Si4+TW6R-a{cY{bz%C>U>2mTnRuJ`m6@NgpbmC|pKs8tqX^u#((Ak%a46XA{0@ z6;14@rACZr;3~F<1>>k08$%HlAx69etX7;*4r?7Mbj-!$W6IT4Kf_A8?jfd4P8m(m zk=i8XecCDIvE`wiQ&c01sXYVH=r-b)fzxh?8)#H5v|V5!p6D0Y_9iE`b{Gy_Qmhw+ z#7IzzkadQ21RD~c)954*7(-aCyXvot)&!OB-F~wcAy(j{M_VY$g7Jg>+E~92G*I&Fw zXn;22iW032ONA3n; z4VPbjjvEKh@(+LJds!?$#8*CdNHNF_HyRyu>JF|=GR>B<2} znk_ckQa3e03DvM7#gZHqAl1jVErvNIea#uD2W>xEJoLKLEC+5lBm z;zPi<9h%fZjXL0}G)dAl9nLtq)}u2}kTR&$Fu1d`-g8y^UIRdMK4E(fY-#XHX#El) zk*c*yWc<#7Z#zm14vloV(WQkZMBK3CXf|UWj%js6X#}^mix$OTIO5>i^)x&&C}@3$ z)B$HT5(3sFy;q|(;?u?#qa+bxt&(_lwqo%i;B%32>G*&qbUb?EEL+MF>Of@;ZR4?` zI9XPx(GGaU^>#`VJXhn4<3-2bXhMm`X_G65#KZ^+oY7d5y2ojgNu>7MCe1P}2&3~z zsQ>}x6k5-*L(OP=z>odhk8|PekD?|HXDz{dv`MA9w8F3b>wm|`{^Tz?G1#G1o~J(W z6ek`yLstlmv}h$1+M)uSfBOT(2!&Yw&A<3JeEiQpo>cOiIo^BR(9!9Z!Cu7={?vE# z&hPwY7RL+NFZkd8)xW2$Yb*|}44wB`axh>u#F#2Ak5K!TCU)F+b{B1Laq+?ym7B9f zW$&~Sqv8Gw53s#`igL7%D#qw?$Y5CE=f_;T`V}s}@GLj4UT47@YEb|HAOJ~3K~z4i z2|l?$)XSPLe&K1}^2C$8`#YZC>gA7e+$l__kr*j#!DuvKu}DJgsU3Uo2piK>cw(Bt3L5O%2 z>0G2PJl;mit%~7f50qkge2i~>k_&4*#waS|SjvKBY>*195yWdM3MPzb7d|(egmP;{ za4mJwapuBV7EQcK;s7%GtV!0@1g>a;4>Ze$E4OaZ)D82)W2VPT zwnmdAmnd*Jn-P^~IrhB!$#-+#eP@uSV|jSY$*moZ4-ScE9G6~tiKo8n-JCpgnnDZ* z$H#o(xo7#Sk9~sr`T;{XNW}P%Z8?;t!zT+CAvNlhL3F~tXX1HjafH7XdDG5W#*-4g zj107)Z98a%t-=z^EmVwL3p3a%=|u6u^g5MILl-(%M`Sk#rFzVB&A;qvNIjLQA1h50 zJP@K!qpU6xe8=-bz9m|~Dc<{m@8jizD}3U^ALF~; z`)!PLp2Lp!p&a2{L3`sCJ16ev{Kdz)^z7g8 z*-w3pu4xc46vlCI{RW@?>?e8qyMKgdKYxSI9DSAcs7)iy!7@Ld0f|pqmF3qBH?Q45 z+GAP0aP8fWuEp9&YdwA-jL+}#!$151_RgH-+V$&PyK;@#1%?;~qY+0(GoJp`(=4yF zsD;OxOU^%ZfgkzFf57!yQ-1G1 z{2rh9@JA@B0#BeA7QE-XpW>Uo^+^U>Lrh`V-QPuN&0@J^G#PVrH0Oi=#~<*aKln51 zqb1XJfj0$jd;6Ps;IW4=&hh1EzRYJo{xmi^+NMh-v_zCuh>AS^rib|_zx>ZQcm5)O z^oM`Kul}1~;o#s9-6c<-7!uT=%M?hvF413l0g`?=LTjCr$JGK8g$EyhfS>!Xet`>* zoTrU#Mvv2!Rt!QNB6Z!cIG)qYYbL`9S{XzXzxTmE;D7sfzrs)a)KBnJzxWfWs%SeF z(-~W%F@N*9r+NO;*HAAE`Q{&f54-z&h!1F2@a_J4`QGPWb#EWu8QUO37fY>AOJ z`0QSrp^goW5|zg^eKtJQI;FvqxtL0U4qX;^PM=4*fDnl)@V@W=Zr<^pZ({L^3hr<}WZh7diawnUwJ43EA2 z4g9nJ=9l=5U-?Zw{D1u=wk+@qpR^%J*k;llO>1FwWU;);qYqD*&aSexHDpw2%E5r~ z?g>tueTef9zLjEp7Ck(HxB*@nL@6d`_84rRV0vSV(Qu2ctr4I6=$|v6HIOmhYgb;O z8e87-#N&MNQ(q%41?53vpsqu1f@ZA$>m+5b*+43=G7`Jjp$ehX9ZOsD#wVZPy+82- zjL&WpjIbqpyxF`3BbsqJrVGMy-tfpf-^6eK>tE;AS6*RvFhrJ-X1M^R(Z)hy=$z+0 z|H*go=BM6)9}0_ZfmW9L?|YE*{vuIphT>RUe+!q6Uc!s#n}6gfhC5q`z>^Q`gN4uk z_D89YTAZ<{64CQxpzyf${!;pZ@uuq;dtn_3wWRDd6M-r};1c+y5H3yOodh&j|Zi=@BXv=r~k!2;>3d|XjIF0zyEs(Ch|Z1_x}b3dN?57q z2nlma(d_@ojJ7{>L8Rus%c=D)A4aO7MnKP=PBn`@4Gy$IM{va4_Qj zH(ub)?|1`0@c!?^OG8&LlD);qQd9GmZ+aUumb~@JC)hu;M;AIe*U_{ys$#^$k6q-w z-}4=O^22{kY&>m{)JwJokuGJ2J^MmHh0K3Y3R4s`A#%By(H+3!r_M1RS&Z?hWs(A< zQS3^EDio@{MHeDNJD_fxgvX&)(tq@$q%qULq{p-qE*~RV6j^};oD~XJA}BiP2r9C7 zdXMk>?(anfp(;zRK6jO0|5v}xSN`Tp6ryp1f)~E@HGcLV|2$j!`&>MEfp@*_UF@G9 zv1nUVFob!{uluIAyuKoFm$R)0}_XgS_wO zew+{e>VM?w=PxmIC7~4xXR*rADX>a$`qW9f&?I9vrx4#|-x|dt)AX?0$An z>@k=WbW&5614?aq&-Z@^gSOz4AO1M=n@8-QJHeCh{k!ZveuiaLQ@8?DjrVgJ)v|qh zhoAX{pXI6V_%>RplRbipC^~}oh(POWFa-*Oh~ADvyYEPlqL2``!Rwxi5(G=lYlW6 zk*stiin{B-fnOZKE1pO8Pjg~8fG8BLM)^cTa>g(iCW=o-q>F)~DpQsj1?7`RlFDok z5y50WV-DlQ5LbR$k!-VJ%Ot{K6`cv3Jbjv7J;YC2YHB|A2Y-dS(eci6Z^1S~z%zaN zC4Tk4``G3yRE|93C&J)CEF`$y_PoAmhC^}t=ipMuWRL6 zNfy^uHYrh*M34YU5FiK=BnTps1VMlRh{>_Lr^D;l@4b8PN&CmSuV+YFsQuUQo$BhD z>F(F}-goZr{K7Y!d-)8v-t`tX%@`{igb~Ep8sNrAkDRsRE4=jemw4N|@5ZAEGNZ8y zf+yyY+kW<4tmPxlojA@7x8BIzA9yE~uP9|sXadS8jL_`q&vM}EE4k^W!;I|&jKnn! zF?e#JzyU$fmtC~dNF$Pu&Ya@iKXxxcHk>?j8b1km8IdMqb3EbleV1`~*A6Hf41g@FcMVw49A`Rvm0>OqPBS)+8IK}iz*_O(!AW5#6P|>`$ z%$Gj?X>Pvv4(R0gC@@8it!rfPXz!RvXatmnA=d(%2`CJ8OjGYBM7*ytXmVwU4g{J> z?GP$bZ8c;fC%S-+3e!l!pkg%K;@G3#W?uGLH`WBuO3@Z_*dEE z8xK6rRfn!3?wNyrhuQ8N^{ESVVh7g*q>9upFEcp1ftoMr_H+6(efI6z#f>-IfR_TV z1X?H_edrO6zWN&EhVz4U-uJ-|uybb#xn$QhS8>lz{wSaLw|~Mu(IEy&um%7xBT+Z# zY(x|_y~Q0&h8FJwMaR=ym}73=L4ujX#|$GJMuL(CA-V**WQ>WSCTN3MSYW)h$f4VR zgfBn+EjE@;lS!D2hJ^7Lxl2*blw_inc?=GtGH?*RLga?mtL@*IffTl}k3J*}D56!( zSBjt{J_KYTdEbZL&%(joOx&2#WcVP6W5=s6y~KE9#Msun>4$D-cK1A+ZVPENgL=f3 zH(krG{Kl{HAOH35BP#G?kF^e|CCb4!zVbBlmoJcC+2yipFGm*!p%k|Elsf0DpL>iK zpZo@4WV!yD>!_O=qYNff1RrtI;iKa{AAB#F64aq)tio3WkGqLQ`Y&z(85v_TG1J*FASKu{C5l zgn-tqZ@LI{O_6}{#4E@D>q0S{jPX(9Ltq2nYfxGkox= zjid!ycw9B%!nyOc~mSkEZWKNcM5IRG}q{z1I9^!hWP1+{A^v?17}gcGEo36`?oMH!6?9xXJTti#~!21md38by_nS0dr| zh5|VVtgWACbYc~=a0S(Hi{mf8%GTNdtpr|4f&_e9I<`VCN~&}ZrJyhwS|`D4?;@dP z*O*R@7~5p@CL~fxvQ`x-whA3Ww3xhUZ?UBQQXkpi4hDPYQJTqS+klY(dnf@lmC zk~5Pb?t@bPh$cR#g$#@K|!RSciZ5s5pOvKpcPco);CxoM} zHt2Q~t{GET6O>Y95<0yOoqiWvTSlWXQ7Rk)q(W=ml12jIzs5icq*7kW_GXA}uyPVJ zNd2gBRWqt8I>Ds0z6tm`AR0kObYK|JLL+Rl^myn`9$@9Q^X$7~KgW+8^q zwIjGB9-B79n9A5DGF;t6Mn$jJ$H{~PJil}fSJ!l8LG*CswIl4k<4|k#mi)n!Jex;p zjnpcs@hDAQrQqO#Bg;z`7IrY(pCNdUR!RLolI&EPx*?YaTh}x$@c0*>M2;ohpt$dM zKf-5Ba@b{p^f*&id!YAP&7 z8k94{q2ybSJV!nh?CA6{AxRB};K)lu)6|$;Q8x`SBr=B35KW{}0-eqBo?rS&KK&p5 znyr`5)3b`K4(v5En4aX!aGhlrw%KL0V#C|wEp5e zqnDRB+CJx{)zc+Mg6;X#+iyikLQFm7)Cp)usWB3TNgpwtmnJ41S{soa$@v#w=E%9z z>^*dV+9zDH_n!HE3%vIy-%r`iA;RvP53umc0oFHG$meGfMaI@(i_@E{xX}ph(xA|8 zdM;bo$G(I62_^}l*kCzz_9WwaL^@7d*&AkoEwsrirh$s>&rC56|(smOp9m` zB&K3$1F8z3R3zFVTZ41#zj8Onp8p1$8>>he5lYaX?NN3+4A%!NonOZKNQep}4I(P) zszC^a_^;JP^dio#)dck(r82bAG_l5ePrtu|qUhp%f}JFcqhLI#(9R{H2S7B5#wV-5 zQ=fXA#x`_{4*gIjH79A1CQ(E^fYL;jWVvp=>1O5@cQR=j@-k0T=#GI*;p*hgQ`HSZ zN$RR0*Bv%D20Zo5Q@r(#Te;%O1BpxSEds$-Q!$u~C_5b>Wkj)d5RxfaB(aYA3q3*s zYipZG5g;h)NhAbCAxh%Nm0uR8b0(BAEY;1a%$x)n`;}auWqC_ML@6Dr`zu)IwvG0F7J5p zspom(^N-U}CBE_q4_TQ}tA>E!?eDvbcl`8^;ibn)NAQ6%^r)9AKK-YkX7Jh?v$01l zEt$zuW|nE{V3C=`Mn{%sEu}XSaj6d%0%%Qt?+owwsrT^oeP3qv`IBfXF+nhI`ovjH zy}riCTSmbWjlu=r>ba8`Su$nV9)Su8ARm213b4XsGsTh{Guo)pTH{T=tv)~XcE3~y zQwUH>pyb6Uy^Ta^$tK&ve%>R zcj@*z2&K?c@!03T#Icu-U{IVoewt^VeVQnKf`ivw2{BM~3N}WYEN>0itj09HLPU)u zBMFoSHqY0rjKgsuv2-pzVwPz1yUUKBvDMo`Kb?uPoj?fBF0}t1D~loY~WQ^=O3AU=&d%mChJFAtcs_L{f-?LKTThmiqm; z2*iM4IwSyM#1m0@PE@iLIEi@YXo97Q9_64kJr);sG9Hh~%8~%&I_LRkpXdCMliYjH zJ>Wd&PoH6J^#V7(>1Os_bD+)QlBT5d0j&&~(V$2JARpOqTP$rZp&Nw=1}P0$F7aAX z1xu`Is!%f=R$RCEW~>Nwi;UnLc~P)B8gO!bnb2r5m6Iz)Rd0|r3kWSSD%o8NB?&rm z<&B5<<$wGus7&FNG~%yWF_*jciepk&cm ztg5)_`dj$G-}?}%XD~h_Bt_O^<<(`Ly#H&Q{^qOnqG949Go2X>1yLD-aF{Ghn~)du z^FEWU3Fpq9rYJSt*^;cIQx_wbT>qx)8Jt<=t4Gcx)|!oUq5&y!T^QI2%ab8vpKO0a zyyy`XTG5->T8cnOS~g08Ryd$0F`-0^G?N-7)6g@vj4!42c9u$n=o6QGI?10-?UUKx zB?8$hDJZF!)T)#cIO)jpoLla=o?rcE|CC1_eS}BudkDAL5JR92p1Q8FZDwn&MMg!p z+hgCJedJk5?JRXw(L_rv9Yz_nDHu#P2}UxmE3z^t2*J3ilTJa5xTYaD9b9E`BTpS2 zD%Y4YXLe?uqA0Q6B1L4lzL|!!UQv@A00@HUTM?WnS(sbk#H&l(e%o#ao99@Uo0Po) zQ5|P>b)AtlTzli2x%}FjL8LYmZUkg()YTwrm>T*8N` z1W$3nB{l3A@NFa8i_og2w|~M#5sx^fqNX`v`ajrKCVKhXFLL1YVRl}Q+gv5@WccW@!6!AIra=gSF(zej?eNLDWarQX z*m9mR0jDC822{iCZ@q?ds)=FD&Q3~t_k2ho>6)hLpdxw}#h1;Igr4|TPHO4g+ZW7R)EWLGM+Q=6qv1N&r zE)iOgNyH??)H8`mzEZU+MoG0PWhgQv_4o|I-d(#9x)qD{fv)N#{YDJFajY+`vb8xt z^mC+v*||Q#2mAzbkS?rQ2ov@c8lJ`34p>8Z%YMP0osv8^< z>r-1#2v1|{R$*PWrK3Oz$ciHIiCgs`?`*4f-jJD+#(Qjtm{yj}dPj&FA0rZtw}GQa zj&bbBF)q7e9{`v@XTK4THYLJlL?_W%xgGeewMmmQCdSRi#s(kxqmQz5ZW(QIe2hdD zdF!2T<{$t1KV;A4JE>ib(K+=X@{y1JHD7u3E9eUo?pVBvuF_2WnAx&qFm8D93(s=p zfvZ^T&$F?y#;eC(;{H#5mM0&34kHR=CVBRmZ}ZvDe3AG6)O*vzt|CpebQZhBu0oC@ zqV`EtMkGIbsSV@2OGBWkJr2^n;-cY4>ZL`3B=wX@$O{n_A}U(%N}_k$VmgrEVa}#N zI1Qp{Gr#yfQnbGFAwdK}+X65$PfQ@;aWVn(X|bG-S7ZpHeW=;u9}iA5Q~!s2e;`j&e+bz+rgpLmJkQiZTd)Y%71W|GFQ(y}FPybeEjx={Bw~ zL3%_K+qUJ=dDd1|=yev53YsVqAY2+UnNbIi@R6*gmkL5s+R=&}!;J2*)AT7^n#fke zif*Uh_SYi4ejnY*vC+}EhCDN5CTHSZdN74fSVRdPhsqT~iS7G=kgTt-bN19JuDSjy zy!B*-K?=#-%q)e;llN0dC8JUbtxd`{qlG9^U)5wBdF3_!_kaC=@H0RAGtA6)sNIOo z&6*1<>v$g+4To$FhYSY;T;ph(nwkC#=gyqr^s!|!m4SdJG~DyUck}E2{8#AC8JbX& zcMAraLq7HKNBP7jK1XaUvo)MJeUbz73zWG*_=X;mm6wk5XTSYn?tIsseB-5W@c5Ho zqpAW09kebP)e{hkS6(~LyDT_wDZ2)#C1YQ4bom5V#YGl-J>uA5Cp8_B;ay}#Wi&+> zCt#x)LrW2ziZ06pSZ+c4BzTgirLsn%OR7;(#9aSKs#Kt7|EPR9*$TG*+^wNk_; zAklp3^N;b|)6Y}P7wo!xCkL+BkF}PCJ&Q?WKC$O%ypVuKHsh^5dS zY9ClyA930Kom?1fGT$jMI#Lh|J6*O$ z1MXN((%aCyo~bEsm2G^tT8U4p=D zxdzoUNLAr#h42|3MXe&T0H+cYMoNv41;w7ll#%!bRA6H?gb*pDKnqD#Tk4Gwi(0Zv z_vyHt5CV;Gtgf$7XlP=DJZHRBQH>^GEuCCpou%;(D+RI05JsSV63?)qK^kz%GP|SC z%assNaDuGp2~}otN#!%=MXUBzTF7$%RuYjmb1ZCO1eQEi?Ttr7BrE zy29`LZyyE?K}W20EmJ3M_xUcZ4y0@|u2`m?w5)miJ-6~t|NCE}J69s4M2iBP;-Lrb z=f1!E8_XnN8`wf|R0P(B11_7NV^^m{RAX{ALCB1kp8qC;)eZK~UBU9w2E%$nur*4i zLDA~+5>3_6>85JLHWn8HOU)MJQNwkeeeBLkvI?SdHdsMYesu@UB&`Pass~lkZgY{vzOBi*4dU!lT91V-7J*%xTi3 zItr9cOtBCpjgy=>b%EdhH~*f$_xFE}8}GU)fzVBcuPsI@GBPHEiu><-fKPtx6ZB-x zb6T!S(KEhFAqwAR>(=Rf}5AMu^9e}`z{=qsnWaB9F+SMOkb zV}s50Rids4K1l@Hra>Zj{>c~EHM@t?7rx6gPdtlO;9Nrt8Pf)u!hq039|$tCJ{X~N z#=^oPMxA3vcaF8u5?iO%C`(1R=n|czo;ZSYjH?CI3te~qEt`qPX(3M<$_*(9K*S#Eh^(aTb^IguLKg(P1 zy_4&1zmX7YmX59P`M-IXtcjFF_RjV>xO*q#=&?P4!;P{)cxhY#^D{?-4&-o3jyb^Ij1|GU4B&J|GwoON`vgfn!Lnr1R?(F+1&6kdC_ z2J6_yB8{SJN|eYz80sbvq6S*FlaF|p0>pMZFHSXLTU>7tI3IDYA(M*3H(tyC@IU`1 zvkM(2bwh9hDGVo$9_4}iK0`BU2rkKHhZt$1XKg$tLT%Zeu^A4p9S<$75g5~iRqB@7|?_|$hA2DuP zn+#7TC38iGS_CFrH9ktbNLDAJwJM1hSKIcGC|y6T-Ap^CpJJZ3zaF+t8@+Qa`efQ4 zy=Y&ZAXn+9yidbBt&(^9bYNv0%gjv4vDc3AJOA$g;cYLxoz85Brm6|v(#gAQt_^tQ zrSEd~=u9#mjQBVI>;FaBDcQ4oH*bC0TbP@hN&Q#bP*oF%krPMH@P&uING3A8 z4J@Bp;h+DvzsU_Z-@ssFgR`g3k;?)tGlF+0p$U!WkN@94=IO6KgR_BSFCSyJKhLll zUov568zpVeSIX2en6`NT^L*rAva724E%sS`}gp3zw-0!J$wa~^c=kF1}>aB z$A|y@?{Uk!Z)5SmUZPg)yXiV=E%@q#UxX&m-!n@SJt0Q2EKibgfGRR%%o)+}!|#4C zJ9qCU;ou{-YEVI;J71B{M>q8}7dIZ9Mwm zBY5wSM$u4n`&(}1zxkDaz~Y`AG_L0AYYy?Dzw<$k9DNNJ8p>`-Z7oIKL1vPDSM25V z(X;4M<3df|HQf1*w_)-ukq?ByHj$-st5g$9aDY!%CcYh_#8%BHl3Famx7g9?;*1IR zm?_28hpwXAD;Z6OXq}^_;guI(JtyJ#gMWn=`Z%U`(1aEl@jYJ3Y{k#jCKeZv}diUkdqA> z;kl~pBaA>)4&?(KG`or(QNp>=I-7Pv6cVRIJ8WtPog!tEQ^0-;LFES~z=9-r?UOm9 z5Yr(kNewAXOZ%9n+AY3xn$?FW@ZJHs9o9sY7ObtVp^ap?xy5Jx>N5zHJd}h;wjdIj z1k7C$OCC)oXrl>Ro~o)iv38PUFCK*{p0%AnNGX_%E#16_tsOcVViV|PeO~$2s~BzQ zsvfTP$udT&^gc^Lp$$i0Iz~OI$yLtQg)MTOD9qn~UqpL;J|=yJ)e9SBqQlPJJ$gNZ zR*r7BgLflhuy{KmM2E^UF59<&cY(KFdp&!0?FV1*;;+t{lfQfcz4{gb`va&)onb1)s(WLCii@?1<{!WhUd6}1< ze+e-=!;jweZVny3ir&6?F2pUevcserkT@RlEc2gO34l{2Tg z;f@<|-8}WpqQtp~)|#LNBUe-Fz`jG5Bb1<;OfWJ}%0@2Yn?P_9g~Z1|(1L4jxDJ&| zJf2)<7y;GRn9cbN1;6l%Kh5sNIaV*M6GcE3lK21kds*DO6GU=)9BmER zwR0zreBt5kOeiSWsz>ZOu$N!^&0pn#`##Oq<`%Pav+TQaH}C(+_hPaPBQ@2yp_k8a z>i8LK?eUH@PzV45p;~VqpMq-I*{5Xkc8CIG#^9Qo(Qq>vr4 zL=X-m4VlWQw;Eph`gd?62SHND!1?h8TjL>}h0B=Bx@aT72bA;ljE20AL|{gn41LXr zfQ?gQx^#&`weY!k$@=^OdB+xX-v;5(KD@FGUXiH*q1X=6NhJHCE@=qK*;B|wI`Gb+ zjY3L=ZERw<1(^OoRLQZ_T90);DT)F0R&t1_TuqTD`w*=)xORi^$p^k?`izGaMj4z< zgRgo#LS=^FlF)eY+rJK>5)C`JWWkfmoM55U1x;lWN#gtNNkSH;DZWyPT(Pudsp=7P z^M)M@8U21ve`cOeDJcp?W+a_{Nic$Lw?|V2UU_-I>iH!G7hw5p&DMqhUy>WpsvQW* zG(VVDJ0YYBE$MZ<{_%zkq#<0K%uk0Z7wMtXMJ%x61~;-4GG{Q^B+qlaXt?^0>$vXL z!yGztGv)3D7JGBVXc48sHDm0kVpexqzi^)8FP|j58$<>|ra^$0kz4M*0}*e>3Cmap zj4}wX=oUSOD;F5oL$o$r7;UmNSm8>upV+{7JZX1Bk>D&M!Ii8D*etNHeFrEO@Ve`Ttqg3JO=g@GvrZoW^0|skBL617YRYz zI}O{*Zb}FL{tQQm#AZw0Q0?GK$>cEGW~P^#-lZQ(f4448%BMI~L9!Btl;uv7iO`C# zXq|lQQ_ng{0v1_D;~Jz?iO(J--J*-N79|DFyGzbC38~c9qJ*TbE6Sonh>=ovao*vb zOF?Nm*d^kuLn)ay)=1mu71XxIXhW0eESKJuZ5+6il4??uWd)7ZTv%-wY)-has+gV6 z*fC!)H`k%lk$B%=GKi|cxpktK4A&Y~&Q2H)B++Gvs4z;lq9%#8rj#azn4}uZf*8}f zC8iDS^`hw;GLXtvO3Yf@KD<-ev1D(dRO;bn6TyQY`6M6wCqK*VRf{yi;$s3UXG(JD z`u$9#$3>rv=z^mZY1+PibeTW--9KcwIpkYUeTSRwybUFrqz8#(YH}>22kTQG(M6tl z=4p;S`z?wnn79d!hF$x2(gcT#0WwWP)w;`jY64M8D&;u4zRZc0Q|!}M;M$((=K3b{ zdWM(2_5wFvb3J$5^Jc8Hc;N`fQu_%~NrX0d>k}R`B%9}E;`!{S9^#?Td;uTe4?g^# zs3r~Xc-Nf(7$ea#BC%;Y;v$&@Usn`G0YP)>)EORl;M1Hvdkz^*OQB3tY%N=;kBBXz zA*u3Q95ki!-pAxEFN~&g9_yi#b?_F(BS%$vy1GLX9TJ&J*p{^xeI)vbmZn8z2wwQc zi~P-Be1c#4M?X(*zK0c#Kzdj#9xalZQ4EqCL2f#HDI+{8hBmYwt4X~32oy-3yDj8*{T{NBxzb6 zlNXl{HW3f}_Q`zDA=>O%YDw*Dq(~Z`AX@e6E^6;O3mON&>>E1Unsfbl@z>T`fSa3m$#=Veb3rrwCOlyDDGvhrjp7gu3C~@Ba}>lT&$*x1J&^us#K{ z=p@DzoH}ui-}$${!wb*8NLQ8AlP0N%t2C7HjoZ$eL|X++=YC0SBetI7>0hpLTsXag zsuiX-_=#gR_RY-VhYi?( zaFIf57P68k1OtVoTF8RVGuW?DsK(z9D zQl`v3xV9`7h9Dh5Bsf*FeO758OGpqOk+Rb$MN2P946XDgPEYRQNh;C$c(t3<)H_#9 zXGJ0sMN3p@&t1f%PasIyy12y5PsSe{=!k8VEU`Ui4U9(-s3AJE z@F*2fDkk5vC=fL5Yshv5ru(XtLMyecYapfAzSOkVe&E!;=TN`(Tfg;Num3IoWgb3Q zCYuwEzHpM|69b&BD2-sQED2SUM0T5qDGHWWmI*O(^R2fbqo$knkQU}TGmO`V7@5&m zC5#-a$Ch~F!LRV0$De1`7qDdsm1T8lh0V29Zn^Om%AzDQIi0LTI!SH~XJ0zWNB`X) zV%8nAwj_FJv|x2I54IK;}p(&!Ih?3k(j13eRG8b{1TWp+J;^3|;c>HsZ z@xaIKM^?~L1*!$AhtOI?D+O}uN}3)t8Io>i6q0Yh@FL@_G1nfvnmj7v&=NKp-0FmS zdC2I@Dks1B3LpQIzhdqDkl-ZAC_80NK}e!dEv!B%d(}1xwm_uU?V_c^JHK6e=US6# zgSCz(IHHo@3)pWfBU&(i${^Fj{DXfY$>o6UV0tl2<>Cj^c$)&>bWjDYD0C7t1X@2N zk^!Dg-jnzKMSOC>F$ISOykr$E0X?=PNjQDz_Y0}x*%;Zk`ySFQb-|DLST$W zYty!*z~ma;)f~F%N*4DoAhbvdXqS*EE^B)nFs&uOT6&dF~;K! zc62od=I3y$BbvrDw%~Q7mNlK7UFI&|MSs^KMW;j4RP?(A7naYVixL&#?8!5%o?9hs z1-ea!9w%MSkO{U#&Fn&#L$@EMTv z)P}S$bwO`#md0ByoIi(jkj0!(fp;D+e3HBqN!m@t#De<%0fJI;`$3N};U--mIYa75 z2sQIN<`|7@0ty#lV>G0)6V6p*Cc!07d6mSLz4IucPyuulNnpZgJT;x3W^qT4EBEeU zR+X4W;ztd3Qd3tGMDUD}oZ8rA-8#lGi3(e1Q-&oHBh84=T9;TdADEXJ*Y4WSPSb^n zC)yO`rB=9HalYE*?0CQc%T};SYhhbhJXRl2e30wKzzJls-+uTh?A0s-%rTNf3!E-Vnein^I|qU{RkM{5Q8Dc#Dt15B6WJft7NSr9iI&p-Sm zVbjuc8O~Yg8X7-g>}#Ty2n&m9mg?Am5Dd}DMB^kqpwbIEB4;Z$tgo!|r3W8pPk)}h z+Q3r%cS%Pr1CEX=KAV!3z)jUvXx-0@tfV7b;LJX2}An1xNwRJQxFx%O| z=48mQas(lWI4qGcr4+T#TViXapjLJ|RKp?bjiXuK9AH%Z%!u+7L4^!fFT9Mh1geYL63NlZ{PDO%@KnKHD{W|e6eo(4yL zIt-Ko+CFB&qo%Wym%NV`i~QK)VcV>F`~Ta|QEZ#_Z70!fP@IZkr`NwU!)x!&_H~68 z-O*;eq|8+yx7#o2`y7ZAge59vrZJ{|uP_OIg=%3GayuSOj}TgkO&PY|7bR1Kdrq(DuWK78%ZfLTqQ7GCuWALQ@_Po zWNbhQYy=@Qf)&&XGzG>B#HcL?5y{&prruTKDwGK5OrSy_lc_ftOGzhaq!+jliAtgx z$VJ46hT1yjJ9Es$K6&j?K_+~v2uZoVrM}wAB1E8>Saey?H}e#A&d!AyR-0vxojb~0 z+2_icE2%eYbjTn|d=MydqPG|s@RJDW?W|J9qzJEwsnnf-3OQaRp0x3ST1CXltaHw7QU{L= zq3yGJk`|&Tikd2m*q9Twps|5kD_%H%j)U{N*l9}gMv%vX;Y6T-t_bWYyM(G{scF)H zOr)Tq62J*X0HbN5!%0DnV{7FcH!SXB!6-6Xl`rp@4Fv@=%ybOLstcTD3oF|7AT*Ao zZX~8bOH4B}P*Eh9k|2pS!*)RX-cZ&aZB!Cdm3S@*Tx}~L1WP@&dYSfRw{a}7-H1dh z5}kPNaf*daS;_Wqp7vy&bg9od9jyuoEgH0a;pBPL_E&|NVuvrLHN=RD0)^U6a8l6n z&{AL#uDvz|QQ%#MkW=l^{}sL?_aV?c@m zAv}>Lt@5A7sn-_T0Iec^f)blN}`L& z3OeO;?Q6Az2QJOZ(jZ35lvRWnQ@I}7u5)~*} z6a^9h2@w=PkOTpOL?VDe8UO=K?CIP$z2SuYaNgT9G=pltLZ_;0db)b%cE9($&-Da?ZO8v&=|)?G2o1as6ES+PBCSH6cNH0G(ku2 z>Qh)DSutZW?{G34C-E18=_ckhNYBV*oLW6cGCRjiEkUl0aVjRa78PrzL=z(|qL3^V zLrNd6ne!em1xkfq);k}%!O8HZDuxq9m=G81pMKW5sQdq^>!){BQdPz&)`9fZKrnQQ zVF$MnCIy+1v*g{qz+Ed7=Bh7*4289y-H1g&+mo41UobDf@kG~18c0oMIz9IWU#+;$jt$RAmo61DR8bb zT9FE4N-{HMtTk(Et3;*54-GQ$ET3OO>WZSGKt&4SDl=QJs7&^-6%W!?*q*5BZ0K1W zrI0u*%0Vu|jVM&ekU`!~~f%T0*qH%aH5TX(p;4u=;t}P?1$F=9!(w)X{j8WbrUBGpvt|Mw1 zF3Ak>=RT^#0ZB~p{NF&g+Sksg3OgjFVJXQ5n3hZCovOM1jpv9|F;*s>P{#04??lS zhhnJ!9SNicB7w|3lpg6Ex)ueDHFG#6@XCP-+{TF~YIuKL6-^QB{URBW>X^P8F*HL~ z3d;+xynrg86*rJxa^mDkVq(08TvU8psltQ7SFuJSFk-{T4R?_AVe%XDlq5z-tPtUA z)`Y}>%3D)M5+Oq`YA2nnP(cN=dAf5TEY4b@DCDx6(pJMNMItl}rI5y<3y0U5ND4YC z!6kt{BO=F$0z-8ScQ7%Daa2jN5}a@(I%b1{*Vh-(amsXB;g-20vXV&Xz=upaU@a@< zkeuLnq@=>;t|~eq3(RScQ?Ovy$jgrF!gL;^AvY}wXBF0C*u3Y_Op#O5%rq|?&qU*|3B{)*z}{2o4i&o8t_cu0r6uy+Y<_p^OK{y z*!;eqT$2Hq*!;M-SWi|s?YPY%>z$~in->OLfy^HfhJX$&OXA4Us717!DXm6AT#^1! zo+5LMMuu!`Da$chC4?tfxL1^nzz2EkOx&|Cpzxbp#<@Ts zb`xyMgOD06AQF&hP>Fz=C6_r?IZ~<6zM4oY&)63T0Y++^cGxIP(UlFIODQT{yYp2P zv!gvR)1XfyGK(5r#qGh6)|26&D^F(z(#R zNsSc(BV@q)09=Ln;ZaJWv_eD{hY4154usRV%vI2d!)b$;hCDB6Hrq&{gVM-HV4#~e znXk3!>6p6H6k3C|#3f9{F``~aNQ=!gz@TJ=D=nqTsMi%qoFa8ZTu;c$jNxjZL0&Q( z7ZhhtaM?_cR;^AgPH{s+Im}75V!qyl)Pgl^_>4?VR9IElD+6KODMQ>;TyfRa?C8z$ z#t&a68?UmnIYqYGCuydLnHo3V@D|p_LmqkPyTtt=#b8KQhBio6;*B4xEaJi^qUu8b z{*F)l{n&piHc#T=Ve2bAvl;@4i;v|0&Chi)E($+Zs3(6; zI`L3UCrkl3!FXT-qxl%6A&H^Wj_GzHX1WPlt z)Ci|hS`$SH&J-7hdDU<%JRk@;XtFvc{G9csETl?FeBsFQtV$8RkfAOFL~(?*1wOHq zv1jYyJsf!J5kxB{ZKl-g3Eo-KC?<&$N)3@w-2H_wbME<*xIu}wl2~ZUGRX6cEm7KE zL=&kd(}K;vPgW?XCG|8y8B3$r;P4Gc>F5^2SC?3M{xo(7DsE8X`S?HnB-h?}HTm)e z-}=(uQWhhewZux}jKE4+6)A@nf<_Wi$QpVo=J54baLHwd=uS-|l*S1|J*m-7Iz%$2 z-m0^(y1>`Jb|3fO`*)$YHUf+d+g^%IE~K-88l$Bkj7F*fiKqzNG7OTOGw4L&bV=M% z-1yF$_|zvp#nt4pDq#M;J2L;xQ zD90Arm_{a1(2om=HWncr?WTfmgKMt2iW`3MW@_~o8yiEs&FIa}qf|s%uY;15*7EqH zKje#_|01KsA)~_Z^3rMc^tRIxb!v$Ytc=oOM+LpOM%?OgKHuQ9ACis6IIqI*=?qaS zi5oE=|IA0Y{a1d8Mx((W{l`D%8(;Vv8oh{_=^A~Lam(!=8^8t@lN+Bn*(y(IyDwsrU4uLlJ)8xs`g_E+Z#3z$~9=@jnY&MV17Y0-T z3UeR=FL#2;hSRmcm@xfU6JJz9Vb_%`)f%%o3%Kw|2*pz=wP_aQy$i*0avv}Wr3??> z@O7B*YP}a|t+2KTL3S8ot!T9(dcBBF+o9DuI?736j}U=yKgx29%h9Sqq?$B4ZKkH% zwA*!-mn`cm1zK1j#57xDF3_4L*Rq0Bj5Wd5@8_&HWg(r!Fcd{jt(Fo+F-0LOuAD?j zi&TQLY3S~o`8GJ2; z&;gjm;oSs7tw_li%iRc^wnz(dY3Y|69C`Z@e)YHhG1J@TQKjbWk52G~|ML%MsFRb`upo1^pwV))eOewDYq=X#_Ts6SK3u>PN5g+S;oD@5RxcZt=?>`XF;#wsPdkBkbI> zlh6PD=P@fqknL&BQZ}L(c}%Crbd(@QhFAz9Eh!?&ou9drx7~I#eVb#9XP1a+rV&|| zqjikM2Llb@BOm(^ufKYNul@CXh$v#s6uh{2ioLz zx1VBtd4scO7O@@*1Wx#HO#U(I(PYXEo06a(qYJ?WtntF~6~SIsG30@67WQB$Y7SRH zAQvnCoVA<7rwLLUn(ztdbpkKAikKdprlhLy+lh*60%iTT$NeAs9mGW+uCfYr)oX;J zFDnBU=N(8x96PpdkxX?ZQmi5w(5QQ)$ceSYn4Gc*N2);k$|;I5&aI*vEvDx?w7N}} z&MOwrt>MZ#u9V;toR6>$oRdT%!kCggFE&{}KX1J$l}$l|>?npAYi9?XeCaHCG2T=* z$ueYTFV*^d;t=>U^?EGpWjFWnesU+b*$PNo`M;|KZ>K3p!i7cpQ;aoPGHWFFo-BiH|5u!ThD$ zdCN_2L8K0yC_1wO8ieBb~$vh42#P!7E1|p%9KGx?ufK4D@zQ`T^$y$8HuG_d>8Qzc(x$5$Ohqkb;uhVw zMK^9T9oLzP8%)IwX5uDu%?{goGgy~%>+SF5UAMj)XD!odi>JQ*7|(v|2|8t+9j!U) zB4TQ)#ex01*mrOb<09kGp-Xt-spn9ALtVtgal)X;7@GpCAXbt_t%h|0iaB`W5w7{* zO>DSva49MkViZjU)FCQ|V{r8Gs=1}EV|Zc?Mz zY$(FqKrk`q@RjsdX*HozBIO14i;{Bl>k~Js$;=_VmLrbi&0%i!6Cf&T6Pumzr1QK0 zA^1(0APjIX(wP#v=$v{}(d)%@JAFFMf>xuT)i5+_o{&Z#yj*ounKL^<97lxI34>M+ zDGTQ2XPD_tQ)?uwt*>Fm;kC35CoK@@C`P1?{fBolw__HSM4MgyPg6F%DLYaC=Pji% zjK|}E`)n#gF6gx1b=&)B&-ciUrIFSdo?fEAu*|SOLPv4H>xz>4Y|6}ztvDg5&9vEl zbRT>bTyBEJowYa-Y|;W(t~yHn7_KtG*F0VsWGm%ux86iL+r+w@np6Dnf$#CiSH4Fw zlDOQE)FYmK_Gun@?! z69hxP8x7WE8T}7tWob+!(O6)kQ@)MLwc*As$*ySQ%lv{>1ue zIO$KtCOuVA5}RGsg?}45Naw=vvU>W52pey!6GP}$m8u>pm2;O+1iFy5$cc%%t<+^o zY;r+eMdjM$O#R$3S=E_}N{IwjB5R<6rD;TWs!neSwGsWg!hWy9}-^Wmy%{@O1OlQPoLDYkme*PqEfgtd058-~D6OUOk5y8|lMy!tyZ+X}S9PYjMU9#|gdZY3AEqYJH0y zhtRfQY9)zPuz4$tL5YC>%8GLHeg3dg# z)a0clA6cG#ggr=Z!FWwYs4mEG#rD5b8F|g`)}^%(j%9$ZRa+eH%R3|G_?yt4Vh{NdBMvI zCyBT3BZ_N8LZF04BQaLdl!7iXV-@3*1Y>i&@2L1t$>$XoPj!@^-1OCV z1sF*NN|kh2X_3-b*kd5k5d~PlTaQM8aiI~Y*eFVRRHEq3%wTM2OtR64JkM#Sb)*Q= zWM76Oca$=*C3-^B^FJ|e;zD8d)z`&lBQoKyDxpXsNvEZlYD1@0lBOp3P8g4t zohFAqCbGd>X4(8DmIEC76Brrv=S{f+Bp;uxu8mM6^>+MiB;ge zMYynuO9fG@20*Md*|^}j7mhPpE9e$=tn)Y}si`^*4KKfNlJ$*}xD_F-p;k&F6Qqz* zE2J&3BA7+HSW@pcnVRl|BWeNTl`%D0!$mMI4Aw|W5e!>S96!nH&!6Dn!2=X|Mv;xF z2~ApB5*Jg-7^8!UvMdZ9Ln*@`N)ikr!p&>2!hv(dPEu15-PtZVV?-gD=}dE`lq6`9 zR)8(6a3~#<$Qpz75gti@IA-De5@lvFWkDQ8%-1_eEm<9}!W+dBGoh0&{jiDTk5fbvEAW9NC-8N_C0x~MF1lg-4*eDLhIcXeYeSvot zAtEA~QY$?3Mx%6sN;RiOBTAd#X@V~iB4fhlbDPw?Kq#MZJZ;4;5hmcGPD#ALHo_2!JsZ(0Ceyy7UOba`+kl@jMbD~T3{*>22iyU)HIHP(kYQaGCJI%zEFbehc0 z%@en#up*-L3Mn=7TX!=Ea6{i?e^3-#Waq#FNZurmv&h=L)-Vm6P zLdG$rHPlr^VI8G$)KM4z0za|dl!a9IiR+EnJo0$JSc|nGvLKR@*m+{-QPQDPNvTT; zS)l8ola)#^CPV86wk%0xigSXxOsF}Huny@$u(C0REEX6KS_*LBe87fel~-;F7->{G z(h?d@LGEazb$0LB#j#yI)?PY~NEM~<_!?wU&Vi%*n3 zz5;0lsfvk&Br6Mi?9pk2NJZrVkoO@=N=U2>n@$#jnv9VR&2_ij!0A(GSbq5|Nm1fUgN+=%8L|E9 z101^kO2$}PtuC`OJ=XO}WG+xf&?G|Z4!vfbQ(~R9@djBrVs%ikH15-j0*1FXSYxD1 zv@Y?&(e1SGgYf>(Y@OkTM0rS0 z&_XdK>qr5OfutN5O6^f;%v*1IJNTG!p5dGgR5}TG$2)I%C%Tqka*Ohcx>5{XiMOCp zOr;$%B^Vc;)p3DU1x|sTV5EWz10f%-`sA=2jPN{E;fWz~#!(7O($efYxP#yR*Z-Vt z2e&a84@hNx z8wN|lk`U3|I>VoR;fpMuTVl_i?c93Xt)x>8+VeejUUmtOpZg(otwL&o5Bn5AsGlr7 z22*+0Qu$<9N|$kH&vukL&z5a7EG@qdzM$ERX-_qo?oBf@yPZ~d2k2>ZI*pE-pkO>c zL$g1iJ++ni)nlAHb)3;~NLh?fXwIKI!_!Ya!P{>95XYWc=h(t42y-D`vO!JPtH=gVo{z|_WhgDBEvQGW z3K^84V9GFPva&knR#XyHpl*bAqAEfHz>_2?&;RIo<{sU}^&hyIL76jma5r!N<#+R= zho2-H=H#xVJ=35)+u`!-jsk(io`{&mHx@Yg;t5hBTu}zqMpfvnEpb_aEIo}{ox&At z+qZ-FeCQUUM3K}Q#AzL=CACIEcdAKex{V`vr{=~`ItNk*sK8sijBphZUqdCKb$H=$ zBG90yh|Gm^SmQ7w!}4qANq!+_-Hz$*o#T#w@oCIP&c^9QPQ7*lFCCX$dz2lQ?xpYr zW@JdbqJM4$J1)_pi6{k;1Fa)ul#pvjJ{mEymfRRt2LqxcCM!qG?cKtM|NBo;S9Qku zkY=liiZu0Rjo$WIR83>7qfx74P*|@k4Wh956A{D`zUP=ao0o_iQr@#F;8;i@- zv_dP7umW3ndb*8lDC%;9m3+v^n+g)DRz+17)e|kaI|bZ*B1VWLNa2FtYAR`NY4IEX z`k&I6PB_1Oo=&%mvXbG(8aj!Hn+Y4EAxGYNgn#reKga+6KmBhME9>0y!T0dtkAIln z_8!(7I<+>L&x1vvEwM<}%?3B!dLy&j=lK19_xtQQu#32%F~Z`|bZ4efQH;og!cPi; zS87va@Z-yaw|F72zUsImh!al~kLdMMwr!v0#phq55jpDhh_v0Hy=4dOEeEMJ_A=Ew zNK&7nbOPgZ>UKM3&}aSZYcv~8YO&&#m!E^IY9@*?uf6gj*WH+N_=-z-I8jXWcbo2XLo^{;;yyP6?0kCGZ+$=ZaoNDJj4 zV|{6r=`D4v_8h+E2v=Nt1feWCO0hP?J4glA=0uSO8){04XL;18sk_v)M4Diwu{lKb z7p~z%!8gIT908Y>LLiLch3`GX&ZGO8KfIevj%m%b(X*N@d$w@t+YjTsBlkH2)5m8J zXOd?g`60uT%hY9xD?xaHGgaT^EmI=K$5SlitBlHm@y0L=yS!y?#~fRCY$wrm@FiLX z)8{DCcm)PaS%!{iFdUO*C6P~p@v`s%NA!M^>SMj+^|eKe^lYzBQIi@u_5nM$idq@- zgReeBx7p;#yRT!p7=8Q1v{KjwnCi6SziDOBZ z4iDb-AbZ@U}LbsnbT)UU6@;}E-jE{8|*u@m#O(SYv(sAeAuIv z-ee(cdLjIb_2w+37257$vqiU+#n~n;$qVw8A*qW)yoe1Kc5HLJhd7BsT#2_(8k)@p zL;_cO60eYjBSKOV-0-6qC@d&hi8dtCNu-s5s4T;c>V&U&oQkt&miaIL{tx)vzxoX> zx#}>!rh^lX6S%^lM2aYbY_*|lES_8C2lqX~>rcK&S_Wg2!dZmWRbr||slX;!KD)@= zk=@8xW4$FSvtW+o9L7RfmPC<6;#lA4(`|Mck4sLUKhNT5gQ;enB(5P!i>iz|0GzyF zT(LQ5^#bV~(uW(|m!5i@ke^-W?mzqzAN$SEvg6QhOyMYfL8KGB^`vo%ENn1>jvBoD z)bo7#^IwFelDeo-S{tYkN`&s$Thc-@AGe9L;`Py49{cw9xb>HQk$R&>k!AE(R~Y*~ zNRJkhe4HUgnB}+dF{S6&@fZ2S|MW*Jo;Xk2 zBuwcIw$|EE6dTR}03ZNKL_t(2EQ||OZmD~iRVi_Eny$+*3X}{y%CaaoO|2oQl9bXo zB-T~KP6SE{GF{TyKF<}G9cHD!ifASrf9!dFc-KQT*Pt%DjE*ny)&KaXs88R?p|>1C z3dxSR%asQ&Wy@@je!q`OVottrf@dFijA-bQ7S6u9$d8JM%MTqQ^Oh*KL}O1)MiiqA zEd`^MHKJk3Wi#7JtOVk(Q)vlTNn zGt2DO{q(k7hS5EYs8JRAxyN&hLMS43Av43NYQ|InSV9+wy4=pdB zXZx#fmMo%V|HpGBD_P`^w zw)EI}o9&;lEKESA`%!5zMkY%KKo5C6yi%{$-!ZW^s7+AG%2E~5*);Vj&WlVE$1RJ1rybz3X1S`^pp4<~!VU^G(cenZp^! za5SVS9i}Y6TeK1+QOwffDi1&O2tR!CX^bs6(_bM?demYaH12?P;FYYj;2|A!LVOk> zc8S1z6htOuBCVcW+$aA!jm{AchFj0`p0#Cxq>q{g##3H85O1zL2 zW)=o(2#c_i*he%(%4~g#lgD4@cmCJk;Vo}F3f54rjbI!Mn&T*D)E|O()EWs^2EzM^ zS5EWF3$LJsgDA&3$0#3@HWKibIMFm4b<(&)tJR=hucPZV$~1>acKfkvC4Aqf_fJ+9-K>;VfpVWNWiS zT}srjMB89uqI8XBoMJ1!CPIW5ZgIgobHdehUf`?YQzR8q3-Z`fOS<@toHWr0D|zGP zSCP44OKS>71vAY#3Rm#`zj}Zt?|l?odWxZ;HU<5qb*4Klq|>atdXAoNl9ZO%D++4l zFD>$yzw@85N+Gr8)Vb4axpW8GD{@m%6Pl*b%qI=hFx-p5l`U*iRZYP!r2KlcFRD|V zMEHndf6TUB9oFnQY7I?2R>W~kQiCXM)0x?Yif1Tn9qS>E1X_mEQ#b=!JQC*xNxR3& z@;ZADU&UjOKgs!1CrE@xdl+XURH~@8Q&cR`+9O=Jo;nKg){{)9pS9kcg_K}0A*Bim zBdrj|f}B`s32=__pg;>9vaG3iaXx&{nNz2E<>eQNg(Obuq)EgmA0wUO^;0J?0#scx zaAWpfeUQCJ58&sgsKuJZc)ol0{q$d3#tw^+DW5pD9^OsTuCejjD$7d?h(uFb!|e1d zyv&1U%dM7u&_ZQeQwT0skKZjp0g88rtDUrfg?T83aMx-?x zqXGMOA7ETm9;RpJIs57v?){U$fssW=p|ceTln{ZBXf57pMBzxaVy-bo(x~&^_q>n2 zSL`Fwg2aN(p-du*(hzGMCclZsNk^L08Lj7h?XJJ&um9r9WVTOtW}463@iBJq*-gDs zqgii|rZGC!L~%r%rZ}b9IKRR}U%Z!%r(S19CzOMnL0z-^%FB57$KOwTYma-r@^?IX z|D(7fB(dh?{L_E+n_TnOYZ&!&{_GF`f``BP2=!Wx;V9>g^<^BEJySiT6Zo-3Rz3`izs7jI zPb8Y;gN%G(Kua`fX9T-ybRD>vxZYX_z&1X zYc$3{C5HZo*O9_z*BSgfC(~s%ccu59Mz>AWtc7&SG!#?m1aVU1ifgXq@RdiX#}TCw zs7i#9=#=C8U*Plq%kR-IGN$*FaJCC9o&a6B`0TJ=Z!~Rqvd04k<*)<;bWip z7<;Zbz-Tb$)qR)pjX(JsYsb$~(-K>hC@Jy6AylyD^Fpw9&ptl%f!i6X40Mq3DHkm6 zYK=Nc60y3nNIn|TZFgxVbuK-ymzSP>g_oXuf!un|+aW16rfM-d_fUk+LdoDT>Rh<4 zrFRHviPIP}wnzmgmE>*BHSfQkU;M}iD3s%-`5EqY3EzC`bda|iIDF(NSHAUH*2jI? zGaXv(Hh=ve{v4ZSC_`n0L2%-?o+ys7rJ<%H+&JgZ-d$XO_!^?QI%Aik5ojmyiKaA` zY&@p42B!rG#V{+Fp6YRE?;&hfGQGXaouB+Dx8Lz$2EzeK6ouBinu1#aD%O}hXJ${2 zkNmSw^57rc#j6iJg{XVxuegL?`rOB`4G_+=wb5ZN=`hSQMuQBMO7`yFOMAM_*6mF` z{cE4#g=5ci=9P0H(tB)h>l+BA+0|;Jw8xArTEl8EiWFja40Bd9l< z6osK)Zz83}7*8!p7>)wAjw?|pv=!7;g!GPbIKtWzt36f;N+l}hL9nuP(qE8F%Si|& zRRaJHg%Xtut_T@SQpFTSD6Y~#mKW4Sf)NrKN0ioJy(1CHrpgewD620hx0D1W95PZw zu|!82DFwZ`t+bn6N*CU1kHC~Au}A{HybSqVKVMAnW-X*XP@SB2nF%53mwx?YeCtbp$MerTPpWgW)UxJA_=bnnQA=Vz{@G8m|B^lACc|c)!CIfD ztfO;FlqBRL!%Isca?04U@9IlA@X{%Mu&{zz3p`8jE3A~@7@ije&cVW&1#0t6Y*}DU zpxOwj5T)VV(gNqtpJnmdI#J)WT7!5N9Yiq6||Eg)h^?n~lYjFu67MqK&cn|bdi-_KZ#iKCe3pMHiHAAgFP6{JofbjlOo`#!zP z=Gb@DA<6_Uz4mhE_HX0t!f|39;cU=`ORrEU#wHAr%ED5sMfA@sbNq+Tvh&J)WU6GX zzY$I%kw@#8-t24`VmOENf_Bp4_z$1syI=h#ThnQ-e#f=k_QBieZw&Cxb8caQtUq8p z9%Jwn&Jm@WD=yiKu^yXvuKK_YoLyR=8@0Llw)c^1&nO$=1{vpGc$F!UpuD5oY_e+C z_}X1}^U3*7kk^LH&v*H)-~J8$)9?PjEWN%0Dq^j$$kjElhW%61L^8%18I*F-1^V8m z`;(ujkb<-`xSIj48UU(*`%39qdgByNeg83b-}DxeB*7FVeKVleYZ1@4Fs`66pKzdi z7@u06`}Py$(y=ibFr}u*jiI+?j@MF6DFiyMVQh)C9y4juq(CQ{w4NfQz~DeD;#!J` zVpKyRjYqf(R(zA8*`zDQgLM%ofpiv>M%oy!HF2X!;Rlu3x2lpULgcuLWzfo_tLtO2 zvcw2W@S+X2)MYWI)rfKVfNazcg&B#ll6I?$ah~C5TzO;!m7a4xME;0>sD-p*<5=fV zS|EJzyY#|WQ&bO5^29?=uw&m|+B>JPiO2ea_2Gc|9XqIXS`b$$m2OO$q$D=s)n{Je zo2%)pG8-MJO31oM~d;)V~uiw!YGCL#pwxq?Qgj#F^e zl~;4)O*b*H8L>?G!S^2HyMOU5YQqrTWrb%r9`W$^9_0i3=RiwJ#=P~GxAW@L$JiL1 zrYy?f^6o>thwzF~zu>tazQBop^Y18|mLWrA1ik5L-gf;BTygbVSXy1?)mL9*w9#i* zZx;{U{QxgL`x4JR@gh@E1DhKRj-fZKnlVWnkt8u%Kxs@EYA69J7$&E4E%sk}fH#i6 z&ic6(R4buA-=v5P))>eH_x{5Tl%@Zi1Qq&wf_jyvzbX~C6O z9btA$k5k9bP>))areNp=CpI=Hg=go~96FN0e7K_ET)+~m5kS>(Ip;7om}N`vgK|lF zbR@}af%Fky|JwZ=&4*lf{k5cV3>rpeOy3Skr&7{JO0uoR)$hNa6AN#!er}Pt+aPHq ztSqkZ+$%3&>k(_&m_$cpt{_T1rWDjtg|#I{7+l^bcfplD8;u!cBgWcN6r<{B%w}^Z zl&tKm{N@14xG={6kC2X`gj1_))O#%=F~FF0@}iH)1wQXn4wp$Qx|36r_z{N{1}8nr z#Yh~=kFnV@ofP_u=NPZAV~U(Osgai%Mmo$mXMK4ClUoEKIo3HBJU1$w_2;3aZ^}aI z1)vpKQ34KYGNcD@T*VvoI3nV{8iL{r#;C~~ZA ztnui5Kj7u>Jj=$b3na~${a0K<9yuCO#M+rf?){UyIlp|KPk!#xba%{Qk^#L#^L+TT zxAWNdA7z*g>C8;A+FvJWwYc)Sw=pg)QM1A6*LIeU)t@gm>($^*E5#*9m-DTNenG}<*p>4*$CXV|do zw0CXgy`R3Ft8ToCrBe(1>F@s$%Zsb@=9u}0rtw4_z)3q*k!IDIhx{G<+yKmx` zKl3r_NsKdwM!n9<&%Vm3r(Wmj`@c`NI-nLSn$vA|?%IwMmcr(YhC_Vj@gqg5yIAj0 z&Jh)!uig7C4qkbbqgNd!jw9ML9fph%4Nq(pZs^e?Mcu`?VM$BXX?TsZ1x|UMc;qSG zbIUDk**ZsA7_1klNa6Alr4*%7HN4z9lOI&5r-Y6;ih_8z`||KH&o z8l+)rs=>%-ytr@@ITT<$xgX&ZLtVEiHJEE5MC#A3~I_E-0D>X|oamkCp{P2ZPvw{1r@npmOOSlXa}{2U@1^QGVYV{ZG*N7#PF zK1{f~vOFeDSu6HP$p*MSo18=#U zz1LpCl38bZ_bk&}XE=ZE9BYf`(B)CIPdI!0ByJ-o^-a<^VmumSMNt3vyaZ#2l|&dz zE3F}1aMlt+21-?!Pg7v4393b6@RSUVB{!CxZ`sGMed?dlJFuO|N5KtCMm+rBqdfSP zZ=x4V8bd+bYRb$Z#-9H2fST$cw8AOH*p{Sm62b&=!R$gfWF&|Z9asd`F*`lW;^HE; zdYxf^NQt38Sf^oB2wfaIYH^Bc%`h5|>81_pX^It|%#_%&tPDataill7tj;?&@*%Ma z=?rBQ$l#m&XXnBoW-}5baBQ`T&`MO$OAv3Un#L&0HP>Iw`f!6+o`0Fh2t?IP*r?># zQ_phkTd%=+iSGIsMg>!IYss^W(il>iR?z`JeZ6T5DL@=WfgoN<7B8mL z3LuGKNY15K9O6A6{{Z#54uxY&~zT*0c zKq*I@X#PL)-YZ(J>pt`R?QlZn8<9a?5QzW-z)X-5GeygiEQ!|0mMw>Fd+gS9&+_!k zteKZtlUC1~;MKi)+C6Q1B)2SCwj@hbA|+9oIf*0$f&hq|FK(`Q;@*26cGU$a(dv0^ zdUMsPi_5y_)Tuh>JOA+gzmHJUD+g?tnPKDR4J_w9vMi@6Vg_l38&2eC>3MoXLW$?Q z2GEfM_C0hL`#y3XYqoD7bp_5^v=Myg@yGezW8a2$!I-FGFqA?N1rbS+GB(-d;g5Zo zdw=WwtQ1|!EF~-*c`rc)5%su5ztttdg4|lR?7fy# z$Ij56?a;|nXgW$|v9aK`_ufHk!!)@wP~?PROyL~iP$B)YV4T8=oFJ5xCdX+*5tMAa zVTM~Dxtr;0H`3TNNs2*47254KKX~$ceB&!$BPuoPg9(C072D6zQOKa^6B`g|feACJ z%?j~EmEK$jV;w;ppyB{D-2K2lHqLBBN<|<-<}WO9=InX0G)E{wtyN{)%{zGc)I~ZM zSExr7WMJtFLu-1H2R`@^<7+4BC4DM!l}JU{(p#Tk9i{c>0|I;=ewHto0?*^KBcr#R)K_YE`a`Hg@2aduw2gJz|{=RWs& z3RmKkVvwY$YCtFLkcpH?)x0RU^r{Sn%Wy(d8iO>k+vV)3nFMXy1iUHvBHu4r%2j40iiGY<7s9=7hnBNYW&dJk}{;MG@N=J_8zMYUeV)fDw=gNg{~ z%*~SyR=9BD7!#YuKx=NlXCHJV-~H^@s27UP=@q{DmtW@YU%!W4cU?~^4M}M!3PU}v z)1F`E%!yM>Zka}pg^aJ8;+BW*VsgVe>QR+S9D`Dn+7L}tXs3Ow5@;3SQcG1v!~`hk zRz;P4dC8G0OIcUk`_T`w_ujpocXhtFj?WdrjaCS#*D9>V0`l$j1{0FlGGqngjE7HRMzt2k-phdlqEXW zq!g^Zb`$$P`XD>@-M~uOBgbMgOFvtpqBZY%?_Jz~-+LK!69NM2vciEEUggziUnCn0 zICJC}yY9M~L7uVmy6yb&pZu4!q9&CvMhB80R)m#+xEd42-tTAr(h|qsIKjE|=XvUT zPxHPHK1{FM<)(XYXKej6`AS08Nzqypja3OIDy*4VLvPS04k9j{zQpYLS(H#1Ybo>6 zdrFPGrnExJ0Efhx5oO31{-si@=djXV!cJO03}Kw`jke)@coao!*)ro5oSflfzx^od zH?C*@Yp;_G25i}R4SVjmg)=HxgRXJ^qWATJBjJYjmnB%8Kvq*a*!=crU7D%F^* zD5%w%EM02z`U^ip2}POah#+Jnqc-Z^D?(=Hm#H^f^wI)d(b%LwEG<*1RcW;*2xUnx zZ?pe}$4NV9xNvEn*|}MEZQnwfEYV#O9Dd^{v*+h2QbV4XG@CVU*mDcx&2>Ea-NVeD zTB7JX0_!s%r8O!L1Um4J1@E9idgXdo0_n*6#jl~M*U;Q+#JzJ^Tr1+Hhwodx@`n?n`{~PyPwx6E(6tW&2In zv-9Sg(1G@M?!wRe2bF-NObLZX7K#_X`!olidzCnIV0;9lk*J}zWMK=|ZM}+nAAN*G z4@hOf$S+C?iII}Mx8KBVcicuO0@7Ya+RLcb8vN+9-{F;SKEtI8m-zbMeUd6qj}L?KwdG>^+urYEMkYWGfbTqPjHC6F#2h*cfbetrp@@0xi+{tLuN^@LipRe64Yu#x&c;pau+Fe%+ghr! zg0c!7gjg+bks!%4sv_iPFYo8m|L!xKKXZXtRfYy@V(0pz zQFLcKUzN?G#IuRe&hegGf{6oa&jafU!eJpbH_eD{g(v1`|E zvR+0Icu}B-9=@N4AH1J9YT%qBj5I;0NQ#^|s&eVvB7gRO{Ci$|`n4hZ#Q5sy&@Kew zsYuQlR=OEMB_b;!bPdu>(rp*Gd!jb*Ya$)`wy+NO)^M@!3n7g!u6xu6V zl?6cGucZc}`IK#Q!ZBWrad}Rj8P?shm3<$2fI(1_k^`1NXtdBcCx|OCm1<1T2uNcn zVu=eRSuf?aXI|p$@zY#2a}AY7liXPvwUCYDYkB>dR|yJ*GLp2{_N&)1KP_AymjK;e|2Rd1mR z$D1#_#{7v3WbKqAhYquK>o!`g7QJpCN=w#DSXo+Tabb~OzmG#Od*Kpa{=(n$%=e$C z9C-EoZqnwBLkHNoV>>ffU5zLT$|T361zD1iXF2VaF5Tq;&;RH}zVz3Raqi?S3Q1Xb zx}A`UReKGA?{c`2(2cj;057V-P!L6|&O!S@1l+oN*-!3v--4eS%FJH&LIc zlT#3cdMI`RS}H0*g@tqT{Pkb_HS=c|spy!Wy}qBrhYz!N?_Q=Srzmo7*^y>_(rf_I zQV;4Jd*cM3{`Y^yh10W)*IV4QXAf(pCJD8oUa!)qH_%aqxLWb$1}V^CKwetv)h1~_ zMkA;(001BWNklRD=`) zt+dz5s0gmUb|Y8q*zAKK`421P3-`{pfB#u82lNJAW>22y;L~sNlgD16y)vM#9M?>Z zBl-#Hz)`zl4Uhc(N6>3xQkmk)g3xN56(p(GluYx4EKeAlnxbB9uy}fb13!9|gFkr{ zQ9^C9$)0;}=bjJT$71IUU;E5gnLRX1#nw6pFhaimkzSn zU*^1BV&34xM+zegw)N@}t}&ivUqp8VqDlxI6cJ%vgE=S>z$ z>#)Kiw8MraOi1qf=zZ+mw})IAgbgVAmMl*xOa{s!6-1SYJkQDVocXy04nOfa9P6R; z0xb-AWNBPAMOjr`>MSwaS;9t|rR7CTmePzOCadG@*mEOWuHDZ3$$3sZ{T5LVa@Aoa z?6H35)l6<&iyo^nxp^InofVS7fDO}Y*?QFsHZvT5=@2h{=UG(OLDvuv;EV?ia2V-T z_*JQiRg5(yx~6EWHtTP?inbasxoI6*$C%8r~Z^CNxI$265Fqs$j6iwhhUo2;uvi1$@^i9ty7wvbv= zZ`EQx9sB4PyQye7w7rbV~?Xl z&8C@+WJN+8M@&vlQe-)A9eRtGo_~SO@dh?9PRl4%k|S#YZJA+O0k=MUH`nglgRN;6 z=H@wf;sha{-n7_l6INn+7rHF$zkpfDn4W2|?_=+yr%Ec#Dk4@`Ef|{^r{C`r>4@p^ zX@2nC@AH$t{U+6(Am|FJwnCnkLw`LFE=EA1Bo*r^I3UsWki1f`q?dT;Z)C7_c}y%j>Va&Qsrenx(VLtcxbu5sx!AR;BL-%-p<_ z>+avj+HG5KQXrI|(x~F3MVo@c8M1!Kli&Cu-~969tSm3F=g#Z+$j3jx`gLp3LQ#~K zN>D*M{6GN?9Y%cVOONr@FMbnO1Qbb*a9)eR8iw5FVWbIO#{dPwH(r3t9r|IKKZ=T+ zm%8^gWZ|PxF{Bnb;T;~lYi`N(`a0ESNSc-8S?Nb_jUgMPB<+M)*D$$2#)@{oO{E&) zoIz@6O*YX{hzc}$S<+8Z=oxJ8kSg#ECM8JHF7-wQ>x|a~Fy5X-T2DXphL95D1g3NZ zGC&%ED=fLvn4x&JuL}EdLhIacV98K#giNo2si~Oh>3}FqFhv_%CUiS(-)xhTdZSKO z6qL>}J~6>nGh5iT`v&@5!>QvdoH^Fx(%F<=+u~e^q(K-+l<+_*gBYrC|D$(u+k-bz z8LJG<^xhdr-<35|@Io3v5RfJb&f1~SvwK_p)MSROJGZj$(FYjYGKEx*zyG^0^S}cS zv3ctj21SMp6^4>}P-X7uMHWsib7J-wRUMIMB|6ZgS;E@ZIKTS4A7bOwG+ID&VvO0P z1;T1XEviryIZg?xag|dq9_H_l{T0(wYxtf2`ct&7SwmnQMQTZ%!I_*&Gp4>~ify}g z6Gt_k{=w6H@h?7)bP9@+KnJ9`LC9f4##)3>!;4Ab0>_6w{xLS~*}=rxb+pDOnVK9Y zti_B^Pmr4o6=|0mdgP*+;az;_ipFf+jrw?Fd$`W z!#KNc*h;K5qLh>p@**cp1ODd!`Yb1w4s*@S7Pj7T9a$heWk(B2>+7|RMvXivNb-#P z9)6JZ)iJ*M=U<>gOxXoliOI7RHPiQV5dX3Q~KIDguFwB#(aLQ7&G*#5ce3b?&(L4))%*mm*8O^JG4ZON66zzLptQ z1K#)H2RMKJJg+^!9}2LA^b{*O6n{2=^_Is%NN`?;+l_>f#mL(oU+Z>qNa+(pOOlbu z=df;yPmNs(!b+-PgU-c1?Ms~@aotZrDd9-^10o%hB?VH16j@2AVy_RY{QUf2F2RTa zMo5hFk#9u^(tbi*)4sys98pju@0WzycfSKPd60XlNuf|Gq$o=A!VpF=NtP2RFTIF0 zC7mIzVcTRGK8q zyB?__a@d zm?zbDc)v&{FycXBUiwx0fYm{|QLuSUWz> z+Fe(1^RL`ZbHgNkn^O*QOytN-Nh7GB@bt3O7p#;y_{mXPv7RgKB_gn zZkI-_#?J#l<v^GYpG zXYHzB_~;qor_Rcv@SIj>De`O>rAqJFWi7^*C@F};h8Mrlg1j(jC5L(n0oHmDDN9dC za&pxCf+SA}!-yiy{C71BScHghrN9}VJec9AwlR(*&k#ZqMiE76&_O^^l-~bK%F!(B zko)dd)y2xvpoh)kY#^D<2K2f)-A;v8E1=a1sMjRbYK6KEFr_13(abGo^tx@*RM2a~ z^1LDGDnuEh@D8zH(8A$`hW$QO;LzHkhK)^Q3|jufaQUtUQm=~RKbw)xoN*3=CD0B^ z$K>{PY}m7fMbkk?F&9o>;*D1ia^sCRcu(uHB+?bKK}oY2GAIX(ZEo@5-~AAOdhiHY zH%C_$_k7?!Zh8M*ESij(Qe;Je(3-rk$Wn6nx!1UK>>_d88r}$t0 zr+>xWkKDr@dv2tzB1~>bdI?#U(=jPCH*9C^hAB!>a_57$GBw%c`=90Ch_P_iJCr%vYp$~t6P{kyjE@w`hV0mScy?5S5hGosh zY3{i1ZubB505UYxsulk5pMI3;REx|NzPDkNzd)?vts}=c|FaXM{e%nsMV1$rahFmm z3yyjbaPF0p{OdRVXA13D>~^WO#>w-7t2b|A`>w5wZ=B%TeK!)1$4Kqib=UO-QOFaY z`8qnchygeuumS{zz&ec6LuUeu)g?E-XAjl2O^78+i*0`V#1A=l;v9F~eFuS%gh9-+ z&pgMu!^imWuYZtQsHwNA+3hj0Tql^qju6%Ywun|%W zW$OGCRB1hN-cSq`&xWb86T`-o7f%)lisEvnCX}C8Tb<%r1!-SO7$)1`EJ7*o9y;V# zmd00lrI5ZzA-us};1sU(5{4rRhAT_7lVBX-@bAqk%gZ<2M%n@nJk<-I_G{%EbiGba zGU%|h6ri-FRtsq~D^#ixN=i)DBhL+G4tZk85{Dv2T8S3cHk|d?ltYZqn z@t+;#@y~sOdJ^CgZ}1hG5*G>Taf`WyIllIVZ}7_3pJLnidR%5HlEP2aXv4`{xAXqr z`ZZc>$4K&&-M8-L#B0ZS_0%(Hp$M#`9G(o)$2Y|FDx0=mjg1r$iZ>7Zj3*xZDy^|P zLKsq$QfX9JTAt@e-}@eG)=aW>_fE8wOiZ+>kJoV&-1mV8n7n!o-8>`94f!A^3^ZX7 z(WtaIdG-yS`pS3cEp?c8eNtzc)Z^?Py9Q|sRN;`RrJ^)-IfYsB4TSFgv%GrvEOI>H z{E3s?^3Ywhu33Yt#aw^qZ5(|55XWYJMn(APq>=7W=tJNnlj9S7>W}{!|J(oguUT4HB-DX#E@{ACk-IabJYC`01fyE12hP=6 zso)>H(65})_X?7~D5%V80QmEcrEgzi^)-Hb)|yqBB{5W;Vg$%yqz&XLT)tlF0bDAH z__;k?E=usWo5edE5ylp%VHv9^47TS-7`P(^Cw}f+&tD zlZ;Cz&oEhQG0`0NB;i5Mf#+W3;=!XVoSVfshtrxu7zQR~&DQnQH;>VlJxpYw%*fIK zNs=I(BoF~Am*`Yb&qCIeRT^DK)hWV4;07f!afAa&GmELNNNUT9@m`hjZiUTujAJhz zp|_c!kQ}QYhv9vEq=hQAbx|uWT>` zrC{Uq1|}K}YEkHYynr;%kXjMQ5R)2AYKU}1SW0v$5CxQ3iF1A^p|lQDIurp~1W2P% zg+LXKs)|qs+DmPcL5h|Efz-6>4XSZv=(FXIO-nTdy30|el%Al!N_E0__ZbRZ4?PLr z(NE}|A!taK`niW2Zgcd!+Vr~OA+Pw^zic!pVLh+aIV8jK(%T-q{lU-ueC2kBjWkvp zX77A?`_IF7*tF6}5g~Yt$?YL4J5XVa5lo4k(02G-2Dw^L@j%#eF&uTLk~j! zau9`gE0E$(3j_pOk8G51ri7twvcgdfDhMMevXV5-!3olS%JSS25h1;~E^oYifG`ex zm@B+lUcFvttkp#07^~M&LQtB5qR1%9935$d_EAGvjW7X}p(T|$s;0@^v*Qy=X%>A27Xc4cG3vmLSxmN#cP8L8vssLL5e`p5ddIq)c;`FU&z+B8Tsx z#B%QRc}^TUM%m4|aQrM6PG6u=A7|rL*I)@i#fX#`a+p1sJ6&%Vfbt$`>Ds&PQA z5feq;XwOMO*r;Mdfvjo>pr7|K+EFM&E(>yUmg&){@vsqze(hVa%K!`a>HjOC0HP&8!^ z7nsmcsGMA6h}dC+601r|nPYUpK;>Li3A0hgrAo#*(V-lV_?3@+gz@QVln6L?@+|-N zpZ;6sXXnvU<4QZ!T)iBDjr2H$xEy(|f~B~^iusE5^FSqqLsb1IqR>*GD9k{8l8^bpL3V>UH#|y&Jd`ScLwfux>#fXlM(5=GPMWaeDSul{+6xu zP?F7fw?&C#@ze#b-FG9o5KOL{X763M@zPVz@y#c`#clW8&ARFJ%2u=s!>r%Fk-`;h+B(DU{Ifsg#UDJ&51;-C6GskGBq=z@?f1TyT{rKgaE{n17S7M( zGC`+1;LCsW6{gosv;D@MloDK{f*jVTQdQ90JVoWI32HLnrp8sY^OTDxXK7z*Gu5aP zHLF~A=M97t4XhOCI7S7E)_9A|WY_@KZ`nwyOX4EHEu}p9g|E{+eUaEIO5AFV%43Vb z6ox=6&zE$Lx(=xaA-$x_hMDzz;*WltEXg@~1YA9_^5NNjDxQz`P*Kpuxuk*tG{RkbS&>Vbi zKZ8z>?K`&ek&pcvYu8Q^NX4L&5Ew}$6a<3ix(R}*20E;8{LSNh`rrNqr%#+iSV57O z1S%NzhrBqqb613Fa7E4Za-=#+n^$k2SAfj0*EHP3W&O|9^xxUl5cYB-%lQm_xbIO4 zFINA-sPA*dU*N@2;O!Bt9L27_?kY!9S$HmiyL?bXKoeJ#6oy8D?uz66x$D{?FvhG- zd#%<3R^OxtPk|T$z8w0t38XLtDp=j7HO8A$3gHi3jmF3QwzbmOD?YDZw%(OM>iNt9 zslD*9Lm*^;EfTC1C>3H&%F5{rr1Q(@xJ6PX+<4b5+;z`B3R#k3P&(%K{+mC-%98G& zgDp!!718cz*nUC14Ef1do}@9>V#hsuNo7eC#=b!yyamV9#wq^rzxx!`ASO#PrdpFc z|E;I^>gPX4PYn3T?|hW^JaQksP8)@H1PxV4qt;-l*JksM8FHIZA!KE4iLZVB%k+-S z(hwo3Es;w36GjYud@O`Ua^c_!rzyGP&HTovexLQz)5u1E z4npQnUE+WLZ~qq-yDQwZ=LSCd$NvRgm1C73P3>ptFuIgT30azWHK&!F$3OoSj=gYz zTA^`;7piu{3uScijwX15K$4{i-}=&5`9S@{%-nblN!}-(s8S2Yc<}10Nb(#RML0Q> zq$>-wmCT+v!^t;~lJ`=2-GtYE`UaJWF@FD3zlTr~9eUbOUgiX`Vq#{R_g?b=_y5+1 za8{y?;%`3vS-$$kFLTd>`*`24J;)&KA%&#O!5QzTRoIehvxd?EXHT8y|NRet#nHnj zaS6Cmp^!K;6l-2h=`X9syDI^LQA#`d=M`b&5RgW|cO@0-O2}m7s5|_#5x}kD<;Xq4 z*eibjbCK`rKJeaMc$%1Vc6CqyRxx>4BNeOaYoqVp6JCc3R>M2P>hX@g?~#!8+xE{D z$1nnDi79>5XoXw-IS|UzaTyLPxRIU#t9PD}vK9_o? zYV{i3g*HEU;(P2X?_&3@H-lR z3I>BdDo|8vRoo!w(9t7&%`B)#tl=>bJ>K`kyUo=#@4CqtP}bS2W9p z+7F1!fVmnJi+2Xm)x#ZvHUgX#I4h7cL=4r!q|`pLbl`@*VgiX23f!;@??!djQ3N{L zwp(qI8Eb|jF$!z#I}-6n>s<+?(m8}F$r3L(fRvP0fKbe}dlZ?WRvDwTA&2%K!&E{V z>nCZBk1;XUpc-qkA_rX(ikL7ADD#5lxh1~zAODt%N6u0$0`j~-g_;w`&$0CQk69Y@ zShIEwl{i8xNqc3PFbCPg5fe?(!OSDt^3t}eN5 z;YKRW3R#(gRH)KYwiBv4;^M_iWTxQ6(Gwhcbw9msPLer<4#;yyt=eG!i*K@UX^~I< z{wJ8(u#wJ%IiwS0X+eLGAu16o#R`|^=Q;l7aZaDQh%|zqJo_SDRdVC4dl;LXKm{6$ zW6|Kh8-QuD1Zf0qNV9->-{(WPTkWfCnQ z?RHqdaRar9FypS0W$Kka`4^6957cXg@Y0~h4%2pTE90!e37^7C~*g4@zQKQILL8X;eY=W?`%8y0sQ5l^@7} z)wJJ^jun34`SLz}DsP8yr<6b{kCQ>52!?{qQhG;GDJ5lYDbf;K3PR<-S1khq6`-U- zONr8wP%8rM|6a!u)r8w0xsCUJ;613STvdU&AfpI>K5egA_FfoZD>1F;Rl?IIVX>)9mRY#Wf2?9mC*T)nF zt0l&Q)&XVV2ttjt4qG@vp@^Izat3P?0tt?SLKtkGqn#xZf-sITCdTBFyZ|L5u$E>e zMq!6a>5@oDjIced6p|pZfRfr;qEeB+#Ags2iR0J|i zaAlv03J9w)y>3P&EojxoSy{=jr6fxVf>6NuAnU4~JM1YzPmjTBTGRiqQFoLgdI ztU;0nI3qA+F$5+*x-6x{I)hlHAdQ+YmveM^h0rx`i#~_NzSUUj9n$*MYr|auQlrT9 zo$H{h?IAbxc}J|)HUXp*mq}9soNx#O!ddK4bqgU8#(3s{5T2AjJPzdLNLDz99J

    =8+Yh9q#d5z8ACcHs22b2x`h&3Hxs$m({up5-W5hCFAlyQ&`jm z!^eN=ll;Ul{WNAH!%OUAKb_9-AyD~>@?61h{P+JQfA~B9mOuaZU*?&ge3r`}yTY40 zxA@rK`ZR}=Isfi|{oTmDbPA^f?u_R7&%A&YN2xX#T|UG3>?UCV6L*BGB3@~%u&@;l zXxtoIIDYDvKf~6gExz!-{~q_hbBod!*qKKYUk;BGsFbHRj!Re1ke3t2BOx~ylV{)> z#{E9S(SS3TF0*m&Y5K#<42Rp~S%wOh#dN{#Td(u>o8MyZ!F}e_Ifd@iR5d|6-n(_3 z$?OiF{`^n#_N@mjuTM$!)A9bYE~=!cfTKaZkGXs-4XFkiAL4Epp+CF=@eSibldB%q zd#cQ{KeJST(m9KT=l;$i&ptIKGdb4Q@p#EQwYFxt*k^zDZO%UNELs;h7fTeCL>2xI z9`7F_{GdZTg_0wCJZtrhFl6}JwX#+ zD(VKA%wSNMV4x9bh_oAM8Eyzr*LA#>0Kubzj+7sXMs}qzy{;h?Jz8PSLrz|!)+@y? zmH4euwMli%1|NK<;MD$%?wp}zLBz|JK0#JEYX^{~KZ|_Q)qU0`+(LUFBvp5(ExsRk z;WN+kbN}!c@VQV|6|>!a-n@MuEt;pVJ;M^qQsB&$Gd%N&7x?Nozd`>@pJH6#wP)5W zdEu3h^2W!$$L&9Vn}Hc{SkEZV4WNi@wxzXLC8#XJ|MZtx$=ecn8 zDwm)880F@(47Q%dWCOsH>%ekWapvliTzU2>ZocsyzWa?=xqs(AI@bho?C#y=JFkC( zpZr_@gy%nbje}dS5*BGQR6eRniQs8c3hZx~A$2~=#N~P9O8R;Zp`o8CE{sN$Rz(40 zpP`!thmFNHHH+zz;D(GxTWoA?F`YPq%ULXHeB)ToD<%iK?A*Pg~) zq{8~QE4o!HSR9j_YwzfAUFi&J%N{sQV7mLuv`($TT@{=}V;j}<HxBucBjLJSA|Cvv6@uN@k!lzzgcRJyv&wPTPdi!18e&c%_ z?j16^yv?GrY@OfY*Z-^koPTlaH#xj{B-lP4EozA%pRlUcXOOH4J(KmeY!V z_dCDOop0S_KB>q@eJ)?S%CG(xe;->pDz)H~pZ)}QUVVq_U-};PWR5Z+ih^x`vyN1VU%G*_N|h2i$Il;fw!2AgWw~8#!5S zm``Usd2~RvoKn@Xv#0{zz4;EG(w>jL{374}_ur$cV%|iM*vmePnxvxN(m0a71Onc zlBI9ZBB_Q0!~g&w07*naRA>y&HU#Gw_A~0{i2Z{*ESot+o-ynxw$EcAX!cw1g``MTa=sd^hX>|KYf{<-Mid)^9F@vWXdo(++(>oU*nmjY)TA_l+H8tXdP(`ukLTkhe2m5ml4wu}z z^MGD|5KAZ<8!<8`V8Jdd%fmh1yZ$PdF1>*6Wz=?nn6}{bhtC54a3`yx*XWaEn5%Ki zLk5Load?+^-hP9ESm@Q@Wh3yvOjlruk|Dzo;>E06sr{`8xNq8iyYQ!cGoMYf`qP=6p7c%i_jkou_$)$ z?NR7H)xr}R$aKl(2Ad4bkYE?|DudOY<=pX=Fa8NHe(qz8`WwueB~?;x@*zTF z%EzrM$8dggi_PSzr!iW{3pjJ>GTT?4r74C~K10! z=N47HzWqQP&<$}b7DWiHx3m@}#~CLh6947H zs&eW0tBq$@Ic!PkX`hlUN=fQ*9}RVIu>#F`hZB$2U~|O`%fdSZ%}{z=$TqkrL#~wD zJW+15X@-=#z)MV$+4O3>qYjQLSZ2Oq;%fHof}MKGo$8RCW=3s5m4-k-2gpdtptgS% zE2Gxc!6&>|N$M0pd+B9mIM?~O-7#9BljxQzQK?7P@fRGgit4CblKkZLo>s|lOWL}E z2#dPnaC$^z8;sTz!;IbLfNHF$FZ8I+7Brg~y$hQZXGaugMpUKZ$!pKk>knAW7u1U- zxPWyHwQBhMum3XVp1FV&8l!c@rV(;&DDs@DiDEdlbsQZ|!6|f5U<09Xy!hfrID7sa z)_az=A!tM6K*T_5Q{o$s5yRGK#JFFuF(}AYpqE82vKWrozW5Zy@B)jFVGRV`U`%Rj z5(FbciBK2=I!E`;pa)Oz{L4Rs>5mYTA;A!=P}g&mhF-70q#}ag<8=>&4)=b)@pyWq zq)cdt+1%(&wb{Uc1!@ls3g^LzLaUtMYL1R->RL0IS}t6;!kwFMAX+EGDA-1r9?qE^ z?s4dc&CM~vRRk|wdE#0A@QZ)JVhQtE#jqSxqA7xowa!YfH7#4qey5Cc zXBv`6)p|~kI*s<%U42yRNd;Ei&tw!Nh09)G5iFC&GPO&zS8SO+=dvLql}A9_L6PMg zD#Jt?4y6Xy9P^N)&{s$vl%jE#WnD2h8=`buh}1VP$5o*pQWNVC zgf)-zm~$D9|GULG+ha)T9dsJTo;IL1@3amH9RIxd!}k9{34`&7jqNSww!!-)GdJbQ zk3Y#T{Nm^7ZH^gjk8ng1{MKlL+5U`w^;^HqOj&FQ7?a^@$Ah~MxbXBP0)eNlUFB1M z`_oM4M>yvxvK)h;eV|$_D9aKX0$E|`4M!|#sGTEZAX=DCr%Y#4!cc?Jn4*ZXbwNcj z^#C}qwjnG7XYwJgsVPl{UCb#4J+g9xqJJLr81HhF(I`CPL3tgSA0eQpki_q*e@N|p1I1--FIo~B@h!z&Uu=-W%u4LdH-Er`}SA(sh{2^ zD>PM=k>^EM)ncvvvG=%-wayI&kE{0By?dRfFO|G|>jpPozs~e%#&9@B>k^YyXam#b zlC9ANhJ*9`(U-o6=RDP7!gis^okClcdaSR+vE%u#`?B^BHEdAkQ<_U;YN4$#OQ%ZBXe2pZ(d-GOcDDOb*!|Z&Bt2dRf!xGr-Yo)y!GJK$&|XkRlNDtw{k9RZ@@aDl&Lci1 zT3zaS_NejL8d8FyS~f`vFR9AJu3d-&?G!?tNZE=)45ef&tz++g#h{n-V7Fp0KEwXK zyPz#%92$ddG8Qw(;m$6`yvBEn0U!PNFOZF&=_oHo8|+CLxF5%v28+Vtnitx+`w^^(mMvSKDmt=V!uTKyPa=!k@U*-Jx zJXfB63ZHv6FK&|cbG&$#iy8eg=h73GCx12e*#p38L1;V0QaCEo>c1|fJSuo&L5?S}j632)N*Fb2n%Uv>6ad7`F>gf@- zTH>^#H!R4@9+Uf1=0`KUhuV93DkBQQ`4o)2|EBqv8d6eK69^hSk)-VcVgt&8@`8j0 zLsXUbB9uB~x}5Xgjr;WaXXur}+3hW+`Vg%p?-+*6m>s}8w2*`-t&uUvhOgE#L|P(*RwsEddXky<4o zRyIW)h6sm@vK~+9z}>}!rMFCcO*KEjD9z*Lvk|7gj?bsV)5o<7B$ z_eq|P5Lp6oz4Xb0vC`jN8E5AlRa2As0s-l65_v|IaD7+SYZm4`9*HM_o1VgXLSvX5x zCiNKMcU0h0b(cEy<1;xS^9rfp4;AyIW*WnfBz z6tOKzC1fF%dRk?v77IiIXD^ueC{YG4B^2a!AxF(I!b?M|DRc(cS`Y6*(oU$*>4IR}kC>wh?-4JyHlL4PF|8#8N_! zk8NL7Ky)Cu7CViZ5{+QIA(tMz_ht;Yb97m-)f;07c)MUwYO1D=yvC+sGFedQL$(6k zy8b78x!UE^pZg_>jjLp8K+qYDwOAj}DkCOR){_dd0unn~OY~4Yv1PQVEcRAvY?S#5 z4T5DcJz($N>nx6LqDy#hvgDmN-{SUr5135@)@Kx>0uf8q%o&dReC(xj&x+)Hm;xq0ITOFzf%&v8EEo$GI5gU4jC{kE5=XBo|R6rJ!*fFxEDtb-sZ zXBaBY`C?26o$4Tk#F~ys0Ew70iqO@sI^p^$o-5G!I+h5@4{_!s|==BgFQ#s;c&>JGo z<0_BNG*w+Q+8VQO?z1T8cpBW$^W0Bfqr#$eL1B7aIe!J3kXn4iwNN28D=bvbyoOBo zxqt7Ft!D>JCwrhW>iL|V_ugPKImDYScJ95$)u&!$^UN6n7V8$wclWsc?rWUiDmc1- zll$-8;Lff0n9e2?y#Y_0JI_k-s8=0zs+J+BQgRnh>H!LI|+-wnaQSyN6TAm zv*=nIL}KMhynxXwG%BOihQ)HpgWC%>w+0ksY>dv~ssl3P7>x%U98GB|N4;?D+9Qn4 z>6^ga8{g!MvjaZ&vwxrAxod=GfYK40Lu&$V&9I!zIHdG9@u3SEjLET0YzI+j4SoTt zW^(s+-hS)b^i0i@=eIfB+vWQ8o7}&1#IjNZ(dazG1&7Ww3P-Oj8TT*oKmFG4BiSYH zy?e+|kGPQc*}$Nji%K_ZfL#nd+wameNydc4^CZ@zx3s1c3%@$eHc4~J?k=h9baky( zVX6dBETS$2@steIkXtzCaFf0e`-rAv_)#O__<<=&D?;rgG zUV7yfzWT*KW3qS1-~Hvk!^M}bFubtAa#@ih9NxLlu;^j390y!^<{3s?Th#me6j{mb z*WTgo>+kXtPrMQ$FYxjwex8d@zC@mtSZ{H`kx9nN zvs?E_yZ^;hPl(D@S_#SrXqN2VeT&z=`zP%0yvB3SoM)6}?B71*=FK}?f9)o>@9eW! zI&Hu~!{3uWP(gU_IgjnP@U?=$8XFOu=SZFw{AIUJ;Z*TSqB|-28v!y;-nr*L9xv z&2Fu=yVKqlw?PlEhe?wH)q!d#S&BMR5^bxEtWxBZ9amXZN~Q9Yhg9V$d5g=bxNIk} zBr7U4R$@_2BvGOyQtU~HASn_ccmZ7Cw&$L+&u&&T=Nx&MbM3wF#l2)wc}W4Q3OK+y z`|PvVTx*Rv#y|e?{{!3*P{NI7j@OZ|9bKgkE$7WPy0EA=Sy))5lW?}ml6Y(gd*^*< zg#&NmpTY(gcYSPTqCI8`8#)H8+g+RA6M=xwZl6iCg#fx!9KC#t5C8s$_CNpMKiC7uE2Kz5slLY)JZ(% znZNifyZhUmfBU18-hcil@UAB4NJpTyKv0Ys^1AnPbK&BB+_yWR zdgufPM+=Ux{Vk1eQ=$|c?R?6uc1Byz84Mj=Q{%no-QV&a-u}e9_{%@~E1v)IO{NDO z#45p@CXjt%#AB4jDTnrs>n|N6roiYC zaRTF^!#8tcNI}E<4(k-N#T=t5tTwpP6XPwOedfbF|J>hj@!=~|qp_y}V;}s6BzQ89w^2c0x@ozb~TT=R)aOMmzeeDWg{Nh)+ zert{oFqjN`4IQeo;=zj#a_ZCtKKO^9;LDeeIj;Ay+A?s8{c=nh9NAJdW$1D9LEZ?A z8`ZsJx3tyV{B6>B-1a;DYT zlb9IOX3Dgk(V2iahnA#IY49lNi1Q^QWjR|+xH#CMDAM{nWiV|(2iPr2e7T(@6GO|q zt9jw@8gUpnJ=|h|hDDd{gR@gY41Iut1nz)e)W(^Yj9X%7r6A0;dhZcew0( zG$Ry6)Ff%#uxjFzTC+76aNI1p{z}cTDk!u?A`FTFAueg#CaXRLl(y7uXUYK+afsJ+8TW%eIQD7iMoGVs1@)QM?d!hoX6s%! zxi5M9fZPX{JCEFC5mEFmcD+oULj#)qVhi5|8q=|8mMm3+F%~>1t?<4}HoVRf>W;z~ z3T=r9or**)9QzKs4)GlqcTQm&jkF#nG$y$Yu>HE_O+{4RbCZ^7%zsDeq&^l^ z%pr~lxudF=dy>^*#%xM=ZROIv$_4|w14m1jT8$Nuyq+9j*eByWilKUTfn8ToGzIs5YYrgb{pFm9t z8VR(E8r=wks^o>sFJsD*svPr~k9?ZLOV==SLHX2f^u$&3&T2~pf={Jwo?r zx1MWgyFXBXWH4}`Bb^AdMp(9*h{MOgXf$DKYlrc8!q(O{!3XMQ z0SF; z%Xg2_Hy zltCMl4GaZWDjMBlw<_Ycg+ikO#JWR#Aap)q#+{;+65|!E>!_tknYJfU;-X2S#|o5H zXaff`OB zX=>{^sBh8gj>%rhiE}l(J0(WdDCWetz^F7$*pCIreBVkY$y~hn0B?N5TNw{ea_PAv zUc9vAmCFq`u6HQC#n4w66VXM|-*9C?amMkJ|NQTB=7G~_4Mkycg7E4x|23JB!n&O7 zPrCQ^(I%znDd`I9J6aSvm)RzFmo=JkF`%nG#|KkhB+zyPPM;Yw8CC4;YG(86__&}b zDr%V{7@7u}rei*{42LDUFcc`X6~LqLwDYSR9be^@#gd{Z8I4BF=QE1Ja{j_O>TKPx zH?b_IH)&D$uH(upH`v+U=4f`z&4UBxiw5h)Xq%{AqiVo-Ys_@ITXdc;UpbVnlPzs1^dJvLdr!DtBf9Wh?Lr}ZMQgX7tF6Vgb3YIv%R~;crsyFb+{t1 zT+T32upv^G1(ueF9(sgF9(kO$RlI!p7GM6-WiDS@a_vfBdI(jyn{ef*z~o9yE0i+0 zqNFIRyz_ni`~Ni>NCoR0gTVl!lPOoPG!A{oGk^+!phSbDF0X_{#h{0%v}I>dqG~uk zn$w0FbOom?#zVzm5b<5PQ_JA0lF zedzQ2?X$NC_AD=7tx=ufR5|3V9Wn?Oyvh?yT^g5*j^t^sHkb1M#gTDPdg+Y*yRUlH ztA2BxwdK*#RS?OWnk0oQ=LKUOg)?l~3QaO7b47&_L(yusR6%H#2x%z7YBK}&E&u=^ z07*naR4^V+7ejO@IODj{%$TkS#CU~qmag#xpF}IR^#EHMS{=FBCeah$ z9@9(%=O_CNl|}okxUW?jOa2DuyJkY%@!gF{rxmVzTM*^824A*$B<3vD0*Z)Nf=38s z(V5QBE&|Ru3Zucu$^=mxjg1bK?V|;S?vkQbh+!oqr&RiDI$r>)Kvln{pcFbN6v;_6 z_<(Umx_^3G<1Ro{w5>q)O$y>Ev?ch!s+lG|;=5VuWGvZxBnacGq8bc1TpV-j#v#qJ zVKIl%wqZCa*xD(ms$F)rCJd^I;h-Y4HEpYS`swQ&9km?Y47~i}F$Xt1U2So8jQE%Z zXJmEnfkI{O^RiwN;|ObCm(3B9L1U=S)!)bac$&GwMStJq$<(|6TymNtSo1$F(Sg%2Jnni4G=-Ydg!b zIRkrvJi#X`5)CSG zmKSx+d@)Cxllb5hCVr3OH5y0(rD)nV2OdY=2zBd;l_o?(A}*K7iP1m}3qjJ>@R%x3fC#@6ghMOHw4W4Y zk>vH$8o>Ytg^wYLPZ&ifkq}{047o5qK`}jGig3_1)N+fNh6lG#Q??4*g%pH3kF|zV zvW=@Mf)}ngM|c&v(H-J+^i8!GWu4LY z4Zr?(a<-&ZZx$#Z>AkE@?xdm>0Z?MlAvL9xRv;ZZ-SYT;v&!oKQPx;11Y+mYzyhFR zBz8VM3px?hgLqQj3#Lf2gIbdPM=#~5B#l*S<5Dp8o!owE=Avh1OKsV9EC468jUEe9Kfz z)D~wfpmCBg_&~bfG#ahawBy($aT8vj87ZWVIc8(E6ckd~(N9n)5Y2jIGtbnny2?4# z7ll&}qmswH*aEE#3*T{cv*r14%=Vr_mpdr8jVniNZCRqPnI7F>I4m(%v#6IT;AqW! zF=x40qP1qRn6s?w>{9BHC@hyXWnrlbi?xQuvc@@sF{#`LKJo2N?C-O)b%HaeAL8J+ z;Wz%nUvT+)O<GhC2v>8_Po))p2EUh(>W{xPy)4^^Q+f03Xuo z=D=pseGrpq&F1w>YtQ=c=gF(|t^RY#<}HvKajVzJN^a5Uq@=dqJS2}$uP2=H2V6tv zDrqs8P7_pQs~8cLaAkHA<0@hVA2hWntSGdt(h4a}$`Ep&Q+3FDl_=(R!F$|Feb*$2t5SwG-WB=7PXrz|6-utspP;HVW2uFaS& zg=h-4wkygq;X&ikgfo+Ex@L-Rmn`QCoVEBa5KX#~%27$zdG>dAn9XNc>nMwY*=&xr zin2(}v5_8NjKlkwiYsk7d*3PmONN!Jp6xBvgf8?CO@ z=1*dNUr~A$-<5#s@oyiftY%bA&}h2DYqS!mC35NT1|o`!J0}=wi(Uqt(JVrX=@ci2 zBeY7+t%sqeCGzs(2(01EXqTe4gw7|C?HpJ{sf0618g;nyJno!;+7$O*2jJ`lwc0%7 zuGe7mJvSAm?scr2T=~DX+DIh&Fn{;a-+R5^t3S;8-dLSaU-gJ&HLE;!n_s_bsYSJ> z=H^01ivleat{|8Z({{mJ5`!Z2RBTbWUgmWpIByE;Y)+ruehy>^us}#+F;=}!Gg7TI z*4oTXT!Z-Qi+Qgb5Z13qdwv(dNZOPNl|&+(F0oa~R4Qimj2FH($JmzL{SlLiXE=e|NYb_%EEJS{g?tTq7ML*U;Alw$5Q>L1^uW7^zk<@5O z;>^AMMh-$Tb@G)6S{wH5faPeP`RqDVTH?TRxjv#h=y+`J3}t1IMT@bZT2E1HPP-9q z%kkCeb*{I^%$4WT>^e)|@^Ez)t2C+!>2qsHrEpx~z#5f>rt=wy>OcBz=bpam)taVn zq;*?EBI~;1&SO0xb?@sPGd5^U&t8$uFSmV`|3}BYc(NPGOj2e`bfvYXfUM491yu?? zNW7w1E2Xdk7@O3*L>Lc-EEY#dcG6W@Fs83E)88~Xv)7v+>Yf{okb>!aK4&{@f5VOB zH5*8y#1%%mDVn>^Nbj{%=RI@d^@7einX)Qtl~N3GC^Nx{W8Ti`I^p1zn#I&HniL#X zk-;Fcw_P$S9i@v5CPVfo70czEwyi-4F>0#8m})div<+iGgkd$n+5tfxHYPA#gk<|>*@!@^lJT~6i$br|o`Rvi z?b+zd(ao%7bM5Z7p0E1O#zVczV()RMYOPaM!RCXuo)RJl`-o0eVE=Z#eqR2aWXZ0w zrHM%+q#}%3*d2@*)yEun9SwnKg{$o`?iM^a*=KKDVVVZ#3^oWRM0Ty?!f+o^aHBn< zR*_ehM_6w;Gu~rZXmm`aYD|@4DsAt2qIY)jQ`FEZ4=D7?`KuClU0vKWBV8@&`seFz z|HkWbX|3};x3Y|p)gQZ8Y`p7n_p{@+XAr>q)SOEYNFI>sHxF28$*%MVHcrAQg%1IR zMJduml~!4>J@g4_f-8ETEBgC+y|J$c!|(XKlGffBjqkb@_OH#o%lp@CAWe9WCdNLS zNd$33@WBIS{r%jXjvEiSQYzyn3Z*StWvOHFMDd^ms}w^K3gy@;w>a|9`i}abV|Hss zG@fc~xG^?tO&nFJFs1{2jJ1ZcEGPO2sXOM=BMy&VCPYIBmPIXe zon_f*mP?`aCK0AZu~%-hXU0rSMG*|T6O7VnQbR}dt0*R{&r@RZr_w41t@WW;KLoea zaW=B09F(=vx7|?+g|!xmvUc1gWxXMbUYl&=Vy($pN~RIzpZ9-HBuT85!vS@@1i%_g z=R1rxtJn565iz7V+MBAy++DFbGeJUnkc`1uoht-M6F~&#G4j&!LAsH4PctqJ+A357 zHfrqBb9OwU+%njiaAkQ&N8oZeq>G-5lYK@5M_jh3nBascz308koW0>^Zy{DN2iV3LIFcuvSp2 zMkIhb!djg%L!oN}5=$2IlITH#B6bRbLPf(sN=DjJS<9BGsC2fz{2@_>#3~j9UTNoq!>c^JeS+=Lh!{I; z6B!j2Uw7(~PSa4;bIaO^j9+apyP#Q~)MR`NMyL-ZIQ%(6H?>DSS zk`zqAYz?7ouHVKbxo4TZT4Qyuj4VGZMz0tJ>-S&#Lfz}Q^Bz$-D8_Ul=!ZOdyuJTk zdfs{;s=Vns10ke5Gi!$|RR`9v#54Cxnvk;FUMm-6k*HCUJ(tAfG9Ee~Fj;Tcrfh2k zN%dzKV%=xQOf3U445eQBH-1ro8=pp@W!pc<4kHMFfD!6gMFOtM2U z1qFuEI0|hklx3i*G^G+%a%+@?5hwm-_8wP}G=OmXAsOKBC%(d6tcO<~MIvkQjoUV$ zuOCEjdmnnNRaQYD1@z5QbsZ$qHHxbe--l$m8ztTBTAP)v^SYr(G9FYhb!T(aK_EL9 zsPrCMb6qXDzML`-b)p3M9lh_hRUIy}c+l8~5nF*828q4Xfa` z`uVGe17iMpFC3k!gH5~@)(nHY9IK#||GhGROdG(u!Li=G_vU!Z!^@S&VV18y}&nTrw{dg>epN4514c<4{>rybt(2$2@tut*f@4 z?eL9`*Hs{mS&vk0+z@?w->3RL4x;GwHeymo*Fc^WQIf|@B{w;8nWhzx0dPa|fZB2+ zycRkMv@y^TXyX9ib@!4HPzHrY?z7;?P|lkiI0_2!NZoW{*{Vy{5$7g2tLfpmM;_DN|gP zv1EvA-H?cR%@u1-rL6zRs;q5em&O_kgDMQsY65{SB#{}3fzAhRsfJl>SkeJW8^9Wq z_`sqFD3&5znjg^#JUrQFG^o;pTc|YAgJxF`aHXY=OJ+38eaF@Im=@u5xt&}BqTF`x z^>}kH;4FFg;WkWPB=KhRq>;#7*6=RNe)kr@I%uwf)!kmVQtRKqNAsGmKl7`z;M@Q9 zTJXDvC6G05H9;7#8QAZ%<`I(C113?}qJmBWFCQIIOHD(K8481;;q++2pfZ%h0#jO) zP9*;rHSIDoo3lfpldt4_X#@s20-!aCXn_W;2v|? zC{#CJh3U!BS@Btj80&Lv(nwH9?1O@^wwDk*OSITz#ud_TrNYV$qCv9Y$%V--uQW53&74^XbnOg0xN4V?v6;9ocb@QV*W|X%UDoHN`|`do z$)&%8@3!c#4sy3!gKu8v+h41dUJ20jfqR9GZ~UIz1D@zJy!ACvDFf7?VlTLouH$Mm z)xCD@dTAv8J~nxW)m_8Fchm~JGYltVw)QNeQD9Iu6t>0|N8kdYBLh>SRY_@fAnr3g z5U#)6a(EE&4M;Reuu|m))y6qPp88U0%E`wh%zm%qH5*8^)=4EjXEJTu5}iSt^k4{S z3c|-okUVp)A)}$I8#=~_@(!cYEKPqilN(h^CBkv)eilR&UI}7)`(A*El8B88Bbv%6 zLQvWERbz|-Ngg(W0?DqYA&(Jw1zI7=00;$2T$zl~~0% zv6!HU(G!)&YmX-)m{js8K`ReIC693F@zJc>zp`yfC8~)@b}%(=be_{sYht1zsEwu( z(1Wt6gv)^A>(EHy`A$@O~1 zJhth<(26E_>gW-zm;^&ycwF{F($*pY94UkEblxo5hNBR9uI^}$B9HH#Wp7a8mVpLg zsXT&aXFjH^#>D0tm)iqs<9Q`^L?1cpCP`BvXe8*>1nrt(rW1ib=6p`lSfoY~x-MmH zN+Ti3LR#liQwort=a}IDrPFXgSroKwOX&)HOcIh^SfVXBV~L$$Fc@u6q#689T7m?u zHW=m5DqVvR`=N1bt$h~x}3y*_pMWEB_?!N$}j7m+m5#wM1OFjf^4 zr&9?;$tG~gvNPvu2~igm(IgyJ%Vrjk-Yp_@d5WhGmp$Vry=H?Nqf#e4*--~1=wt+^ zHOakE5YZS+veNC#O|@>!^g%f)azO3ZE>8^sQOk-Ssp;V-$v@q^IC-)Aj93Ir?{S`K zFea^?gq(aojkZgBF^1G&NIjDqv2CIk~f>j)~H8<-S$6bS{6xa*p7#0H>0=4gu z5LTsQ5P=vmJ^r|Hhgjn1+{&eooYy&*I2CxO-CWg{b0YE&{^R|JtZO> zcMDtqRZSS%3e)B0UWh3JmZUAJ^SK~tjr;6bNacOX?$U;jq^}9jH0#C9uSt5l8mApd zy5`y%j4O#Mxiw%@b0$QPkk-C*Wy%(FV@?^Bs}-SiE>CYoyzelsz>80_fo-7Bh8P9s z66aT2OKclTW0T`Sj7h(Dm3sEiRFY<}Dw!&V7zipL*0EH98_OxRZKx)OGiNkP-J&dO zMkCFzQXnmD*Pwu|O)`^2hjE6ktvTpwj42pRU@)ApzrV#RmjgGh-6X1tDByiZ>5>g& zjDo~~wPvM#@b!+@Y#@yybZwiXN-AA-k(v}fb4zocg(CZ@=jO&rhbVXSvcDKn#dI@@ z!dL|{u0&t~j3k8{Q8{y6VTipTgQR#WS#&~lehB)EF)LAJTLWc0{oG#~1I(BcLQq1N zHvo%HUP3v;OOBoE>7;~d=7&P(am)M<^mFTijv*luJ@-zpgVnkLkk+Yha;zJ_a@#0m zRDkZ+_4Y&7@qHDLjkaqF8tHS!%$881Q2AUsEvx4*f1uTybrR9efHlli$3a~)%jNgb z7HruHhsIb#E0LMh9H}L(gmt!MRB9yV57vMF7$P`BFq)b7Ty5v5>2)62JBO-~ z_cnYwzrbpP=!ow^;zTL~Dj=ajo1}auibSE(HVK}KN#`5$)@L=*k~h?}(fTf+MX)N( z*((dQ5re~M3qDfXD#0)Ybg8g9dD<6cYW_%A!xz#Eh9XHSQ73joR0>r(Y6I7gryRCZ z#wQ9+-#1{lxyfx@}eFx8-<5WUB!lm|5R0;MARCkx*3u19(PtH=EH zN1o&GhM=NF1&xTIZ6Z}Ehy;qlqD_K2zTRxpYcr5adf2SB7`rB+kH=%GvSO(_l+%R9 zuO3p}V^bLi>UoEP!sKb>WSy&0FeQm7Km-+6B{$?uMx{a>@)XOe>z{63rIKxJ3J);{ zub3lC$|xM`Kofs={o8CG-?IDD@Xwog_7jLzUs)60^+NH`a3%wN?|3*j7a{R=uA~&-CPm` zG3nfO)>2g=J>)?tn&=bUVl~s)vWOk7aO?~xY}=BdSGWK=D#R#utCAubj+zC>Avq>s zOwv5aXSXUSRGJNMkYu8$J0xFcnzFmbN>l zi;=1*DY6WnL2$Y^rcU>c(&^z>8;%40u{q3Obb{K#8I!K@>3Tze@@!q2bk*GQ_ zg6Px?5+8_?V1v>aR2QhNu!tQEZStvd5JE>~9omEO3a2#fvVquQ3x^erv}r>`MRZ{( z2bSYz&Rlo6QAtob`IXhlk)Rh{Npt=&QI}%AfvqA|nmTl}O4!;NGTsghs$))`)UfQq7Mf;RV^oPzin^Y2<=S)D%JS}S|2~fEDWCf5YqZBp3=Ba)x614433CsT9#bXM`wS@@2{mC@q2mbdvVLcuC?LM= zuh!Si4+TW6R-a{cY{bz%C>U>2mTnRuJ`m6@NgpbmC|pKs8tqX^u#((Ak%a46XA{0@ z6;14@rACZr;3~F<1>>k08$%HlAx69etX7;*4r?7Mbj-!$W6IT4Kf_A8?jfd4P8m(m zk=i8XecCDIvE`wiQ&c01sXYVH=r-b)fzxh?8)#H5v|V5!p6D0Y_9iE`b{Gy_Qmhw+ z#7IzzkadQ21RD~c)954*7(-aCyXvot)&!OB-F~wcAy(j{M_VY$g7Jg>+E~92G*I&Fw zXn;22iW032ONA3n; z4VPbjjvEKh@(+LJds!?$#8*CdNHNF_HyRyu>JF|=GR>B<2} znk_ckQa3e03DvM7#gZHqAl1jVErvNIea#uD2W>xEJoLKLEC+5lBm z;zPi<9h%fZjXL0}G)dAl9nLtq)}u2}kTR&$Fu1d`-g8y^UIRdMK4E(fY-#XHX#El) zk*c*yWc<#7Z#zm14vloV(WQkZMBK3CXf|UWj%js6X#}^mix$OTIO5>i^)x&&C}@3$ z)B$HT5(3sFy;q|(;?u?#qa+bxt&(_lwqo%i;B%32>G*&qbUb?EEL+MF>Of@;ZR4?` zI9XPx(GGaU^>#`VJXhn4<3-2bXhMm`X_G65#KZ^+oY7d5y2ojgNu>7MCe1P}2&3~z zsQ>}x6k5-*L(OP=z>odhk8|PekD?|HXDz{dv`MA9w8F3b>wm|`{^Tz?G1#G1o~J(W z6ek`yLstlmv}h$1+M)uSfBOT(2!&Yw&A<3JeEiQpo>cOiIo^BR(9!9Z!Cu7={?vE# z&hPwY7RL+NFZkd8)xW2$Yb*|}44wB`axh>u#F#2Ak5K!TCU)F+b{B1Laq+?ym7B9f zW$&~Sqv8Gw53s#`igL7%D#qw?$Y5CE=f_;T`V}s}@GLj4UT47@YEb|HAOJ~3K~z4i z2|l?$)XSPLe&K1}^2C$8`#YZC>gA7e+$l__kr*j#!DuvKu}DJgsU3Uo2piK>cw(Bt3L5O%2 z>0G2PJl;mit%~7f50qkge2i~>k_&4*#waS|SjvKBY>*195yWdM3MPzb7d|(egmP;{ za4mJwapuBV7EQcK;s7%GtV!0@1g>a;4>Ze$E4OaZ)D82)W2VPT zwnmdAmnd*Jn-P^~IrhB!$#-+#eP@uSV|jSY$*moZ4-ScE9G6~tiKo8n-JCpgnnDZ* z$H#o(xo7#Sk9~sr`T;{XNW}P%Z8?;t!zT+CAvNlhL3F~tXX1HjafH7XdDG5W#*-4g zj107)Z98a%t-=z^EmVwL3p3a%=|u6u^g5MILl-(%M`Sk#rFzVB&A;qvNIjLQA1h50 zJP@K!qpU6xe8=-bz9m|~Dc<{m@8jizD}3U^ALF~; z`)!PLp2Lp!p&a2{L3`sCJ16ev{Kdz)^z7g8 z*-w3pu4xc46vlCI{RW@?>?e8qyMKgdKYxSI9DSAcs7)iy!7@Ld0f|pqmF3qBH?Q45 z+GAP0aP8fWuEp9&YdwA-jL+}#!$151_RgH-+V$&PyK;@#1%?;~qY+0(GoJp`(=4yF zsD;OxOU^%ZfgkzFf57!yQ-1G1 z{2rh9@JA@B0#BeA7QE-XpW>Uo^+^U>Lrh`V-QPuN&0@J^G#PVrH0Oi=#~<*aKln51 zqb1XJfj0$jd;6Ps;IW4=&hh1EzRYJo{xmi^+NMh-v_zCuh>AS^rib|_zx>ZQcm5)O z^oM`Kul}1~;o#s9-6c<-7!uT=%M?hvF413l0g`?=LTjCr$JGK8g$EyhfS>!Xet`>* zoTrU#Mvv2!Rt!QNB6Z!cIG)qYYbL`9S{XzXzxTmE;D7sfzrs)a)KBnJzxWfWs%SeF z(-~W%F@N*9r+NO;*HAAE`Q{&f54-z&h!1F2@a_J4`QGPWb#EWu8QUO37fY>AOJ z`0QSrp^goW5|zg^eKtJQI;FvqxtL0U4qX;^PM=4*fDnl)@V@W=Zr<^pZ({L^3hr<}WZh7diawnUwJ43EA2 z4g9nJ=9l=5U-?Zw{D1u=wk+@qpR^%J*k;llO>1FwWU;);qYqD*&aSexHDpw2%E5r~ z?g>tueTef9zLjEp7Ck(HxB*@nL@6d`_84rRV0vSV(Qu2ctr4I6=$|v6HIOmhYgb;O z8e87-#N&MNQ(q%41?53vpsqu1f@ZA$>m+5b*+43=G7`Jjp$ehX9ZOsD#wVZPy+82- zjL&WpjIbqpyxF`3BbsqJrVGMy-tfpf-^6eK>tE;AS6*RvFhrJ-X1M^R(Z)hy=$z+0 z|H*go=BM6)9}0_ZfmW9L?|YE*{vuIphT>RUe+!q6Uc!s#n}6gfhC5q`z>^Q`gN4uk z_D89YTAZ<{64CQxpzyf${!;pZ@uuq;dtn_3wWRDd6M-r};1c+y5H3yOodh&j|Zi=@BXv=r~k!2;>3d|XjIF0zyEs(Ch|Z1_x}b3dN?57q z2nlma(d_@ojJ7{>L8Rus%c=D)A4aO7MnKP=PBn`@4Gy$IM{va4_Qj zH(ub)?|1`0@c!?^OG8&LlD);qQd9GmZ+aUumb~@JC)hu;M;AIe*U_{ys$#^$k6q-w z-}4=O^22{kY&>m{)JwJokuGJ2J^MmHh0K3Y3R4s`A#%By(H+3!r_M1RS&Z?hWs(A< zQS3^EDio@{MHeDNJD_fxgvX&)(tq@$q%qULq{p-qE*~RV6j^};oD~XJA}BiP2r9C7 zdXMk>?(anfp(;zRK6jO0|5v}xSN`Tp6ryp1f)~E@HGcLV|2$j!`&>MEfp@*_UF@G9 zv1nUVFob!{uluIAyuKoFm$R)0}_XgS_wO zew+{e>VM?w=PxmIC7~4xXR*rADX>a$`qW9f&?I9vrx4#|-x|dt)AX?0$An z>@k=WbW&5614?aq&-Z@^gSOz4AO1M=n@8-QJHeCh{k!ZveuiaLQ@8?DjrVgJ)v|qh zhoAX{pXI6V_%>RplRbipC^~}oh(POWFa-*Oh~ADvyYEPlqL2``!Rwxi5(G=lYlW6 zk*stiin{B-fnOZKE1pO8Pjg~8fG8BLM)^cTa>g(iCW=o-q>F)~DpQsj1?7`RlFDok z5y50WV-DlQ5LbR$k!-VJ%Ot{K6`cv3Jbjv7J;YC2YHB|A2Y-dS(eci6Z^1S~z%zaN zC4Tk4``G3yRE|93C&J)CEF`$y_PoAmhC^}t=ipMuWRL6 zNfy^uHYrh*M34YU5FiK=BnTps1VMlRh{>_Lr^D;l@4b8PN&CmSuV+YFsQuUQo$BhD z>F(F}-goZr{K7Y!d-)8v-t`tX%@`{igb~Ep8sNrAkDRsRE4=jemw4N|@5ZAEGNZ8y zf+yyY+kW<4tmPxlojA@7x8BIzA9yE~uP9|sXadS8jL_`q&vM}EE4k^W!;I|&jKnn! zF?e#JzyU$fmtC~dNF$Pu&Ya@iKXxxcHk>?j8b1km8IdMqb3EbleV1`~*A6Hf41g@FcMVw49A`Rvm0>OqPBS)+8IK}iz*_O(!AW5#6P|>`$ z%$Gj?X>Pvv4(R0gC@@8it!rfPXz!RvXatmnA=d(%2`CJ8OjGYBM7*ytXmVwU4g{J> z?GP$bZ8c;fC%S-+3e!l!pkg%K;@G3#W?uGLH`WBuO3@Z_*dEE z8xK6rRfn!3?wNyrhuQ8N^{ESVVh7g*q>9upFEcp1ftoMr_H+6(efI6z#f>-IfR_TV z1X?H_edrO6zWN&EhVz4U-uJ-|uybb#xn$QhS8>lz{wSaLw|~Mu(IEy&um%7xBT+Z# zY(x|_y~Q0&h8FJwMaR=ym}73=L4ujX#|$GJMuL(CA-V**WQ>WSCTN3MSYW)h$f4VR zgfBn+EjE@;lS!D2hJ^7Lxl2*blw_inc?=GtGH?*RLga?mtL@*IffTl}k3J*}D56!( zSBjt{J_KYTdEbZL&%(joOx&2#WcVP6W5=s6y~KE9#Msun>4$D-cK1A+ZVPENgL=f3 zH(krG{Kl{HAOH35BP#G?kF^e|CCb4!zVbBlmoJcC+2yipFGm*!p%k|Elsf0DpL>iK zpZo@4WV!yD>!_O=qYNff1RrtI;iKa{AAB#F64aq)tio3WkGqLQ`Y&z(85v_TG1J*FASKu{C5l zgn-tqZ@LI{O_6}{#4E@D>q0S{jPX(9Ltq2nYfxGkox= zjid!ycw9B%!nyOc~mSkEZWKNcM5IRG}q{z1I9^!hWP1+{A^v?17}gcGEo36`?oMH!6?9xXJTti#~!21md38by_nS0dr| zh5|VVtgWACbYc~=a0S(Hi{mf8%GTNdtpr|4f&_e9I<`VCN~&}ZrJyhwS|`D4?;@dP z*O*R@7~5p@CL~fxvQ`x-whA3Ww3xhUZ?UBQQXkpi4hDPYQJTqS+klY(dnf@lmC zk~5Pb?t@bPh$cR#g$#@K|!RSciZ5s5pOvKpcPco);CxoM} zHt2Q~t{GET6O>Y95<0yOoqiWvTSlWXQ7Rk)q(W=ml12jIzs5icq*7kW_GXA}uyPVJ zNd2gBRWqt8I>Ds0z6tm`AR0kObYK|JLL+Rl^myn`9$@9Q^X$7~KgW+8^q zwIjGB9-B79n9A5DGF;t6Mn$jJ$H{~PJil}fSJ!l8LG*CswIl4k<4|k#mi)n!Jex;p zjnpcs@hDAQrQqO#Bg;z`7IrY(pCNdUR!RLolI&EPx*?YaTh}x$@c0*>M2;ohpt$dM zKf-5Ba@b{p^f*&id!YAP&7 z8k94{q2ybSJV!nh?CA6{AxRB};K)lu)6|$;Q8x`SBr=B35KW{}0-eqBo?rS&KK&p5 znyr`5)3b`K4(v5En4aX!aGhlrw%KL0V#C|wEp5e zqnDRB+CJx{)zc+Mg6;X#+iyikLQFm7)Cp)usWB3TNgpwtmnJ41S{soa$@v#w=E%9z z>^*dV+9zDH_n!HE3%vIy-%r`iA;RvP53umc0oFHG$meGfMaI@(i_@E{xX}ph(xA|8 zdM;bo$G(I62_^}l*kCzz_9WwaL^@7d*&AkoEwsrirh$s>&rC56|(smOp9m` zB&K3$1F8z3R3zFVTZ41#zj8Onp8p1$8>>he5lYaX?NN3+4A%!NonOZKNQep}4I(P) zszC^a_^;JP^dio#)dck(r82bAG_l5ePrtu|qUhp%f}JFcqhLI#(9R{H2S7B5#wV-5 zQ=fXA#x`_{4*gIjH79A1CQ(E^fYL;jWVvp=>1O5@cQR=j@-k0T=#GI*;p*hgQ`HSZ zN$RR0*Bv%D20Zo5Q@r(#Te;%O1BpxSEds$-Q!$u~C_5b>Wkj)d5RxfaB(aYA3q3*s zYipZG5g;h)NhAbCAxh%Nm0uR8b0(BAEY;1a%$x)n`;}auWqC_ML@6Dr`zu)IwvG0F7J5p zspom(^N-U}CBE_q4_TQ}tA>E!?eDvbcl`8^;ibn)NAQ6%^r)9AKK-YkX7Jh?v$01l zEt$zuW|nE{V3C=`Mn{%sEu}XSaj6d%0%%Qt?+owwsrT^oeP3qv`IBfXF+nhI`ovjH zy}riCTSmbWjlu=r>ba8`Su$nV9)Su8ARm213b4XsGsTh{Guo)pTH{T=tv)~XcE3~y zQwUH>pyb6Uy^Ta^$tK&ve%>R zcj@*z2&K?c@!03T#Icu-U{IVoewt^VeVQnKf`ivw2{BM~3N}WYEN>0itj09HLPU)u zBMFoSHqY0rjKgsuv2-pzVwPz1yUUKBvDMo`Kb?uPoj?fBF0}t1D~loY~WQ^=O3AU=&d%mChJFAtcs_L{f-?LKTThmiqm; z2*iM4IwSyM#1m0@PE@iLIEi@YXo97Q9_64kJr);sG9Hh~%8~%&I_LRkpXdCMliYjH zJ>Wd&PoH6J^#V7(>1Os_bD+)QlBT5d0j&&~(V$2JARpOqTP$rZp&Nw=1}P0$F7aAX z1xu`Is!%f=R$RCEW~>Nwi;UnLc~P)B8gO!bnb2r5m6Iz)Rd0|r3kWSSD%o8NB?&rm z<&B5<<$wGus7&FNG~%yWF_*jciepk&cm ztg5)_`dj$G-}?}%XD~h_Bt_O^<<(`Ly#H&Q{^qOnqG949Go2X>1yLD-aF{Ghn~)du z^FEWU3Fpq9rYJSt*^;cIQx_wbT>qx)8Jt<=t4Gcx)|!oUq5&y!T^QI2%ab8vpKO0a zyyy`XTG5->T8cnOS~g08Ryd$0F`-0^G?N-7)6g@vj4!42c9u$n=o6QGI?10-?UUKx zB?8$hDJZF!)T)#cIO)jpoLla=o?rcE|CC1_eS}BudkDAL5JR92p1Q8FZDwn&MMg!p z+hgCJedJk5?JRXw(L_rv9Yz_nDHu#P2}UxmE3z^t2*J3ilTJa5xTYaD9b9E`BTpS2 zD%Y4YXLe?uqA0Q6B1L4lzL|!!UQv@A00@HUTM?WnS(sbk#H&l(e%o#ao99@Uo0Po) zQ5|P>b)AtlTzli2x%}FjL8LYmZUkg()YTwrm>T*8N` z1W$3nB{l3A@NFa8i_og2w|~M#5sx^fqNX`v`ajrKCVKhXFLL1YVRl}Q+gv5@WccW@!6!AIra=gSF(zej?eNLDWarQX z*m9mR0jDC822{iCZ@q?ds)=FD&Q3~t_k2ho>6)hLpdxw}#h1;Igr4|TPHO4g+ZW7R)EWLGM+Q=6qv1N&r zE)iOgNyH??)H8`mzEZU+MoG0PWhgQv_4o|I-d(#9x)qD{fv)N#{YDJFajY+`vb8xt z^mC+v*||Q#2mAzbkS?rQ2ov@c8lJ`34p>8Z%YMP0osv8^< z>r-1#2v1|{R$*PWrK3Oz$ciHIiCgs`?`*4f-jJD+#(Qjtm{yj}dPj&FA0rZtw}GQa zj&bbBF)q7e9{`v@XTK4THYLJlL?_W%xgGeewMmmQCdSRi#s(kxqmQz5ZW(QIe2hdD zdF!2T<{$t1KV;A4JE>ib(K+=X@{y1JHD7u3E9eUo?pVBvuF_2WnAx&qFm8D93(s=p zfvZ^T&$F?y#;eC(;{H#5mM0&34kHR=CVBRmZ}ZvDe3AG6)O*vzt|CpebQZhBu0oC@ zqV`EtMkGIbsSV@2OGBWkJr2^n;-cY4>ZL`3B=wX@$O{n_A}U(%N}_k$VmgrEVa}#N zI1Qp{Gr#yfQnbGFAwdK}+X65$PfQ@;aWVn(X|bG-S7ZpHeW=;u9}iA5Q~!s2e;`j&e+bz+rgpLmJkQiZTd)Y%71W|GFQ(y}FPybeEjx={Bw~ zL3%_K+qUJ=dDd1|=yev53YsVqAY2+UnNbIi@R6*gmkL5s+R=&}!;J2*)AT7^n#fke zif*Uh_SYi4ejnY*vC+}EhCDN5CTHSZdN74fSVRdPhsqT~iS7G=kgTt-bN19JuDSjy zy!B*-K?=#-%q)e;llN0dC8JUbtxd`{qlG9^U)5wBdF3_!_kaC=@H0RAGtA6)sNIOo z&6*1<>v$g+4To$FhYSY;T;ph(nwkC#=gyqr^s!|!m4SdJG~DyUck}E2{8#AC8JbX& zcMAraLq7HKNBP7jK1XaUvo)MJeUbz73zWG*_=X;mm6wk5XTSYn?tIsseB-5W@c5Ho zqpAW09kebP)e{hkS6(~LyDT_wDZ2)#C1YQ4bom5V#YGl-J>uA5Cp8_B;ay}#Wi&+> zCt#x)LrW2ziZ06pSZ+c4BzTgirLsn%OR7;(#9aSKs#Kt7|EPR9*$TG*+^wNk_; zAklp3^N;b|)6Y}P7wo!xCkL+BkF}PCJ&Q?WKC$O%ypVuKHsh^5dS zY9ClyA930Kom?1fGT$jMI#Lh|J6*O$ z1MXN((%aCyo~bEsm2G^tT8U4p=D zxdzoUNLAr#h42|3MXe&T0H+cYMoNv41;w7ll#%!bRA6H?gb*pDKnqD#Tk4Gwi(0Zv z_vyHt5CV;Gtgf$7XlP=DJZHRBQH>^GEuCCpou%;(D+RI05JsSV63?)qK^kz%GP|SC z%assNaDuGp2~}otN#!%=MXUBzTF7$%RuYjmb1ZCO1eQEi?Ttr7BrE zy29`LZyyE?K}W20EmJ3M_xUcZ4y0@|u2`m?w5)miJ-6~t|NCE}J69s4M2iBP;-Lrb z=f1!E8_XnN8`wf|R0P(B11_7NV^^m{RAX{ALCB1kp8qC;)eZK~UBU9w2E%$nur*4i zLDA~+5>3_6>85JLHWn8HOU)MJQNwkeeeBLkvI?SdHdsMYesu@UB&`Pass~lkZgY{vzOBi*4dU!lT91V-7J*%xTi3 zItr9cOtBCpjgy=>b%EdhH~*f$_xFE}8}GU)fzVBcuPsI@GBPHEiu><-fKPtx6ZB-x zb6T!S(KEhFAqwAR>(=Rf}5AMu^9e}`z{=qsnWaB9F+SMOkb zV}s50Rids4K1l@Hra>Zj{>c~EHM@t?7rx6gPdtlO;9Nrt8Pf)u!hq039|$tCJ{X~N z#=^oPMxA3vcaF8u5?iO%C`(1R=n|czo;ZSYjH?CI3te~qEt`qPX(3M<$_*(9K*S#Eh^(aTb^IguLKg(P1 zy_4&1zmX7YmX59P`M-IXtcjFF_RjV>xO*q#=&?P4!;P{)cxhY#^D{?-4&-o3jyb^Ij1|GU4B&J|GwoON`vgfn!Lnr1R?(F+1&6kdC_ z2J6_yB8{SJN|eYz80sbvq6S*FlaF|p0>pMZFHSXLTU>7tI3IDYA(M*3H(tyC@IU`1 zvkM(2bwh9hDGVo$9_4}iK0`BU2rkKHhZt$1XKg$tLT%Zeu^A4p9S<$75g5~iRqB@7|?_|$hA2DuP zn+#7TC38iGS_CFrH9ktbNLDAJwJM1hSKIcGC|y6T-Ap^CpJJZ3zaF+t8@+Qa`efQ4 zy=Y&ZAXn+9yidbBt&(^9bYNv0%gjv4vDc3AJOA$g;cYLxoz85Brm6|v(#gAQt_^tQ zrSEd~=u9#mjQBVI>;FaBDcQ4oH*bC0TbP@hN&Q#bP*oF%krPMH@P&uING3A8 z4J@Bp;h+DvzsU_Z-@ssFgR`g3k;?)tGlF+0p$U!WkN@94=IO6KgR_BSFCSyJKhLll zUov568zpVeSIX2en6`NT^L*rAva724E%sS`}gp3zw-0!J$wa~^c=kF1}>aB z$A|y@?{Uk!Z)5SmUZPg)yXiV=E%@q#UxX&m-!n@SJt0Q2EKibgfGRR%%o)+}!|#4C zJ9qCU;ou{-YEVI;J71B{M>q8}7dIZ9Mwm zBY5wSM$u4n`&(}1zxkDaz~Y`AG_L0AYYy?Dzw<$k9DNNJ8p>`-Z7oIKL1vPDSM25V z(X;4M<3df|HQf1*w_)-ukq?ByHj$-st5g$9aDY!%CcYh_#8%BHl3Famx7g9?;*1IR zm?_28hpwXAD;Z6OXq}^_;guI(JtyJ#gMWn=`Z%U`(1aEl@jYJ3Y{k#jCKeZv}diUkdqA> z;kl~pBaA>)4&?(KG`or(QNp>=I-7Pv6cVRIJ8WtPog!tEQ^0-;LFES~z=9-r?UOm9 z5Yr(kNewAXOZ%9n+AY3xn$?FW@ZJHs9o9sY7ObtVp^ap?xy5Jx>N5zHJd}h;wjdIj z1k7C$OCC)oXrl>Ro~o)iv38PUFCK*{p0%AnNGX_%E#16_tsOcVViV|PeO~$2s~BzQ zsvfTP$udT&^gc^Lp$$i0Iz~OI$yLtQg)MTOD9qn~UqpL;J|=yJ)e9SBqQlPJJ$gNZ zR*r7BgLflhuy{KmM2E^UF59<&cY(KFdp&!0?FV1*;;+t{lfQfcz4{gb`va&)onb1)s(WLCii@?1<{!WhUd6}1< ze+e-=!;jweZVny3ir&6?F2pUevcserkT@RlEc2gO34l{2Tg z;f@<|-8}WpqQtp~)|#LNBUe-Fz`jG5Bb1<;OfWJ}%0@2Yn?P_9g~Z1|(1L4jxDJ&| zJf2)<7y;GRn9cbN1;6l%Kh5sNIaV*M6GcE3lK21kds*DO6GU=)9BmER zwR0zreBt5kOeiSWsz>ZOu$N!^&0pn#`##Oq<`%Pav+TQaH}C(+_hPaPBQ@2yp_k8a z>i8LK?eUH@PzV45p;~VqpMq-I*{5Xkc8CIG#^9Qo(Qq>vr4 zL=X-m4VlWQw;Eph`gd?62SHND!1?h8TjL>}h0B=Bx@aT72bA;ljE20AL|{gn41LXr zfQ?gQx^#&`weY!k$@=^OdB+xX-v;5(KD@FGUXiH*q1X=6NhJHCE@=qK*;B|wI`Gb+ zjY3L=ZERw<1(^OoRLQZ_T90);DT)F0R&t1_TuqTD`w*=)xORi^$p^k?`izGaMj4z< zgRgo#LS=^FlF)eY+rJK>5)C`JWWkfmoM55U1x;lWN#gtNNkSH;DZWyPT(Pudsp=7P z^M)M@8U21ve`cOeDJcp?W+a_{Nic$Lw?|V2UU_-I>iH!G7hw5p&DMqhUy>WpsvQW* zG(VVDJ0YYBE$MZ<{_%zkq#<0K%uk0Z7wMtXMJ%x61~;-4GG{Q^B+qlaXt?^0>$vXL z!yGztGv)3D7JGBVXc48sHDm0kVpexqzi^)8FP|j58$<>|ra^$0kz4M*0}*e>3Cmap zj4}wX=oUSOD;F5oL$o$r7;UmNSm8>upV+{7JZX1Bk>D&M!Ii8D*etNHeFrEO@Ve`Ttqg3JO=g@GvrZoW^0|skBL617YRYz zI}O{*Zb}FL{tQQm#AZw0Q0?GK$>cEGW~P^#-lZQ(f4448%BMI~L9!Btl;uv7iO`C# zXq|lQQ_ng{0v1_D;~Jz?iO(J--J*-N79|DFyGzbC38~c9qJ*TbE6Sonh>=ovao*vb zOF?Nm*d^kuLn)ay)=1mu71XxIXhW0eESKJuZ5+6il4??uWd)7ZTv%-wY)-has+gV6 z*fC!)H`k%lk$B%=GKi|cxpktK4A&Y~&Q2H)B++Gvs4z;lq9%#8rj#azn4}uZf*8}f zC8iDS^`hw;GLXtvO3Yf@KD<-ev1D(dRO;bn6TyQY`6M6wCqK*VRf{yi;$s3UXG(JD z`u$9#$3>rv=z^mZY1+PibeTW--9KcwIpkYUeTSRwybUFrqz8#(YH}>22kTQG(M6tl z=4p;S`z?wnn79d!hF$x2(gcT#0WwWP)w;`jY64M8D&;u4zRZc0Q|!}M;M$((=K3b{ zdWM(2_5wFvb3J$5^Jc8Hc;N`fQu_%~NrX0d>k}R`B%9}E;`!{S9^#?Td;uTe4?g^# zs3r~Xc-Nf(7$ea#BC%;Y;v$&@Usn`G0YP)>)EORl;M1Hvdkz^*OQB3tY%N=;kBBXz zA*u3Q95ki!-pAxEFN~&g9_yi#b?_F(BS%$vy1GLX9TJ&J*p{^xeI)vbmZn8z2wwQc zi~P-Be1c#4M?X(*zK0c#Kzdj#9xalZQ4EqCL2f#HDI+{8hBmYwt4X~32oy-3yDj8*{T{NBxzb6 zlNXl{HW3f}_Q`zDA=>O%YDw*Dq(~Z`AX@e6E^6;O3mON&>>E1Unsfbl@z>T`fSa3m$#=Veb3rrwCOlyDDGvhrjp7gu3C~@Ba}>lT&$*x1J&^us#K{ z=p@DzoH}ui-}$${!wb*8NLQ8AlP0N%t2C7HjoZ$eL|X++=YC0SBetI7>0hpLTsXag zsuiX-_=#gR_RY-VhYi?( zaFIf57P68k1OtVoTF8RVGuW?DsK(z9D zQl`v3xV9`7h9Dh5Bsf*FeO758OGpqOk+Rb$MN2P946XDgPEYRQNh;C$c(t3<)H_#9 zXGJ0sMN3p@&t1f%PasIyy12y5PsSe{=!k8VEU`Ui4U9(-s3AJE z@F*2fDkk5vC=fL5Yshv5ru(XtLMyecYapfAzSOkVe&E!;=TN`(Tfg;Num3IoWgb3Q zCYuwEzHpM|69b&BD2-sQED2SUM0T5qDGHWWmI*O(^R2fbqo$knkQU}TGmO`V7@5&m zC5#-a$Ch~F!LRV0$De1`7qDdsm1T8lh0V29Zn^Om%AzDQIi0LTI!SH~XJ0zWNB`X) zV%8nAwj_FJv|x2I54IK;}p(&!Ih?3k(j13eRG8b{1TWp+J;^3|;c>HsZ z@xaIKM^?~L1*!$AhtOI?D+O}uN}3)t8Io>i6q0Yh@FL@_G1nfvnmj7v&=NKp-0FmS zdC2I@Dks1B3LpQIzhdqDkl-ZAC_80NK}e!dEv!B%d(}1xwm_uU?V_c^JHK6e=US6# zgSCz(IHHo@3)pWfBU&(i${^Fj{DXfY$>o6UV0tl2<>Cj^c$)&>bWjDYD0C7t1X@2N zk^!Dg-jnzKMSOC>F$ISOykr$E0X?=PNjQDz_Y0}x*%;Zk`ySFQb-|DLST$W zYty!*z~ma;)f~F%N*4DoAhbvdXqS*EE^B)nFs&uOT6&dF~;K! zc62od=I3y$BbvrDw%~Q7mNlK7UFI&|MSs^KMW;j4RP?(A7naYVixL&#?8!5%o?9hs z1-ea!9w%MSkO{U#&Fn&#L$@EMTv z)P}S$bwO`#md0ByoIi(jkj0!(fp;D+e3HBqN!m@t#De<%0fJI;`$3N};U--mIYa75 z2sQIN<`|7@0ty#lV>G0)6V6p*Cc!07d6mSLz4IucPyuulNnpZgJT;x3W^qT4EBEeU zR+X4W;ztd3Qd3tGMDUD}oZ8rA-8#lGi3(e1Q-&oHBh84=T9;TdADEXJ*Y4WSPSb^n zC)yO`rB=9HalYE*?0CQc%T};SYhhbhJXRl2e30wKzzJls-+uTh?A0s-%rTNf3!E-Vnein^I|qU{RkM{5Q8Dc#Dt15B6WJft7NSr9iI&p-Sm zVbjuc8O~Yg8X7-g>}#Ty2n&m9mg?Am5Dd}DMB^kqpwbIEB4;Z$tgo!|r3W8pPk)}h z+Q3r%cS%Pr1CEX=KAV!3z)jUvXx-0@tfV7b;LJX2}An1xNwRJQxFx%O| z=48mQas(lWI4qGcr4+T#TViXapjLJ|RKp?bjiXuK9AH%Z%!u+7L4^!fFT9Mh1geYL63NlZ{PDO%@KnKHD{W|e6eo(4yL zIt-Ko+CFB&qo%Wym%NV`i~QK)VcV>F`~Ta|QEZ#_Z70!fP@IZkr`NwU!)x!&_H~68 z-O*;eq|8+yx7#o2`y7ZAge59vrZJ{|uP_OIg=%3GayuSOj}TgkO&PY|7bR1Kdrq(DuWK78%ZfLTqQ7GCuWALQ@_Po zWNbhQYy=@Qf)&&XGzG>B#HcL?5y{&prruTKDwGK5OrSy_lc_ftOGzhaq!+jliAtgx z$VJ46hT1yjJ9Es$K6&j?K_+~v2uZoVrM}wAB1E8>Saey?H}e#A&d!AyR-0vxojb~0 z+2_icE2%eYbjTn|d=MydqPG|s@RJDW?W|J9qzJEwsnnf-3OQaRp0x3ST1CXltaHw7QU{L= zq3yGJk`|&Tikd2m*q9Twps|5kD_%H%j)U{N*l9}gMv%vX;Y6T-t_bWYyM(G{scF)H zOr)Tq62J*X0HbN5!%0DnV{7FcH!SXB!6-6Xl`rp@4Fv@=%ybOLstcTD3oF|7AT*Ao zZX~8bOH4B}P*Eh9k|2pS!*)RX-cZ&aZB!Cdm3S@*Tx}~L1WP@&dYSfRw{a}7-H1dh z5}kPNaf*daS;_Wqp7vy&bg9od9jyuoEgH0a;pBPL_E&|NVuvrLHN=RD0)^U6a8l6n z&{AL#uDvz|QQ%#MkW=l^{}sL?_aV?c@m zAv}>Lt@5A7sn-_T0Iec^f)blN}`L& z3OeO;?Q6Az2QJOZ(jZ35lvRWnQ@I}7u5)~*} z6a^9h2@w=PkOTpOL?VDe8UO=K?CIP$z2SuYaNgT9G=pltLZ_;0db)b%cE9($&-Da?ZO8v&=|)?G2o1as6ES+PBCSH6cNH0G(ku2 z>Qh)DSutZW?{G34C-E18=_ckhNYBV*oLW6cGCRjiEkUl0aVjRa78PrzL=z(|qL3^V zLrNd6ne!em1xkfq);k}%!O8HZDuxq9m=G81pMKW5sQdq^>!){BQdPz&)`9fZKrnQQ zVF$MnCIy+1v*g{qz+Ed7=Bh7*4289y-H1g&+mo41UobDf@kG~18c0oMIz9IWU#+;$jt$RAmo61DR8bb zT9FE4N-{HMtTk(Et3;*54-GQ$ET3OO>WZSGKt&4SDl=QJs7&^-6%W!?*q*5BZ0K1W zrI0u*%0Vu|jVM&ekU`!~~f%T0*qH%aH5TX(p;4u=;t}P?1$F=9!(w)X{j8WbrUBGpvt|Mw1 zF3Ak>=RT^#0ZB~p{NF&g+Sksg3OgjFVJXQ5n3hZCovOM1jpv9|F;*s>P{#04??lS zhhnJ!9SNicB7w|3lpg6Ex)ueDHFG#6@XCP-+{TF~YIuKL6-^QB{URBW>X^P8F*HL~ z3d;+xynrg86*rJxa^mDkVq(08TvU8psltQ7SFuJSFk-{T4R?_AVe%XDlq5z-tPtUA z)`Y}>%3D)M5+Oq`YA2nnP(cN=dAf5TEY4b@DCDx6(pJMNMItl}rI5y<3y0U5ND4YC z!6kt{BO=F$0z-8ScQ7%Daa2jN5}a@(I%b1{*Vh-(amsXB;g-20vXV&Xz=upaU@a@< zkeuLnq@=>;t|~eq3(RScQ?Ovy$jgrF!gL;^AvY}wXBF0C*u3Y_Op#O5%rq|?&qU*|3B{)*z}{2o4i&o8t_cu0r6uy+Y<_p^OK{y z*!;eqT$2Hq*!;M-SWi|s?YPY%>z$~in->OLfy^HfhJX$&OXA4Us717!DXm6AT#^1! zo+5LMMuu!`Da$chC4?tfxL1^nzz2EkOx&|Cpzxbp#<@Ts zb`xyMgOD06AQF&hP>Fz=C6_r?IZ~<6zM4oY&)63T0Y++^cGxIP(UlFIODQT{yYp2P zv!gvR)1XfyGK(5r#qGh6)|26&D^F(z(#R zNsSc(BV@q)09=Ln;ZaJWv_eD{hY4154usRV%vI2d!)b$;hCDB6Hrq&{gVM-HV4#~e znXk3!>6p6H6k3C|#3f9{F``~aNQ=!gz@TJ=D=nqTsMi%qoFa8ZTu;c$jNxjZL0&Q( z7ZhhtaM?_cR;^AgPH{s+Im}75V!qyl)Pgl^_>4?VR9IElD+6KODMQ>;TyfRa?C8z$ z#t&a68?UmnIYqYGCuydLnHo3V@D|p_LmqkPyTtt=#b8KQhBio6;*B4xEaJi^qUu8b z{*F)l{n&piHc#T=Ve2bAvl;@4i;v|0&Chi)E($+Zs3(6; zI`L3UCrkl3!FXT-qxl%6A&H^Wj_GzHX1WPlt z)Ci|hS`$SH&J-7hdDU<%JRk@;XtFvc{G9csETl?FeBsFQtV$8RkfAOFL~(?*1wOHq zv1jYyJsf!J5kxB{ZKl-g3Eo-KC?<&$N)3@w-2H_wbME<*xIu}wl2~ZUGRX6cEm7KE zL=&kd(}K;vPgW?XCG|8y8B3$r;P4Gc>F5^2SC?3M{xo(7DsE8X`S?HnB-h?}HTm)e z-}=(uQWhhewZux}jKE4+6)A@nf<_Wi$QpVo=J54baLHwd=uS-|l*S1|J*m-7Iz%$2 z-m0^(y1>`Jb|3fO`*)$YHUf+d+g^%IE~K-88l$Bkj7F*fiKqzNG7OTOGw4L&bV=M% z-1yF$_|zvp#nt4pDq#M;J2L;xQ zD90Arm_{a1(2om=HWncr?WTfmgKMt2iW`3MW@_~o8yiEs&FIa}qf|s%uY;15*7EqH zKje#_|01KsA)~_Z^3rMc^tRIxb!v$Ytc=oOM+LpOM%?OgKHuQ9ACis6IIqI*=?qaS zi5oE=|IA0Y{a1d8Mx((W{l`D%8(;Vv8oh{_=^A~Lam(!=8^8t@lN+Bn*(y(IyDwsrU4uLlJ)8xs`g_E+Z#3z$~9=@jnY&MV17Y0-T z3UeR=FL#2;hSRmcm@xfU6JJz9Vb_%`)f%%o3%Kw|2*pz=wP_aQy$i*0avv}Wr3??> z@O7B*YP}a|t+2KTL3S8ot!T9(dcBBF+o9DuI?736j}U=yKgx29%h9Sqq?$B4ZKkH% zwA*!-mn`cm1zK1j#57xDF3_4L*Rq0Bj5Wd5@8_&HWg(r!Fcd{jt(Fo+F-0LOuAD?j zi&TQLY3S~o`8GJ2; z&;gjm;oSs7tw_li%iRc^wnz(dY3Y|69C`Z@e)YHhG1J@TQKjbWk52G~|ML%MsFRb`upo1^pwV))eOewDYq=X#_Ts6SK3u>PN5g+S;oD@5RxcZt=?>`XF;#wsPdkBkbI> zlh6PD=P@fqknL&BQZ}L(c}%Crbd(@QhFAz9Eh!?&ou9drx7~I#eVb#9XP1a+rV&|| zqjikM2Llb@BOm(^ufKYNul@CXh$v#s6uh{2ioLz zx1VBtd4scO7O@@*1Wx#HO#U(I(PYXEo06a(qYJ?WtntF~6~SIsG30@67WQB$Y7SRH zAQvnCoVA<7rwLLUn(ztdbpkKAikKdprlhLy+lh*60%iTT$NeAs9mGW+uCfYr)oX;J zFDnBU=N(8x96PpdkxX?ZQmi5w(5QQ)$ceSYn4Gc*N2);k$|;I5&aI*vEvDx?w7N}} z&MOwrt>MZ#u9V;toR6>$oRdT%!kCggFE&{}KX1J$l}$l|>?npAYi9?XeCaHCG2T=* z$ueYTFV*^d;t=>U^?EGpWjFWnesU+b*$PNo`M;|KZ>K3p!i7cpQ;aoPGHWFFo-BiH|5u!ThD$ zdCN_2L8K0yC_1wO8ieBb~$vh42#P!7E1|p%9KGx?ufK4D@zQ`T^$y$8HuG_d>8Qzc(x$5$Ohqkb;uhVw zMK^9T9oLzP8%)IwX5uDu%?{goGgy~%>+SF5UAMj)XD!odi>JQ*7|(v|2|8t+9j!U) zB4TQ)#ex01*mrOb<09kGp-Xt-spn9ALtVtgal)X;7@GpCAXbt_t%h|0iaB`W5w7{* zO>DSva49MkViZjU)FCQ|V{r8Gs=1}EV|Zc?Mz zY$(FqKrk`q@RjsdX*HozBIO14i;{Bl>k~Js$;=_VmLrbi&0%i!6Cf&T6Pumzr1QK0 zA^1(0APjIX(wP#v=$v{}(d)%@JAFFMf>xuT)i5+_o{&Z#yj*ounKL^<97lxI34>M+ zDGTQ2XPD_tQ)?uwt*>Fm;kC35CoK@@C`P1?{fBolw__HSM4MgyPg6F%DLYaC=Pji% zjK|}E`)n#gF6gx1b=&)B&-ciUrIFSdo?fEAu*|SOLPv4H>xz>4Y|6}ztvDg5&9vEl zbRT>bTyBEJowYa-Y|;W(t~yHn7_KtG*F0VsWGm%ux86iL+r+w@np6Dnf$#CiSH4Fw zlDOQE)FYmK_Gun@?! z69hxP8x7WE8T}7tWob+!(O6)kQ@)MLwc*As$*ySQ%lv{>1ue zIO$KtCOuVA5}RGsg?}45Naw=vvU>W52pey!6GP}$m8u>pm2;O+1iFy5$cc%%t<+^o zY;r+eMdjM$O#R$3S=E_}N{IwjB5R<6rD;TWs!neSwGsWg!hWy9}-^Wmy%{@O1OlQPoLDYkme*PqEfgtd058-~D6OUOk5y8|lMy!tyZ+X}S9PYjMU9#|gdZY3AEqYJH0y zhtRfQY9)zPuz4$tL5YC>%8GLHeg3dg# z)a0clA6cG#ggr=Z!FWwYs4mEG#rD5b8F|g`)}^%(j%9$ZRa+eH%R3|G_?yt4Vh{NdBMvI zCyBT3BZ_N8LZF04BQaLdl!7iXV-@3*1Y>i&@2L1t$>$XoPj!@^-1OCV z1sF*NN|kh2X_3-b*kd5k5d~PlTaQM8aiI~Y*eFVRRHEq3%wTM2OtR64JkM#Sb)*Q= zWM76Oca$=*C3-^B^FJ|e;zD8d)z`&lBQoKyDxpXsNvEZlYD1@0lBOp3P8g4t zohFAqCbGd>X4(8DmIEC76Brrv=S{f+Bp;uxu8mM6^>+MiB;ge zMYynuO9fG@20*Md*|^}j7mhPpE9e$=tn)Y}si`^*4KKfNlJ$*}xD_F-p;k&F6Qqz* zE2J&3BA7+HSW@pcnVRl|BWeNTl`%D0!$mMI4Aw|W5e!>S96!nH&!6Dn!2=X|Mv;xF z2~ApB5*Jg-7^8!UvMdZ9Ln*@`N)ikr!p&>2!hv(dPEu15-PtZVV?-gD=}dE`lq6`9 zR)8(6a3~#<$Qpz75gti@IA-De5@lvFWkDQ8%-1_eEm<9}!W+dBGoh0&{jiDTk5fbvEAW9NC-8N_C0x~MF1lg-4*eDLhIcXeYeSvot zAtEA~QY$?3Mx%6sN;RiOBTAd#X@V~iB4fhlbDPw?Kq#MZJZ;4;5hmcGPD#ALHo_2!JsZ(0Ceyy7UOba`+kl@jMbD~T3{*>22iyU)HIHP(kYQaGCJI%zEFbehc0 z%@en#up*-L3Mn=7TX!=Ea6{i?e^3-#Waq#FNZurmv&h=L)-Vm6P zLdG$rHPlr^VI8G$)KM4z0za|dl!a9IiR+EnJo0$JSc|nGvLKR@*m+{-QPQDPNvTT; zS)l8ola)#^CPV86wk%0xigSXxOsF}Huny@$u(C0REEX6KS_*LBe87fel~-;F7->{G z(h?d@LGEazb$0LB#j#yI)?PY~NEM~<_!?wU&Vi%*n3 zz5;0lsfvk&Br6Mi?9pk2NJZrVkoO@=N=U2>n@$#jnv9VR&2_ij!0A(GSbq5|Nm1fUgN+=%8L|E9 z101^kO2$}PtuC`OJ=XO}WG+xf&?G|Z4!vfbQ(~R9@djBrVs%ikH15-j0*1FXSYxD1 zv@Y?&(e1SGgYf>(Y@OkTM0rS0 z&_XdK>qr5OfutN5O6^f;%v*1IJNTG!p5dGgR5}TG$2)I%C%Tqka*Ohcx>5{XiMOCp zOr;$%B^Vc;)p3DU1x|sTV5EWz10f%-`sA=2jPN{E;fWz~#!(7O($efYxP#yR*Z-Vt z2e&a84@hNx z8wN|lk`U3|I>VoR;fpMuTVl_i?c93Xt)x>8+VeejUUmtOpZg(otwL&o5Bn5AsGlr7 z22*+0Qu$<9N|$kH&vukL&z5a7EG@qdzM$ERX-_qo?oBf@yPZ~d2k2>ZI*pE-pkO>c zL$g1iJ++ni)nlAHb)3;~NLh?fXwIKI!_!Ya!P{>95XYWc=h(t42y-D`vO!JPtH=gVo{z|_WhgDBEvQGW z3K^84V9GFPva&knR#XyHpl*bAqAEfHz>_2?&;RIo<{sU}^&hyIL76jma5r!N<#+R= zho2-H=H#xVJ=35)+u`!-jsk(io`{&mHx@Yg;t5hBTu}zqMpfvnEpb_aEIo}{ox&At z+qZ-FeCQUUM3K}Q#AzL=CACIEcdAKex{V`vr{=~`ItNk*sK8sijBphZUqdCKb$H=$ zBG90yh|Gm^SmQ7w!}4qANq!+_-Hz$*o#T#w@oCIP&c^9QPQ7*lFCCX$dz2lQ?xpYr zW@JdbqJM4$J1)_pi6{k;1Fa)ul#pvjJ{mEymfRRt2LqxcCM!qG?cKtM|NBo;S9Qku zkY=liiZu0Rjo$WIR83>7qfx74P*|@k4Wh956A{D`zUP=ao0o_iQr@#F;8;i@- zv_dP7umW3ndb*8lDC%;9m3+v^n+g)DRz+17)e|kaI|bZ*B1VWLNa2FtYAR`NY4IEX z`k&I6PB_1Oo=&%mvXbG(8aj!Hn+Y4EAxGYNgn#reKga+6KmBhME9>0y!T0dtkAIln z_8!(7I<+>L&x1vvEwM<}%?3B!dLy&j=lK19_xtQQu#32%F~Z`|bZ4efQH;og!cPi; zS87va@Z-yaw|F72zUsImh!al~kLdMMwr!v0#phq55jpDhh_v0Hy=4dOEeEMJ_A=Ew zNK&7nbOPgZ>UKM3&}aSZYcv~8YO&&#m!E^IY9@*?uf6gj*WH+N_=-z-I8jXWcbo2XLo^{;;yyP6?0kCGZ+$=ZaoNDJj4 zV|{6r=`D4v_8h+E2v=Nt1feWCO0hP?J4glA=0uSO8){04XL;18sk_v)M4Diwu{lKb z7p~z%!8gIT908Y>LLiLch3`GX&ZGO8KfIevj%m%b(X*N@d$w@t+YjTsBlkH2)5m8J zXOd?g`60uT%hY9xD?xaHGgaT^EmI=K$5SlitBlHm@y0L=yS!y?#~fRCY$wrm@FiLX z)8{DCcm)PaS%!{iFdUO*C6P~p@v`s%NA!M^>SMj+^|eKe^lYzBQIi@u_5nM$idq@- zgReeBx7p;#yRT!p7=8Q1v{KjwnCi6SziDOBZ z4iDb-AbZ@U}LbsnbT)UU6@;}E-jE{8|*u@m#O(SYv(sAeAuIv z-ee(cdLjIb_2w+37257$vqiU+#n~n;$qVw8A*qW)yoe1Kc5HLJhd7BsT#2_(8k)@p zL;_cO60eYjBSKOV-0-6qC@d&hi8dtCNu-s5s4T;c>V&U&oQkt&miaIL{tx)vzxoX> zx#}>!rh^lX6S%^lM2aYbY_*|lES_8C2lqX~>rcK&S_Wg2!dZmWRbr||slX;!KD)@= zk=@8xW4$FSvtW+o9L7RfmPC<6;#lA4(`|Mck4sLUKhNT5gQ;enB(5P!i>iz|0GzyF zT(LQ5^#bV~(uW(|m!5i@ke^-W?mzqzAN$SEvg6QhOyMYfL8KGB^`vo%ENn1>jvBoD z)bo7#^IwFelDeo-S{tYkN`&s$Thc-@AGe9L;`Py49{cw9xb>HQk$R&>k!AE(R~Y*~ zNRJkhe4HUgnB}+dF{S6&@fZ2S|MW*Jo;Xk2 zBuwcIw$|EE6dTR}03ZNKL_t(2EQ||OZmD~iRVi_Eny$+*3X}{y%CaaoO|2oQl9bXo zB-T~KP6SE{GF{TyKF<}G9cHD!ifASrf9!dFc-KQT*Pt%DjE*ny)&KaXs88R?p|>1C z3dxSR%asQ&Wy@@je!q`OVottrf@dFijA-bQ7S6u9$d8JM%MTqQ^Oh*KL}O1)MiiqA zEd`^MHKJk3Wi#7JtOVk(Q)vlTNn zGt2DO{q(k7hS5EYs8JRAxyN&hLMS43Av43NYQ|InSV9+wy4=pdB zXZx#fmMo%V|HpGBD_P`^w zw)EI}o9&;lEKESA`%!5zMkY%KKo5C6yi%{$-!ZW^s7+AG%2E~5*);Vj&WlVE$1RJ1rybz3X1S`^pp4<~!VU^G(cenZp^! za5SVS9i}Y6TeK1+QOwffDi1&O2tR!CX^bs6(_bM?demYaH12?P;FYYj;2|A!LVOk> zc8S1z6htOuBCVcW+$aA!jm{AchFj0`p0#Cxq>q{g##3H85O1zL2 zW)=o(2#c_i*he%(%4~g#lgD4@cmCJk;Vo}F3f54rjbI!Mn&T*D)E|O()EWs^2EzM^ zS5EWF3$LJsgDA&3$0#3@HWKibIMFm4b<(&)tJR=hucPZV$~1>acKfkvC4Aqf_fJ+9-K>;VfpVWNWiS zT}srjMB89uqI8XBoMJ1!CPIW5ZgIgobHdehUf`?YQzR8q3-Z`fOS<@toHWr0D|zGP zSCP44OKS>71vAY#3Rm#`zj}Zt?|l?odWxZ;HU<5qb*4Klq|>atdXAoNl9ZO%D++4l zFD>$yzw@85N+Gr8)Vb4axpW8GD{@m%6Pl*b%qI=hFx-p5l`U*iRZYP!r2KlcFRD|V zMEHndf6TUB9oFnQY7I?2R>W~kQiCXM)0x?Yif1Tn9qS>E1X_mEQ#b=!JQC*xNxR3& z@;ZADU&UjOKgs!1CrE@xdl+XURH~@8Q&cR`+9O=Jo;nKg){{)9pS9kcg_K}0A*Bim zBdrj|f}B`s32=__pg;>9vaG3iaXx&{nNz2E<>eQNg(Obuq)EgmA0wUO^;0J?0#scx zaAWpfeUQCJ58&sgsKuJZc)ol0{q$d3#tw^+DW5pD9^OsTuCejjD$7d?h(uFb!|e1d zyv&1U%dM7u&_ZQeQwT0skKZjp0g88rtDUrfg?T83aMx-?x zqXGMOA7ETm9;RpJIs57v?){U$fssW=p|ceTln{ZBXf57pMBzxaVy-bo(x~&^_q>n2 zSL`Fwg2aN(p-du*(hzGMCclZsNk^L08Lj7h?XJJ&um9r9WVTOtW}463@iBJq*-gDs zqgii|rZGC!L~%r%rZ}b9IKRR}U%Z!%r(S19CzOMnL0z-^%FB57$KOwTYma-r@^?IX z|D(7fB(dh?{L_E+n_TnOYZ&!&{_GF`f``BP2=!Wx;V9>g^<^BEJySiT6Zo-3Rz3`izs7jI zPb8Y;gN%G(Kua`fX9T-ybRD>vxZYX_z&1X zYc$3{C5HZo*O9_z*BSgfC(~s%ccu59Mz>AWtc7&SG!#?m1aVU1ifgXq@RdiX#}TCw zs7i#9=#=C8U*Plq%kR-IGN$*FaJCC9o&a6B`0TJ=Z!~Rqvd04k<*)<;bWip z7<;Zbz-Tb$)qR)pjX(JsYsb$~(-K>hC@Jy6AylyD^Fpw9&ptl%f!i6X40Mq3DHkm6 zYK=Nc60y3nNIn|TZFgxVbuK-ymzSP>g_oXuf!un|+aW16rfM-d_fUk+LdoDT>Rh<4 zrFRHviPIP}wnzmgmE>*BHSfQkU;M}iD3s%-`5EqY3EzC`bda|iIDF(NSHAUH*2jI? zGaXv(Hh=ve{v4ZSC_`n0L2%-?o+ys7rJ<%H+&JgZ-d$XO_!^?QI%Aik5ojmyiKaA` zY&@p42B!rG#V{+Fp6YRE?;&hfGQGXaouB+Dx8Lz$2EzeK6ouBinu1#aD%O}hXJ${2 zkNmSw^57rc#j6iJg{XVxuegL?`rOB`4G_+=wb5ZN=`hSQMuQBMO7`yFOMAM_*6mF` z{cE4#g=5ci=9P0H(tB)h>l+BA+0|;Jw8xArTEl8EiWFja40Bd9l< z6osK)Zz83}7*8!p7>)wAjw?|pv=!7;g!GPbIKtWzt36f;N+l}hL9nuP(qE8F%Si|& zRRaJHg%Xtut_T@SQpFTSD6Y~#mKW4Sf)NrKN0ioJy(1CHrpgewD620hx0D1W95PZw zu|!82DFwZ`t+bn6N*CU1kHC~Au}A{HybSqVKVMAnW-X*XP@SB2nF%53mwx?YeCtbp$MerTPpWgW)UxJA_=bnnQA=Vz{@G8m|B^lACc|c)!CIfD ztfO;FlqBRL!%Isca?04U@9IlA@X{%Mu&{zz3p`8jE3A~@7@ije&cVW&1#0t6Y*}DU zpxOwj5T)VV(gNqtpJnmdI#J)WT7!5N9Yiq6||Eg)h^?n~lYjFu67MqK&cn|bdi-_KZ#iKCe3pMHiHAAgFP6{JofbjlOo`#!zP z=Gb@DA<6_Uz4mhE_HX0t!f|39;cU=`ORrEU#wHAr%ED5sMfA@sbNq+Tvh&J)WU6GX zzY$I%kw@#8-t24`VmOENf_Bp4_z$1syI=h#ThnQ-e#f=k_QBieZw&Cxb8caQtUq8p z9%Jwn&Jm@WD=yiKu^yXvuKK_YoLyR=8@0Llw)c^1&nO$=1{vpGc$F!UpuD5oY_e+C z_}X1}^U3*7kk^LH&v*H)-~J8$)9?PjEWN%0Dq^j$$kjElhW%61L^8%18I*F-1^V8m z`;(ujkb<-`xSIj48UU(*`%39qdgByNeg83b-}DxeB*7FVeKVleYZ1@4Fs`66pKzdi z7@u06`}Py$(y=ibFr}u*jiI+?j@MF6DFiyMVQh)C9y4juq(CQ{w4NfQz~DeD;#!J` zVpKyRjYqf(R(zA8*`zDQgLM%ofpiv>M%oy!HF2X!;Rlu3x2lpULgcuLWzfo_tLtO2 zvcw2W@S+X2)MYWI)rfKVfNazcg&B#ll6I?$ah~C5TzO;!m7a4xME;0>sD-p*<5=fV zS|EJzyY#|WQ&bO5^29?=uw&m|+B>JPiO2ea_2Gc|9XqIXS`b$$m2OO$q$D=s)n{Je zo2%)pG8-MJO31oM~d;)V~uiw!YGCL#pwxq?Qgj#F^e zl~;4)O*b*H8L>?G!S^2HyMOU5YQqrTWrb%r9`W$^9_0i3=RiwJ#=P~GxAW@L$JiL1 zrYy?f^6o>thwzF~zu>tazQBop^Y18|mLWrA1ik5L-gf;BTygbVSXy1?)mL9*w9#i* zZx;{U{QxgL`x4JR@gh@E1DhKRj-fZKnlVWnkt8u%Kxs@EYA69J7$&E4E%sk}fH#i6 z&ic6(R4buA-=v5P))>eH_x{5Tl%@Zi1Qq&wf_jyvzbX~C6O z9btA$k5k9bP>))areNp=CpI=Hg=go~96FN0e7K_ET)+~m5kS>(Ip;7om}N`vgK|lF zbR@}af%Fky|JwZ=&4*lf{k5cV3>rpeOy3Skr&7{JO0uoR)$hNa6AN#!er}Pt+aPHq ztSqkZ+$%3&>k(_&m_$cpt{_T1rWDjtg|#I{7+l^bcfplD8;u!cBgWcN6r<{B%w}^Z zl&tKm{N@14xG={6kC2X`gj1_))O#%=F~FF0@}iH)1wQXn4wp$Qx|36r_z{N{1}8nr z#Yh~=kFnV@ofP_u=NPZAV~U(Osgai%Mmo$mXMK4ClUoEKIo3HBJU1$w_2;3aZ^}aI z1)vpKQ34KYGNcD@T*VvoI3nV{8iL{r#;C~~ZA ztnui5Kj7u>Jj=$b3na~${a0K<9yuCO#M+rf?){UyIlp|KPk!#xba%{Qk^#L#^L+TT zxAWNdA7z*g>C8;A+FvJWwYc)Sw=pg)QM1A6*LIeU)t@gm>($^*E5#*9m-DTNenG}<*p>4*$CXV|do zw0CXgy`R3Ft8ToCrBe(1>F@s$%Zsb@=9u}0rtw4_z)3q*k!IDIhx{G<+yKmx` zKl3r_NsKdwM!n9<&%Vm3r(Wmj`@c`NI-nLSn$vA|?%IwMmcr(YhC_Vj@gqg5yIAj0 z&Jh)!uig7C4qkbbqgNd!jw9ML9fph%4Nq(pZs^e?Mcu`?VM$BXX?TsZ1x|UMc;qSG zbIUDk**ZsA7_1klNa6Alr4*%7HN4z9lOI&5r-Y6;ih_8z`||KH&o z8l+)rs=>%-ytr@@ITT<$xgX&ZLtVEiHJEE5MC#A3~I_E-0D>X|oamkCp{P2ZPvw{1r@npmOOSlXa}{2U@1^QGVYV{ZG*N7#PF zK1{f~vOFeDSu6HP$p*MSo18=#U zz1LpCl38bZ_bk&}XE=ZE9BYf`(B)CIPdI!0ByJ-o^-a<^VmumSMNt3vyaZ#2l|&dz zE3F}1aMlt+21-?!Pg7v4393b6@RSUVB{!CxZ`sGMed?dlJFuO|N5KtCMm+rBqdfSP zZ=x4V8bd+bYRb$Z#-9H2fST$cw8AOH*p{Sm62b&=!R$gfWF&|Z9asd`F*`lW;^HE; zdYxf^NQt38Sf^oB2wfaIYH^Bc%`h5|>81_pX^It|%#_%&tPDataill7tj;?&@*%Ma z=?rBQ$l#m&XXnBoW-}5baBQ`T&`MO$OAv3Un#L&0HP>Iw`f!6+o`0Fh2t?IP*r?># zQ_phkTd%=+iSGIsMg>!IYss^W(il>iR?z`JeZ6T5DL@=WfgoN<7B8mL z3LuGKNY15K9O6A6{{Z#54uxY&~zT*0c zKq*I@X#PL)-YZ(J>pt`R?QlZn8<9a?5QzW-z)X-5GeygiEQ!|0mMw>Fd+gS9&+_!k zteKZtlUC1~;MKi)+C6Q1B)2SCwj@hbA|+9oIf*0$f&hq|FK(`Q;@*26cGU$a(dv0^ zdUMsPi_5y_)Tuh>JOA+gzmHJUD+g?tnPKDR4J_w9vMi@6Vg_l38&2eC>3MoXLW$?Q z2GEfM_C0hL`#y3XYqoD7bp_5^v=Myg@yGezW8a2$!I-FGFqA?N1rbS+GB(-d;g5Zo zdw=WwtQ1|!EF~-*c`rc)5%su5ztttdg4|lR?7fy# z$Ij56?a;|nXgW$|v9aK`_ufHk!!)@wP~?PROyL~iP$B)YV4T8=oFJ5xCdX+*5tMAa zVTM~Dxtr;0H`3TNNs2*47254KKX~$ceB&!$BPuoPg9(C072D6zQOKa^6B`g|feACJ z%?j~EmEK$jV;w;ppyB{D-2K2lHqLBBN<|<-<}WO9=InX0G)E{wtyN{)%{zGc)I~ZM zSExr7WMJtFLu-1H2R`@^<7+4BC4DM!l}JU{(p#Tk9i{c>0|I;=ewHto0?*^KBcr#R)K_YE`a`Hg@2aduw2gJz|{=RWs& z3RmKkVvwY$YCtFLkcpH?)x0RU^r{Sn%Wy(d8iO>k+vV)3nFMXy1iUHvBHu4r%2j40iiGY<7s9=7hnBNYW&dJk}{;MG@N=J_8zMYUeV)fDw=gNg{~ z%*~SyR=9BD7!#YuKx=NlXCHJV-~H^@s27UP=@q{DmtW@YU%!W4cU?~^4M}M!3PU}v z)1F`E%!yM>Zka}pg^aJ8;+BW*VsgVe>QR+S9D`Dn+7L}tXs3Ow5@;3SQcG1v!~`hk zRz;P4dC8G0OIcUk`_T`w_ujpocXhtFj?WdrjaCS#*D9>V0`l$j1{0FlGGqngjE7HRMzt2k-phdlqEXW zq!g^Zb`$$P`XD>@-M~uOBgbMgOFvtpqBZY%?_Jz~-+LK!69NM2vciEEUggziUnCn0 zICJC}yY9M~L7uVmy6yb&pZu4!q9&CvMhB80R)m#+xEd42-tTAr(h|qsIKjE|=XvUT zPxHPHK1{FM<)(XYXKej6`AS08Nzqypja3OIDy*4VLvPS04k9j{zQpYLS(H#1Ybo>6 zdrFPGrnExJ0Efhx5oO31{-si@=djXV!cJO03}Kw`jke)@coao!*)ro5oSflfzx^od zH?C*@Yp;_G25i}R4SVjmg)=HxgRXJ^qWATJBjJYjmnB%8Kvq*a*!=crU7D%F^* zD5%w%EM02z`U^ip2}POah#+Jnqc-Z^D?(=Hm#H^f^wI)d(b%LwEG<*1RcW;*2xUnx zZ?pe}$4NV9xNvEn*|}MEZQnwfEYV#O9Dd^{v*+h2QbV4XG@CVU*mDcx&2>Ea-NVeD zTB7JX0_!s%r8O!L1Um4J1@E9idgXdo0_n*6#jl~M*U;Q+#JzJ^Tr1+Hhwodx@`n?n`{~PyPwx6E(6tW&2In zv-9Sg(1G@M?!wRe2bF-NObLZX7K#_X`!olidzCnIV0;9lk*J}zWMK=|ZM}+nAAN*G z4@hOf$S+C?iII}Mx8KBVcicuO0@7Ya+RLcb8vN+9-{F;SKEtI8m-zbMeUd6qj}L?KwdG>^+urYEMkYWGfbTqPjHC6F#2h*cfbetrp@@0xi+{tLuN^@LipRe64Yu#x&c;pau+Fe%+ghr! zg0c!7gjg+bks!%4sv_iPFYo8m|L!xKKXZXtRfYy@V(0pz zQFLcKUzN?G#IuRe&hegGf{6oa&jafU!eJpbH_eD{g(v1`|E zvR+0Icu}B-9=@N4AH1J9YT%qBj5I;0NQ#^|s&eVvB7gRO{Ci$|`n4hZ#Q5sy&@Kew zsYuQlR=OEMB_b;!bPdu>(rp*Gd!jb*Ya$)`wy+NO)^M@!3n7g!u6xu6V zl?6cGucZc}`IK#Q!ZBWrad}Rj8P?shm3<$2fI(1_k^`1NXtdBcCx|OCm1<1T2uNcn zVu=eRSuf?aXI|p$@zY#2a}AY7liXPvwUCYDYkB>dR|yJ*GLp2{_N&)1KP_AymjK;e|2Rd1mR z$D1#_#{7v3WbKqAhYquK>o!`g7QJpCN=w#DSXo+Tabb~OzmG#Od*Kpa{=(n$%=e$C z9C-EoZqnwBLkHNoV>>ffU5zLT$|T361zD1iXF2VaF5Tq;&;RH}zVz3Raqi?S3Q1Xb zx}A`UReKGA?{c`2(2cj;057V-P!L6|&O!S@1l+oN*-!3v--4eS%FJH&LIc zlT#3cdMI`RS}H0*g@tqT{Pkb_HS=c|spy!Wy}qBrhYz!N?_Q=Srzmo7*^y>_(rf_I zQV;4Jd*cM3{`Y^yh10W)*IV4QXAf(pCJD8oUa!)qH_%aqxLWb$1}V^CKwetv)h1~_ zMkA;(001BWNklRD=`) zt+dz5s0gmUb|Y8q*zAKK`421P3-`{pfB#u82lNJAW>22y;L~sNlgD16y)vM#9M?>Z zBl-#Hz)`zl4Uhc(N6>3xQkmk)g3xN56(p(GluYx4EKeAlnxbB9uy}fb13!9|gFkr{ zQ9^C9$)0;}=bjJT$71IUU;E5gnLRX1#nw6pFhaimkzSn zU*^1BV&34xM+zegw)N@}t}&ivUqp8VqDlxI6cJ%vgE=S>z$ z>#)Kiw8MraOi1qf=zZ+mw})IAgbgVAmMl*xOa{s!6-1SYJkQDVocXy04nOfa9P6R; z0xb-AWNBPAMOjr`>MSwaS;9t|rR7CTmePzOCadG@*mEOWuHDZ3$$3sZ{T5LVa@Aoa z?6H35)l6<&iyo^nxp^InofVS7fDO}Y*?QFsHZvT5=@2h{=UG(OLDvuv;EV?ia2V-T z_*JQiRg5(yx~6EWHtTP?inbasxoI6*$C%8r~Z^CNxI$265Fqs$j6iwhhUo2;uvi1$@^i9ty7wvbv= zZ`EQx9sB4PyQye7w7rbV~?Xl z&8C@+WJN+8M@&vlQe-)A9eRtGo_~SO@dh?9PRl4%k|S#YZJA+O0k=MUH`nglgRN;6 z=H@wf;sha{-n7_l6INn+7rHF$zkpfDn4W2|?_=+yr%Ec#Dk4@`Ef|{^r{C`r>4@p^ zX@2nC@AH$t{U+6(Am|FJwnCnkLw`LFE=EA1Bo*r^I3UsWki1f`q?dT;Z)C7_c}y%j>Va&Qsrenx(VLtcxbu5sx!AR;BL-%-p<_ z>+avj+HG5KQXrI|(x~F3MVo@c8M1!Kli&Cu-~969tSm3F=g#Z+$j3jx`gLp3LQ#~K zN>D*M{6GN?9Y%cVOONr@FMbnO1Qbb*a9)eR8iw5FVWbIO#{dPwH(r3t9r|IKKZ=T+ zm%8^gWZ|PxF{Bnb;T;~lYi`N(`a0ESNSc-8S?Nb_jUgMPB<+M)*D$$2#)@{oO{E&) zoIz@6O*YX{hzc}$S<+8Z=oxJ8kSg#ECM8JHF7-wQ>x|a~Fy5X-T2DXphL95D1g3NZ zGC&%ED=fLvn4x&JuL}EdLhIacV98K#giNo2si~Oh>3}FqFhv_%CUiS(-)xhTdZSKO z6qL>}J~6>nGh5iT`v&@5!>QvdoH^Fx(%F<=+u~e^q(K-+l<+_*gBYrC|D$(u+k-bz z8LJG<^xhdr-<35|@Io3v5RfJb&f1~SvwK_p)MSROJGZj$(FYjYGKEx*zyG^0^S}cS zv3ctj21SMp6^4>}P-X7uMHWsib7J-wRUMIMB|6ZgS;E@ZIKTS4A7bOwG+ID&VvO0P z1;T1XEviryIZg?xag|dq9_H_l{T0(wYxtf2`ct&7SwmnQMQTZ%!I_*&Gp4>~ify}g z6Gt_k{=w6H@h?7)bP9@+KnJ9`LC9f4##)3>!;4Ab0>_6w{xLS~*}=rxb+pDOnVK9Y zti_B^Pmr4o6=|0mdgP*+;az;_ipFf+jrw?Fd$`W z!#KNc*h;K5qLh>p@**cp1ODd!`Yb1w4s*@S7Pj7T9a$heWk(B2>+7|RMvXivNb-#P z9)6JZ)iJ*M=U<>gOxXoliOI7RHPiQV5dX3Q~KIDguFwB#(aLQ7&G*#5ce3b?&(L4))%*mm*8O^JG4ZON66zzLptQ z1K#)H2RMKJJg+^!9}2LA^b{*O6n{2=^_Is%NN`?;+l_>f#mL(oU+Z>qNa+(pOOlbu z=df;yPmNs(!b+-PgU-c1?Ms~@aotZrDd9-^10o%hB?VH16j@2AVy_RY{QUf2F2RTa zMo5hFk#9u^(tbi*)4sys98pju@0WzycfSKPd60XlNuf|Gq$o=A!VpF=NtP2RFTIF0 zC7mIzVcTRGK8q zyB?__a@d zm?zbDc)v&{FycXBUiwx0fYm{|QLuSUWz> z+Fe(1^RL`ZbHgNkn^O*QOytN-Nh7GB@bt3O7p#;y_{mXPv7RgKB_gn zZkI-_#?J#l<v^GYpG zXYHzB_~;qor_Rcv@SIj>De`O>rAqJFWi7^*C@F};h8Mrlg1j(jC5L(n0oHmDDN9dC za&pxCf+SA}!-yiy{C71BScHghrN9}VJec9AwlR(*&k#ZqMiE76&_O^^l-~bK%F!(B zko)dd)y2xvpoh)kY#^D<2K2f)-A;v8E1=a1sMjRbYK6KEFr_13(abGo^tx@*RM2a~ z^1LDGDnuEh@D8zH(8A$`hW$QO;LzHkhK)^Q3|jufaQUtUQm=~RKbw)xoN*3=CD0B^ z$K>{PY}m7fMbkk?F&9o>;*D1ia^sCRcu(uHB+?bKK}oY2GAIX(ZEo@5-~AAOdhiHY zH%C_$_k7?!Zh8M*ESij(Qe;Je(3-rk$Wn6nx!1UK>>_d88r}$t0 zr+>xWkKDr@dv2tzB1~>bdI?#U(=jPCH*9C^hAB!>a_57$GBw%c`=90Ch_P_iJCr%vYp$~t6P{kyjE@w`hV0mScy?5S5hGosh zY3{i1ZubB505UYxsulk5pMI3;REx|NzPDkNzd)?vts}=c|FaXM{e%nsMV1$rahFmm z3yyjbaPF0p{OdRVXA13D>~^WO#>w-7t2b|A`>w5wZ=B%TeK!)1$4Kqib=UO-QOFaY z`8qnchygeuumS{zz&ec6LuUeu)g?E-XAjl2O^78+i*0`V#1A=l;v9F~eFuS%gh9-+ z&pgMu!^imWuYZtQsHwNA+3hj0Tql^qju6%Ywun|%W zW$OGCRB1hN-cSq`&xWb86T`-o7f%)lisEvnCX}C8Tb<%r1!-SO7$)1`EJ7*o9y;V# zmd00lrI5ZzA-us};1sU(5{4rRhAT_7lVBX-@bAqk%gZ<2M%n@nJk<-I_G{%EbiGba zGU%|h6ri-FRtsq~D^#ixN=i)DBhL+G4tZk85{Dv2T8S3cHk|d?ltYZqn z@t+;#@y~sOdJ^CgZ}1hG5*G>Taf`WyIllIVZ}7_3pJLnidR%5HlEP2aXv4`{xAXqr z`ZZc>$4K&&-M8-L#B0ZS_0%(Hp$M#`9G(o)$2Y|FDx0=mjg1r$iZ>7Zj3*xZDy^|P zLKsq$QfX9JTAt@e-}@eG)=aW>_fE8wOiZ+>kJoV&-1mV8n7n!o-8>`94f!A^3^ZX7 z(WtaIdG-yS`pS3cEp?c8eNtzc)Z^?Py9Q|sRN;`RrJ^)-IfYsB4TSFgv%GrvEOI>H z{E3s?^3Ywhu33Yt#aw^qZ5(|55XWYJMn(APq>=7W=tJNnlj9S7>W}{!|J(oguUT4HB-DX#E@{ACk-IabJYC`01fyE12hP=6 zso)>H(65})_X?7~D5%V80QmEcrEgzi^)-Hb)|yqBB{5W;Vg$%yqz&XLT)tlF0bDAH z__;k?E=usWo5edE5ylp%VHv9^47TS-7`P(^Cw}f+&tD zlZ;Cz&oEhQG0`0NB;i5Mf#+W3;=!XVoSVfshtrxu7zQR~&DQnQH;>VlJxpYw%*fIK zNs=I(BoF~Am*`Yb&qCIeRT^DK)hWV4;07f!afAa&GmELNNNUT9@m`hjZiUTujAJhz zp|_c!kQ}QYhv9vEq=hQAbx|uWT>` zrC{Uq1|}K}YEkHYynr;%kXjMQ5R)2AYKU}1SW0v$5CxQ3iF1A^p|lQDIurp~1W2P% zg+LXKs)|qs+DmPcL5h|Efz-6>4XSZv=(FXIO-nTdy30|el%Al!N_E0__ZbRZ4?PLr z(NE}|A!taK`niW2Zgcd!+Vr~OA+Pw^zic!pVLh+aIV8jK(%T-q{lU-ueC2kBjWkvp zX77A?`_IF7*tF6}5g~Yt$?YL4J5XVa5lo4k(02G-2Dw^L@j%#eF&uTLk~j! zau9`gE0E$(3j_pOk8G51ri7twvcgdfDhMMevXV5-!3olS%JSS25h1;~E^oYifG`ex zm@B+lUcFvttkp#07^~M&LQtB5qR1%9935$d_EAGvjW7X}p(T|$s;0@^v*Qy=X%>A27Xc4cG3vmLSxmN#cP8L8vssLL5e`p5ddIq)c;`FU&z+B8Tsx z#B%QRc}^TUM%m4|aQrM6PG6u=A7|rL*I)@i#fX#`a+p1sJ6&%Vfbt$`>Ds&PQA z5feq;XwOMO*r;Mdfvjo>pr7|K+EFM&E(>yUmg&){@vsqze(hVa%K!`a>HjOC0HP&8!^ z7nsmcsGMA6h}dC+601r|nPYUpK;>Li3A0hgrAo#*(V-lV_?3@+gz@QVln6L?@+|-N zpZ;6sXXnvU<4QZ!T)iBDjr2H$xEy(|f~B~^iusE5^FSqqLsb1IqR>*GD9k{8l8^bpL3V>UH#|y&Jd`ScLwfux>#fXlM(5=GPMWaeDSul{+6xu zP?F7fw?&C#@ze#b-FG9o5KOL{X763M@zPVz@y#c`#clW8&ARFJ%2u=s!>r%Fk-`;h+B(DU{Ifsg#UDJ&51;-C6GskGBq=z@?f1TyT{rKgaE{n17S7M( zGC`+1;LCsW6{gosv;D@MloDK{f*jVTQdQ90JVoWI32HLnrp8sY^OTDxXK7z*Gu5aP zHLF~A=M97t4XhOCI7S7E)_9A|WY_@KZ`nwyOX4EHEu}p9g|E{+eUaEIO5AFV%43Vb z6ox=6&zE$Lx(=xaA-$x_hMDzz;*WltEXg@~1YA9_^5NNjDxQz`P*Kpuxuk*tG{RkbS&>Vbi zKZ8z>?K`&ek&pcvYu8Q^NX4L&5Ew}$6a<3ix(R}*20E;8{LSNh`rrNqr%#+iSV57O z1S%NzhrBqqb613Fa7E4Za-=#+n^$k2SAfj0*EHP3W&O|9^xxUl5cYB-%lQm_xbIO4 zFINA-sPA*dU*N@2;O!Bt9L27_?kY!9S$HmiyL?bXKoeJ#6oy8D?uz66x$D{?FvhG- zd#%<3R^OxtPk|T$z8w0t38XLtDp=j7HO8A$3gHi3jmF3QwzbmOD?YDZw%(OM>iNt9 zslD*9Lm*^;EfTC1C>3H&%F5{rr1Q(@xJ6PX+<4b5+;z`B3R#k3P&(%K{+mC-%98G& zgDp!!718cz*nUC14Ef1do}@9>V#hsuNo7eC#=b!yyamV9#wq^rzxx!`ASO#PrdpFc z|E;I^>gPX4PYn3T?|hW^JaQksP8)@H1PxV4qt;-l*JksM8FHIZA!KE4iLZVB%k+-S z(hwo3Es;w36GjYud@O`Ua^c_!rzyGP&HTovexLQz)5u1E z4npQnUE+WLZ~qq-yDQwZ=LSCd$NvRgm1C73P3>ptFuIgT30azWHK&!F$3OoSj=gYz zTA^`;7piu{3uScijwX15K$4{i-}=&5`9S@{%-nblN!}-(s8S2Yc<}10Nb(#RML0Q> zq$>-wmCT+v!^t;~lJ`=2-GtYE`UaJWF@FD3zlTr~9eUbOUgiX`Vq#{R_g?b=_y5+1 za8{y?;%`3vS-$$kFLTd>`*`24J;)&KA%&#O!5QzTRoIehvxd?EXHT8y|NRet#nHnj zaS6Cmp^!K;6l-2h=`X9syDI^LQA#`d=M`b&5RgW|cO@0-O2}m7s5|_#5x}kD<;Xq4 z*eibjbCK`rKJeaMc$%1Vc6CqyRxx>4BNeOaYoqVp6JCc3R>M2P>hX@g?~#!8+xE{D z$1nnDi79>5XoXw-IS|UzaTyLPxRIU#t9PD}vK9_o? zYV{i3g*HEU;(P2X?_&3@H-lR z3I>BdDo|8vRoo!w(9t7&%`B)#tl=>bJ>K`kyUo=#@4CqtP}bS2W9p z+7F1!fVmnJi+2Xm)x#ZvHUgX#I4h7cL=4r!q|`pLbl`@*VgiX23f!;@??!djQ3N{L zwp(qI8Eb|jF$!z#I}-6n>s<+?(m8}F$r3L(fRvP0fKbe}dlZ?WRvDwTA&2%K!&E{V z>nCZBk1;XUpc-qkA_rX(ikL7ADD#5lxh1~zAODt%N6u0$0`j~-g_;w`&$0CQk69Y@ zShIEwl{i8xNqc3PFbCPg5fe?(!OSDt^3t}eN5 z;YKRW3R#(gRH)KYwiBv4;^M_iWTxQ6(Gwhcbw9msPLer<4#;yyt=eG!i*K@UX^~I< z{wJ8(u#wJ%IiwS0X+eLGAu16o#R`|^=Q;l7aZaDQh%|zqJo_SDRdVC4dl;LXKm{6$ zW6|Kh8-QuD1Zf0qNV9->-{(WPTkWfCnQ z?RHqdaRar9FypS0W$Kka`4^6957cXg@Y0~h4%2pTE90!e37^7C~*g4@zQKQILL8X;eY=W?`%8y0sQ5l^@7} z)wJJ^jun34`SLz}DsP8yr<6b{kCQ>52!?{qQhG;GDJ5lYDbf;K3PR<-S1khq6`-U- zONr8wP%8rM|6a!u)r8w0xsCUJ;613STvdU&AfpI>K5egA_FfoZD>1F;Rl?IIVX>)9mRY#Wf2?9mC*T)nF zt0l&Q)&XVV2ttjt4qG@vp@^Izat3P?0tt?SLKtkGqn#xZf-sITCdTBFyZ|L5u$E>e zMq!6a>5@oDjIced6p|pZfRfr;qEeB+#Ags2iR0J|i zaAlv03J9w)y>3P&EojxoSy{=jr6fxVf>6NuAnU4~JM1YzPmjTBTGRiqQFoLgdI ztU;0nI3qA+F$5+*x-6x{I)hlHAdQ+YmveM^h0rx`i#~_NzSUUj9n$*MYr|auQlrT9 zo$H{h?IAbxc}J|)HUXp*mq}9soNx#O!ddK4bqgU8#(3s{5T2AjJPzdLNLDz99J